25 auto wam7 = std::make_shared<Robot>(
"wam7");
26 wam7->initialize(
"package://barrett_model/robots/wam7_bhand.urdf.xacro",
27 "package://barrett_wam_moveit_config/config/wam7_hand.srdf",
28 "package://barrett_wam_moveit_config/config/joint_limits.yaml",
29 "package://barrett_wam_moveit_config/config/kinematics.yaml"
33 wam7->loadKinematics(
"arm");
36 auto scene = std::make_shared<Scene>(wam7);
37 scene->fromOpenRAVEXMLFile(
"package://optplanners_openrave/scripts/data/envs/wam7_realistic.env.xml");
40 auto planner = std::make_shared<OMPL::OMPLPipelinePlanner>(wam7);
41 planner->initialize(
"package://barrett_wam_moveit_config/config/ompl_planning.yaml"
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});
51 options.
metrics = Profiler::LENGTH;
53 Experiment experiment(
"wam7_demo", options, 5.0, 10);
54 experiment.addQuery(
"ompl",
scene, planner, request);
56 auto dataset = experiment.benchmark(4);
59 json_output.dump(*dataset);
62 traj_output.dump(*dataset);
A helper class for benchmarking that controls running multiple queries.
A benchmark outputter for storing data in a single JSON file.
A shared pointer wrapper for robowflex::MotionRequestBuilder.
A helper class to build motion planning requests for a robowflex::Planner.
RAII-pattern for starting up ROS.
Benchmark outputter that saves each trajectory from each run to a rosbag file.
Functions for loading and animating scenes in Blender.
double progress_update_rate
Update rate for progress callbacks.
uint32_t metrics
Bitmask of which metrics to compute after planning.