-
Notifications
You must be signed in to change notification settings - Fork 150
/
modular.cpp
129 lines (112 loc) · 4.77 KB
/
modular.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
/*********************************************************************
* Copyright (c) 2019 Bielefeld University
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* * Redistributions of source code must retain the above copyright notice, this
* list of conditions and the following disclaimer.
*
* * Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
*
* * Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from
* this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
/* Author: Robert Haschke
Desc: Planning a simple sequence of Cartesian motions
*/
#include <moveit/task_constructor/task.h>
#include <moveit/task_constructor/stages/current_state.h>
#include <moveit/task_constructor/solvers/cartesian_path.h>
#include <moveit/task_constructor/solvers/joint_interpolation.h>
#include <moveit/task_constructor/stages/move_to.h>
#include <moveit/task_constructor/stages/move_relative.h>
#include <moveit/task_constructor/stages/connect.h>
#include <moveit/task_constructor/container.h>
#include <ros/ros.h>
#include <moveit/planning_scene/planning_scene.h>
using namespace moveit::task_constructor;
std::unique_ptr<SerialContainer> createModule(const std::string& group) {
auto c = std::make_unique<SerialContainer>("Cartesian Path");
c->setProperty("group", group);
// create Cartesian interpolation "planner" to be used in stages
auto cartesian = std::make_shared<solvers::CartesianPath>();
// create joint interpolation "planner"
auto joint_interpolation = std::make_shared<solvers::JointInterpolationPlanner>();
{
auto stage = std::make_unique<stages::MoveRelative>("x +0.2", cartesian);
stage->properties().configureInitFrom(Stage::PARENT, { "group" });
geometry_msgs::Vector3Stamped direction;
direction.header.frame_id = "world";
direction.vector.x = 0.2;
stage->setDirection(direction);
c->insert(std::move(stage));
}
{
auto stage = std::make_unique<stages::MoveRelative>("y -0.3", cartesian);
stage->properties().configureInitFrom(Stage::PARENT);
geometry_msgs::Vector3Stamped direction;
direction.header.frame_id = "world";
direction.vector.y = -0.3;
stage->setDirection(direction);
c->insert(std::move(stage));
}
{ // rotate about TCP
auto stage = std::make_unique<stages::MoveRelative>("rz +45°", cartesian);
stage->properties().configureInitFrom(Stage::PARENT);
geometry_msgs::TwistStamped twist;
twist.header.frame_id = "world";
twist.twist.angular.z = M_PI / 4.;
stage->setDirection(twist);
c->insert(std::move(stage));
}
{ // move back to ready pose
auto stage = std::make_unique<stages::MoveTo>("moveTo ready", joint_interpolation);
stage->properties().configureInitFrom(Stage::PARENT);
stage->setGoal("ready");
c->insert(std::move(stage));
}
return c;
}
Task createTask() {
Task t;
t.stages()->setName("Reusable Containers");
t.add(std::make_unique<stages::CurrentState>("current"));
const std::string group = "panda_arm";
t.add(createModule(group));
t.add(createModule(group));
t.add(createModule(group));
t.add(createModule(group));
t.add(createModule(group));
return t;
}
int main(int argc, char** argv) {
ros::init(argc, argv, "mtc_tutorial");
// run an asynchronous spinner to communicate with the move_group node and rviz
ros::AsyncSpinner spinner(1);
spinner.start();
auto task = createTask();
try {
if (task.plan())
task.introspection().publishSolution(*task.solutions().front());
} catch (const InitStageException& ex) {
std::cerr << "planning failed with exception" << std::endl << ex << task;
}
ros::waitForShutdown(); // keep alive for interactive inspection in rviz
return 0;
}