35     auto fetch = std::make_shared<FetchRobot>();
 
   39     scene->fromYAMLFile(
"package://robowflex_library/yaml/test_fetch_wall.yml");
 
   44     auto fetch_dart = std::make_shared<darts::Robot>(
fetch);
 
   45     auto fetch_name = fetch_dart->getName();
 
   46     auto scene_dart = std::make_shared<darts::Structure>(
"scene", 
scene);
 
   47     auto ground = std::make_shared<darts::Structure>(
"ground");
 
   48     ground->addGround(-0.2);
 
   51     auto world = std::make_shared<darts::World>();
 
   52     world->addRobot(fetch_dart);
 
   53     world->addStructure(scene_dart);
 
   54     world->addStructure(ground);
 
   60     builder.addGroup(fetch_name, 
GROUP);
 
   66     start_spec.
setFrame(fetch_name, 
"wrist_roll_link", 
"base_link");
 
   67     start_spec.
setPose(-0.2, 0.6, 0.92,  
 
   71     start_tsr.useGroup(
GROUP);
 
   72     start_tsr.initialize();
 
   73     start_tsr.solveWorld();
 
   74     builder.setStartConfigurationFromWorld();
 
   80     constraint_spec.
setFrame(fetch_name, 
"wrist_roll_link", 
"base_link");
 
   81     constraint_spec.
setPose(0.3, 0.8, 0.92,  
 
   88     auto constraint_tsr = std::make_shared<darts::TSR>(world, constraint_spec);
 
   89     builder.addConstraint(constraint_tsr);
 
  100     goal_spec.
setFrame(fetch_name, 
"wrist_roll_link", 
"base_link");
 
  101     goal_spec.
setPose(0.5, 0.6, 0.92,  
 
  102                       0.5, -0.5, 0.5, 0.5);
 
  104     auto goal_tsr = std::make_shared<darts::TSR>(world, goal_spec);
 
  105     auto goal = builder.getGoalTSR(goal_tsr);
 
  106     builder.setGoal(goal);
 
  112     auto rrt = std::make_shared<ompl::geometric::RRTConnect>(builder.info, 
true);
 
  114     builder.ss->setPlanner(rrt);
 
  118     if (builder.ss->getOptimizationObjective())
 
  119         builder.ss->getOptimizationObjective()->setCostThreshold(
 
  127             goal->startSampling();
 
  128             ompl::base::PlannerStatus solved = builder.ss->solve(60.0);
 
  129             goal->stopSampling();
 
  135                 window.animatePath(builder, builder.getSolutionPath());
 
RAII-pattern for starting up ROS.
 
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.
 
void setYPosTolerance(double bound)
Set the Y position tolerance to (-bound, bound).
 
void setXPosTolerance(double bound)
Setting Position Tolerances.
 
A Task Space Region (TSR). TSRs are workspace regions that impose a constraints on a robot....
 
Open Scene Graph GUI for DART visualization.
 
static const std::string GROUP
 
#define RBX_WARN(fmt,...)
Output a warning logging message.
 
#define RBX_INFO(fmt,...)
Output a info logging message.
 
Functions for loading and animating scenes in Blender.