Robowflex  v0.1
Making MoveIt Easy
ur5_cylinder.cpp File Reference

Go to the source code of this file.

Functions

int main (int argc, char **argv)
 

Function Documentation

◆ main()

int main ( int  argc,
char **  argv 
)

Definition at line 22 of file ur5_cylinder.cpp.

23 {
24  // Startup ROS
25  ROS ros(argc, argv);
26 
27  // Create the default UR5 robot.
28  auto ur5 = std::make_shared<UR5Robot>();
29  ur5->initialize();
30 
31  // Create an RViz visualization helper. Publishes all topics and parameter under `/robowflex` by default.
32  IO::RVIZHelper rviz(ur5);
33 
34  RBX_INFO("RViz Initialized! Press enter to continue (after your RViz is setup)...");
35  std::cin.get();
36 
37  // Create the cylinder we want to grasp
38  RobotPose pose = RobotPose::Identity();
39  pose.translate(Eigen::Vector3d{-0.268, -0.826, 1.313});
40 
41  auto cylinder = Geometry::makeCylinder(0.025, 0.1);
42 
43  // Create an empty scene.
44  auto scene = std::make_shared<Scene>(ur5);
45  scene->updateCollisionObject("cylinder", cylinder, pose);
46 
47  // Visualize the scene.
48  rviz.updateScene(scene);
49 
50  // Create the default planner for the UR5.
51  auto planner = std::make_shared<OMPL::UR5OMPLPipelinePlanner>(ur5);
52  planner->initialize();
53 
54  // Create a motion planning request with a pose goal.
55  MotionRequestBuilder request(planner, "manipulator");
56  request.setStartConfiguration({0.0677, -0.8235, 0.9860, -0.1624, 0.0678, 0.0});
57 
58  request.addCylinderSideGrasp("ee_link", "world", //
59  pose, cylinder, //
60  0.15, 0.04, 16); //
61 
62  rviz.addGoalMarker("goal", request); // Visualize the grasping regions
63  rviz.updateMarkers();
64 
65  RBX_INFO("Scene and Goal displayed! Press enter to plan...");
66  std::cin.get();
67 
68  // Do motion planning!
69  planning_interface::MotionPlanResponse res = planner->plan(scene, request.getRequest());
70  if (res.error_code_.val != moveit_msgs::MoveItErrorCodes::SUCCESS)
71  return 1;
72 
73  // Publish the trajectory to a topic to display in RViz
74  rviz.updateTrajectory(res);
75 
76  RBX_INFO("Press enter to remove goal and scene.");
77  std::cin.get();
78 
79  rviz.removeMarker("goal");
80  rviz.updateMarkers();
81 
82  rviz.removeScene();
83 
84  RBX_INFO("Press enter to exit.");
85  std::cin.get();
86 
87  return 0;
88 }
RVIZ visualization helper. See Live Visualization with RViz for more information.
Definition: visualization.h:38
A helper class to build motion planning requests for a robowflex::Planner.
Definition: builder.h:34
RAII-pattern for starting up ROS.
Definition: util.h:52
#define RBX_INFO(fmt,...)
Output a info logging message.
Definition: log.h:118
std::shared_ptr< dart::dynamics::CylinderShape > makeCylinder(double radius, double height)
Create a cylinder.
Definition: structure.cpp:380
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.
Definition: adapter.h:24
Functions for loading and animating scenes in Blender.
moveit_msgs::MoveItErrorCodes error_code_