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

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 19 of file wam7_benchmark.cpp.

20 {
21  // Startup ROS
22  ROS ros(argc, argv);
23 
24  // Create a WAM7 robot, specifying all necessary files.
25  auto wam7 = std::make_shared<Robot>("wam7");
26  wam7->initialize("package://barrett_model/robots/wam7_bhand.urdf.xacro", // urdf
27  "package://barrett_wam_moveit_config/config/wam7_hand.srdf", // srdf
28  "package://barrett_wam_moveit_config/config/joint_limits.yaml", // joint limits
29  "package://barrett_wam_moveit_config/config/kinematics.yaml" // kinematics
30  );
31 
32  // Load kinematics for the WAM7 arm.
33  wam7->loadKinematics("arm");
34 
35  // Create an empty scene.
36  auto scene = std::make_shared<Scene>(wam7);
37  scene->fromOpenRAVEXMLFile("package://optplanners_openrave/scripts/data/envs/wam7_realistic.env.xml");
38 
39  // Create the default OMPL planner, with the WAM7 planning configuration.
40  auto planner = std::make_shared<OMPL::OMPLPipelinePlanner>(wam7);
41  planner->initialize("package://barrett_wam_moveit_config/config/ompl_planning.yaml" // planner config
42  );
43 
44  // Create a motion planning request with a joint position goal.
45  MotionRequestBuilderPtr request(new MotionRequestBuilder(planner, "arm"));
46  request->setStartConfiguration({0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0});
47  request->setGoalConfiguration({0.0, 1.89, 0.0, -0.3, 1.3, 0.0, 0.2});
48 
49  Profiler::Options options;
50  options.progress_update_rate = 0.1;
51  options.metrics = Profiler::LENGTH;
52 
53  Experiment experiment("wam7_demo", options, 5.0, 10);
54  experiment.addQuery("ompl", scene, planner, request);
55 
56  auto dataset = experiment.benchmark(4);
57 
58  JSONPlanDataSetOutputter json_output("test_log.json");
59  json_output.dump(*dataset);
60 
61  TrajectoryPlanDataSetOutputter traj_output("test_log.bag");
62  traj_output.dump(*dataset);
63 
64  return 0;
65 }
A helper class for benchmarking that controls running multiple queries.
Definition: benchmarking.h:349
A benchmark outputter for storing data in a single JSON file.
Definition: benchmarking.h:523
A shared pointer wrapper for robowflex::MotionRequestBuilder.
A helper class to build motion planning requests for a robowflex::Planner.
Definition: builder.h:34
RAII-pattern for starting up ROS.
Definition: util.h:52
Benchmark outputter that saves each trajectory from each run to a rosbag file.
Definition: benchmarking.h:548
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