Robowflex  v0.1
Making MoveIt Easy
cob4_test.cpp
Go to the documentation of this file.
1 /* Author: Juan D. Hernandez */
2 
13 #include <robowflex_library/util.h>
14 
15 using namespace robowflex;
16 
17 /* \file cob4_visualization.cpp
18  * A simple script that demonstrates how to use RViz with Robowflex with the
19  * COB4 robot. See https://kavrakilab.github.io/robowflex/rviz.html for how to
20  * use RViz visualization. Here, the scene, the pose goal, and motion plan
21  * displayed in RViz.
22  */
23 
24 static const std::string LEFT_ARM = "arm_left";
25 static const std::string RIGHT_ARM = "arm_right";
26 
27 int main(int argc, char **argv)
28 {
29  // Startup ROS
30  ROS ros(argc, argv);
31 
32  // Create the default Care-O-Bot4 robot.
33  auto cob4 = std::make_shared<Cob4Robot>();
34  cob4->initialize();
35 
36  // Create an empty scene.
37  auto scene = std::make_shared<Scene>(cob4);
38 
39  // Load kinematics for the COB4 robot.
40  cob4->loadKinematics(RIGHT_ARM);
41  cob4->loadKinematics(LEFT_ARM);
42 
43  // Extend the arms.
44  cob4->setGroupState(RIGHT_ARM, {0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0});
45  cob4->setGroupState(LEFT_ARM, {0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0});
46 
47  // Create the default planner for the COB4.
48  auto planner = std::make_shared<OMPL::Cob4OMPLPipelinePlanner>(cob4);
49  planner->initialize();
50 
51  // Create a motion planning request with a joint position goal for the right arm.
52  MotionRequestBuilder request_right_arm(planner, RIGHT_ARM);
53  request_right_arm.setStartConfiguration(cob4->getScratchState());
54 
55  // Create a motion planning request with a pose goal to fold the right arm.
56  cob4->setGroupState(RIGHT_ARM, {2.69, 1.70, -0.91, 1.50, -2.14, -2.35, 1.06});
57  request_right_arm.setGoalConfiguration(cob4->getScratchState());
58 
59  request_right_arm.setConfig("RRTConnect");
60 
61  // Do motion planning!
62  planning_interface::MotionPlanResponse res = planner->plan(scene, request_right_arm.getRequest());
63  if (res.error_code_.val != moveit_msgs::MoveItErrorCodes::SUCCESS)
64  return 1;
65 
66  // Create a trajectory object for better manipulation.
67  auto right_arm_trajectory = std::make_shared<Trajectory>(res.trajectory_);
68 
69  // Output path to a file for visualization.
70  right_arm_trajectory->toYAMLFile("cob4_right_arm_path.yml");
71 
72  // Create a motion planning request with a joint position goal for the left arm.
73  MotionRequestBuilder request_left_arm(planner, LEFT_ARM);
74  request_left_arm.setStartConfiguration(cob4->getScratchState());
75 
76  // Create a motion planning request with a pose goal to fold the left arm.
77  cob4->setGroupState(LEFT_ARM, {-1.14, -1.50, 0.34, -1.50, 0.43, -1.56, -1.20});
78  request_left_arm.setGoalConfiguration(cob4->getScratchState());
79 
80  request_left_arm.setConfig("RRTConnect");
81 
82  // Do motion planning!
83  res = planner->plan(scene, request_left_arm.getRequest());
84  if (res.error_code_.val != moveit_msgs::MoveItErrorCodes::SUCCESS)
85  return 1;
86 
87  // Create a trajectory object for better manipulation.
88  auto left_arm_trajectory = std::make_shared<Trajectory>(res.trajectory_);
89 
90  // Output path to a file for visualization.
91  left_arm_trajectory->toYAMLFile("cob4_left_arm_path.yml");
92 
93  return 0;
94 }
A helper class to build motion planning requests for a robowflex::Planner.
Definition: builder.h:34
bool setConfig(const std::string &requested_config)
Set the planning configuration to use for the motion planning request. Attempts to match requested_co...
Definition: builder.cpp:114
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 setGoalConfiguration(const std::vector< double > &joints)
Set the goal configuration from a vector joints. All joints are assumed to be specified and in the de...
Definition: builder.cpp:372
RAII-pattern for starting up ROS.
Definition: util.h:52
int main(int argc, char **argv)
Definition: cob4_test.cpp:27
static const std::string LEFT_ARM
Definition: cob4_test.cpp:24
static const std::string RIGHT_ARM
Definition: cob4_test.cpp:25
Main namespace. Contains all library classes and functions.
Definition: scene.cpp:25
Functions for loading and animating scenes in Blender.
moveit_msgs::MoveItErrorCodes error_code_
robot_trajectory::RobotTrajectoryPtr trajectory_