Robowflex  v0.1
Making MoveIt Easy
fetch_robowflex_plan.cpp File Reference
#include <chrono>
#include <thread>
#include <ompl/geometric/planners/rrt/RRTConnect.h>
#include <robowflex_library/builder.h>
#include <robowflex_library/detail/fetch.h>
#include <robowflex_library/log.h>
#include <robowflex_library/planning.h>
#include <robowflex_library/robot.h>
#include <robowflex_library/scene.h>
#include <robowflex_library/tf.h>
#include <robowflex_library/util.h>
#include <robowflex_dart/gui.h>
#include <robowflex_dart/planning.h>
#include <robowflex_dart/robot.h>
#include <robowflex_dart/space.h>
#include <robowflex_dart/tsr.h>
#include <robowflex_dart/world.h>

Go to the source code of this file.

Functions

int main (int argc, char **argv)
 

Variables

static const std::string GROUP = "arm_with_torso"
 

Function Documentation

◆ main()

int main ( int  argc,
char **  argv 
)

Definition at line 26 of file fetch_robowflex_plan.cpp.

27 {
28  // Startup ROS
29  ROS ros(argc, argv);
30 
31  //
32  // Standard Robowflex setup
33  // Create the default Fetch robot and scene.
34  //
35  auto fetch = std::make_shared<FetchRobot>();
36  fetch->initialize();
37 
38  auto scene = std::make_shared<Scene>(fetch);
39  scene->fromYAMLFile("package://robowflex_library/yaml/test_fetch_wall.yml");
40 
41  //
42  // Convert to Dart
43  //
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);
49 
50  // Setup world
51  auto world = std::make_shared<darts::World>();
52  world->addRobot(fetch_dart);
53  world->addStructure(scene_dart);
54  world->addStructure(ground);
55 
56  //
57  // Setup Planning
58  //
59  darts::PlanBuilder builder(world);
60  builder.addGroup(fetch_name, GROUP);
61 
62  //
63  // Sample Start from TSR
64  //
65  darts::TSR::Specification start_spec;
66  start_spec.setFrame(fetch_name, "wrist_roll_link", "base_link");
67  start_spec.setPose(-0.2, 0.6, 0.92, //
68  0.5, -0.5, 0.5, 0.5);
69 
70  darts::TSR start_tsr(world, start_spec);
71  start_tsr.useGroup(GROUP);
72  start_tsr.initialize();
73  start_tsr.solveWorld();
74  builder.setStartConfigurationFromWorld();
75 
76  //
77  // Create constraint
78  //
79  darts::TSR::Specification constraint_spec;
80  constraint_spec.setFrame(fetch_name, "wrist_roll_link", "base_link");
81  constraint_spec.setPose(0.3, 0.8, 0.92, //
82  0.5, -0.5, 0.5, 0.5);
83 
84  double table = 0.5;
85  constraint_spec.setXPosTolerance(-table, table);
86  constraint_spec.setYPosTolerance(-table, table);
87 
88  auto constraint_tsr = std::make_shared<darts::TSR>(world, constraint_spec);
89  builder.addConstraint(constraint_tsr);
90 
91  //
92  // Initialize and setup
93  //
94  builder.initialize();
95 
96  //
97  // Setup Goal
98  //
99  darts::TSR::Specification goal_spec;
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);
103 
104  auto goal_tsr = std::make_shared<darts::TSR>(world, goal_spec);
105  auto goal = builder.getGoalTSR(goal_tsr);
106  builder.setGoal(goal);
107 
108  //
109  // Setup Planner
110  //
111 
112  auto rrt = std::make_shared<ompl::geometric::RRTConnect>(builder.info, true);
113  rrt->setRange(2);
114  builder.ss->setPlanner(rrt);
115 
116  builder.setup();
117 
118  if (builder.ss->getOptimizationObjective())
119  builder.ss->getOptimizationObjective()->setCostThreshold(
120  ompl::base::Cost(std::numeric_limits<double>::infinity()));
121 
122  darts::Window window(world);
123  window.run([&] {
125  while (true)
126  {
127  goal->startSampling();
128  ompl::base::PlannerStatus solved = builder.ss->solve(60.0);
129  goal->stopSampling();
130 
132  if (solved)
133  {
134  RBX_INFO("Found solution!");
135  window.animatePath(builder, builder.getSolutionPath());
136  }
137  else
138  RBX_WARN("No solution found");
139 
140  builder.ss->clear();
141  }
142  });
143 
144  return 0;
145 }
RAII-pattern for starting up ROS.
Definition: util.h:52
A helper class to setup common OMPL structures for planning.
The specification of a TSR.
Definition: tsr.h:70
void setPose(const RobotPose &other)
Set the pose of the TSR.
Definition: tsr.cpp:93
void setFrame(const std::string &structure, const std::string &target, const std::string &base=magic::ROOT_FRAME)
Set the base and target frame.
Definition: tsr.cpp:48
void setYPosTolerance(double bound)
Set the Y position tolerance to (-bound, bound).
Definition: tsr.cpp:133
void setXPosTolerance(double bound)
Setting Position Tolerances.
Definition: tsr.cpp:128
A Task Space Region (TSR). TSRs are workspace regions that impose a constraints on a robot....
Definition: tsr.h:63
Open Scene Graph GUI for DART visualization.
Definition: gui.h:67
static const std::string GROUP
#define RBX_WARN(fmt,...)
Output a warning logging message.
Definition: log.h:110
#define RBX_INFO(fmt,...)
Output a info logging message.
Definition: log.h:118
Functions for loading and animating scenes in Blender.
T sleep_for(T... args)

Variable Documentation

◆ GROUP

const std::string GROUP = "arm_with_torso"
static

Definition at line 24 of file fetch_robowflex_plan.cpp.