00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034 #ifndef MOTION_PLANNING_CONVERT_MESSAGES_
00035 #define MOTION_PLANNING_CONVERT_MESSAGES_
00036
00037 #include <ros/ros.h>
00038 #include <tf/tf.h>
00039
00040 #include <motion_planning_msgs/RobotTrajectory.h>
00041 #include <motion_planning_msgs/RobotState.h>
00042
00043 #include <motion_planning_msgs/JointConstraint.h>
00044 #include <trajectory_msgs/JointTrajectory.h>
00045 #include <motion_planning_msgs/JointPath.h>
00046 #include <sensor_msgs/JointState.h>
00047
00048 #include <motion_planning_msgs/OrientationConstraint.h>
00049 #include <motion_planning_msgs/SimplePoseConstraint.h>
00050 #include <motion_planning_msgs/PositionConstraint.h>
00051 #include <motion_planning_msgs/ArmNavigationErrorCodes.h>
00052 #include <motion_planning_msgs/GetMotionPlan.h>
00053
00054 namespace motion_planning_msgs
00055 {
00056
00062 inline trajectory_msgs::JointTrajectory jointPathToJointTrajectory(const motion_planning_msgs::JointPath &path)
00063 {
00064 trajectory_msgs::JointTrajectory trajectory;
00065 trajectory.header = path.header;
00066 trajectory.joint_names = path.joint_names;
00067 trajectory.points.resize(path.points.size());
00068 for(unsigned int i=0; i< path.points.size(); i++)
00069 trajectory.points[i].positions = path.points[i].positions;
00070 return trajectory;
00071 }
00072
00078 inline motion_planning_msgs::JointPath jointTrajectoryToJointPath(const trajectory_msgs::JointTrajectory &trajectory)
00079 {
00080 motion_planning_msgs::JointPath path;
00081 path.header = trajectory.header;
00082 path.joint_names = trajectory.joint_names;
00083 path.points.resize(trajectory.points.size());
00084 for(unsigned int i=0; i< trajectory.points.size(); i++)
00085 path.points[i].positions = trajectory.points[i].positions;
00086 return path;
00087 }
00088
00094 inline motion_planning_msgs::JointPathPoint jointStateToJointPathPoint(const sensor_msgs::JointState &state)
00095 {
00096 motion_planning_msgs::JointPathPoint point;
00097 point.positions = state.position;
00098 return point;
00099 }
00100
00106 inline trajectory_msgs::JointTrajectoryPoint jointStateToJointTrajectoryPoint(const sensor_msgs::JointState &state)
00107 {
00108 trajectory_msgs::JointTrajectoryPoint point;
00109 point.positions = state.position;
00110 return point;
00111 }
00112
00118 inline motion_planning_msgs::MultiDOFJointTrajectoryPoint multiDOFJointStateToMultiDOFJointTrajectoryPoint(const motion_planning_msgs::MultiDOFJointState &state)
00119 {
00120 motion_planning_msgs::MultiDOFJointTrajectoryPoint point;
00121 point.poses = state.poses;
00122 point.time_from_start = ros::Duration(0.0);
00123 return point;
00124 }
00125
00131 inline void robotStateToRobotTrajectoryPoint(const motion_planning_msgs::RobotState &state,
00132 trajectory_msgs::JointTrajectoryPoint &point,
00133 motion_planning_msgs::MultiDOFJointTrajectoryPoint &multi_dof_point)
00134 {
00135 point = jointStateToJointTrajectoryPoint(state.joint_state);
00136 multi_dof_point = multiDOFJointStateToMultiDOFJointTrajectoryPoint(state.multi_dof_joint_state);
00137 return;
00138 }
00139
00145 inline sensor_msgs::JointState jointConstraintsToJointState(const std::vector<motion_planning_msgs::JointConstraint> &constraints)
00146 {
00147 sensor_msgs::JointState state;
00148 state.name.resize(constraints.size());
00149 state.position.resize(constraints.size());
00150 for(unsigned int i=0; i < constraints.size(); i++)
00151 {
00152 state.name[i] = constraints[i].joint_name;
00153 state.position[i] = constraints[i].position;
00154 }
00155 return state;
00156 }
00157
00163 inline motion_planning_msgs::JointPath jointConstraintsToJointPath(const std::vector<motion_planning_msgs::JointConstraint> &constraints)
00164 {
00165 motion_planning_msgs::JointPath path;
00166 if(constraints.empty())
00167 return path;
00168 sensor_msgs::JointState state = jointConstraintsToJointState(constraints);
00169 motion_planning_msgs::JointPathPoint point = jointStateToJointPathPoint(state);
00170
00171 path.points.push_back(point);
00172 path.joint_names = state.name;
00173 return path;
00174 }
00175
00181 inline trajectory_msgs::JointTrajectory jointConstraintsToJointTrajectory(const std::vector<motion_planning_msgs::JointConstraint> &constraints)
00182 {
00183 trajectory_msgs::JointTrajectory path;
00184 if(constraints.empty())
00185 return path;
00186 sensor_msgs::JointState state = jointConstraintsToJointState(constraints);
00187 trajectory_msgs::JointTrajectoryPoint point = jointStateToJointTrajectoryPoint(state);
00188
00189 path.points.push_back(point);
00190 path.joint_names = state.name;
00191 return path;
00192 }
00193
00200 inline geometry_msgs::PoseStamped poseConstraintsToPoseStamped(const motion_planning_msgs::PositionConstraint &position_constraint, const motion_planning_msgs::OrientationConstraint &orientation_constraint)
00201 {
00202 geometry_msgs::PoseStamped pose_stamped;
00203 btQuaternion tmp_quat;
00204 pose_stamped.header = position_constraint.header;
00205 pose_stamped.pose.position = position_constraint.position;
00206
00207
00208 pose_stamped.pose.orientation = orientation_constraint.orientation;
00209 return pose_stamped;
00210 }
00211
00218 inline sensor_msgs::JointState createJointState(std::vector<std::string> joint_names, std::vector<double> joint_values)
00219 {
00220 sensor_msgs::JointState state;
00221 state.name = joint_names;
00222 state.position = joint_values;
00223 return state;
00224 }
00225
00232 inline void poseConstraintToPositionOrientationConstraints(const motion_planning_msgs::SimplePoseConstraint &pose_constraint, motion_planning_msgs::PositionConstraint &position_constraint, motion_planning_msgs::OrientationConstraint &orientation_constraint)
00233 {
00234 position_constraint.header = pose_constraint.header;
00235 position_constraint.link_name = pose_constraint.link_name;
00236 position_constraint.position = pose_constraint.pose.position;
00237 position_constraint.constraint_region_shape.type = geometric_shapes_msgs::Shape::BOX;
00238 position_constraint.constraint_region_shape.dimensions.push_back(2*pose_constraint.absolute_position_tolerance.x);
00239 position_constraint.constraint_region_shape.dimensions.push_back(2*pose_constraint.absolute_position_tolerance.y);
00240 position_constraint.constraint_region_shape.dimensions.push_back(2*pose_constraint.absolute_position_tolerance.z);
00241
00242 position_constraint.constraint_region_orientation.x = 0.0;
00243 position_constraint.constraint_region_orientation.y = 0.0;
00244 position_constraint.constraint_region_orientation.z = 0.0;
00245 position_constraint.constraint_region_orientation.w = 1.0;
00246
00247 position_constraint.weight = 1.0;
00248
00249 orientation_constraint.header = pose_constraint.header;
00250 orientation_constraint.link_name = pose_constraint.link_name;
00251 orientation_constraint.orientation = pose_constraint.pose.orientation;
00252 orientation_constraint.type = pose_constraint.orientation_constraint_type;
00253
00254 orientation_constraint.absolute_roll_tolerance = pose_constraint.absolute_roll_tolerance;
00255 orientation_constraint.absolute_pitch_tolerance = pose_constraint.absolute_pitch_tolerance;
00256 orientation_constraint.absolute_yaw_tolerance = pose_constraint.absolute_yaw_tolerance;
00257 orientation_constraint.weight = 1.0;
00258 }
00259
00260
00267 inline void poseStampedToPositionOrientationConstraints(const geometry_msgs::PoseStamped &pose_stamped, const std::string &link_name, motion_planning_msgs::PositionConstraint &position_constraint, motion_planning_msgs::OrientationConstraint &orientation_constraint)
00268 {
00269 position_constraint.header = pose_stamped.header;
00270 position_constraint.link_name = link_name;
00271 position_constraint.position = pose_stamped.pose.position;
00272 position_constraint.weight = 1.0;
00273 position_constraint.constraint_region_shape.type = geometric_shapes_msgs::Shape::BOX;
00274 position_constraint.constraint_region_shape.dimensions.push_back(0.01);
00275 position_constraint.constraint_region_shape.dimensions.push_back(0.01);
00276 position_constraint.constraint_region_shape.dimensions.push_back(0.01);
00277
00278 orientation_constraint.header = pose_stamped.header;
00279 orientation_constraint.link_name = link_name;
00280 orientation_constraint.orientation = pose_stamped.pose.orientation;
00281
00282 orientation_constraint.absolute_roll_tolerance = 0.01;
00283 orientation_constraint.absolute_pitch_tolerance = 0.01;
00284 orientation_constraint.absolute_yaw_tolerance = 0.01;
00285 orientation_constraint.weight = 1.0;
00286 }
00287
00288
00293 inline void printJointState(const sensor_msgs::JointState &joint_state)
00294 {
00295 ROS_INFO("frame_id: %s stamp: %f",joint_state.header.frame_id.c_str(),joint_state.header.stamp.toSec());
00296 if(joint_state.name.size() != joint_state.position.size())
00297 ROS_ERROR("Size of joint_names field: %d does not match size of positions field: %d",(int) joint_state.name.size(),(int) joint_state.position.size());
00298 else
00299 {
00300 for(unsigned int i=0; i< joint_state.name.size(); i++)
00301 {
00302 ROS_INFO("Joint name: %s, position: %f",joint_state.name[i].c_str(),joint_state.position[i]);
00303 }
00304 }
00305 }
00306
00312 inline std::string armNavigationErrorCodeToString(const motion_planning_msgs::ArmNavigationErrorCodes &error_code)
00313 {
00314 std::string result;
00315 if(error_code.val == error_code.PLANNING_FAILED)
00316 result = "Planning failed";
00317 else if(error_code.val == error_code.SUCCESS)
00318 result = "Success";
00319 else if(error_code.val == error_code.TIMED_OUT)
00320 result = "Timed out";
00321 else if (error_code.val == error_code.START_STATE_IN_COLLISION)
00322 result = "Start state in collision";
00323 else if (error_code.val == error_code.START_STATE_VIOLATES_PATH_CONSTRAINTS)
00324 result = "Start state violates path constraints";
00325 else if (error_code.val == error_code.GOAL_IN_COLLISION)
00326 result = "Goal in collision";
00327 else if (error_code.val == error_code.GOAL_VIOLATES_PATH_CONSTRAINTS)
00328 result = "Goal violates path constraints";
00329 else if (error_code.val == error_code.INVALID_ROBOT_STATE)
00330 result = "Initial robot state invalid";
00331 else if (error_code.val == error_code.INCOMPLETE_ROBOT_STATE)
00332 result = "Initial robot state incomplete";
00333 else if (error_code.val == error_code.INVALID_PLANNER_ID)
00334 result = "Invalid planner id";
00335 else if (error_code.val == error_code.INVALID_NUM_PLANNING_ATTEMPTS)
00336 result = "Invalid num planning attempts (must be > 0)";
00337 else if (error_code.val == error_code.INVALID_ALLOWED_PLANNING_TIME)
00338 result = "Invalid allowed planning time (must be > 0)";
00339 else if (error_code.val == error_code.INVALID_GROUP_NAME)
00340 result = "Invalid group name for planning";
00341 else if (error_code.val == error_code.INVALID_GOAL_JOINT_CONSTRAINTS)
00342 result = "Invalid goal joint constraints";
00343 else if (error_code.val == error_code.INVALID_GOAL_POSITION_CONSTRAINTS)
00344 result = "Invalid goal position constraints";
00345 else if (error_code.val == error_code.INVALID_GOAL_ORIENTATION_CONSTRAINTS)
00346 result = "Invalid goal orientation constraints";
00347 else if (error_code.val == error_code.INVALID_PATH_JOINT_CONSTRAINTS)
00348 result = "Invalid path joint constraints";
00349 else if (error_code.val == error_code.INVALID_PATH_POSITION_CONSTRAINTS)
00350 result = "Invalid path position constraints";
00351 else if (error_code.val == error_code.INVALID_PATH_ORIENTATION_CONSTRAINTS)
00352 result = "Invalid path orientation constraints";
00353 else if (error_code.val == error_code.INVALID_TRAJECTORY)
00354 result = "Invalid trajectory";
00355 else if (error_code.val == error_code.INVALID_INDEX)
00356 result = "Invalid index for trajectory check";
00357 else if (error_code.val == error_code.JOINT_LIMITS_VIOLATED)
00358 result = "Joint limits violated";
00359 else if (error_code.val == error_code.PATH_CONSTRAINTS_VIOLATED)
00360 result = "Path constraints violated";
00361 else if (error_code.val == error_code.COLLISION_CONSTRAINTS_VIOLATED)
00362 result = "Collision constraints violated";
00363 else if (error_code.val == error_code.GOAL_CONSTRAINTS_VIOLATED)
00364 result = "Collision constraints violated";
00365 else if (error_code.val == error_code.JOINTS_NOT_MOVING)
00366 result = "Joints not moving - robot may be stuck";
00367 else if (error_code.val == error_code.TRAJECTORY_CONTROLLER_FAILED)
00368 result = "Trajectory controller failed";
00369 else if (error_code.val == error_code.FRAME_TRANSFORM_FAILURE)
00370 result = "Frame transform failed";
00371 else if (error_code.val == error_code.COLLISION_CHECKING_UNAVAILABLE)
00372 result = "Collision checking unavailable";
00373 else if (error_code.val == error_code.ROBOT_STATE_STALE)
00374 result = "Robot state is not being updated";
00375 else if (error_code.val == error_code.SENSOR_INFO_STALE)
00376 result = "Sensor information is not being updated";
00377 else if (error_code.val == error_code.NO_IK_SOLUTION)
00378 result = "Inverse kinematics solution was not found";
00379 else if (error_code.val == error_code.IK_LINK_IN_COLLISION)
00380 result = "Inverse kinematics link was in collision";
00381 else if (error_code.val == error_code.INVALID_LINK_NAME)
00382 result = "Invalid link name";
00383 else if (error_code.val == error_code.NO_FK_SOLUTION)
00384 result = "No forward kinematics solution";
00385 else if (error_code.val == error_code.KINEMATICS_STATE_IN_COLLISION)
00386 result = "Current robot state is in collision";
00387 else if (error_code.val == error_code.INVALID_TIMEOUT)
00388 result = "Time given for planning invalid (must be > 0)";
00389 else
00390 result = "Unknown error code";
00391 return result;
00392 }
00393
00400 inline bool constraintsToPoseStampedVector(const motion_planning_msgs::Constraints &constraints,
00401 std::vector<geometry_msgs::PoseStamped> &poses)
00402 {
00403 if(constraints.position_constraints.size() != constraints.orientation_constraints.size())
00404 {
00405 ROS_ERROR("Number of position constraints does not match number of orientation constraints");
00406 return false;
00407 }
00408 for(unsigned int i =0; i < constraints.position_constraints.size(); i++)
00409 {
00410 geometry_msgs::PoseStamped pose = poseConstraintsToPoseStamped(constraints.position_constraints[i],
00411 constraints.orientation_constraints[i]);
00412 poses.push_back(pose);
00413 }
00414 return true;
00415 }
00416
00417
00424 inline motion_planning_msgs::MultiDOFJointState poseConstraintsToMultiDOFJointState(const std::vector<motion_planning_msgs::PositionConstraint> &position_constraints,
00425 const std::vector<motion_planning_msgs::OrientationConstraint> &orientation_constraints)
00426 {
00427 motion_planning_msgs::MultiDOFJointState multi_dof_joint_state;
00428 if(position_constraints.size() != orientation_constraints.size())
00429 return multi_dof_joint_state;
00430 for(unsigned int i=0; i < position_constraints.size(); i++)
00431 {
00432 if(position_constraints[i].header.frame_id != orientation_constraints[i].header.frame_id)
00433 {
00434 ROS_ERROR("Frame id for position constraint %d does not match frame id for corresponding orientation constraint",i);
00435 return multi_dof_joint_state;
00436 }
00437 if(position_constraints[i].link_name != orientation_constraints[i].link_name)
00438 {
00439 ROS_ERROR("Link name for position constraint %d does not match link name for corresponding orientation constraint",i);
00440 return multi_dof_joint_state;
00441 }
00442 }
00443 return multi_dof_joint_state;
00444 }
00445
00446
00447 }
00448
00449 #endif