28 auto ur5 = std::make_shared<UR5Robot>();
34 RBX_INFO(
"RViz Initialized! Press enter to continue (after your RViz is setup)...");
39 pose.translate(Eigen::Vector3d{-0.268, -0.826, 1.313});
44 auto scene = std::make_shared<Scene>(ur5);
45 scene->updateCollisionObject(
"cylinder", cylinder, pose);
48 rviz.updateScene(
scene);
51 auto planner = std::make_shared<OMPL::UR5OMPLPipelinePlanner>(ur5);
52 planner->initialize();
56 request.setStartConfiguration({0.0677, -0.8235, 0.9860, -0.1624, 0.0678, 0.0});
58 request.addCylinderSideGrasp(
"ee_link",
"world",
62 rviz.addGoalMarker(
"goal", request);
65 RBX_INFO(
"Scene and Goal displayed! Press enter to plan...");
70 if (res.
error_code_.val != moveit_msgs::MoveItErrorCodes::SUCCESS)
74 rviz.updateTrajectory(res);
76 RBX_INFO(
"Press enter to remove goal and scene.");
79 rviz.removeMarker(
"goal");
RVIZ visualization helper. See Live Visualization with RViz for more information.
A helper class to build motion planning requests for a robowflex::Planner.
RAII-pattern for starting up ROS.
#define RBX_INFO(fmt,...)
Output a info logging message.
std::shared_ptr< dart::dynamics::CylinderShape > makeCylinder(double radius, double height)
Create a cylinder.
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_