24 auto ur5 = std::make_shared<UR5Robot>();
28 auto scene = std::make_shared<Scene>(ur5);
31 auto default_planner = std::make_shared<OMPL::UR5OMPLPipelinePlanner>(ur5,
"default");
32 default_planner->initialize();
35 auto simple_planner = std::make_shared<OMPL::UR5OMPLPipelinePlanner>(ur5,
"simple");
40 simple_planner->initialize(settings);
43 for (
const auto &planner : {default_planner, simple_planner})
47 request.setStartConfiguration({0.0677, -0.8235, 0.9860, -0.1624, 0.0678, 0.0});
50 pose.translate(Eigen::Vector3d{-0.268, -0.826, 1.313});
51 Eigen::Quaterniond orn{0, 0, 1, 0};
53 request.setGoalRegion(
"ee_link",
"world",
55 orn, {0.01, 0.01, 0.01}
60 if (res.
error_code_.val != moveit_msgs::MoveItErrorCodes::SUCCESS)
A helper class to build motion planning requests for a robowflex::Planner.
Settings descriptor for settings provided by the default MoveIt! OMPL planning pipeline.
bool simplify_solutions
Whether or not planner should simplify solutions.
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.
moveit_msgs::MoveItErrorCodes error_code_