00001
00002 #ifndef MOTION_PLANNING_MSGS_SERVICE_GETMOTIONPLAN_H
00003 #define MOTION_PLANNING_MSGS_SERVICE_GETMOTIONPLAN_H
00004 #include <string>
00005 #include <vector>
00006 #include <ostream>
00007 #include "ros/serialization.h"
00008 #include "ros/builtin_message_traits.h"
00009 #include "ros/message_operations.h"
00010 #include "ros/message.h"
00011 #include "ros/time.h"
00012
00013 #include "ros/service_traits.h"
00014
00015 #include "motion_planning_msgs/MotionPlanRequest.h"
00016
00017
00018 #include "motion_planning_msgs/RobotTrajectory.h"
00019 #include "motion_planning_msgs/RobotState.h"
00020 #include "motion_planning_msgs/ArmNavigationErrorCodes.h"
00021 #include "motion_planning_msgs/ArmNavigationErrorCodes.h"
00022
00023 namespace motion_planning_msgs
00024 {
00025 template <class ContainerAllocator>
00026 struct GetMotionPlanRequest_ : public ros::Message
00027 {
00028 typedef GetMotionPlanRequest_<ContainerAllocator> Type;
00029
00030 GetMotionPlanRequest_()
00031 : motion_plan_request()
00032 {
00033 }
00034
00035 GetMotionPlanRequest_(const ContainerAllocator& _alloc)
00036 : motion_plan_request(_alloc)
00037 {
00038 }
00039
00040 typedef ::motion_planning_msgs::MotionPlanRequest_<ContainerAllocator> _motion_plan_request_type;
00041 ::motion_planning_msgs::MotionPlanRequest_<ContainerAllocator> motion_plan_request;
00042
00043
00044 private:
00045 static const char* __s_getDataType_() { return "motion_planning_msgs/GetMotionPlanRequest"; }
00046 public:
00047 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00048
00049 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00050
00051 private:
00052 static const char* __s_getMD5Sum_() { return "e019cf7ddef76622c851e221d4cf164d"; }
00053 public:
00054 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00055
00056 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00057
00058 private:
00059 static const char* __s_getServerMD5Sum_() { return "dc1bde6dccfb9e1ff4f7ed84e081f964"; }
00060 public:
00061 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); }
00062
00063 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); }
00064
00065 private:
00066 static const char* __s_getMessageDefinition_() { return "\n\
00067 \n\
00068 \n\
00069 MotionPlanRequest motion_plan_request\n\
00070 \n\
00071 \n\
00072 ================================================================================\n\
00073 MSG: motion_planning_msgs/MotionPlanRequest\n\
00074 # This service contains the definition for a request to the motion\n\
00075 # planner and the output it provides\n\
00076 \n\
00077 # Parameters for the workspace that the planner should work inside\n\
00078 motion_planning_msgs/WorkspaceParameters workspace_parameters\n\
00079 \n\
00080 # Starting state updates. If certain joints should be considered\n\
00081 # at positions other than the current ones, these positions should\n\
00082 # be set here\n\
00083 motion_planning_msgs/RobotState start_state\n\
00084 \n\
00085 # The goal state for the model to plan for. The goal is achieved\n\
00086 # if all constraints are satisfied\n\
00087 motion_planning_msgs/Constraints goal_constraints\n\
00088 \n\
00089 # No state at any point along the path in the produced motion plan will violate these constraints\n\
00090 motion_planning_msgs/Constraints path_constraints\n\
00091 \n\
00092 # A specification for regions where contact is \n\
00093 # allowed up to a certain depth\n\
00094 # Any collision within this set of regions with a link \n\
00095 # specified in the message will be allowed if\n\
00096 # it is less than the penetration depth specified in the message\n\
00097 AllowedContactSpecification[] allowed_contacts\n\
00098 \n\
00099 # A set of ordered collision operations, \n\
00100 # these are applied to all links, objects, \n\
00101 # namespaces in the collision space\n\
00102 OrderedCollisionOperations ordered_collision_operations\n\
00103 \n\
00104 # Specifies a set of links and paddings to change from the default\n\
00105 # specified in the yaml file\n\
00106 motion_planning_msgs/LinkPadding[] link_padding\n\
00107 \n\
00108 # The name of the motion planner to use. If no name is specified,\n\
00109 # a default motion planner will be used\n\
00110 string planner_id\n\
00111 \n\
00112 # The name of the group of joints on which this planner is operating\n\
00113 string group_name\n\
00114 \n\
00115 # The number of times this plan is to be computed. Shortest solution\n\
00116 # will be reported.\n\
00117 int32 num_planning_attempts\n\
00118 \n\
00119 # The maximum amount of time the motion planner is allowed to plan for\n\
00120 duration allowed_planning_time\n\
00121 \n\
00122 # An expected path duration (in seconds) along with an expected discretization of the path allows the planner to determine the discretization of the trajectory that it returns\n\
00123 duration expected_path_duration\n\
00124 duration expected_path_dt\n\
00125 \n\
00126 ================================================================================\n\
00127 MSG: motion_planning_msgs/WorkspaceParameters\n\
00128 # This message contains a set of parameters useful in\n\
00129 # setting up the workspace for planning\n\
00130 geometric_shapes_msgs/Shape workspace_region_shape\n\
00131 geometry_msgs/PoseStamped workspace_region_pose\n\
00132 \n\
00133 \n\
00134 ================================================================================\n\
00135 MSG: geometric_shapes_msgs/Shape\n\
00136 byte SPHERE=0\n\
00137 byte BOX=1\n\
00138 byte CYLINDER=2\n\
00139 byte MESH=3\n\
00140 \n\
00141 byte type\n\
00142 \n\
00143 \n\
00144 #### define sphere, box, cylinder ####\n\
00145 # the origin of each shape is considered at the shape's center\n\
00146 \n\
00147 # for sphere\n\
00148 # radius := dimensions[0]\n\
00149 \n\
00150 # for cylinder\n\
00151 # radius := dimensions[0]\n\
00152 # length := dimensions[1]\n\
00153 # the length is along the Z axis\n\
00154 \n\
00155 # for box\n\
00156 # size_x := dimensions[0]\n\
00157 # size_y := dimensions[1]\n\
00158 # size_z := dimensions[2]\n\
00159 float64[] dimensions\n\
00160 \n\
00161 \n\
00162 #### define mesh ####\n\
00163 \n\
00164 # list of triangles; triangle k is defined by tre vertices located\n\
00165 # at indices triangles[3k], triangles[3k+1], triangles[3k+2]\n\
00166 int32[] triangles\n\
00167 geometry_msgs/Point[] vertices\n\
00168 \n\
00169 ================================================================================\n\
00170 MSG: geometry_msgs/Point\n\
00171 # This contains the position of a point in free space\n\
00172 float64 x\n\
00173 float64 y\n\
00174 float64 z\n\
00175 \n\
00176 ================================================================================\n\
00177 MSG: geometry_msgs/PoseStamped\n\
00178 # A Pose with reference coordinate frame and timestamp\n\
00179 Header header\n\
00180 Pose pose\n\
00181 \n\
00182 ================================================================================\n\
00183 MSG: std_msgs/Header\n\
00184 # Standard metadata for higher-level stamped data types.\n\
00185 # This is generally used to communicate timestamped data \n\
00186 # in a particular coordinate frame.\n\
00187 # \n\
00188 # sequence ID: consecutively increasing ID \n\
00189 uint32 seq\n\
00190 #Two-integer timestamp that is expressed as:\n\
00191 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00192 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00193 # time-handling sugar is provided by the client library\n\
00194 time stamp\n\
00195 #Frame this data is associated with\n\
00196 # 0: no frame\n\
00197 # 1: global frame\n\
00198 string frame_id\n\
00199 \n\
00200 ================================================================================\n\
00201 MSG: geometry_msgs/Pose\n\
00202 # A representation of pose in free space, composed of postion and orientation. \n\
00203 Point position\n\
00204 Quaternion orientation\n\
00205 \n\
00206 ================================================================================\n\
00207 MSG: geometry_msgs/Quaternion\n\
00208 # This represents an orientation in free space in quaternion form.\n\
00209 \n\
00210 float64 x\n\
00211 float64 y\n\
00212 float64 z\n\
00213 float64 w\n\
00214 \n\
00215 ================================================================================\n\
00216 MSG: motion_planning_msgs/RobotState\n\
00217 # This message contains information about the robot state, i.e. the positions of its joints and links\n\
00218 sensor_msgs/JointState joint_state\n\
00219 motion_planning_msgs/MultiDOFJointState multi_dof_joint_state\n\
00220 ================================================================================\n\
00221 MSG: sensor_msgs/JointState\n\
00222 # This is a message that holds data to describe the state of a set of torque controlled joints. \n\
00223 #\n\
00224 # The state of each joint (revolute or prismatic) is defined by:\n\
00225 # * the position of the joint (rad or m),\n\
00226 # * the velocity of the joint (rad/s or m/s) and \n\
00227 # * the effort that is applied in the joint (Nm or N).\n\
00228 #\n\
00229 # Each joint is uniquely identified by its name\n\
00230 # The header specifies the time at which the joint states were recorded. All the joint states\n\
00231 # in one message have to be recorded at the same time.\n\
00232 #\n\
00233 # This message consists of a multiple arrays, one for each part of the joint state. \n\
00234 # The goal is to make each of the fields optional. When e.g. your joints have no\n\
00235 # effort associated with them, you can leave the effort array empty. \n\
00236 #\n\
00237 # All arrays in this message should have the same size, or be empty.\n\
00238 # This is the only way to uniquely associate the joint name with the correct\n\
00239 # states.\n\
00240 \n\
00241 \n\
00242 Header header\n\
00243 \n\
00244 string[] name\n\
00245 float64[] position\n\
00246 float64[] velocity\n\
00247 float64[] effort\n\
00248 \n\
00249 ================================================================================\n\
00250 MSG: motion_planning_msgs/MultiDOFJointState\n\
00251 #A representation of a multi-dof joint state\n\
00252 time stamp\n\
00253 string[] joint_names\n\
00254 string[] frame_ids\n\
00255 string[] child_frame_ids\n\
00256 geometry_msgs/Pose[] poses\n\
00257 \n\
00258 ================================================================================\n\
00259 MSG: motion_planning_msgs/Constraints\n\
00260 # This message contains a list of motion planning constraints.\n\
00261 \n\
00262 motion_planning_msgs/JointConstraint[] joint_constraints\n\
00263 motion_planning_msgs/PositionConstraint[] position_constraints\n\
00264 motion_planning_msgs/OrientationConstraint[] orientation_constraints\n\
00265 motion_planning_msgs/VisibilityConstraint[] visibility_constraints\n\
00266 \n\
00267 ================================================================================\n\
00268 MSG: motion_planning_msgs/JointConstraint\n\
00269 # Constrain the position of a joint to be within a certain bound\n\
00270 string joint_name\n\
00271 \n\
00272 # the bound to be achieved is [position - tolerance_below, position + tolerance_above]\n\
00273 float64 position\n\
00274 float64 tolerance_above\n\
00275 float64 tolerance_below\n\
00276 \n\
00277 # A weighting factor for this constraint\n\
00278 float64 weight\n\
00279 ================================================================================\n\
00280 MSG: motion_planning_msgs/PositionConstraint\n\
00281 # This message contains the definition of a position constraint.\n\
00282 Header header\n\
00283 \n\
00284 # The robot link this constraint refers to\n\
00285 string link_name\n\
00286 \n\
00287 # The offset (in the link frame) for the target point on the link we are planning for\n\
00288 geometry_msgs/Point target_point_offset\n\
00289 \n\
00290 # The nominal/target position for the point we are planning for\n\
00291 geometry_msgs/Point position\n\
00292 \n\
00293 # The shape of the bounded region that constrains the position of the end-effector\n\
00294 # This region is always centered at the position defined above\n\
00295 geometric_shapes_msgs/Shape constraint_region_shape\n\
00296 \n\
00297 # The orientation of the bounded region that constrains the position of the end-effector. \n\
00298 # This allows the specification of non-axis aligned constraints\n\
00299 geometry_msgs/Quaternion constraint_region_orientation\n\
00300 \n\
00301 # Constraint weighting factor - a weight for this constraint\n\
00302 float64 weight\n\
00303 ================================================================================\n\
00304 MSG: motion_planning_msgs/OrientationConstraint\n\
00305 # This message contains the definition of an orientation constraint.\n\
00306 Header header\n\
00307 \n\
00308 # The robot link this constraint refers to\n\
00309 string link_name\n\
00310 \n\
00311 # The type of the constraint\n\
00312 int32 type\n\
00313 int32 LINK_FRAME=0\n\
00314 int32 HEADER_FRAME=1\n\
00315 \n\
00316 # The desired orientation of the robot link specified as a quaternion\n\
00317 geometry_msgs/Quaternion orientation\n\
00318 \n\
00319 # optional RPY error tolerances specified if \n\
00320 float64 absolute_roll_tolerance\n\
00321 float64 absolute_pitch_tolerance\n\
00322 float64 absolute_yaw_tolerance\n\
00323 \n\
00324 # Constraint weighting factor - a weight for this constraint\n\
00325 float64 weight\n\
00326 \n\
00327 ================================================================================\n\
00328 MSG: motion_planning_msgs/VisibilityConstraint\n\
00329 # This message contains the definition of a visibility constraint.\n\
00330 Header header\n\
00331 \n\
00332 # The point stamped target that needs to be kept within view of the sensor\n\
00333 geometry_msgs/PointStamped target\n\
00334 \n\
00335 # The local pose of the frame in which visibility is to be maintained\n\
00336 # The frame id should represent the robot link to which the sensor is attached\n\
00337 # The visual axis of the sensor is assumed to be along the X axis of this frame\n\
00338 geometry_msgs/PoseStamped sensor_pose\n\
00339 \n\
00340 # The deviation (in radians) that will be tolerated\n\
00341 # Constraint error will be measured as the solid angle between the \n\
00342 # X axis of the frame defined above and the vector between the origin \n\
00343 # of the frame defined above and the target location\n\
00344 float64 absolute_tolerance\n\
00345 \n\
00346 \n\
00347 ================================================================================\n\
00348 MSG: geometry_msgs/PointStamped\n\
00349 # This represents a Point with reference coordinate frame and timestamp\n\
00350 Header header\n\
00351 Point point\n\
00352 \n\
00353 ================================================================================\n\
00354 MSG: motion_planning_msgs/AllowedContactSpecification\n\
00355 # The names of the regions\n\
00356 string name\n\
00357 \n\
00358 # The shape of the region in the environment\n\
00359 geometric_shapes_msgs/Shape shape\n\
00360 \n\
00361 # The pose of the space defining the region\n\
00362 geometry_msgs/PoseStamped pose_stamped\n\
00363 \n\
00364 # The set of links that will be allowed to have penetration contact within this region\n\
00365 string[] link_names\n\
00366 \n\
00367 # The maximum penetration depth allowed for every link\n\
00368 float64 penetration_depth\n\
00369 ================================================================================\n\
00370 MSG: motion_planning_msgs/OrderedCollisionOperations\n\
00371 # A set of collision operations that will be performed in the order they are specified\n\
00372 CollisionOperation[] collision_operations\n\
00373 ================================================================================\n\
00374 MSG: motion_planning_msgs/CollisionOperation\n\
00375 # A definition of a collision operation\n\
00376 # E.g. (\"gripper\",COLLISION_SET_ALL,ENABLE) will enable collisions \n\
00377 # between the gripper and all objects in the collision space\n\
00378 \n\
00379 string object1\n\
00380 string object2\n\
00381 string COLLISION_SET_ALL=\"all\"\n\
00382 string COLLISION_SET_OBJECTS=\"objects\"\n\
00383 string COLLISION_SET_ATTACHED_OBJECTS=\"attached\"\n\
00384 \n\
00385 # The penetration distance to which collisions are allowed. This is 0.0 by default.\n\
00386 float64 penetration_distance\n\
00387 \n\
00388 # Flag that determines whether collisions will be enabled or disabled for the pair of objects specified above\n\
00389 int32 operation\n\
00390 int32 DISABLE=0\n\
00391 int32 ENABLE=1\n\
00392 \n\
00393 ================================================================================\n\
00394 MSG: motion_planning_msgs/LinkPadding\n\
00395 #name for the link\n\
00396 string link_name\n\
00397 \n\
00398 # padding to apply to the link\n\
00399 float64 padding\n\
00400 \n\
00401 "; }
00402 public:
00403 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00404
00405 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00406
00407 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00408 {
00409 ros::serialization::OStream stream(write_ptr, 1000000000);
00410 ros::serialization::serialize(stream, motion_plan_request);
00411 return stream.getData();
00412 }
00413
00414 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00415 {
00416 ros::serialization::IStream stream(read_ptr, 1000000000);
00417 ros::serialization::deserialize(stream, motion_plan_request);
00418 return stream.getData();
00419 }
00420
00421 ROS_DEPRECATED virtual uint32_t serializationLength() const
00422 {
00423 uint32_t size = 0;
00424 size += ros::serialization::serializationLength(motion_plan_request);
00425 return size;
00426 }
00427
00428 typedef boost::shared_ptr< ::motion_planning_msgs::GetMotionPlanRequest_<ContainerAllocator> > Ptr;
00429 typedef boost::shared_ptr< ::motion_planning_msgs::GetMotionPlanRequest_<ContainerAllocator> const> ConstPtr;
00430 };
00431 typedef ::motion_planning_msgs::GetMotionPlanRequest_<std::allocator<void> > GetMotionPlanRequest;
00432
00433 typedef boost::shared_ptr< ::motion_planning_msgs::GetMotionPlanRequest> GetMotionPlanRequestPtr;
00434 typedef boost::shared_ptr< ::motion_planning_msgs::GetMotionPlanRequest const> GetMotionPlanRequestConstPtr;
00435
00436
00437 template <class ContainerAllocator>
00438 struct GetMotionPlanResponse_ : public ros::Message
00439 {
00440 typedef GetMotionPlanResponse_<ContainerAllocator> Type;
00441
00442 GetMotionPlanResponse_()
00443 : trajectory()
00444 , robot_state()
00445 , planning_time()
00446 , error_code()
00447 , trajectory_error_codes()
00448 {
00449 }
00450
00451 GetMotionPlanResponse_(const ContainerAllocator& _alloc)
00452 : trajectory(_alloc)
00453 , robot_state(_alloc)
00454 , planning_time()
00455 , error_code(_alloc)
00456 , trajectory_error_codes(_alloc)
00457 {
00458 }
00459
00460 typedef ::motion_planning_msgs::RobotTrajectory_<ContainerAllocator> _trajectory_type;
00461 ::motion_planning_msgs::RobotTrajectory_<ContainerAllocator> trajectory;
00462
00463 typedef ::motion_planning_msgs::RobotState_<ContainerAllocator> _robot_state_type;
00464 ::motion_planning_msgs::RobotState_<ContainerAllocator> robot_state;
00465
00466 typedef ros::Duration _planning_time_type;
00467 ros::Duration planning_time;
00468
00469 typedef ::motion_planning_msgs::ArmNavigationErrorCodes_<ContainerAllocator> _error_code_type;
00470 ::motion_planning_msgs::ArmNavigationErrorCodes_<ContainerAllocator> error_code;
00471
00472 typedef std::vector< ::motion_planning_msgs::ArmNavigationErrorCodes_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::motion_planning_msgs::ArmNavigationErrorCodes_<ContainerAllocator> >::other > _trajectory_error_codes_type;
00473 std::vector< ::motion_planning_msgs::ArmNavigationErrorCodes_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::motion_planning_msgs::ArmNavigationErrorCodes_<ContainerAllocator> >::other > trajectory_error_codes;
00474
00475
00476 ROS_DEPRECATED uint32_t get_trajectory_error_codes_size() const { return (uint32_t)trajectory_error_codes.size(); }
00477 ROS_DEPRECATED void set_trajectory_error_codes_size(uint32_t size) { trajectory_error_codes.resize((size_t)size); }
00478 ROS_DEPRECATED void get_trajectory_error_codes_vec(std::vector< ::motion_planning_msgs::ArmNavigationErrorCodes_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::motion_planning_msgs::ArmNavigationErrorCodes_<ContainerAllocator> >::other > & vec) const { vec = this->trajectory_error_codes; }
00479 ROS_DEPRECATED void set_trajectory_error_codes_vec(const std::vector< ::motion_planning_msgs::ArmNavigationErrorCodes_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::motion_planning_msgs::ArmNavigationErrorCodes_<ContainerAllocator> >::other > & vec) { this->trajectory_error_codes = vec; }
00480 private:
00481 static const char* __s_getDataType_() { return "motion_planning_msgs/GetMotionPlanResponse"; }
00482 public:
00483 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00484
00485 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00486
00487 private:
00488 static const char* __s_getMD5Sum_() { return "644f3b4cf5b71b614298ce1d1a472b61"; }
00489 public:
00490 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00491
00492 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00493
00494 private:
00495 static const char* __s_getServerMD5Sum_() { return "dc1bde6dccfb9e1ff4f7ed84e081f964"; }
00496 public:
00497 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); }
00498
00499 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); }
00500
00501 private:
00502 static const char* __s_getMessageDefinition_() { return "\n\
00503 \n\
00504 motion_planning_msgs/RobotTrajectory trajectory\n\
00505 \n\
00506 \n\
00507 motion_planning_msgs/RobotState robot_state\n\
00508 \n\
00509 \n\
00510 duration planning_time\n\
00511 \n\
00512 \n\
00513 motion_planning_msgs/ArmNavigationErrorCodes error_code\n\
00514 \n\
00515 \n\
00516 motion_planning_msgs/ArmNavigationErrorCodes[] trajectory_error_codes\n\
00517 \n\
00518 \n\
00519 ================================================================================\n\
00520 MSG: motion_planning_msgs/RobotTrajectory\n\
00521 trajectory_msgs/JointTrajectory joint_trajectory\n\
00522 motion_planning_msgs/MultiDOFJointTrajectory multi_dof_joint_trajectory\n\
00523 ================================================================================\n\
00524 MSG: trajectory_msgs/JointTrajectory\n\
00525 Header header\n\
00526 string[] joint_names\n\
00527 JointTrajectoryPoint[] points\n\
00528 ================================================================================\n\
00529 MSG: std_msgs/Header\n\
00530 # Standard metadata for higher-level stamped data types.\n\
00531 # This is generally used to communicate timestamped data \n\
00532 # in a particular coordinate frame.\n\
00533 # \n\
00534 # sequence ID: consecutively increasing ID \n\
00535 uint32 seq\n\
00536 #Two-integer timestamp that is expressed as:\n\
00537 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00538 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00539 # time-handling sugar is provided by the client library\n\
00540 time stamp\n\
00541 #Frame this data is associated with\n\
00542 # 0: no frame\n\
00543 # 1: global frame\n\
00544 string frame_id\n\
00545 \n\
00546 ================================================================================\n\
00547 MSG: trajectory_msgs/JointTrajectoryPoint\n\
00548 float64[] positions\n\
00549 float64[] velocities\n\
00550 float64[] accelerations\n\
00551 duration time_from_start\n\
00552 ================================================================================\n\
00553 MSG: motion_planning_msgs/MultiDOFJointTrajectory\n\
00554 #A representation of a multi-dof joint trajectory\n\
00555 duration stamp\n\
00556 string[] joint_names\n\
00557 string[] frame_ids\n\
00558 string[] child_frame_ids\n\
00559 MultiDOFJointTrajectoryPoint[] points\n\
00560 \n\
00561 ================================================================================\n\
00562 MSG: motion_planning_msgs/MultiDOFJointTrajectoryPoint\n\
00563 geometry_msgs/Pose[] poses\n\
00564 duration time_from_start\n\
00565 ================================================================================\n\
00566 MSG: geometry_msgs/Pose\n\
00567 # A representation of pose in free space, composed of postion and orientation. \n\
00568 Point position\n\
00569 Quaternion orientation\n\
00570 \n\
00571 ================================================================================\n\
00572 MSG: geometry_msgs/Point\n\
00573 # This contains the position of a point in free space\n\
00574 float64 x\n\
00575 float64 y\n\
00576 float64 z\n\
00577 \n\
00578 ================================================================================\n\
00579 MSG: geometry_msgs/Quaternion\n\
00580 # This represents an orientation in free space in quaternion form.\n\
00581 \n\
00582 float64 x\n\
00583 float64 y\n\
00584 float64 z\n\
00585 float64 w\n\
00586 \n\
00587 ================================================================================\n\
00588 MSG: motion_planning_msgs/RobotState\n\
00589 # This message contains information about the robot state, i.e. the positions of its joints and links\n\
00590 sensor_msgs/JointState joint_state\n\
00591 motion_planning_msgs/MultiDOFJointState multi_dof_joint_state\n\
00592 ================================================================================\n\
00593 MSG: sensor_msgs/JointState\n\
00594 # This is a message that holds data to describe the state of a set of torque controlled joints. \n\
00595 #\n\
00596 # The state of each joint (revolute or prismatic) is defined by:\n\
00597 # * the position of the joint (rad or m),\n\
00598 # * the velocity of the joint (rad/s or m/s) and \n\
00599 # * the effort that is applied in the joint (Nm or N).\n\
00600 #\n\
00601 # Each joint is uniquely identified by its name\n\
00602 # The header specifies the time at which the joint states were recorded. All the joint states\n\
00603 # in one message have to be recorded at the same time.\n\
00604 #\n\
00605 # This message consists of a multiple arrays, one for each part of the joint state. \n\
00606 # The goal is to make each of the fields optional. When e.g. your joints have no\n\
00607 # effort associated with them, you can leave the effort array empty. \n\
00608 #\n\
00609 # All arrays in this message should have the same size, or be empty.\n\
00610 # This is the only way to uniquely associate the joint name with the correct\n\
00611 # states.\n\
00612 \n\
00613 \n\
00614 Header header\n\
00615 \n\
00616 string[] name\n\
00617 float64[] position\n\
00618 float64[] velocity\n\
00619 float64[] effort\n\
00620 \n\
00621 ================================================================================\n\
00622 MSG: motion_planning_msgs/MultiDOFJointState\n\
00623 #A representation of a multi-dof joint state\n\
00624 time stamp\n\
00625 string[] joint_names\n\
00626 string[] frame_ids\n\
00627 string[] child_frame_ids\n\
00628 geometry_msgs/Pose[] poses\n\
00629 \n\
00630 ================================================================================\n\
00631 MSG: motion_planning_msgs/ArmNavigationErrorCodes\n\
00632 int32 val\n\
00633 \n\
00634 # overall behavior\n\
00635 int32 PLANNING_FAILED=-1\n\
00636 int32 SUCCESS=1\n\
00637 int32 TIMED_OUT=-2\n\
00638 \n\
00639 # start state errors\n\
00640 int32 START_STATE_IN_COLLISION=-3\n\
00641 int32 START_STATE_VIOLATES_PATH_CONSTRAINTS=-4\n\
00642 \n\
00643 # goal errors\n\
00644 int32 GOAL_IN_COLLISION=-5\n\
00645 int32 GOAL_VIOLATES_PATH_CONSTRAINTS=-6\n\
00646 \n\
00647 # robot state\n\
00648 int32 INVALID_ROBOT_STATE=-7\n\
00649 int32 INCOMPLETE_ROBOT_STATE=-8\n\
00650 \n\
00651 # planning request errors\n\
00652 int32 INVALID_PLANNER_ID=-9\n\
00653 int32 INVALID_NUM_PLANNING_ATTEMPTS=-10\n\
00654 int32 INVALID_ALLOWED_PLANNING_TIME=-11\n\
00655 int32 INVALID_GROUP_NAME=-12\n\
00656 int32 INVALID_GOAL_JOINT_CONSTRAINTS=-13\n\
00657 int32 INVALID_GOAL_POSITION_CONSTRAINTS=-14\n\
00658 int32 INVALID_GOAL_ORIENTATION_CONSTRAINTS=-15\n\
00659 int32 INVALID_PATH_JOINT_CONSTRAINTS=-16\n\
00660 int32 INVALID_PATH_POSITION_CONSTRAINTS=-17\n\
00661 int32 INVALID_PATH_ORIENTATION_CONSTRAINTS=-18\n\
00662 \n\
00663 # state/trajectory monitor errors\n\
00664 int32 INVALID_TRAJECTORY=-19\n\
00665 int32 INVALID_INDEX=-20\n\
00666 int32 JOINT_LIMITS_VIOLATED=-21\n\
00667 int32 PATH_CONSTRAINTS_VIOLATED=-22\n\
00668 int32 COLLISION_CONSTRAINTS_VIOLATED=-23\n\
00669 int32 GOAL_CONSTRAINTS_VIOLATED=-24\n\
00670 int32 JOINTS_NOT_MOVING=-25\n\
00671 int32 TRAJECTORY_CONTROLLER_FAILED=-26\n\
00672 \n\
00673 # system errors\n\
00674 int32 FRAME_TRANSFORM_FAILURE=-27\n\
00675 int32 COLLISION_CHECKING_UNAVAILABLE=-28\n\
00676 int32 ROBOT_STATE_STALE=-29\n\
00677 int32 SENSOR_INFO_STALE=-30\n\
00678 \n\
00679 # kinematics errors\n\
00680 int32 NO_IK_SOLUTION=-31\n\
00681 int32 INVALID_LINK_NAME=-32\n\
00682 int32 IK_LINK_IN_COLLISION=-33\n\
00683 int32 NO_FK_SOLUTION=-34\n\
00684 int32 KINEMATICS_STATE_IN_COLLISION=-35\n\
00685 \n\
00686 # general errors\n\
00687 int32 INVALID_TIMEOUT=-36\n\
00688 \n\
00689 \n\
00690 "; }
00691 public:
00692 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00693
00694 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00695
00696 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00697 {
00698 ros::serialization::OStream stream(write_ptr, 1000000000);
00699 ros::serialization::serialize(stream, trajectory);
00700 ros::serialization::serialize(stream, robot_state);
00701 ros::serialization::serialize(stream, planning_time);
00702 ros::serialization::serialize(stream, error_code);
00703 ros::serialization::serialize(stream, trajectory_error_codes);
00704 return stream.getData();
00705 }
00706
00707 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00708 {
00709 ros::serialization::IStream stream(read_ptr, 1000000000);
00710 ros::serialization::deserialize(stream, trajectory);
00711 ros::serialization::deserialize(stream, robot_state);
00712 ros::serialization::deserialize(stream, planning_time);
00713 ros::serialization::deserialize(stream, error_code);
00714 ros::serialization::deserialize(stream, trajectory_error_codes);
00715 return stream.getData();
00716 }
00717
00718 ROS_DEPRECATED virtual uint32_t serializationLength() const
00719 {
00720 uint32_t size = 0;
00721 size += ros::serialization::serializationLength(trajectory);
00722 size += ros::serialization::serializationLength(robot_state);
00723 size += ros::serialization::serializationLength(planning_time);
00724 size += ros::serialization::serializationLength(error_code);
00725 size += ros::serialization::serializationLength(trajectory_error_codes);
00726 return size;
00727 }
00728
00729 typedef boost::shared_ptr< ::motion_planning_msgs::GetMotionPlanResponse_<ContainerAllocator> > Ptr;
00730 typedef boost::shared_ptr< ::motion_planning_msgs::GetMotionPlanResponse_<ContainerAllocator> const> ConstPtr;
00731 };
00732 typedef ::motion_planning_msgs::GetMotionPlanResponse_<std::allocator<void> > GetMotionPlanResponse;
00733
00734 typedef boost::shared_ptr< ::motion_planning_msgs::GetMotionPlanResponse> GetMotionPlanResponsePtr;
00735 typedef boost::shared_ptr< ::motion_planning_msgs::GetMotionPlanResponse const> GetMotionPlanResponseConstPtr;
00736
00737 struct GetMotionPlan
00738 {
00739
00740 typedef GetMotionPlanRequest Request;
00741 typedef GetMotionPlanResponse Response;
00742 Request request;
00743 Response response;
00744
00745 typedef Request RequestType;
00746 typedef Response ResponseType;
00747 };
00748 }
00749
00750 namespace ros
00751 {
00752 namespace message_traits
00753 {
00754 template<class ContainerAllocator>
00755 struct MD5Sum< ::motion_planning_msgs::GetMotionPlanRequest_<ContainerAllocator> > {
00756 static const char* value()
00757 {
00758 return "e019cf7ddef76622c851e221d4cf164d";
00759 }
00760
00761 static const char* value(const ::motion_planning_msgs::GetMotionPlanRequest_<ContainerAllocator> &) { return value(); }
00762 static const uint64_t static_value1 = 0xe019cf7ddef76622ULL;
00763 static const uint64_t static_value2 = 0xc851e221d4cf164dULL;
00764 };
00765
00766 template<class ContainerAllocator>
00767 struct DataType< ::motion_planning_msgs::GetMotionPlanRequest_<ContainerAllocator> > {
00768 static const char* value()
00769 {
00770 return "motion_planning_msgs/GetMotionPlanRequest";
00771 }
00772
00773 static const char* value(const ::motion_planning_msgs::GetMotionPlanRequest_<ContainerAllocator> &) { return value(); }
00774 };
00775
00776 template<class ContainerAllocator>
00777 struct Definition< ::motion_planning_msgs::GetMotionPlanRequest_<ContainerAllocator> > {
00778 static const char* value()
00779 {
00780 return "\n\
00781 \n\
00782 \n\
00783 MotionPlanRequest motion_plan_request\n\
00784 \n\
00785 \n\
00786 ================================================================================\n\
00787 MSG: motion_planning_msgs/MotionPlanRequest\n\
00788 # This service contains the definition for a request to the motion\n\
00789 # planner and the output it provides\n\
00790 \n\
00791 # Parameters for the workspace that the planner should work inside\n\
00792 motion_planning_msgs/WorkspaceParameters workspace_parameters\n\
00793 \n\
00794 # Starting state updates. If certain joints should be considered\n\
00795 # at positions other than the current ones, these positions should\n\
00796 # be set here\n\
00797 motion_planning_msgs/RobotState start_state\n\
00798 \n\
00799 # The goal state for the model to plan for. The goal is achieved\n\
00800 # if all constraints are satisfied\n\
00801 motion_planning_msgs/Constraints goal_constraints\n\
00802 \n\
00803 # No state at any point along the path in the produced motion plan will violate these constraints\n\
00804 motion_planning_msgs/Constraints path_constraints\n\
00805 \n\
00806 # A specification for regions where contact is \n\
00807 # allowed up to a certain depth\n\
00808 # Any collision within this set of regions with a link \n\
00809 # specified in the message will be allowed if\n\
00810 # it is less than the penetration depth specified in the message\n\
00811 AllowedContactSpecification[] allowed_contacts\n\
00812 \n\
00813 # A set of ordered collision operations, \n\
00814 # these are applied to all links, objects, \n\
00815 # namespaces in the collision space\n\
00816 OrderedCollisionOperations ordered_collision_operations\n\
00817 \n\
00818 # Specifies a set of links and paddings to change from the default\n\
00819 # specified in the yaml file\n\
00820 motion_planning_msgs/LinkPadding[] link_padding\n\
00821 \n\
00822 # The name of the motion planner to use. If no name is specified,\n\
00823 # a default motion planner will be used\n\
00824 string planner_id\n\
00825 \n\
00826 # The name of the group of joints on which this planner is operating\n\
00827 string group_name\n\
00828 \n\
00829 # The number of times this plan is to be computed. Shortest solution\n\
00830 # will be reported.\n\
00831 int32 num_planning_attempts\n\
00832 \n\
00833 # The maximum amount of time the motion planner is allowed to plan for\n\
00834 duration allowed_planning_time\n\
00835 \n\
00836 # An expected path duration (in seconds) along with an expected discretization of the path allows the planner to determine the discretization of the trajectory that it returns\n\
00837 duration expected_path_duration\n\
00838 duration expected_path_dt\n\
00839 \n\
00840 ================================================================================\n\
00841 MSG: motion_planning_msgs/WorkspaceParameters\n\
00842 # This message contains a set of parameters useful in\n\
00843 # setting up the workspace for planning\n\
00844 geometric_shapes_msgs/Shape workspace_region_shape\n\
00845 geometry_msgs/PoseStamped workspace_region_pose\n\
00846 \n\
00847 \n\
00848 ================================================================================\n\
00849 MSG: geometric_shapes_msgs/Shape\n\
00850 byte SPHERE=0\n\
00851 byte BOX=1\n\
00852 byte CYLINDER=2\n\
00853 byte MESH=3\n\
00854 \n\
00855 byte type\n\
00856 \n\
00857 \n\
00858 #### define sphere, box, cylinder ####\n\
00859 # the origin of each shape is considered at the shape's center\n\
00860 \n\
00861 # for sphere\n\
00862 # radius := dimensions[0]\n\
00863 \n\
00864 # for cylinder\n\
00865 # radius := dimensions[0]\n\
00866 # length := dimensions[1]\n\
00867 # the length is along the Z axis\n\
00868 \n\
00869 # for box\n\
00870 # size_x := dimensions[0]\n\
00871 # size_y := dimensions[1]\n\
00872 # size_z := dimensions[2]\n\
00873 float64[] dimensions\n\
00874 \n\
00875 \n\
00876 #### define mesh ####\n\
00877 \n\
00878 # list of triangles; triangle k is defined by tre vertices located\n\
00879 # at indices triangles[3k], triangles[3k+1], triangles[3k+2]\n\
00880 int32[] triangles\n\
00881 geometry_msgs/Point[] vertices\n\
00882 \n\
00883 ================================================================================\n\
00884 MSG: geometry_msgs/Point\n\
00885 # This contains the position of a point in free space\n\
00886 float64 x\n\
00887 float64 y\n\
00888 float64 z\n\
00889 \n\
00890 ================================================================================\n\
00891 MSG: geometry_msgs/PoseStamped\n\
00892 # A Pose with reference coordinate frame and timestamp\n\
00893 Header header\n\
00894 Pose pose\n\
00895 \n\
00896 ================================================================================\n\
00897 MSG: std_msgs/Header\n\
00898 # Standard metadata for higher-level stamped data types.\n\
00899 # This is generally used to communicate timestamped data \n\
00900 # in a particular coordinate frame.\n\
00901 # \n\
00902 # sequence ID: consecutively increasing ID \n\
00903 uint32 seq\n\
00904 #Two-integer timestamp that is expressed as:\n\
00905 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00906 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00907 # time-handling sugar is provided by the client library\n\
00908 time stamp\n\
00909 #Frame this data is associated with\n\
00910 # 0: no frame\n\
00911 # 1: global frame\n\
00912 string frame_id\n\
00913 \n\
00914 ================================================================================\n\
00915 MSG: geometry_msgs/Pose\n\
00916 # A representation of pose in free space, composed of postion and orientation. \n\
00917 Point position\n\
00918 Quaternion orientation\n\
00919 \n\
00920 ================================================================================\n\
00921 MSG: geometry_msgs/Quaternion\n\
00922 # This represents an orientation in free space in quaternion form.\n\
00923 \n\
00924 float64 x\n\
00925 float64 y\n\
00926 float64 z\n\
00927 float64 w\n\
00928 \n\
00929 ================================================================================\n\
00930 MSG: motion_planning_msgs/RobotState\n\
00931 # This message contains information about the robot state, i.e. the positions of its joints and links\n\
00932 sensor_msgs/JointState joint_state\n\
00933 motion_planning_msgs/MultiDOFJointState multi_dof_joint_state\n\
00934 ================================================================================\n\
00935 MSG: sensor_msgs/JointState\n\
00936 # This is a message that holds data to describe the state of a set of torque controlled joints. \n\
00937 #\n\
00938 # The state of each joint (revolute or prismatic) is defined by:\n\
00939 # * the position of the joint (rad or m),\n\
00940 # * the velocity of the joint (rad/s or m/s) and \n\
00941 # * the effort that is applied in the joint (Nm or N).\n\
00942 #\n\
00943 # Each joint is uniquely identified by its name\n\
00944 # The header specifies the time at which the joint states were recorded. All the joint states\n\
00945 # in one message have to be recorded at the same time.\n\
00946 #\n\
00947 # This message consists of a multiple arrays, one for each part of the joint state. \n\
00948 # The goal is to make each of the fields optional. When e.g. your joints have no\n\
00949 # effort associated with them, you can leave the effort array empty. \n\
00950 #\n\
00951 # All arrays in this message should have the same size, or be empty.\n\
00952 # This is the only way to uniquely associate the joint name with the correct\n\
00953 # states.\n\
00954 \n\
00955 \n\
00956 Header header\n\
00957 \n\
00958 string[] name\n\
00959 float64[] position\n\
00960 float64[] velocity\n\
00961 float64[] effort\n\
00962 \n\
00963 ================================================================================\n\
00964 MSG: motion_planning_msgs/MultiDOFJointState\n\
00965 #A representation of a multi-dof joint state\n\
00966 time stamp\n\
00967 string[] joint_names\n\
00968 string[] frame_ids\n\
00969 string[] child_frame_ids\n\
00970 geometry_msgs/Pose[] poses\n\
00971 \n\
00972 ================================================================================\n\
00973 MSG: motion_planning_msgs/Constraints\n\
00974 # This message contains a list of motion planning constraints.\n\
00975 \n\
00976 motion_planning_msgs/JointConstraint[] joint_constraints\n\
00977 motion_planning_msgs/PositionConstraint[] position_constraints\n\
00978 motion_planning_msgs/OrientationConstraint[] orientation_constraints\n\
00979 motion_planning_msgs/VisibilityConstraint[] visibility_constraints\n\
00980 \n\
00981 ================================================================================\n\
00982 MSG: motion_planning_msgs/JointConstraint\n\
00983 # Constrain the position of a joint to be within a certain bound\n\
00984 string joint_name\n\
00985 \n\
00986 # the bound to be achieved is [position - tolerance_below, position + tolerance_above]\n\
00987 float64 position\n\
00988 float64 tolerance_above\n\
00989 float64 tolerance_below\n\
00990 \n\
00991 # A weighting factor for this constraint\n\
00992 float64 weight\n\
00993 ================================================================================\n\
00994 MSG: motion_planning_msgs/PositionConstraint\n\
00995 # This message contains the definition of a position constraint.\n\
00996 Header header\n\
00997 \n\
00998 # The robot link this constraint refers to\n\
00999 string link_name\n\
01000 \n\
01001 # The offset (in the link frame) for the target point on the link we are planning for\n\
01002 geometry_msgs/Point target_point_offset\n\
01003 \n\
01004 # The nominal/target position for the point we are planning for\n\
01005 geometry_msgs/Point position\n\
01006 \n\
01007 # The shape of the bounded region that constrains the position of the end-effector\n\
01008 # This region is always centered at the position defined above\n\
01009 geometric_shapes_msgs/Shape constraint_region_shape\n\
01010 \n\
01011 # The orientation of the bounded region that constrains the position of the end-effector. \n\
01012 # This allows the specification of non-axis aligned constraints\n\
01013 geometry_msgs/Quaternion constraint_region_orientation\n\
01014 \n\
01015 # Constraint weighting factor - a weight for this constraint\n\
01016 float64 weight\n\
01017 ================================================================================\n\
01018 MSG: motion_planning_msgs/OrientationConstraint\n\
01019 # This message contains the definition of an orientation constraint.\n\
01020 Header header\n\
01021 \n\
01022 # The robot link this constraint refers to\n\
01023 string link_name\n\
01024 \n\
01025 # The type of the constraint\n\
01026 int32 type\n\
01027 int32 LINK_FRAME=0\n\
01028 int32 HEADER_FRAME=1\n\
01029 \n\
01030 # The desired orientation of the robot link specified as a quaternion\n\
01031 geometry_msgs/Quaternion orientation\n\
01032 \n\
01033 # optional RPY error tolerances specified if \n\
01034 float64 absolute_roll_tolerance\n\
01035 float64 absolute_pitch_tolerance\n\
01036 float64 absolute_yaw_tolerance\n\
01037 \n\
01038 # Constraint weighting factor - a weight for this constraint\n\
01039 float64 weight\n\
01040 \n\
01041 ================================================================================\n\
01042 MSG: motion_planning_msgs/VisibilityConstraint\n\
01043 # This message contains the definition of a visibility constraint.\n\
01044 Header header\n\
01045 \n\
01046 # The point stamped target that needs to be kept within view of the sensor\n\
01047 geometry_msgs/PointStamped target\n\
01048 \n\
01049 # The local pose of the frame in which visibility is to be maintained\n\
01050 # The frame id should represent the robot link to which the sensor is attached\n\
01051 # The visual axis of the sensor is assumed to be along the X axis of this frame\n\
01052 geometry_msgs/PoseStamped sensor_pose\n\
01053 \n\
01054 # The deviation (in radians) that will be tolerated\n\
01055 # Constraint error will be measured as the solid angle between the \n\
01056 # X axis of the frame defined above and the vector between the origin \n\
01057 # of the frame defined above and the target location\n\
01058 float64 absolute_tolerance\n\
01059 \n\
01060 \n\
01061 ================================================================================\n\
01062 MSG: geometry_msgs/PointStamped\n\
01063 # This represents a Point with reference coordinate frame and timestamp\n\
01064 Header header\n\
01065 Point point\n\
01066 \n\
01067 ================================================================================\n\
01068 MSG: motion_planning_msgs/AllowedContactSpecification\n\
01069 # The names of the regions\n\
01070 string name\n\
01071 \n\
01072 # The shape of the region in the environment\n\
01073 geometric_shapes_msgs/Shape shape\n\
01074 \n\
01075 # The pose of the space defining the region\n\
01076 geometry_msgs/PoseStamped pose_stamped\n\
01077 \n\
01078 # The set of links that will be allowed to have penetration contact within this region\n\
01079 string[] link_names\n\
01080 \n\
01081 # The maximum penetration depth allowed for every link\n\
01082 float64 penetration_depth\n\
01083 ================================================================================\n\
01084 MSG: motion_planning_msgs/OrderedCollisionOperations\n\
01085 # A set of collision operations that will be performed in the order they are specified\n\
01086 CollisionOperation[] collision_operations\n\
01087 ================================================================================\n\
01088 MSG: motion_planning_msgs/CollisionOperation\n\
01089 # A definition of a collision operation\n\
01090 # E.g. (\"gripper\",COLLISION_SET_ALL,ENABLE) will enable collisions \n\
01091 # between the gripper and all objects in the collision space\n\
01092 \n\
01093 string object1\n\
01094 string object2\n\
01095 string COLLISION_SET_ALL=\"all\"\n\
01096 string COLLISION_SET_OBJECTS=\"objects\"\n\
01097 string COLLISION_SET_ATTACHED_OBJECTS=\"attached\"\n\
01098 \n\
01099 # The penetration distance to which collisions are allowed. This is 0.0 by default.\n\
01100 float64 penetration_distance\n\
01101 \n\
01102 # Flag that determines whether collisions will be enabled or disabled for the pair of objects specified above\n\
01103 int32 operation\n\
01104 int32 DISABLE=0\n\
01105 int32 ENABLE=1\n\
01106 \n\
01107 ================================================================================\n\
01108 MSG: motion_planning_msgs/LinkPadding\n\
01109 #name for the link\n\
01110 string link_name\n\
01111 \n\
01112 # padding to apply to the link\n\
01113 float64 padding\n\
01114 \n\
01115 ";
01116 }
01117
01118 static const char* value(const ::motion_planning_msgs::GetMotionPlanRequest_<ContainerAllocator> &) { return value(); }
01119 };
01120
01121 }
01122 }
01123
01124
01125 namespace ros
01126 {
01127 namespace message_traits
01128 {
01129 template<class ContainerAllocator>
01130 struct MD5Sum< ::motion_planning_msgs::GetMotionPlanResponse_<ContainerAllocator> > {
01131 static const char* value()
01132 {
01133 return "644f3b4cf5b71b614298ce1d1a472b61";
01134 }
01135
01136 static const char* value(const ::motion_planning_msgs::GetMotionPlanResponse_<ContainerAllocator> &) { return value(); }
01137 static const uint64_t static_value1 = 0x644f3b4cf5b71b61ULL;
01138 static const uint64_t static_value2 = 0x4298ce1d1a472b61ULL;
01139 };
01140
01141 template<class ContainerAllocator>
01142 struct DataType< ::motion_planning_msgs::GetMotionPlanResponse_<ContainerAllocator> > {
01143 static const char* value()
01144 {
01145 return "motion_planning_msgs/GetMotionPlanResponse";
01146 }
01147
01148 static const char* value(const ::motion_planning_msgs::GetMotionPlanResponse_<ContainerAllocator> &) { return value(); }
01149 };
01150
01151 template<class ContainerAllocator>
01152 struct Definition< ::motion_planning_msgs::GetMotionPlanResponse_<ContainerAllocator> > {
01153 static const char* value()
01154 {
01155 return "\n\
01156 \n\
01157 motion_planning_msgs/RobotTrajectory trajectory\n\
01158 \n\
01159 \n\
01160 motion_planning_msgs/RobotState robot_state\n\
01161 \n\
01162 \n\
01163 duration planning_time\n\
01164 \n\
01165 \n\
01166 motion_planning_msgs/ArmNavigationErrorCodes error_code\n\
01167 \n\
01168 \n\
01169 motion_planning_msgs/ArmNavigationErrorCodes[] trajectory_error_codes\n\
01170 \n\
01171 \n\
01172 ================================================================================\n\
01173 MSG: motion_planning_msgs/RobotTrajectory\n\
01174 trajectory_msgs/JointTrajectory joint_trajectory\n\
01175 motion_planning_msgs/MultiDOFJointTrajectory multi_dof_joint_trajectory\n\
01176 ================================================================================\n\
01177 MSG: trajectory_msgs/JointTrajectory\n\
01178 Header header\n\
01179 string[] joint_names\n\
01180 JointTrajectoryPoint[] points\n\
01181 ================================================================================\n\
01182 MSG: std_msgs/Header\n\
01183 # Standard metadata for higher-level stamped data types.\n\
01184 # This is generally used to communicate timestamped data \n\
01185 # in a particular coordinate frame.\n\
01186 # \n\
01187 # sequence ID: consecutively increasing ID \n\
01188 uint32 seq\n\
01189 #Two-integer timestamp that is expressed as:\n\
01190 # * stamp.secs: seconds (stamp_secs) since epoch\n\
01191 # * stamp.nsecs: nanoseconds since stamp_secs\n\
01192 # time-handling sugar is provided by the client library\n\
01193 time stamp\n\
01194 #Frame this data is associated with\n\
01195 # 0: no frame\n\
01196 # 1: global frame\n\
01197 string frame_id\n\
01198 \n\
01199 ================================================================================\n\
01200 MSG: trajectory_msgs/JointTrajectoryPoint\n\
01201 float64[] positions\n\
01202 float64[] velocities\n\
01203 float64[] accelerations\n\
01204 duration time_from_start\n\
01205 ================================================================================\n\
01206 MSG: motion_planning_msgs/MultiDOFJointTrajectory\n\
01207 #A representation of a multi-dof joint trajectory\n\
01208 duration stamp\n\
01209 string[] joint_names\n\
01210 string[] frame_ids\n\
01211 string[] child_frame_ids\n\
01212 MultiDOFJointTrajectoryPoint[] points\n\
01213 \n\
01214 ================================================================================\n\
01215 MSG: motion_planning_msgs/MultiDOFJointTrajectoryPoint\n\
01216 geometry_msgs/Pose[] poses\n\
01217 duration time_from_start\n\
01218 ================================================================================\n\
01219 MSG: geometry_msgs/Pose\n\
01220 # A representation of pose in free space, composed of postion and orientation. \n\
01221 Point position\n\
01222 Quaternion orientation\n\
01223 \n\
01224 ================================================================================\n\
01225 MSG: geometry_msgs/Point\n\
01226 # This contains the position of a point in free space\n\
01227 float64 x\n\
01228 float64 y\n\
01229 float64 z\n\
01230 \n\
01231 ================================================================================\n\
01232 MSG: geometry_msgs/Quaternion\n\
01233 # This represents an orientation in free space in quaternion form.\n\
01234 \n\
01235 float64 x\n\
01236 float64 y\n\
01237 float64 z\n\
01238 float64 w\n\
01239 \n\
01240 ================================================================================\n\
01241 MSG: motion_planning_msgs/RobotState\n\
01242 # This message contains information about the robot state, i.e. the positions of its joints and links\n\
01243 sensor_msgs/JointState joint_state\n\
01244 motion_planning_msgs/MultiDOFJointState multi_dof_joint_state\n\
01245 ================================================================================\n\
01246 MSG: sensor_msgs/JointState\n\
01247 # This is a message that holds data to describe the state of a set of torque controlled joints. \n\
01248 #\n\
01249 # The state of each joint (revolute or prismatic) is defined by:\n\
01250 # * the position of the joint (rad or m),\n\
01251 # * the velocity of the joint (rad/s or m/s) and \n\
01252 # * the effort that is applied in the joint (Nm or N).\n\
01253 #\n\
01254 # Each joint is uniquely identified by its name\n\
01255 # The header specifies the time at which the joint states were recorded. All the joint states\n\
01256 # in one message have to be recorded at the same time.\n\
01257 #\n\
01258 # This message consists of a multiple arrays, one for each part of the joint state. \n\
01259 # The goal is to make each of the fields optional. When e.g. your joints have no\n\
01260 # effort associated with them, you can leave the effort array empty. \n\
01261 #\n\
01262 # All arrays in this message should have the same size, or be empty.\n\
01263 # This is the only way to uniquely associate the joint name with the correct\n\
01264 # states.\n\
01265 \n\
01266 \n\
01267 Header header\n\
01268 \n\
01269 string[] name\n\
01270 float64[] position\n\
01271 float64[] velocity\n\
01272 float64[] effort\n\
01273 \n\
01274 ================================================================================\n\
01275 MSG: motion_planning_msgs/MultiDOFJointState\n\
01276 #A representation of a multi-dof joint state\n\
01277 time stamp\n\
01278 string[] joint_names\n\
01279 string[] frame_ids\n\
01280 string[] child_frame_ids\n\
01281 geometry_msgs/Pose[] poses\n\
01282 \n\
01283 ================================================================================\n\
01284 MSG: motion_planning_msgs/ArmNavigationErrorCodes\n\
01285 int32 val\n\
01286 \n\
01287 # overall behavior\n\
01288 int32 PLANNING_FAILED=-1\n\
01289 int32 SUCCESS=1\n\
01290 int32 TIMED_OUT=-2\n\
01291 \n\
01292 # start state errors\n\
01293 int32 START_STATE_IN_COLLISION=-3\n\
01294 int32 START_STATE_VIOLATES_PATH_CONSTRAINTS=-4\n\
01295 \n\
01296 # goal errors\n\
01297 int32 GOAL_IN_COLLISION=-5\n\
01298 int32 GOAL_VIOLATES_PATH_CONSTRAINTS=-6\n\
01299 \n\
01300 # robot state\n\
01301 int32 INVALID_ROBOT_STATE=-7\n\
01302 int32 INCOMPLETE_ROBOT_STATE=-8\n\
01303 \n\
01304 # planning request errors\n\
01305 int32 INVALID_PLANNER_ID=-9\n\
01306 int32 INVALID_NUM_PLANNING_ATTEMPTS=-10\n\
01307 int32 INVALID_ALLOWED_PLANNING_TIME=-11\n\
01308 int32 INVALID_GROUP_NAME=-12\n\
01309 int32 INVALID_GOAL_JOINT_CONSTRAINTS=-13\n\
01310 int32 INVALID_GOAL_POSITION_CONSTRAINTS=-14\n\
01311 int32 INVALID_GOAL_ORIENTATION_CONSTRAINTS=-15\n\
01312 int32 INVALID_PATH_JOINT_CONSTRAINTS=-16\n\
01313 int32 INVALID_PATH_POSITION_CONSTRAINTS=-17\n\
01314 int32 INVALID_PATH_ORIENTATION_CONSTRAINTS=-18\n\
01315 \n\
01316 # state/trajectory monitor errors\n\
01317 int32 INVALID_TRAJECTORY=-19\n\
01318 int32 INVALID_INDEX=-20\n\
01319 int32 JOINT_LIMITS_VIOLATED=-21\n\
01320 int32 PATH_CONSTRAINTS_VIOLATED=-22\n\
01321 int32 COLLISION_CONSTRAINTS_VIOLATED=-23\n\
01322 int32 GOAL_CONSTRAINTS_VIOLATED=-24\n\
01323 int32 JOINTS_NOT_MOVING=-25\n\
01324 int32 TRAJECTORY_CONTROLLER_FAILED=-26\n\
01325 \n\
01326 # system errors\n\
01327 int32 FRAME_TRANSFORM_FAILURE=-27\n\
01328 int32 COLLISION_CHECKING_UNAVAILABLE=-28\n\
01329 int32 ROBOT_STATE_STALE=-29\n\
01330 int32 SENSOR_INFO_STALE=-30\n\
01331 \n\
01332 # kinematics errors\n\
01333 int32 NO_IK_SOLUTION=-31\n\
01334 int32 INVALID_LINK_NAME=-32\n\
01335 int32 IK_LINK_IN_COLLISION=-33\n\
01336 int32 NO_FK_SOLUTION=-34\n\
01337 int32 KINEMATICS_STATE_IN_COLLISION=-35\n\
01338 \n\
01339 # general errors\n\
01340 int32 INVALID_TIMEOUT=-36\n\
01341 \n\
01342 \n\
01343 ";
01344 }
01345
01346 static const char* value(const ::motion_planning_msgs::GetMotionPlanResponse_<ContainerAllocator> &) { return value(); }
01347 };
01348
01349 }
01350 }
01351
01352 namespace ros
01353 {
01354 namespace serialization
01355 {
01356
01357 template<class ContainerAllocator> struct Serializer< ::motion_planning_msgs::GetMotionPlanRequest_<ContainerAllocator> >
01358 {
01359 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
01360 {
01361 stream.next(m.motion_plan_request);
01362 }
01363
01364 ROS_DECLARE_ALLINONE_SERIALIZER;
01365 };
01366 }
01367 }
01368
01369
01370 namespace ros
01371 {
01372 namespace serialization
01373 {
01374
01375 template<class ContainerAllocator> struct Serializer< ::motion_planning_msgs::GetMotionPlanResponse_<ContainerAllocator> >
01376 {
01377 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
01378 {
01379 stream.next(m.trajectory);
01380 stream.next(m.robot_state);
01381 stream.next(m.planning_time);
01382 stream.next(m.error_code);
01383 stream.next(m.trajectory_error_codes);
01384 }
01385
01386 ROS_DECLARE_ALLINONE_SERIALIZER;
01387 };
01388 }
01389 }
01390
01391 namespace ros
01392 {
01393 namespace service_traits
01394 {
01395 template<>
01396 struct MD5Sum<motion_planning_msgs::GetMotionPlan> {
01397 static const char* value()
01398 {
01399 return "dc1bde6dccfb9e1ff4f7ed84e081f964";
01400 }
01401
01402 static const char* value(const motion_planning_msgs::GetMotionPlan&) { return value(); }
01403 };
01404
01405 template<>
01406 struct DataType<motion_planning_msgs::GetMotionPlan> {
01407 static const char* value()
01408 {
01409 return "motion_planning_msgs/GetMotionPlan";
01410 }
01411
01412 static const char* value(const motion_planning_msgs::GetMotionPlan&) { return value(); }
01413 };
01414
01415 template<class ContainerAllocator>
01416 struct MD5Sum<motion_planning_msgs::GetMotionPlanRequest_<ContainerAllocator> > {
01417 static const char* value()
01418 {
01419 return "dc1bde6dccfb9e1ff4f7ed84e081f964";
01420 }
01421
01422 static const char* value(const motion_planning_msgs::GetMotionPlanRequest_<ContainerAllocator> &) { return value(); }
01423 };
01424
01425 template<class ContainerAllocator>
01426 struct DataType<motion_planning_msgs::GetMotionPlanRequest_<ContainerAllocator> > {
01427 static const char* value()
01428 {
01429 return "motion_planning_msgs/GetMotionPlan";
01430 }
01431
01432 static const char* value(const motion_planning_msgs::GetMotionPlanRequest_<ContainerAllocator> &) { return value(); }
01433 };
01434
01435 template<class ContainerAllocator>
01436 struct MD5Sum<motion_planning_msgs::GetMotionPlanResponse_<ContainerAllocator> > {
01437 static const char* value()
01438 {
01439 return "dc1bde6dccfb9e1ff4f7ed84e081f964";
01440 }
01441
01442 static const char* value(const motion_planning_msgs::GetMotionPlanResponse_<ContainerAllocator> &) { return value(); }
01443 };
01444
01445 template<class ContainerAllocator>
01446 struct DataType<motion_planning_msgs::GetMotionPlanResponse_<ContainerAllocator> > {
01447 static const char* value()
01448 {
01449 return "motion_planning_msgs/GetMotionPlan";
01450 }
01451
01452 static const char* value(const motion_planning_msgs::GetMotionPlanResponse_<ContainerAllocator> &) { return value(); }
01453 };
01454
01455 }
01456 }
01457
01458 #endif // MOTION_PLANNING_MSGS_SERVICE_GETMOTIONPLAN_H
01459