31 auto fetch = std::make_shared<FetchRobot>();
38 auto planner = std::make_shared<OMPL::FetchOMPLPipelinePlanner>(
fetch,
"default");
39 planner->initialize();
43 options.
metrics = Profiler::WAYPOINTS | Profiler::CORRECT | Profiler::LENGTH | Profiler::SMOOTHNESS;
50 auto request = std::make_shared<MotionRequestBuilder>(planner,
GROUP);
51 fetch->setGroupState(
GROUP, {0.05, 1.32, 1.40, -0.2, 1.72, 0.0, 1.66, 0.0});
52 request->setStartConfiguration(
fetch->getScratchState());
54 fetch->setGroupState(
GROUP, {0.265, 0.501, 1.281, -2.272, 2.243, -2.774, 0.976, -2.007});
55 request->setGoalConfiguration(
fetch->getScratchState());
57 request->setConfig(
"RRTConnect");
58 experiment.addQuery(
"rrtconnect",
scene, planner, request->getRequest());
60 request->setConfig(
"RRT");
61 experiment.addQuery(
"rrt",
scene, planner, request->getRequest());
63 request->setConfig(
"PRM");
64 experiment.addQuery(
"prm",
scene, planner, request->getRequest());
66 request->setConfig(
"KPIECE");
67 experiment.addQuery(
"kpiece",
scene, planner, request->getRequest());
69 request->setConfig(
"BKPIECE");
70 experiment.addQuery(
"bkpiece",
scene, planner, request->getRequest());
72 request->setConfig(
"LBKPIECE");
73 experiment.addQuery(
"lbkpiece",
scene, planner, request->getRequest());
75 request->setConfig(
"EST");
76 experiment.addQuery(
"est",
scene, planner, request->getRequest());
80 experiment.setPostQueryCallback(
83 auto dataset = experiment.benchmark(4);
86 output.dump(*dataset);
A helper class for benchmarking that controls running multiple queries.
Helper class to plot a real metric as a box plot using GNUPlot from benchmarking data.
Benchmark outputter that saves results into OMPL benchmarking log files. If ompl_benchmark_statistics...
A shared pointer wrapper for robowflex::PlanDataSet.
RAII-pattern for starting up ROS.
static const std::string GROUP
Functions for loading and animating scenes in Blender.
A container structure for all elements needed in a planning query, plus an identifying name.
uint32_t metrics
Bitmask of which metrics to compute after planning.