26 auto ur5 = std::make_shared<UR5Robot>();
32 RBX_INFO(
"RViz Initialized! Press enter to continue (after your RViz is setup)...");
36 auto scene = std::make_shared<Scene>(ur5);
37 scene->fromYAMLFile(
"package://robowflex_library/yaml/test.yml");
40 rviz.updateScene(
scene);
43 auto planner = std::make_shared<OMPL::UR5OMPLPipelinePlanner>(ur5);
44 planner->initialize();
48 request.setStartConfiguration({0.0677, -0.8235, 0.9860, -0.1624, 0.0678, 0.0});
51 pose.translate(Eigen::Vector3d{-0.268, -0.826, 1.313});
52 Eigen::Quaterniond orn{0, 0, 1, 0};
56 request.setGoalRegion(
"ee_link",
"world",
61 rviz.addGoalMarker(
"goal", request);
64 RBX_INFO(
"Scene and Goal displayed! Press enter to plan...");
69 if (res.
error_code_.val != moveit_msgs::MoveItErrorCodes::SUCCESS)
73 rviz.updateTrajectory(res);
75 RBX_INFO(
"Press enter to remove goal and scene.");
78 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::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_