cartesian.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 
43 
44 #include <ros/ros.h>
46 
47 using namespace moveit::task_constructor;
48 
50  Task t;
51  t.stages()->setName("Cartesian Path");
52 
53  const std::string group = "panda_arm";
54  const std::string eef = "hand";
55 
56  // create Cartesian interpolation "planner" to be used in various stages
57  auto cartesian_interpolation = std::make_shared<solvers::CartesianPath>();
58  // create a joint-space interpolation "planner" to be used in various stages
59  auto joint_interpolation = std::make_shared<solvers::JointInterpolationPlanner>();
60 
61  // start from a fixed robot state
62  t.loadRobotModel();
63  auto scene = std::make_shared<planning_scene::PlanningScene>(t.getRobotModel());
64  {
65  auto& state = scene->getCurrentStateNonConst();
66  state.setToDefaultValues(state.getJointModelGroup(group), "ready");
67 
68  auto fixed = std::make_unique<stages::FixedState>("initial state");
69  fixed->setState(scene);
70  t.add(std::move(fixed));
71  }
72 
73  {
74  auto stage = std::make_unique<stages::MoveRelative>("x +0.2", cartesian_interpolation);
75  stage->setGroup(group);
76  geometry_msgs::Vector3Stamped direction;
77  direction.header.frame_id = "world";
78  direction.vector.x = 0.2;
79  stage->setDirection(direction);
80  t.add(std::move(stage));
81  }
82 
83  {
84  auto stage = std::make_unique<stages::MoveRelative>("y -0.3", cartesian_interpolation);
85  stage->setGroup(group);
86  geometry_msgs::Vector3Stamped direction;
87  direction.header.frame_id = "world";
88  direction.vector.y = -0.3;
89  stage->setDirection(direction);
90  t.add(std::move(stage));
91  }
92 
93  { // rotate about TCP
94  auto stage = std::make_unique<stages::MoveRelative>("rz +45°", cartesian_interpolation);
95  stage->setGroup(group);
96  geometry_msgs::TwistStamped twist;
97  twist.header.frame_id = "world";
98  twist.twist.angular.z = M_PI / 4.;
99  stage->setDirection(twist);
100  t.add(std::move(stage));
101  }
102 
103  { // perform a Cartesian motion, defined as a relative offset in joint space
104  auto stage = std::make_unique<stages::MoveRelative>("joint offset", cartesian_interpolation);
105  stage->setGroup(group);
106  std::map<std::string, double> offsets = { { "panda_joint1", M_PI / 6. }, { "panda_joint3", -M_PI / 6 } };
107  stage->setDirection(offsets);
108  t.add(std::move(stage));
109  }
110 
111  { // move gripper into predefined open state
112  auto stage = std::make_unique<stages::MoveTo>("open gripper", joint_interpolation);
113  stage->setGroup(eef);
114  stage->setGoal("open");
115  t.add(std::move(stage));
116  }
117 
118  { // move from reached state back to the original state, using joint interpolation
119  // specifying two groups (arm and hand) will try to merge both trajectories
120  stages::Connect::GroupPlannerVector planners = { { group, joint_interpolation }, { eef, joint_interpolation } };
121  auto connect = std::make_unique<stages::Connect>("connect", planners);
122  t.add(std::move(connect));
123  }
124 
125  { // final state is original state again
126  auto fixed = std::make_unique<stages::FixedState>("final state");
127  fixed->setState(scene);
128  t.add(std::move(fixed));
129  }
130 
131  return t;
132 }
133 
134 int main(int argc, char** argv) {
135  ros::init(argc, argv, "mtc_tutorial");
136  // run an asynchronous spinner to communicate with the move_group node and rviz
138  spinner.start();
139 
140  auto task = createTask();
141  try {
142  if (task.plan())
143  task.introspection().publishSolution(*task.solutions().front());
144  } catch (const InitStageException& ex) {
145  std::cerr << "planning failed with exception\n" << ex << task;
146  }
147 
148  ros::waitForShutdown(); // keep alive for interactive inspection in rviz
149  return 0;
150 }
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
moveit::task_constructor::stages::Connect::GroupPlannerVector
std::vector< std::pair< std::string, solvers::PlannerInterfacePtr > > GroupPlannerVector
connect.h
ros::AsyncSpinner
properties.stage
stage
Definition: properties.py:83
move_relative.h
moveit::task_constructor::Task
spinner
void spinner()
pickplace.eef
string eef
Definition: pickplace.py:16
generate_pose.connect
connect
Definition: generate_pose.py:29
moveit::task_constructor
task.h
moveit::task_constructor::state
const InterfaceState * state(const SolutionBase &solution)
createTask
Task createTask()
Definition: cartesian.cpp:49
main
int main(int argc, char **argv)
Definition: cartesian.cpp:134
planning_scene.h
generate_pose.planners
list planners
Definition: generate_pose.py:26
cartesian_path.h
joint_interpolation.h
cartesian.move
move
Definition: cartesian.py:34
ros::waitForShutdown
ROSCPP_DECL void waitForShutdown()
M_PI
#define M_PI
fixed_state.h
t
dictionary t
group
group


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