50 std::unique_ptr<SerialContainer>
createModule(
const std::string& group) {
51 auto c = std::make_unique<SerialContainer>(
"Cartesian Path");
52 c->setProperty(
"group",
group);
55 auto cartesian = std::make_shared<solvers::CartesianPath>();
57 auto joint_interpolation = std::make_shared<solvers::JointInterpolationPlanner>();
60 auto stage = std::make_unique<stages::MoveRelative>(
"x +0.2",
cartesian);
62 geometry_msgs::Vector3Stamped direction;
63 direction.header.frame_id =
"world";
64 direction.vector.x = 0.2;
65 stage->setDirection(direction);
70 auto stage = std::make_unique<stages::MoveRelative>(
"y -0.3",
cartesian);
72 geometry_msgs::Vector3Stamped direction;
73 direction.header.frame_id =
"world";
74 direction.vector.y = -0.3;
75 stage->setDirection(direction);
80 auto stage = std::make_unique<stages::MoveRelative>(
"rz +45°",
cartesian);
82 geometry_msgs::TwistStamped twist;
83 twist.header.frame_id =
"world";
84 twist.twist.angular.z =
M_PI / 4.;
85 stage->setDirection(twist);
90 auto stage = std::make_unique<stages::MoveTo>(
"moveTo ready", joint_interpolation);
92 stage->setGoal(
"ready");
100 t.stages()->setName(
"Reusable Containers");
101 t.add(std::make_unique<stages::CurrentState>(
"current"));
103 const std::string
group =
"panda_arm";
113 int main(
int argc,
char** argv) {
122 task.introspection().publishSolution(*
task.solutions().front());
124 std::cerr <<
"planning failed with exception\n" << ex <<
task;