51 t.stages()->setName(
"Cartesian Path");
53 const std::string
group =
"panda_arm";
54 const std::string
eef =
"hand";
57 auto cartesian_interpolation = std::make_shared<solvers::CartesianPath>();
59 auto joint_interpolation = std::make_shared<solvers::JointInterpolationPlanner>();
63 auto scene = std::make_shared<planning_scene::PlanningScene>(
t.getRobotModel());
65 auto&
state = scene->getCurrentStateNonConst();
68 auto fixed = std::make_unique<stages::FixedState>(
"initial state");
69 fixed->setState(scene);
74 auto stage = std::make_unique<stages::MoveRelative>(
"x +0.2", cartesian_interpolation);
76 geometry_msgs::Vector3Stamped direction;
77 direction.header.frame_id =
"world";
78 direction.vector.x = 0.2;
79 stage->setDirection(direction);
84 auto stage = std::make_unique<stages::MoveRelative>(
"y -0.3", cartesian_interpolation);
86 geometry_msgs::Vector3Stamped direction;
87 direction.header.frame_id =
"world";
88 direction.vector.y = -0.3;
89 stage->setDirection(direction);
94 auto stage = std::make_unique<stages::MoveRelative>(
"rz +45°", cartesian_interpolation);
96 geometry_msgs::TwistStamped twist;
97 twist.header.frame_id =
"world";
98 twist.twist.angular.z =
M_PI / 4.;
99 stage->setDirection(twist);
104 auto stage = std::make_unique<stages::MoveRelative>(
"joint offset", cartesian_interpolation);
106 std::map<std::string, double> offsets = { {
"panda_joint1",
M_PI / 6. }, {
"panda_joint3", -
M_PI / 6 } };
107 stage->setDirection(offsets);
112 auto stage = std::make_unique<stages::MoveTo>(
"open gripper", joint_interpolation);
114 stage->setGoal(
"open");
126 auto fixed = std::make_unique<stages::FixedState>(
"final state");
127 fixed->setState(scene);
134 int main(
int argc,
char** argv) {
143 task.introspection().publishSolution(*
task.solutions().front());
145 std::cerr <<
"planning failed with exception\n" << ex <<
task;