26 auto ur5 = std::make_shared<UR5Robot>();
30 auto scene = std::make_shared<Scene>(ur5);
33 auto planner = std::make_shared<OMPL::UR5OMPLPipelinePlanner>(ur5);
34 planner->initialize();
38 joint_request->setStartConfiguration({0.0677, -0.8235, 0.9860, -0.1624, 0.0678, 0.0});
39 joint_request->setGoalConfiguration({-0.39, -0.69, -2.12, 2.82, -0.39, 0});
43 pose_request->setStartConfiguration({0.0677, -0.8235, 0.9860, -0.1624, 0.0678, 0.0});
46 pose.translate(Eigen::Vector3d{-0.268, -0.826, 1.313});
47 Eigen::Quaterniond orn{0, 0, 1, 0};
49 pose_request->setGoalRegion(
"ee_link",
"world",
51 orn, {0.01, 0.01, 0.01}
60 experiment.addQuery(
"joint",
scene, planner, joint_request);
61 experiment.addQuery(
"pose",
scene, planner, pose_request);
63 auto dataset = experiment.benchmark(4);
66 output.dump(*dataset);
A helper class for benchmarking that controls running multiple queries.
A shared pointer wrapper for robowflex::MotionRequestBuilder.
A helper class to build motion planning requests for a robowflex::Planner.
Benchmark outputter that saves results into OMPL benchmarking log files. If ompl_benchmark_statistics...
RAII-pattern for starting up ROS.
std::shared_ptr< dart::dynamics::SphereShape > makeSphere(double radius)
Create a sphere.
std::decay< decltype(std::declval< moveit::core::Transforms >().getTransform("")) >::type RobotPose
A pose (point in SE(3)) used in various functions. Defined from what MoveIt! uses.
Functions for loading and animating scenes in Blender.