Robowflex  v0.1
Making MoveIt Easy
fetch_bimanual.cpp File Reference
#include <chrono>
#include <thread>
#include <robowflex_library/log.h>
#include <robowflex_dart/gui.h>
#include <robowflex_dart/io.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>
#include <ompl/geometric/SimpleSetup.h>
#include <ompl/geometric/planners/rrt/RRTConnect.h>

Go to the source code of this file.

Functions

int main (int, char **)
 

Function Documentation

◆ main()

int main ( int  ,
char **   
)

Definition at line 21 of file fetch_bimanual.cpp.

22 {
23  //
24  // Load and setup the fetch
25  //
26  auto world = std::make_shared<darts::World>();
27  auto fetch1 = darts::loadMoveItRobot("fetch1", //
28  "package://fetch_description/robots/fetch.urdf", //
29  "package://fetch_moveit_config/config/fetch.srdf");
30  auto fetch2 = fetch1->cloneRobot("fetch2");
31  fetch2->setDof(4, 1);
32 
33  world->addRobot(fetch1);
34  world->addRobot(fetch2);
35 
36  darts::Window window(world);
37 
38  //
39  // Initial goal - touch fingertips
40  //
41  const auto &touch = [&] {
42  darts::PlanBuilder builder(world);
43  builder.addGroup("fetch1", "arm_with_torso");
44  builder.addGroup("fetch2", "arm_with_torso");
45 
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, //
49  });
50 
51  builder.initialize();
52  darts::TSR::Specification goal1_spec;
53  goal1_spec.setFrame("fetch1", "wrist_roll_link", "base_link");
54  goal1_spec.setPose(0.4, 0.3, 0.92, //
55  // 0.5, -0.5, 0.5, 0.5);
56  0.707, 0, 0, 0.707);
57 
58  darts::TSR::Specification goal2_spec;
59  goal2_spec.setFrame("fetch2", "wrist_roll_link", "base_link");
60  goal2_spec.setPose(0.4, -0.3, 0.92, //
61  0.707, 0, 0, -0.707);
62 
63  auto goal1_tsr = std::make_shared<darts::TSR>(world, goal1_spec);
64  auto goal2_tsr = std::make_shared<darts::TSR>(world, goal2_spec);
65 
66  auto goal = builder.getGoalTSR({goal1_tsr, goal2_tsr});
67  builder.setGoal(goal);
68 
69  auto rrt = std::make_shared<ompl::geometric::RRTConnect>(builder.info, true);
70  rrt->setRange(1.);
71  builder.ss->setPlanner(rrt);
72 
73  builder.setup();
74 
75  goal->startSampling();
76  ompl::base::PlannerStatus solved = builder.ss->solve(30.0);
77  goal->stopSampling();
78 
79  if (solved)
80  {
81  RBX_INFO("Found solution!");
82  window.animatePath(builder, builder.getSolutionPath());
83  }
84  else
85  RBX_WARN("No solution found");
86 
87  return solved;
88  };
89 
90  const auto &dance = [&] {
91  darts::PlanBuilder builder(world);
92  builder.addGroup("fetch1", "arm_with_torso");
93  builder.addGroup("fetch2", "arm_with_torso");
94  builder.setStartConfigurationFromWorld();
95 
96  darts::TSR::Specification constraint_spec;
97  constraint_spec.setTarget("fetch2", "wrist_roll_link");
98  constraint_spec.setBase("fetch1", "wrist_roll_link");
99  constraint_spec.setPoseFromWorld(world);
100  auto constraint_tsr = std::make_shared<darts::TSR>(world, constraint_spec);
101  builder.addConstraint(constraint_tsr);
102 
103  // builder.options.constraints.delta = 0.1;
104  builder.initialize();
105 
106  darts::TSR::Specification goal_spec;
107  goal_spec.setFrame("fetch1", "wrist_roll_link", "base_link");
108  goal_spec.setPose(0.6, 0.3, 0.42, //
109  0.707, 0, 0, 0.707);
110  auto goal_tsr = std::make_shared<darts::TSR>(world, goal_spec);
111  auto goal = builder.getGoalTSR(goal_tsr);
112  builder.setGoal(goal);
113 
114  auto rrt = std::make_shared<ompl::geometric::RRTConnect>(builder.info, true);
115  rrt->setRange(100.);
116  builder.ss->setPlanner(rrt);
117 
118  builder.setup();
119 
120  goal->startSampling();
121  ompl::base::PlannerStatus solved = builder.ss->solve(30.0);
122  goal->stopSampling();
123 
124  if (solved)
125  {
126  RBX_INFO("Found solution!");
127  window.animatePath(builder, builder.getSolutionPath());
128  }
129  else
130  RBX_WARN("No solution found");
131 
132  return solved;
133  };
134 
135  window.run([&]() {
137  while (true)
138  {
140 
141  auto solved = touch();
142  if (solved)
143  dance();
144  }
145  });
146  return 0;
147 }
A helper class to setup common OMPL structures for planning.
The specification of a TSR.
Definition: tsr.h:70
void setTarget(const std::string &structure, const std::string &frame)
Setting TSR Frame.
Definition: tsr.cpp:33
void setBase(const std::string &structure, const std::string &frame)
Set the base frame.
Definition: tsr.cpp:42
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 setPoseFromWorld(const WorldPtr &world)
Set the pose of the TSR for the desired frame in a provided world. Uses world's current configuration...
Definition: tsr.cpp:110
Open Scene Graph GUI for DART visualization.
Definition: gui.h:67
#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
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).
T sleep_for(T... args)