Robowflex  v0.1
Making MoveIt Easy
cob4_multi_target.cpp
Go to the documentation of this file.
1 /* Author: Juan D. Hernandez */
2 
3 // Robowflex
12 #include <robowflex_library/util.h>
13 
14 using namespace robowflex;
15 
16 /* \file cob4_multi_target.cpp
17  * A script that demonstrates the multi-target IK query functionality and planning with a cob4 robot. The
18  * robowflex_resouces package needs to be available, see https://github.com/KavrakiLab/robowflex_resources.
19  * You should run RViz and have a RobotState visualization display enabled set to look at
20  * /robowflex/robot_description, and robowflex/state. Also a MarkerArray should be added to visualize the
21  * target IK poses.
22  */
23 
24 static const std::string LEFT_ARM = "arm_left";
25 static const std::string RIGHT_ARM = "arm_right";
26 static const std::string BOTH_ARMS = "both_arms";
27 static const std::string LEFT_EE = "arm_left_7_link";
28 static const std::string RIGHT_EE = "arm_right_7_link";
29 
30 int main(int argc, char **argv)
31 {
32  // Startup ROS
33  ROS ros(argc, argv);
34 
35  // Create the default Care-O-Bot4 robot.
36  auto cob4 = std::make_shared<Cob4Robot>();
37  cob4->initialize();
38 
39  // Load kinematics for the COB4 robot.
40  cob4->loadKinematics(BOTH_ARMS);
41 
42  // Fold the arms.
43  cob4->setGroupState(BOTH_ARMS, {-1.14, -1.50, 0.34, -1.50, 0.43, -1.56, -1.20, 2.69, 1.70, -0.91, 1.50,
44  -2.14, -2.35, 1.06});
45 
46  // Load a scene from a YAML file.
47  auto scene = std::make_shared<Scene>(cob4);
48  scene->fromYAMLFile("package://robowflex_library/yaml/test_cob4.yml");
49 
50  // Visualize the Baxter robot
51  IO::RVIZHelper rviz(cob4);
52  rviz.visualizeCurrentState();
53  rviz.updateScene(scene);
54  RBX_INFO("Care-O-Bot4 with both_arms folded is visualized. Press enter to continue...");
55  std::cin.ignore();
56 
57  // Create the default planner for the COB4.
58  auto planner = std::make_shared<OMPL::Cob4OMPLPipelinePlanner>(cob4);
59  planner->initialize();
60 
61  // Create a motion planning request with a joint position goal for the right arm.
62  MotionRequestBuilder request_both_arms(planner, BOTH_ARMS);
63  request_both_arms.setStartConfiguration(cob4->getScratchState());
64 
65  // Create a motion planning request with a pose goal for both_arms
66  const auto &goal_pose_right = TF::createPoseQ(0.6, -0.26, 0.97, 1.0, 0.0, 0.0, 0.0);
67  const auto &goal_pose_left = TF::createPoseQ(0.38, 0.26, 0.78, 0.0, 0.707, 0.0, 0.707);
68 
69  // Visualizing the target poses.
70  rviz.addTransformMarker("pose_right", "base_link", goal_pose_right);
71  rviz.addTransformMarker("pose_left", "base_link", goal_pose_left);
72  rviz.updateMarkers();
73  RBX_INFO("Target IK poses are visualized. Press enter to continue...");
74  std::cin.ignore();
75 
76  Robot::IKQuery query(BOTH_ARMS, {goal_pose_left, goal_pose_right}, {LEFT_EE, RIGHT_EE});
77  if (not cob4->setFromIK(query))
78  {
79  RBX_ERROR("IK query failed!");
80  return 1;
81  }
82 
83  // Visualize resulting state.
84  rviz.visualizeCurrentState();
85  request_both_arms.setGoalConfiguration(cob4->getScratchState());
86  RBX_INFO("Solution to IK is visualized and set as goal for both_arms! Press enter to plan...");
87  std::cin.ignore();
88 
89  // Do motion planning!
90  request_both_arms.setConfig("RRTConnect");
91  planning_interface::MotionPlanResponse res = planner->plan(scene, request_both_arms.getRequest());
92  if (res.error_code_.val != moveit_msgs::MoveItErrorCodes::SUCCESS)
93  return 1;
94 
95  // Publish the trajectory to a topic to display in RViz
96  rviz.updateTrajectory(res);
97 
98  // Visualize resulting state.
99  auto both_arms_trajectory = std::make_shared<Trajectory>(res.trajectory_);
100  cob4->setGroupState(BOTH_ARMS, both_arms_trajectory->vectorize().back());
101 
102  rviz.visualizeCurrentState();
103 
104  RBX_INFO("Trajectory visualize. Press enter to exit.");
105  std::cin.get();
106 
107  return 0;
108 }
T back(T... args)
RVIZ visualization helper. See Live Visualization with RViz for more information.
Definition: visualization.h:38
void updateMarkers()
Displays the managed list of markers. Keeps track of whether markers have already been displayed and ...
void visualizeCurrentState()
Visualize the current state of the robot.
void updateScene(const SceneConstPtr &scene)
Updates the scene being visualized.
void updateTrajectory(const planning_interface::MotionPlanResponse &response)
Updates the trajectory being visualized.
void addTransformMarker(const std::string &name, const std::string &base_frame, const RobotPose &pose, double scale=1)
Add a transform marker to the managed list of markers. Displayed after an updateMarkers() call.
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)
static const std::string LEFT_EE
static const std::string LEFT_ARM
static const std::string BOTH_ARMS
static const std::string RIGHT_EE
static const std::string RIGHT_ARM
#define RBX_ERROR(fmt,...)
Output a error logging message.
Definition: log.h:102
#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
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_
Robot IK Query options. IK queries in Robowflex consist of: a) A position specified by some geometric...