23 auto world = std::make_shared<darts::World>();
26 "package://fetch_description/robots/fetch.urdf",
27 "package://fetch_moveit_config/config/fetch.srdf");
28 auto fetch2 = fetch1->cloneRobot(
"fetch2");
31 world->addRobot(fetch1);
32 world->addRobot(fetch2);
37 builder.addGroup(
"fetch1",
"arm_with_torso");
38 builder.addGroup(
"fetch2",
"arm_with_torso");
40 builder.setStartConfiguration({
41 0.05, 1.32, 1.40, -0.2, 1.72, 0.0, 1.66, 0.0,
42 0.05, 1.32, 1.40, -0.2, 1.72, 0.0, 1.66, 0.0,
48 goal1_spec.
setFrame(
"fetch1",
"wrist_roll_link",
"base_link");
49 goal1_spec.
setPose(0.4, 0.3, 0.92,
54 goal2_spec.
setFrame(
"fetch2",
"wrist_roll_link",
"base_link");
55 goal2_spec.
setPose(0.4, -0.3, 0.92,
58 auto goal1_tsr = std::make_shared<darts::TSR>(world, goal1_spec);
59 auto goal2_tsr = std::make_shared<darts::TSR>(world, goal2_spec);
61 auto goal = builder.getGoalTSR({goal1_tsr, goal2_tsr});
62 builder.setGoal(goal);
64 auto rrt = std::make_shared<ompl::geometric::RRTConnect>(builder.info,
true);
66 builder.ss->setPlanner(rrt);
75 goal->startSampling();
76 ompl::base::PlannerStatus solved = builder.ss->solve(30.0);
83 window.animatePath(builder, builder.getSolutionPath());
A helper class to setup common OMPL structures for planning.
The specification of a TSR.
void setPose(const RobotPose &other)
Set the pose of the TSR.
void setFrame(const std::string &structure, const std::string &target, const std::string &base=magic::ROOT_FRAME)
Set the base and target frame.
Open Scene Graph GUI for DART visualization.
#define RBX_WARN(fmt,...)
Output a warning logging message.
#define RBX_INFO(fmt,...)
Output a info logging message.
RobotPtr loadMoveItRobot(const std::string &name, const std::string &urdf, const std::string &srdf)
Load a robot from a URDF and SRDF (i.e., a MoveIt enabled robot).