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


demo
Author(s): Robert Haschke , Simon Goldstein , Henning Kayser
autogenerated on Sat May 3 2025 02:40:30