Robowflex  v0.1
Making MoveIt Easy
ur5_visualization.cpp
Go to the documentation of this file.
1 /* Author: Zachary Kingston */
2 
10 
11 using namespace robowflex;
12 
13 /* \file ur5_visualization.cpp
14  * A simple script that demonstrates how to use RViz with Robowflex with the
15  * UR5 robot. See https://kavrakilab.github.io/robowflex/rviz.html for how to
16  * use RViz visualization. Here, the scene, the pose goal, and motion plan
17  * displayed in RViz.
18  */
19 
20 int main(int argc, char **argv)
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 }
static GeometryPtr makeSphere(double radius)
Create a sphere.
Definition: geometry.cpp:43
RVIZ visualization helper. See Live Visualization with RViz for more information.
Definition: visualization.h:38
void removeMarker(const std::string &name)
Removes a marker that was added through addMarker().
void updateMarkers()
Displays the managed list of markers. Keeps track of whether markers have already been displayed and ...
void removeScene()
Removes the scene being visualized.
void updateScene(const SceneConstPtr &scene)
Updates the scene being visualized.
void addGoalMarker(const std::string &name, const MotionRequestBuilder &request)
Adds the current goal of the motion request builder as a set of markers in the marker array.
void updateTrajectory(const planning_interface::MotionPlanResponse &response)
Updates the trajectory being visualized.
A helper class to build motion planning requests for a robowflex::Planner.
Definition: builder.h:34
void setStartConfiguration(const std::vector< double > &joints)
Set the start configuration from a vector joints. All joints are assumed to be specified and in the d...
Definition: builder.cpp:189
planning_interface::MotionPlanRequest & getRequest()
Get a reference to the currently built motion planning request.
Definition: builder.cpp:493
void setGoalRegion(const std::string &ee_name, const std::string &base_name, const RobotPose &pose, const GeometryConstPtr &geometry, const Eigen::Quaterniond &orientation, const Eigen::Vector3d &tolerances)
Set a goal region for an end-effector ee_name. Sets the position constraint from geometry at a pose p...
Definition: builder.cpp:403
RAII-pattern for starting up ROS.
Definition: util.h:52
#define RBX_INFO(fmt,...)
Output a info logging message.
Definition: log.h:118
Main namespace. Contains all library classes and functions.
Definition: scene.cpp:25
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_
int main(int argc, char **argv)