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

Go to the source code of this file.

Functions

int main (int argc, char **argv)
 

Variables

static const std::string GROUP = "arm_with_torso"
 

Function Documentation

◆ main()

int main ( int  argc,
char **  argv 
)

Definition at line 25 of file fetch_visualization.cpp.

26 {
27  // Startup ROS
28  ROS ros(argc, argv);
29 
30  // Create the default Fetch robot.
31  auto fetch = std::make_shared<FetchRobot>();
32  fetch->initialize();
33 
34  // Create an RViz visualization helper. Publishes all topics and parameter under `/robowflex` by
35  // default.
36  IO::RVIZHelper rviz(fetch);
38  bc.start();
39 
40  RBX_INFO("RViz Initialized! Press enter to continue (after your RViz is setup)...");
41  std::cin.get();
42 
43  // Load a scene from a YAML file.
44  auto scene = std::make_shared<Scene>(fetch);
45  scene->fromYAMLFile("package://robowflex_library/yaml/test_fetch.yml");
46 
47  // Visualize the scene in RViz.
48  rviz.updateScene(scene);
49 
50  // Create the default planner for the UR5.
51  auto planner = std::make_shared<OMPL::FetchOMPLPipelinePlanner>(fetch, "default");
52  planner->initialize();
53 
54  // Create a motion planning request with a pose goal.
55  MotionRequestBuilder request(planner, GROUP);
56  fetch->setGroupState(GROUP, {0.05, 1.32, 1.40, -0.2, 1.72, 0.0, 1.66, 0.0}); // Stow
57  request.setStartConfiguration(fetch->getScratchState());
58 
59  // Create a motion planning request with a pose goal. Cube3
60  RobotPose pose = RobotPose::Identity();
61  pose.translate(Eigen::Vector3d{0.4, 0.6, 0.92});
62 
63  Eigen::Quaterniond orn{0.5, -0.5, 0.5, 0.5};
64 
65  auto region = Geometry::makeSphere(0.01);
66 
67  request.setGoalRegion("wrist_roll_link", "base_link", // links
68  pose, region, // position
69  orn, {0.1, 0.1, 0.1} // orientation
70  );
71 
72  // Display the goal region in RViz.
73  rviz.addGoalMarker("goal", request);
74  rviz.updateMarkers();
75 
76  RBX_INFO("Scene and Goal displayed! Press enter to plan...");
77  std::cin.get();
78 
79  // Do motion planning!
80  planning_interface::MotionPlanResponse res = planner->plan(scene, request.getRequest());
81  if (res.error_code_.val != moveit_msgs::MoveItErrorCodes::SUCCESS)
82  return 1;
83 
84  // Publish the trajectory to a topic to display in RViz.
85  rviz.updateTrajectory(res);
86 
87  // Create a trajectory object for better manipulation.
88  auto trajectory = std::make_shared<Trajectory>(res.trajectory_);
89 
90  // Output path to a file for visualization.
91  trajectory->toYAMLFile("fetch_pick.yml");
92 
93  RBX_INFO("Press enter to remove goal and scene.");
94  std::cin.get();
95 
96  // Clean up RViz.
97  rviz.removeMarker("goal");
98  rviz.updateMarkers();
99  rviz.removeScene();
100 
101  RBX_INFO("Press enter to exit.");
102  std::cin.get();
103 
104  return 0;
105 }
RVIZ visualization helper. See Live Visualization with RViz for more information.
Definition: visualization.h:38
Helper class to broadcast transform information on TF and joint states.
Definition: broadcaster.h:24
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
static const std::string GROUP
#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_
robot_trajectory::RobotTrajectoryPtr trajectory_
robot_trajectory::RobotTrajectory trajectory(rmodel,"right_arm")

Variable Documentation

◆ GROUP

const std::string GROUP = "arm_with_torso"
static

Definition at line 23 of file fetch_visualization.cpp.