Robowflex  v0.1
Making MoveIt Easy
fetch_profile.cpp File Reference

Go to the source code of this file.

Functions

Profiler::ProgressCallback getGNUPlotCallback (IO::GNUPlotHelper &plotter, const std::string &field)
 Creates a progress callback function to plot the progress property field live using GNUPlot. More...
 
Profiler::ProgressPropertyAllocator getNumVerticesAllocator ()
 Get a custom progress property function allocator that extracts the planner data from the underlying OMPL motion planner. More...
 
Profiler::ProgressCallbackAllocator getRVIZGraphVisualizationAllocator (IO::RVIZHelperPtr &rviz)
 Get a custom progress callback allocator that allocates a function to visualize the current planning graph of the OMPL planner. More...
 
Profiler::ComputeMetricCallback getGoalDistanceCallback ()
 Get a custom metric that computes the distance to the goal for the best solution the planner found. More...
 
int main (int argc, char **argv)
 

Variables

static const std::string GROUP = "arm_with_torso"
 
static const double TIME = 60.0
 

Function Documentation

◆ getGNUPlotCallback()

Profiler::ProgressCallback getGNUPlotCallback ( IO::GNUPlotHelper plotter,
const std::string field 
)

Creates a progress callback function to plot the progress property field live using GNUPlot.

Definition at line 36 of file fetch_profile.cpp.

37 {
38  return [&, field](const PlannerPtr &planner, //
39  const SceneConstPtr &scene, //
40  const planning_interface::MotionPlanRequest &request, //
41  const PlanData &result) {
42  IO::GNUPlotHelper::TimeSeriesOptions tso; // Plotting options for time series data
43  tso.instance = field;
44  tso.title = "Live Profiling";
45  tso.x.label = "Time (s)";
46  tso.x.min = 0.;
47  tso.x.max = TIME;
48 
49  // Plot all progress collected so far.
50  const auto &points = result.getProgressPropertiesAsPoints("time REAL", field);
51  tso.points.emplace(field, points);
52  plotter.timeseries(tso);
53  };
54 }
void timeseries(const TimeSeriesOptions &options)
Plot timeseries data.
Definition: gnuplot.cpp:80
Detailed statistics and metrics computed from profiling a planner's motion planning.
Definition: benchmarking.h:79
A shared pointer wrapper for robowflex::Planner.
A const shared pointer wrapper for robowflex::Scene.
static const double TIME
moveit_msgs::MotionPlanRequest MotionPlanRequest
double max
Upper axis limit. If NaN, will auto-adjust.
Definition: gnuplot.h:43
double min
Lower axis limit. If NaN, will auto-adjust.
Definition: gnuplot.h:44
std::string title
Title of the plot.
Definition: gnuplot.h:47
Time series plotting options.
Definition: gnuplot.h:61
std::map< std::string, Series > points
Map of names to time series data.
Definition: gnuplot.h:62

◆ getGoalDistanceCallback()

Profiler::ComputeMetricCallback getGoalDistanceCallback ( )

Get a custom metric that computes the distance to the goal for the best solution the planner found.

Definition at line 154 of file fetch_profile.cpp.

155 {
156  return [](const PlannerPtr &planner, //
157  const SceneConstPtr &scene, //
158  const planning_interface::MotionPlanRequest &request, //
159  const PlanData &run) -> PlannerMetric {
160  const auto &ompl_planner = std::dynamic_pointer_cast<const OMPL::OMPLInterfacePlanner>(planner);
161 
162  const auto &pdef = ompl_planner->getLastSimpleSetup()->getProblemDefinition();
163  double distance = pdef->getSolutionDifference();
164 
165  if (distance == -1)
166  {
167  const auto &start = pdef->getStartState(0);
168  const auto &goal = std::dynamic_pointer_cast<ompl::base::GoalRegion>(pdef->getGoal());
169  distance = goal->distanceGoal(start);
170  }
171 
172  return distance;
173  };
174 }
T distance(T... args)
boost::variant< bool, double, int, std::size_t, std::string > PlannerMetric
Variant type of possible values a run metric could be.
Definition: benchmarking.h:33

◆ getNumVerticesAllocator()

Profiler::ProgressPropertyAllocator getNumVerticesAllocator ( )

Get a custom progress property function allocator that extracts the planner data from the underlying OMPL motion planner.

Definition at line 59 of file fetch_profile.cpp.

60 {
61  return [](const PlannerPtr &planner, //
62  const SceneConstPtr &scene, //
64  // Extract OMPL level information
65  const auto &ompl_planner = std::dynamic_pointer_cast<const OMPL::OMPLInterfacePlanner>(planner);
66  const auto &ss = ompl_planner->getLastSimpleSetup();
67  const auto &op = ss->getPlanner();
68 
69  return [op] {
70  ompl::base::PlannerData pd(op->getSpaceInformation());
71  op->getPlannerData(pd);
72 
73  return std::to_string(pd.numVertices());
74  };
75  };
76 }
T to_string(T... args)

◆ getRVIZGraphVisualizationAllocator()

Profiler::ProgressCallbackAllocator getRVIZGraphVisualizationAllocator ( IO::RVIZHelperPtr &  rviz)

Get a custom progress callback allocator that allocates a function to visualize the current planning graph of the OMPL planner.

Definition at line 81 of file fetch_profile.cpp.

82 {
83  return [rviz](const PlannerPtr &planner, //
84  const SceneConstPtr &scene, //
86  // Extract OMPL level information
87  const auto &ompl_planner = std::dynamic_pointer_cast<const OMPL::OMPLInterfacePlanner>(planner);
88  const auto &ss = ompl_planner->getLastSimpleSetup();
89  const auto &op = ss->getPlanner();
90 
91  return [rviz, op](const PlannerPtr &planner, //
92  const SceneConstPtr &scene, //
93  const planning_interface::MotionPlanRequest &request, //
94  const PlanData &result) {
95  const auto &robot = planner->getRobot();
96  const auto &ss = op->getSpaceInformation()->getStateSpace();
97 
98  // Get the planner data
99  ompl::base::PlannerData pd(op->getSpaceInformation());
100  op->getPlannerData(pd);
101 
102  // Compute the pose of the end-effector for all new vertices
103  std::vector<double> reals;
104 
105  RobotPoseVector poses(pd.numVertices());
106  for (std::size_t i = 0; i < pd.numVertices(); ++i)
107  {
108  const auto &pdv = pd.getVertex(i);
109  const auto &state = pdv.getState();
110  ss->copyToReals(reals, state);
111  robot->setGroupState(GROUP, reals);
112 
113  poses[i] = robot->getLinkTF("wrist_roll_link");
114  }
115 
116  // Color map for lines in graph. Vertices have tags used by some planners.
117  const std::vector<Eigen::Vector4d> color_map = {{0, 0, 1, 0.4}, //
118  {0, 1, 0, 0.4}, //
119  {1, 0.37, 0.81, 0.4}};
120 
121  std::vector<Eigen::Vector3d> points; // Points in the line
122  std::vector<Eigen::Vector4d> colors; // Color of the points in the line
123 
124  // Get the points used in the graph
126  for (std::size_t i = 0; i < pd.numVertices(); ++i)
127  {
128  pd.getEdges(i, edges);
129  const auto &src = pd.getVertex(i);
130  for (const auto &edge : edges)
131  {
132  const auto &dst = pd.getVertex(edge);
133 
134  std::size_t si = src.getTag();
135  points.emplace_back(poses[i].translation());
136  colors.emplace_back((si < color_map.size()) ? color_map[si] : color_map[0]);
137 
138  std::size_t di = dst.getTag();
139  points.emplace_back(poses[edge].translation());
140  colors.emplace_back((di < color_map.size()) ? color_map[di] : color_map[0]);
141  }
142  }
143 
144  // Update markers on RViz
145  rviz->removeAllMarkers();
146  rviz->addLineMarker("graph", points, colors, 0.005);
147  rviz->updateMarkers();
148  };
149  };
150 }
T emplace_back(T... args)
static const std::string GROUP
Functions for loading and animating robots in Blender.
T size(T... args)

◆ main()

int main ( int  argc,
char **  argv 
)

Definition at line 176 of file fetch_profile.cpp.

177 {
178  // Startup ROS
179  ROS ros(argc, argv);
180 
181  // Program Arguments
182  bool gnuplot;
183  bool live_plotting;
184  bool custom_progress;
185  bool rviz_enable;
186  double progress_rate;
187  std::string planner_name;
188 
189  po::options_description description;
190  description.add_options() //
191  ("help,h", "Produces this help message") //
192  ("planner,p", po::value<std::string>(&planner_name)->default_value("RRTstar"), //
193  "Which OMPL Planner to use.") //
194  ("rate,r", po::value<double>(&progress_rate)->default_value(0.5), //
195  "Update rate of planner progress property collection in seconds.") //
196  ("gnuplot,g", po::bool_switch(&gnuplot), //
197  "Enables GNUPlot visualization of the best cost path (if a progress property)") //
198  ("liveplot,l", po::bool_switch(&live_plotting), //
199  "Enables live GNUPlot plotting of `best cost` and `num vertices` (if enabled and available).") //
200  ("rviz,v", po::bool_switch(&rviz_enable), //
201  "Enables live visualization of the planning graph through the RViz MarkerArray.") //
202  ("vertices,n", po::bool_switch(&custom_progress), //
203  "Enables the number of vertices in the planning graph with a custom progress property.") //
204  ;
205 
206  po::variables_map vm;
207  po::store(po::parse_command_line(argc, argv, description), vm);
208 
209  if (vm.count("help"))
210  {
211  std::cout << description << std::endl;
212  return false;
213  }
214 
215  po::notify(vm);
216 
217  // Create the default Fetch robot.
218  auto fetch = std::make_shared<FetchRobot>();
219  fetch->initialize(false);
220 
221  // Create the default planner for the Fetch.
222  auto planner = std::make_shared<OMPL::OMPLInterfacePlanner>(fetch);
223 
224  OMPL::Settings settings;
225  settings.simplify_solutions = false;
226 
227  planner->initialize("package://robowflex_resources/fetch/config/ompl_planning.yaml", settings);
228 
229  // Load an example problem of reaching into a box.
230  auto scene = std::make_shared<Scene>(fetch);
231  scene->fromYAMLFile("package://robowflex_library/yaml/fetch_box/scene0001.yaml");
232 
233  // Load the motion planning request and configure for profiling.
234  auto request = std::make_shared<MotionRequestBuilder>(planner, GROUP);
235  request->fromYAMLFile("package://robowflex_library/yaml/fetch_box/request0001.yaml");
236  request->setAllowedPlanningTime(TIME);
237  request->setNumPlanningAttempts(1);
238  request->setConfig(planner_name);
239 
240  scene->getCurrentState() = *request->getStartConfiguration();
241 
242  // Create the profiler. We will add some progress callbacks to plot progress properties while the planner
243  // solves the problem.
244  Profiler profiler;
245 
246  // Example of using plotting with the GNUPlot helper.
248 
249  // Setup RViz
250  auto rviz = std::make_shared<IO::RVIZHelper>(fetch);
251  if (rviz_enable)
252  rviz->updateScene(scene);
253 
254  // Plotting options for time series data to display after planning is complete.
256  tso.title = "Best Cost";
257  tso.x.min = 0.;
258  tso.x.max = TIME;
259 
260  // Add a custom metric
261  profiler.addProgressAllocator("num vertices INTEGER", getNumVerticesAllocator());
262 
263  // Add progress callbacks to plot progress data live while planning.
264  if (live_plotting)
265  {
266  profiler.addProgressCallback(getGNUPlotCallback(gp, "best cost REAL"));
267  profiler.addProgressCallback(getGNUPlotCallback(gp, "num vertices INTEGER"));
268  }
269 
270  // Add a callback to visualize the planning graph in RViz.
271  if (rviz_enable)
273 
274  // Add a custom metric to compute the distance to go to the goal.
275  profiler.addMetricCallback("goal_distance", getGoalDistanceCallback());
276 
277  // Profiler options.
278  Profiler::Options options;
279  options.metrics = Profiler::WAYPOINTS | Profiler::CORRECT | Profiler::LENGTH | Profiler::SMOOTHNESS;
280  options.progress_update_rate = progress_rate;
281 
282  // 5 iterations of profiling the same problem
283  for (std::size_t i = 0; i < 5; ++i)
284  {
285  PlanData result;
286  if (profiler.profilePlan(planner, scene, request->getRequest(), options, result))
287  {
288  if (gnuplot)
289  {
290  tso.points.emplace(log::format("Trial %1%", i + 1), //
291  result.getProgressPropertiesAsPoints("time REAL", "best cost REAL"));
292 
293  // Plot all progress collected so far.
294  gp.timeseries(tso);
295  }
296 
297  if (rviz_enable)
298  rviz->updateTrajectory(*result.trajectory);
299  }
300 
301  RBX_INFO("Press Enter to Continue...");
302  std::cin.ignore();
303  }
304 
305  RBX_INFO("Press Enter to Exit...");
306  std::cin.ignore();
307 
308  return 0;
309 }
Helper class to open a pipe to a GNUPlot instance for live visualization of data.
Definition: gnuplot.h:21
Settings descriptor for settings provided by the default MoveIt! OMPL planning pipeline.
bool simplify_solutions
Whether or not planner should simplify solutions.
std::vector< std::pair< double, double > > getProgressPropertiesAsPoints(const std::string &xprop, const std::string &yprop) const
Retrieves the time series data of a planner progress property for a given X-,Y- pair of progress prop...
TrajectoryPtr trajectory
The resulting trajectory, if available.
Definition: benchmarking.h:87
void addProgressCallbackAllocator(const ProgressCallbackAllocator &allocator)
Add a function that is called in the planner progress property loop.
void addProgressCallback(const ProgressCallback &callback)
Add a function that is called in the planner progress property loop.
void addMetricCallback(const std::string &name, const ComputeMetricCallback &metric)
Add a callback function to compute a metric at the end of planning.
void addProgressAllocator(const std::string &name, const ProgressPropertyAllocator &allocator)
Add a function that allocates a function that returns a planner progress property function.
bool profilePlan(const PlannerPtr &planner, const SceneConstPtr &scene, const planning_interface::MotionPlanRequest &request, const Options &options, PlanData &result) const
Profiling a single plan using a planner.
RAII-pattern for starting up ROS.
Definition: util.h:52
T endl(T... args)
Profiler::ProgressCallbackAllocator getRVIZGraphVisualizationAllocator(IO::RVIZHelperPtr &rviz)
Get a custom progress callback allocator that allocates a function to visualize the current planning ...
Profiler::ComputeMetricCallback getGoalDistanceCallback()
Get a custom metric that computes the distance to the goal for the best solution the planner found.
Profiler::ProgressPropertyAllocator getNumVerticesAllocator()
Get a custom progress property function allocator that extracts the planner data from the underlying ...
Profiler::ProgressCallback getGNUPlotCallback(IO::GNUPlotHelper &plotter, const std::string &field)
Creates a progress callback function to plot the progress property field live using GNUPlot.
#define RBX_INFO(fmt,...)
Output a info logging message.
Definition: log.h:118
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.
Options for profiling.
Definition: benchmarking.h:220
double progress_update_rate
Update rate for progress callbacks.
Definition: benchmarking.h:224
uint32_t metrics
Bitmask of which metrics to compute after planning.
Definition: benchmarking.h:221

Variable Documentation

◆ GROUP

const std::string GROUP = "arm_with_torso"
static

Definition at line 30 of file fetch_profile.cpp.

◆ TIME

const double TIME = 60.0
static

Definition at line 31 of file fetch_profile.cpp.