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

Go to the source code of this file.

Functions

int main (int argc, char **argv)
 

Variables

static const std::string LEFT_ARM = "arm_left"
 
static const std::string RIGHT_ARM = "arm_right"
 
static const std::string LEFT_EE = "arm_left_7_link"
 
static const std::string RIGHT_EE = "arm_right_7_link"
 

Function Documentation

◆ main()

int main ( int  argc,
char **  argv 
)

Definition at line 29 of file cob4_visualization.cpp.

30 {
31  // Startup ROS
32  ROS ros(argc, argv);
33 
34  // Create the default Care-O-Bot4 robot.
35  auto cob4 = std::make_shared<Cob4Robot>();
36  cob4->initialize();
37 
38  // Create an RViz visualization helper. Publishes all topics and parameter under `/robowflex` by default.
39  IO::RVIZHelper rviz(cob4);
40  IO::RobotBroadcaster bc(cob4);
41  bc.start();
42 
43  RBX_INFO("RViz Initialized! Press enter to continue (after your RViz is setup)...");
44  std::cin.get();
45 
46  // Load kinematics for the COB4 robot.
47  cob4->loadKinematics(RIGHT_ARM);
48  cob4->loadKinematics(LEFT_ARM);
49 
50  // Fold the arms.
51  cob4->setGroupState(RIGHT_ARM, {2.69, 1.70, -0.91, 1.50, -2.14, -2.35, 1.06});
52  cob4->setGroupState(LEFT_ARM, {-1.14, -1.50, 0.34, -1.50, 0.43, -1.56, -1.20});
53 
54  // Load a scene from a YAML file.
55  auto scene = std::make_shared<Scene>(cob4);
56  scene->fromYAMLFile("package://robowflex_library/yaml/test_cob4.yml");
57 
58  // Visualize the scene.
59  rviz.visualizeCurrentState();
60  rviz.updateScene(scene);
61 
62  // Create the default planner for the COB4.
63  auto planner = std::make_shared<OMPL::Cob4OMPLPipelinePlanner>(cob4);
64  planner->initialize();
65 
66  // Sets the Cob4's base pose.
67  cob4->pointHead({0.6, -0.26, 0.95});
68 
69  // Create a motion planning request with a joint position goal for the right arm.
70  MotionRequestBuilder request_right_arm(planner, RIGHT_ARM);
71  request_right_arm.setStartConfiguration(cob4->getScratchState());
72 
73  // Create a motion planning request with a pose goal for the right arm.
74  const auto &goal_pose_right = TF::createPoseQ(0.6, -0.26, 0.95, 1.0, 0.0, 0.0, 0.0);
75  request_right_arm.setGoalPose(RIGHT_EE, "base_link", goal_pose_right);
76 
77  // Visualizing the target poses for the right arm.
78  rviz.addGoalMarker("goal", request_right_arm);
79  rviz.addTransformMarker("pose_right", "base_link", goal_pose_right);
80  rviz.updateMarkers();
81 
82  RBX_INFO("Scene and Goal displayed for the right arm! Press enter to plan...");
83  std::cin.get();
84 
85  // Do motion planning!
86  request_right_arm.setConfig("RRTConnect");
87  planning_interface::MotionPlanResponse res = planner->plan(scene, request_right_arm.getRequest());
88  if (res.error_code_.val != moveit_msgs::MoveItErrorCodes::SUCCESS)
89  return 1;
90 
91  // Publish the trajectory to a topic to display in RViz
92  rviz.updateTrajectory(res);
93 
94  // Visualize resulting state.
95  // Create a trajectory object for better manipulation.
96  auto right_arm_trajectory = std::make_shared<Trajectory>(res.trajectory_);
97  cob4->setGroupState(RIGHT_ARM, right_arm_trajectory->vectorize().back());
98 
99  rviz.visualizeCurrentState();
100 
101  RBX_INFO("Press enter to continue with the left arm.");
102 
103  // Sets the Cob4's base pose.
104  cob4->pointHead({0.4, 0.26, 0.79});
105 
106  // Create a motion planning request with a joint position goal for the right arm.
107  MotionRequestBuilder request_left_arm(planner, LEFT_ARM);
108  request_left_arm.setStartConfiguration(cob4->getScratchState());
109 
110  // Create a motion planning request with a pose goal for the left arm.
111  const auto &goal_pose_left = TF::createPoseQ(0.38, 0.26, 0.76, 0.0, 0.707, 0.0, 0.707);
112  request_left_arm.setGoalPose(LEFT_EE, "base_link", goal_pose_left);
113 
114  // Visualizing the target poses for the left arm.
115  rviz.addGoalMarker("goal_left", request_left_arm);
116  rviz.addTransformMarker("pose_left", "base_link", goal_pose_left);
117  rviz.updateMarkers();
118 
119  RBX_INFO("Scene and Goal displayed for the left arm! Press enter to plan...");
120  std::cin.get();
121 
122  // Do motion planning!
123  request_left_arm.setConfig("RRTConnect");
124  res = planner->plan(scene, request_left_arm.getRequest());
125  if (res.error_code_.val != moveit_msgs::MoveItErrorCodes::SUCCESS)
126  return 1;
127 
128  // Publish the trajectory to a topic to display in RViz
129  rviz.updateTrajectory(res);
130 
131  // Visualize resulting state.
132  auto left_arm_trajectory = std::make_shared<Trajectory>(res.trajectory_);
133  cob4->setGroupState(LEFT_ARM, left_arm_trajectory->vectorize().back());
134 
135  rviz.visualizeCurrentState();
136 
137  RBX_INFO("Press enter to remove goal and scene.");
138  std::cin.get();
139 
140  // Clean up RViz.
141  rviz.removeMarker("goal");
142  rviz.updateMarkers();
143  rviz.removeScene();
144 
145  RBX_INFO("Press enter to exit.");
146  std::cin.get();
147 
148  return 0;
149 }
T back(T... args)
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 LEFT_EE
static const std::string LEFT_ARM
static const std::string RIGHT_EE
static const std::string RIGHT_ARM
#define RBX_INFO(fmt,...)
Output a info logging message.
Definition: log.h:118
RobotPose createPoseQ(double x, double y, double z, double W, double X, double Y, double Z)
Creates a robot pose from a linear component and a Quaternion.
Definition: tf.cpp:47
Functions for loading and animating scenes in Blender.
moveit_msgs::MoveItErrorCodes error_code_
robot_trajectory::RobotTrajectoryPtr trajectory_

Variable Documentation

◆ LEFT_ARM

const std::string LEFT_ARM = "arm_left"
static

Definition at line 24 of file cob4_visualization.cpp.

◆ LEFT_EE

const std::string LEFT_EE = "arm_left_7_link"
static

Definition at line 26 of file cob4_visualization.cpp.

◆ RIGHT_ARM

const std::string RIGHT_ARM = "arm_right"
static

Definition at line 25 of file cob4_visualization.cpp.

◆ RIGHT_EE

const std::string RIGHT_EE = "arm_right_7_link"
static

Definition at line 27 of file cob4_visualization.cpp.