Robowflex  v0.1
Making MoveIt Easy
ur5_visualization.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 20 of file ur5_visualization.cpp.

21 {
22  // Startup ROS
23  ROS ros(argc, argv);
24 
25  // Create the default UR5 robot.
26  auto ur5 = std::make_shared<UR5Robot>();
27  ur5->initialize();
28 
29  // Create an RViz visualization helper. Publishes all topics and parameter under `/robowflex` by default.
30  IO::RVIZHelper rviz(ur5);
31 
32  RBX_INFO("RViz Initialized! Press enter to continue (after your RViz is setup)...");
33  std::cin.get();
34 
35  // Load a scene from a YAML file.
36  auto scene = std::make_shared<Scene>(ur5);
37  scene->fromYAMLFile("package://robowflex_library/yaml/test.yml");
38 
39  // Visualize the scene.
40  rviz.updateScene(scene);
41 
42  // Create the default planner for the UR5.
43  auto planner = std::make_shared<OMPL::UR5OMPLPipelinePlanner>(ur5);
44  planner->initialize();
45 
46  // Create a motion planning request with a pose goal.
47  MotionRequestBuilder request(planner, "manipulator");
48  request.setStartConfiguration({0.0677, -0.8235, 0.9860, -0.1624, 0.0678, 0.0});
49 
50  RobotPose pose = RobotPose::Identity();
51  pose.translate(Eigen::Vector3d{-0.268, -0.826, 1.313});
52  Eigen::Quaterniond orn{0, 0, 1, 0};
53 
54  auto region = Geometry::makeSphere(0.1);
55 
56  request.setGoalRegion("ee_link", "world", // links
57  pose, region, // position
58  orn, {0.1, 0.1, 0.1} // orientation
59  );
60 
61  rviz.addGoalMarker("goal", request);
62  rviz.updateMarkers();
63 
64  RBX_INFO("Scene and Goal displayed! Press enter to plan...");
65  std::cin.get();
66 
67  // Do motion planning!
68  planning_interface::MotionPlanResponse res = planner->plan(scene, request.getRequest());
69  if (res.error_code_.val != moveit_msgs::MoveItErrorCodes::SUCCESS)
70  return 1;
71 
72  // Publish the trajectory to a topic to display in RViz
73  rviz.updateTrajectory(res);
74 
75  RBX_INFO("Press enter to remove goal and scene.");
76  std::cin.get();
77 
78  rviz.removeMarker("goal");
79  rviz.updateMarkers();
80 
81  rviz.removeScene();
82 
83  RBX_INFO("Press enter to exit.");
84  std::cin.get();
85 
86  return 0;
87 }
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::SphereShape > makeSphere(double radius)
Create a sphere.
Definition: structure.cpp:385
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_