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

Go to the source code of this file.

Functions

int main (int argc, char **argv)
 

Variables

static const std::string GROUP = "arm_with_torso"
 

Function Documentation

◆ main()

int main ( int  argc,
char **  argv 
)

Definition at line 29 of file fetch_scenes_benchmark.cpp.

30 {
31  // Startup ROS
32  ROS ros(argc, argv);
33 
34  // Create the default Fetch robot.
35  auto fetch = std::make_shared<FetchRobot>();
36 
37  // Do not add the virtual joint since the real robot does not have one.
38  fetch->initialize(false);
39 
40  // Setup a benchmarking request for the joint and pose motion plan requests.
41  Profiler::Options options;
42  options.metrics = Profiler::WAYPOINTS | Profiler::CORRECT | Profiler::LENGTH;
43  Experiment experiment("fetch_scenes", options, 10.0, 10);
44 
45  const std::size_t start = 1;
46  const std::size_t end = 10;
47  for (std::size_t i = start; i <= end; i++)
48  {
49  const auto &scene_file =
50  log::format("package://robowflex_library/yaml/fetch_scenes/scene_vicon%1$04d.yaml", i);
51  const auto &request_file =
52  log::format("package://robowflex_library/yaml/fetch_scenes/request%1$04d.yaml", i);
53 
54  // Create an empty Scene.
55  auto scene = std::make_shared<Scene>(fetch);
56  if (not scene->fromYAMLFile(scene_file))
57  {
58  RBX_ERROR("Failed to read file: %s for scene", scene_file);
59  continue;
60  }
61 
62  // Create the default planner for the Fetch.
63  auto planner = std::make_shared<OMPL::FetchOMPLPipelinePlanner>(fetch);
64 
65  // Disable simplification
66  auto settings = OMPL::Settings();
67  settings.simplify_solutions = false;
68 
69  planner->initialize(settings);
70 
71  // Create an empty motion planning request.
72  auto request = std::make_shared<robowflex::MotionRequestBuilder>(planner, GROUP);
73  if (not request->fromYAMLFile(request_file))
74  {
75  RBX_ERROR("Failed to read file: %s for request", request_file);
76  continue;
77  }
78 
79  // Add request
80  experiment.addQuery("vicon", scene, planner, request);
81  }
82 
83  auto dataset = experiment.benchmark(4);
84 
85  OMPLPlanDataSetOutputter output("robowflex");
86  output.dump(*dataset);
87 
88  return 0;
89 }
A helper class for benchmarking that controls running multiple queries.
Definition: benchmarking.h:349
Benchmark outputter that saves results into OMPL benchmarking log files. If ompl_benchmark_statistics...
Definition: benchmarking.h:572
Settings descriptor for settings provided by the default MoveIt! OMPL planning pipeline.
RAII-pattern for starting up ROS.
Definition: util.h:52
T end(T... args)
static const std::string GROUP
#define RBX_ERROR(fmt,...)
Output a error logging message.
Definition: log.h:102
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
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 27 of file fetch_scenes_benchmark.cpp.