Robowflex  v0.1
Making MoveIt Easy
fetch_se2.cpp File Reference
#include <chrono>
#include <thread>
#include <robowflex_library/log.h>
#include <robowflex_library/random.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 <robowflex_dart/acm.h>
#include <ompl/geometric/SimpleSetup.h>
#include <ompl/geometric/planners/rrt/RRTstar.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 22 of file fetch_se2.cpp.

23 {
24  auto world = std::make_shared<darts::World>();
25 
26  auto fetch = darts::loadMoveItRobot("fetch", //
27  "package://robowflex_resources/fetch/robots/fetch.urdf", //
28  "package://robowflex_resources/fetch/config/fetch.srdf");
29 
30  // Reparent Fetch with a planar joint
31  auto *base_link = fetch->getFrame("base_link");
32  dart::dynamics::PlanarJoint::Properties planar_joint;
33  planar_joint.mName = "planar_joint";
34 
35  base_link->moveTo<dart::dynamics::PlanarJoint>(nullptr, planar_joint);
36 
37  // Construct new group out of base and head
38  fetch->addJointToGroup("observation", "planar_joint");
39  fetch->addJointToGroup("observation", "head_pan_joint");
40  fetch->addJointToGroup("observation", "head_tilt_joint");
41 
42  world->addRobot(fetch);
43 
44  // Add obstacle
45  auto scene = std::make_shared<darts::Structure>("object");
46  scene->addGround(-0.01, 10);
47 
48  size_t nobs = 20;
49 
50  for (size_t i = 0; i < nobs; ++i)
51  {
52  dart::dynamics::WeldJoint::Properties box_joint;
53  box_joint.mName = log::format("box%1%", i);
54  box_joint.mT_ParentBodyToJoint.translation() =
55  Eigen::Vector3d(RNG::uniformReal(-4, 4), RNG::uniformReal(-4, 4), 0.5);
56  scene->addWeldedFrame(box_joint, darts::makeBox(0.5, 0.5, 1));
57  }
58 
59  for (size_t i = 0; i < nobs; ++i)
60  for (size_t j = i + 1; j < nobs; ++j)
61  scene->getACM()->disableCollision(log::format("box%1%", i), log::format("box%1%", j));
62 
63  world->addStructure(scene);
64 
65  // Planning
66 
67  darts::PlanBuilder builder(world);
68  builder.addGroup("fetch", "observation");
69 
70  builder.setStartConfiguration({
71  -5, -5, 1.57, 0., 0., //
72  });
73 
74  builder.initialize();
75 
76  auto goal = builder.getGoalConfiguration({
77  5, 5, -1.57, 0., 0., //
78  });
79 
80  builder.setGoal(goal);
81 
82  auto rrt = std::make_shared<ompl::geometric::RRTstar>(builder.info);
83  builder.ss->setPlanner(rrt);
84 
85  builder.setup();
86  builder.ss->print();
87 
88  darts::Window window(world);
89  window.run([&] {
90  ompl::base::PlannerStatus solved = builder.ss->solve(5.0);
91 
92  if (solved)
93  {
94  RBX_INFO("Found solution!");
95  window.animatePath(builder, builder.getSolutionPath(), 10);
96  }
97  else
98  RBX_WARN("No solution found");
99  });
100 
101  return 0;
102 }
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
double uniformReal(double lower_bound, double upper_bound)
Generate a random real within given bounds: [lower_bound, upper_bound)
Definition: random.cpp:25
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).
std::shared_ptr< dart::dynamics::BoxShape > makeBox(const Eigen::Ref< const Eigen::Vector3d > &v)
Create a box.
Definition: structure.cpp:370
std::string format(const std::string &fmt, Args &&... args)
Recursion base case, return string form of formatted arguments.
Definition: log.h:60
Functions for loading and animating scenes in Blender.