26     auto world = std::make_shared<darts::World>();
 
   28                                          "package://fetch_description/robots/fetch.urdf",  
 
   29                                          "package://fetch_moveit_config/config/fetch.srdf");
 
   30     auto fetch2 = fetch1->cloneRobot(
"fetch2");
 
   33     world->addRobot(fetch1);
 
   34     world->addRobot(fetch2);
 
   41     const auto &touch = [&] {
 
   43         builder.addGroup(
"fetch1", 
"arm_with_torso");
 
   44         builder.addGroup(
"fetch2", 
"arm_with_torso");
 
   46         builder.setStartConfiguration({
 
   47             0.05, 1.32, 1.40, -0.2, 1.72, 0.0, 1.66, 0.0,  
 
   48             0.05, 1.32, 1.40, -0.2, 1.72, 0.0, 1.66, 0.0,  
 
   53         goal1_spec.
setFrame(
"fetch1", 
"wrist_roll_link", 
"base_link");
 
   54         goal1_spec.
setPose(0.4, 0.3, 0.92,  
 
   59         goal2_spec.
setFrame(
"fetch2", 
"wrist_roll_link", 
"base_link");
 
   60         goal2_spec.
setPose(0.4, -0.3, 0.92,  
 
   63         auto goal1_tsr = std::make_shared<darts::TSR>(world, goal1_spec);
 
   64         auto goal2_tsr = std::make_shared<darts::TSR>(world, goal2_spec);
 
   66         auto goal = builder.getGoalTSR({goal1_tsr, goal2_tsr});
 
   67         builder.setGoal(goal);
 
   69         auto rrt = std::make_shared<ompl::geometric::RRTConnect>(builder.info, 
true);
 
   71         builder.ss->setPlanner(rrt);
 
   75         goal->startSampling();
 
   76         ompl::base::PlannerStatus solved = builder.ss->solve(30.0);
 
   82             window.animatePath(builder, builder.getSolutionPath());
 
   90     const auto &dance = [&] {
 
   92         builder.addGroup(
"fetch1", 
"arm_with_torso");
 
   93         builder.addGroup(
"fetch2", 
"arm_with_torso");
 
   94         builder.setStartConfigurationFromWorld();
 
   97         constraint_spec.
setTarget(
"fetch2", 
"wrist_roll_link");
 
   98         constraint_spec.
setBase(
"fetch1", 
"wrist_roll_link");
 
  100         auto constraint_tsr = std::make_shared<darts::TSR>(world, constraint_spec);
 
  101         builder.addConstraint(constraint_tsr);
 
  104         builder.initialize();
 
  107         goal_spec.
setFrame(
"fetch1", 
"wrist_roll_link", 
"base_link");
 
  108         goal_spec.
setPose(0.6, 0.3, 0.42,  
 
  110         auto goal_tsr = std::make_shared<darts::TSR>(world, goal_spec);
 
  111         auto goal = builder.getGoalTSR(goal_tsr);
 
  112         builder.setGoal(goal);
 
  114         auto rrt = std::make_shared<ompl::geometric::RRTConnect>(builder.info, 
true);
 
  116         builder.ss->setPlanner(rrt);
 
  120         goal->startSampling();
 
  121         ompl::base::PlannerStatus solved = builder.ss->solve(30.0);
 
  122         goal->stopSampling();
 
  127             window.animatePath(builder, builder.getSolutionPath());
 
  141             auto solved = touch();
 
A helper class to setup common OMPL structures for planning.
 
The specification of a TSR.
 
void setTarget(const std::string &structure, const std::string &frame)
Setting TSR Frame.
 
void setBase(const std::string &structure, const std::string &frame)
Set the base frame.
 
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.
 
void setPoseFromWorld(const WorldPtr &world)
Set the pose of the TSR for the desired frame in a provided world. Uses world's current configuration...
 
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).