Robowflex  v0.1
Making MoveIt Easy
fetch_plan.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/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 argc, char **argv)
 

Function Documentation

◆ main()

int main ( int  argc,
char **  argv 
)

Definition at line 20 of file fetch_plan.cpp.

21 {
22  auto world = std::make_shared<darts::World>();
23 
24  auto fetch1 = darts::loadMoveItRobot("fetch1", //
25  "package://fetch_description/robots/fetch.urdf", //
26  "package://fetch_moveit_config/config/fetch.srdf");
27 
28  world->addRobot(fetch1);
29 
30  int nfetch = 1;
31  if (argc > 1)
32  nfetch = atoi(argv[1]);
33 
34  if (nfetch > 1)
35  {
36  auto fetch2 = fetch1->cloneRobot("fetch2");
37  fetch2->setDof(2, -1.57);
38  fetch2->setDof(3, 0.525);
39  fetch2->setDof(4, 0.525);
40  world->addRobot(fetch2);
41  }
42 
43  if (nfetch > 2)
44  {
45  auto fetch3 = fetch1->cloneRobot("fetch3");
46  fetch3->setDof(2, 1.57);
47  fetch3->setDof(3, 0.525);
48  fetch3->setDof(4, -0.525);
49  world->addRobot(fetch3);
50  }
51 
52  if (nfetch > 3)
53  {
54  auto fetch4 = fetch1->cloneRobot("fetch4");
55  fetch4->setDof(2, 3.14);
56  fetch4->setDof(3, 1.05);
57  world->addRobot(fetch4);
58  }
59 
60  darts::Window window(world);
61  window.run([&] {
62  darts::PlanBuilder builder(world);
63  builder.addGroup("fetch1", "arm_with_torso");
64  if (nfetch > 1)
65  builder.addGroup("fetch2", "arm_with_torso");
66  if (nfetch > 2)
67  builder.addGroup("fetch3", "arm_with_torso");
68  if (nfetch > 3)
69  builder.addGroup("fetch4", "arm_with_torso");
70 
71  builder.setStartConfiguration({
72  0.05, 1.32, 1.40, -0.2, 1.72, 0.0, 1.66, 0.0, //
73  0.05, 1.32, 1.40, -0.2, 1.72, 0.0, 1.66, 0.0, //
74  0.05, 1.32, 1.40, -0.2, 1.72, 0.0, 1.66, 0.0, //
75  0.05, 1.32, 1.40, -0.2, 1.72, 0.0, 1.66, 0.0,
76  });
77 
78  builder.initialize();
79 
80  auto goal = builder.getGoalConfiguration({
81  0.0, 0.501, 1.281, -2.272, 2.243, -2.774, 0.976, -2.007,
82  0.13, 0.501, 1.281, -2.272, 2.243, -2.774, 0.976, -2.007, //
83  0.38, 0.501, 1.281, -2.272, 2.243, -2.774, 0.976, -2.007, //
84  0.26, 0.501, 1.281, -2.272, 2.243, -2.774, 0.976, -2.007, //
85  });
86  builder.setGoal(goal);
87 
88  auto rrt = std::make_shared<ompl::geometric::RRTConnect>(builder.info, true);
89  rrt->setRange(1.);
90  builder.ss->setPlanner(rrt);
91 
92  builder.setup();
93  builder.ss->print();
94 
95  ompl::base::PlannerStatus solved = builder.ss->solve(30.0);
96 
97  if (solved)
98  {
99  RBX_INFO("Found solution!");
100  window.animatePath(builder, builder.getSolutionPath());
101  }
102  else
103  RBX_WARN("No solution found");
104  });
105 
106  return 0;
107 }
T atoi(T... args)
A helper class to setup common OMPL structures for planning.
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).