35 auto cob4 = std::make_shared<Cob4Robot>();
43 RBX_INFO(
"RViz Initialized! Press enter to continue (after your RViz is setup)...");
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});
55 auto scene = std::make_shared<Scene>(cob4);
56 scene->fromYAMLFile(
"package://robowflex_library/yaml/test_cob4.yml");
59 rviz.visualizeCurrentState();
60 rviz.updateScene(
scene);
63 auto planner = std::make_shared<OMPL::Cob4OMPLPipelinePlanner>(cob4);
64 planner->initialize();
67 cob4->pointHead({0.6, -0.26, 0.95});
71 request_right_arm.setStartConfiguration(cob4->getScratchState());
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);
78 rviz.addGoalMarker(
"goal", request_right_arm);
79 rviz.addTransformMarker(
"pose_right",
"base_link", goal_pose_right);
82 RBX_INFO(
"Scene and Goal displayed for the right arm! Press enter to plan...");
86 request_right_arm.setConfig(
"RRTConnect");
88 if (res.
error_code_.val != moveit_msgs::MoveItErrorCodes::SUCCESS)
92 rviz.updateTrajectory(res);
96 auto right_arm_trajectory = std::make_shared<Trajectory>(res.
trajectory_);
97 cob4->setGroupState(
RIGHT_ARM, right_arm_trajectory->vectorize().
back());
99 rviz.visualizeCurrentState();
101 RBX_INFO(
"Press enter to continue with the left arm.");
104 cob4->pointHead({0.4, 0.26, 0.79});
108 request_left_arm.setStartConfiguration(cob4->getScratchState());
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);
115 rviz.addGoalMarker(
"goal_left", request_left_arm);
116 rviz.addTransformMarker(
"pose_left",
"base_link", goal_pose_left);
117 rviz.updateMarkers();
119 RBX_INFO(
"Scene and Goal displayed for the left arm! Press enter to plan...");
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)
129 rviz.updateTrajectory(res);
132 auto left_arm_trajectory = std::make_shared<Trajectory>(res.
trajectory_);
133 cob4->setGroupState(
LEFT_ARM, left_arm_trajectory->vectorize().
back());
135 rviz.visualizeCurrentState();
137 RBX_INFO(
"Press enter to remove goal and scene.");
141 rviz.removeMarker(
"goal");
142 rviz.updateMarkers();
RVIZ visualization helper. See Live Visualization with RViz for more information.
Helper class to broadcast transform information on TF and joint states.
A helper class to build motion planning requests for a robowflex::Planner.
RAII-pattern for starting up ROS.
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.
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.
Functions for loading and animating scenes in Blender.
moveit_msgs::MoveItErrorCodes error_code_
robot_trajectory::RobotTrajectoryPtr trajectory_