00001
00002 #ifndef PLANNING_ENVIRONMENT_MSGS_SERVICE_SETCONSTRAINTS_H
00003 #define PLANNING_ENVIRONMENT_MSGS_SERVICE_SETCONSTRAINTS_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/Constraints.h"
00016 #include "motion_planning_msgs/Constraints.h"
00017
00018
00019 #include "motion_planning_msgs/Constraints.h"
00020 #include "motion_planning_msgs/Constraints.h"
00021 #include "motion_planning_msgs/ArmNavigationErrorCodes.h"
00022
00023 namespace planning_environment_msgs
00024 {
00025 template <class ContainerAllocator>
00026 struct SetConstraintsRequest_ : public ros::Message
00027 {
00028 typedef SetConstraintsRequest_<ContainerAllocator> Type;
00029
00030 SetConstraintsRequest_()
00031 : path_constraints()
00032 , goal_constraints()
00033 {
00034 }
00035
00036 SetConstraintsRequest_(const ContainerAllocator& _alloc)
00037 : path_constraints(_alloc)
00038 , goal_constraints(_alloc)
00039 {
00040 }
00041
00042 typedef ::motion_planning_msgs::Constraints_<ContainerAllocator> _path_constraints_type;
00043 ::motion_planning_msgs::Constraints_<ContainerAllocator> path_constraints;
00044
00045 typedef ::motion_planning_msgs::Constraints_<ContainerAllocator> _goal_constraints_type;
00046 ::motion_planning_msgs::Constraints_<ContainerAllocator> goal_constraints;
00047
00048
00049 private:
00050 static const char* __s_getDataType_() { return "planning_environment_msgs/SetConstraintsRequest"; }
00051 public:
00052 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00053
00054 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00055
00056 private:
00057 static const char* __s_getMD5Sum_() { return "6d13bc5e83c4c2ef090eae3053dfae3a"; }
00058 public:
00059 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00060
00061 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00062
00063 private:
00064 static const char* __s_getServerMD5Sum_() { return "60cfcfae4d588cf6b9a94199b57d97db"; }
00065 public:
00066 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); }
00067
00068 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); }
00069
00070 private:
00071 static const char* __s_getMessageDefinition_() { return "\n\
00072 \n\
00073 \n\
00074 \n\
00075 \n\
00076 \n\
00077 motion_planning_msgs/Constraints path_constraints\n\
00078 motion_planning_msgs/Constraints goal_constraints\n\
00079 \n\
00080 \n\
00081 ================================================================================\n\
00082 MSG: motion_planning_msgs/Constraints\n\
00083 # This message contains a list of motion planning constraints.\n\
00084 \n\
00085 motion_planning_msgs/JointConstraint[] joint_constraints\n\
00086 motion_planning_msgs/PositionConstraint[] position_constraints\n\
00087 motion_planning_msgs/OrientationConstraint[] orientation_constraints\n\
00088 motion_planning_msgs/VisibilityConstraint[] visibility_constraints\n\
00089 \n\
00090 ================================================================================\n\
00091 MSG: motion_planning_msgs/JointConstraint\n\
00092 # Constrain the position of a joint to be within a certain bound\n\
00093 string joint_name\n\
00094 \n\
00095 # the bound to be achieved is [position - tolerance_below, position + tolerance_above]\n\
00096 float64 position\n\
00097 float64 tolerance_above\n\
00098 float64 tolerance_below\n\
00099 \n\
00100 # A weighting factor for this constraint\n\
00101 float64 weight\n\
00102 ================================================================================\n\
00103 MSG: motion_planning_msgs/PositionConstraint\n\
00104 # This message contains the definition of a position constraint.\n\
00105 Header header\n\
00106 \n\
00107 # The robot link this constraint refers to\n\
00108 string link_name\n\
00109 \n\
00110 # The offset (in the link frame) for the target point on the link we are planning for\n\
00111 geometry_msgs/Point target_point_offset\n\
00112 \n\
00113 # The nominal/target position for the point we are planning for\n\
00114 geometry_msgs/Point position\n\
00115 \n\
00116 # The shape of the bounded region that constrains the position of the end-effector\n\
00117 # This region is always centered at the position defined above\n\
00118 geometric_shapes_msgs/Shape constraint_region_shape\n\
00119 \n\
00120 # The orientation of the bounded region that constrains the position of the end-effector. \n\
00121 # This allows the specification of non-axis aligned constraints\n\
00122 geometry_msgs/Quaternion constraint_region_orientation\n\
00123 \n\
00124 # Constraint weighting factor - a weight for this constraint\n\
00125 float64 weight\n\
00126 ================================================================================\n\
00127 MSG: std_msgs/Header\n\
00128 # Standard metadata for higher-level stamped data types.\n\
00129 # This is generally used to communicate timestamped data \n\
00130 # in a particular coordinate frame.\n\
00131 # \n\
00132 # sequence ID: consecutively increasing ID \n\
00133 uint32 seq\n\
00134 #Two-integer timestamp that is expressed as:\n\
00135 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00136 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00137 # time-handling sugar is provided by the client library\n\
00138 time stamp\n\
00139 #Frame this data is associated with\n\
00140 # 0: no frame\n\
00141 # 1: global frame\n\
00142 string frame_id\n\
00143 \n\
00144 ================================================================================\n\
00145 MSG: geometry_msgs/Point\n\
00146 # This contains the position of a point in free space\n\
00147 float64 x\n\
00148 float64 y\n\
00149 float64 z\n\
00150 \n\
00151 ================================================================================\n\
00152 MSG: geometric_shapes_msgs/Shape\n\
00153 byte SPHERE=0\n\
00154 byte BOX=1\n\
00155 byte CYLINDER=2\n\
00156 byte MESH=3\n\
00157 \n\
00158 byte type\n\
00159 \n\
00160 \n\
00161 #### define sphere, box, cylinder ####\n\
00162 # the origin of each shape is considered at the shape's center\n\
00163 \n\
00164 # for sphere\n\
00165 # radius := dimensions[0]\n\
00166 \n\
00167 # for cylinder\n\
00168 # radius := dimensions[0]\n\
00169 # length := dimensions[1]\n\
00170 # the length is along the Z axis\n\
00171 \n\
00172 # for box\n\
00173 # size_x := dimensions[0]\n\
00174 # size_y := dimensions[1]\n\
00175 # size_z := dimensions[2]\n\
00176 float64[] dimensions\n\
00177 \n\
00178 \n\
00179 #### define mesh ####\n\
00180 \n\
00181 # list of triangles; triangle k is defined by tre vertices located\n\
00182 # at indices triangles[3k], triangles[3k+1], triangles[3k+2]\n\
00183 int32[] triangles\n\
00184 geometry_msgs/Point[] vertices\n\
00185 \n\
00186 ================================================================================\n\
00187 MSG: geometry_msgs/Quaternion\n\
00188 # This represents an orientation in free space in quaternion form.\n\
00189 \n\
00190 float64 x\n\
00191 float64 y\n\
00192 float64 z\n\
00193 float64 w\n\
00194 \n\
00195 ================================================================================\n\
00196 MSG: motion_planning_msgs/OrientationConstraint\n\
00197 # This message contains the definition of an orientation constraint.\n\
00198 Header header\n\
00199 \n\
00200 # The robot link this constraint refers to\n\
00201 string link_name\n\
00202 \n\
00203 # The type of the constraint\n\
00204 int32 type\n\
00205 int32 LINK_FRAME=0\n\
00206 int32 HEADER_FRAME=1\n\
00207 \n\
00208 # The desired orientation of the robot link specified as a quaternion\n\
00209 geometry_msgs/Quaternion orientation\n\
00210 \n\
00211 # optional RPY error tolerances specified if \n\
00212 float64 absolute_roll_tolerance\n\
00213 float64 absolute_pitch_tolerance\n\
00214 float64 absolute_yaw_tolerance\n\
00215 \n\
00216 # Constraint weighting factor - a weight for this constraint\n\
00217 float64 weight\n\
00218 \n\
00219 ================================================================================\n\
00220 MSG: motion_planning_msgs/VisibilityConstraint\n\
00221 # This message contains the definition of a visibility constraint.\n\
00222 Header header\n\
00223 \n\
00224 # The point stamped target that needs to be kept within view of the sensor\n\
00225 geometry_msgs/PointStamped target\n\
00226 \n\
00227 # The local pose of the frame in which visibility is to be maintained\n\
00228 # The frame id should represent the robot link to which the sensor is attached\n\
00229 # The visual axis of the sensor is assumed to be along the X axis of this frame\n\
00230 geometry_msgs/PoseStamped sensor_pose\n\
00231 \n\
00232 # The deviation (in radians) that will be tolerated\n\
00233 # Constraint error will be measured as the solid angle between the \n\
00234 # X axis of the frame defined above and the vector between the origin \n\
00235 # of the frame defined above and the target location\n\
00236 float64 absolute_tolerance\n\
00237 \n\
00238 \n\
00239 ================================================================================\n\
00240 MSG: geometry_msgs/PointStamped\n\
00241 # This represents a Point with reference coordinate frame and timestamp\n\
00242 Header header\n\
00243 Point point\n\
00244 \n\
00245 ================================================================================\n\
00246 MSG: geometry_msgs/PoseStamped\n\
00247 # A Pose with reference coordinate frame and timestamp\n\
00248 Header header\n\
00249 Pose pose\n\
00250 \n\
00251 ================================================================================\n\
00252 MSG: geometry_msgs/Pose\n\
00253 # A representation of pose in free space, composed of postion and orientation. \n\
00254 Point position\n\
00255 Quaternion orientation\n\
00256 \n\
00257 "; }
00258 public:
00259 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00260
00261 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00262
00263 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00264 {
00265 ros::serialization::OStream stream(write_ptr, 1000000000);
00266 ros::serialization::serialize(stream, path_constraints);
00267 ros::serialization::serialize(stream, goal_constraints);
00268 return stream.getData();
00269 }
00270
00271 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00272 {
00273 ros::serialization::IStream stream(read_ptr, 1000000000);
00274 ros::serialization::deserialize(stream, path_constraints);
00275 ros::serialization::deserialize(stream, goal_constraints);
00276 return stream.getData();
00277 }
00278
00279 ROS_DEPRECATED virtual uint32_t serializationLength() const
00280 {
00281 uint32_t size = 0;
00282 size += ros::serialization::serializationLength(path_constraints);
00283 size += ros::serialization::serializationLength(goal_constraints);
00284 return size;
00285 }
00286
00287 typedef boost::shared_ptr< ::planning_environment_msgs::SetConstraintsRequest_<ContainerAllocator> > Ptr;
00288 typedef boost::shared_ptr< ::planning_environment_msgs::SetConstraintsRequest_<ContainerAllocator> const> ConstPtr;
00289 };
00290 typedef ::planning_environment_msgs::SetConstraintsRequest_<std::allocator<void> > SetConstraintsRequest;
00291
00292 typedef boost::shared_ptr< ::planning_environment_msgs::SetConstraintsRequest> SetConstraintsRequestPtr;
00293 typedef boost::shared_ptr< ::planning_environment_msgs::SetConstraintsRequest const> SetConstraintsRequestConstPtr;
00294
00295
00296 template <class ContainerAllocator>
00297 struct SetConstraintsResponse_ : public ros::Message
00298 {
00299 typedef SetConstraintsResponse_<ContainerAllocator> Type;
00300
00301 SetConstraintsResponse_()
00302 : path_constraints()
00303 , goal_constraints()
00304 , error_code()
00305 {
00306 }
00307
00308 SetConstraintsResponse_(const ContainerAllocator& _alloc)
00309 : path_constraints(_alloc)
00310 , goal_constraints(_alloc)
00311 , error_code(_alloc)
00312 {
00313 }
00314
00315 typedef ::motion_planning_msgs::Constraints_<ContainerAllocator> _path_constraints_type;
00316 ::motion_planning_msgs::Constraints_<ContainerAllocator> path_constraints;
00317
00318 typedef ::motion_planning_msgs::Constraints_<ContainerAllocator> _goal_constraints_type;
00319 ::motion_planning_msgs::Constraints_<ContainerAllocator> goal_constraints;
00320
00321 typedef ::motion_planning_msgs::ArmNavigationErrorCodes_<ContainerAllocator> _error_code_type;
00322 ::motion_planning_msgs::ArmNavigationErrorCodes_<ContainerAllocator> error_code;
00323
00324
00325 private:
00326 static const char* __s_getDataType_() { return "planning_environment_msgs/SetConstraintsResponse"; }
00327 public:
00328 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00329
00330 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00331
00332 private:
00333 static const char* __s_getMD5Sum_() { return "02fb232aac2c27a28d6a5482c3fbefef"; }
00334 public:
00335 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00336
00337 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00338
00339 private:
00340 static const char* __s_getServerMD5Sum_() { return "60cfcfae4d588cf6b9a94199b57d97db"; }
00341 public:
00342 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); }
00343
00344 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); }
00345
00346 private:
00347 static const char* __s_getMessageDefinition_() { return "\n\
00348 \n\
00349 \n\
00350 motion_planning_msgs/Constraints path_constraints\n\
00351 motion_planning_msgs/Constraints goal_constraints\n\
00352 \n\
00353 motion_planning_msgs/ArmNavigationErrorCodes error_code\n\
00354 \n\
00355 ================================================================================\n\
00356 MSG: motion_planning_msgs/Constraints\n\
00357 # This message contains a list of motion planning constraints.\n\
00358 \n\
00359 motion_planning_msgs/JointConstraint[] joint_constraints\n\
00360 motion_planning_msgs/PositionConstraint[] position_constraints\n\
00361 motion_planning_msgs/OrientationConstraint[] orientation_constraints\n\
00362 motion_planning_msgs/VisibilityConstraint[] visibility_constraints\n\
00363 \n\
00364 ================================================================================\n\
00365 MSG: motion_planning_msgs/JointConstraint\n\
00366 # Constrain the position of a joint to be within a certain bound\n\
00367 string joint_name\n\
00368 \n\
00369 # the bound to be achieved is [position - tolerance_below, position + tolerance_above]\n\
00370 float64 position\n\
00371 float64 tolerance_above\n\
00372 float64 tolerance_below\n\
00373 \n\
00374 # A weighting factor for this constraint\n\
00375 float64 weight\n\
00376 ================================================================================\n\
00377 MSG: motion_planning_msgs/PositionConstraint\n\
00378 # This message contains the definition of a position constraint.\n\
00379 Header header\n\
00380 \n\
00381 # The robot link this constraint refers to\n\
00382 string link_name\n\
00383 \n\
00384 # The offset (in the link frame) for the target point on the link we are planning for\n\
00385 geometry_msgs/Point target_point_offset\n\
00386 \n\
00387 # The nominal/target position for the point we are planning for\n\
00388 geometry_msgs/Point position\n\
00389 \n\
00390 # The shape of the bounded region that constrains the position of the end-effector\n\
00391 # This region is always centered at the position defined above\n\
00392 geometric_shapes_msgs/Shape constraint_region_shape\n\
00393 \n\
00394 # The orientation of the bounded region that constrains the position of the end-effector. \n\
00395 # This allows the specification of non-axis aligned constraints\n\
00396 geometry_msgs/Quaternion constraint_region_orientation\n\
00397 \n\
00398 # Constraint weighting factor - a weight for this constraint\n\
00399 float64 weight\n\
00400 ================================================================================\n\
00401 MSG: std_msgs/Header\n\
00402 # Standard metadata for higher-level stamped data types.\n\
00403 # This is generally used to communicate timestamped data \n\
00404 # in a particular coordinate frame.\n\
00405 # \n\
00406 # sequence ID: consecutively increasing ID \n\
00407 uint32 seq\n\
00408 #Two-integer timestamp that is expressed as:\n\
00409 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00410 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00411 # time-handling sugar is provided by the client library\n\
00412 time stamp\n\
00413 #Frame this data is associated with\n\
00414 # 0: no frame\n\
00415 # 1: global frame\n\
00416 string frame_id\n\
00417 \n\
00418 ================================================================================\n\
00419 MSG: geometry_msgs/Point\n\
00420 # This contains the position of a point in free space\n\
00421 float64 x\n\
00422 float64 y\n\
00423 float64 z\n\
00424 \n\
00425 ================================================================================\n\
00426 MSG: geometric_shapes_msgs/Shape\n\
00427 byte SPHERE=0\n\
00428 byte BOX=1\n\
00429 byte CYLINDER=2\n\
00430 byte MESH=3\n\
00431 \n\
00432 byte type\n\
00433 \n\
00434 \n\
00435 #### define sphere, box, cylinder ####\n\
00436 # the origin of each shape is considered at the shape's center\n\
00437 \n\
00438 # for sphere\n\
00439 # radius := dimensions[0]\n\
00440 \n\
00441 # for cylinder\n\
00442 # radius := dimensions[0]\n\
00443 # length := dimensions[1]\n\
00444 # the length is along the Z axis\n\
00445 \n\
00446 # for box\n\
00447 # size_x := dimensions[0]\n\
00448 # size_y := dimensions[1]\n\
00449 # size_z := dimensions[2]\n\
00450 float64[] dimensions\n\
00451 \n\
00452 \n\
00453 #### define mesh ####\n\
00454 \n\
00455 # list of triangles; triangle k is defined by tre vertices located\n\
00456 # at indices triangles[3k], triangles[3k+1], triangles[3k+2]\n\
00457 int32[] triangles\n\
00458 geometry_msgs/Point[] vertices\n\
00459 \n\
00460 ================================================================================\n\
00461 MSG: geometry_msgs/Quaternion\n\
00462 # This represents an orientation in free space in quaternion form.\n\
00463 \n\
00464 float64 x\n\
00465 float64 y\n\
00466 float64 z\n\
00467 float64 w\n\
00468 \n\
00469 ================================================================================\n\
00470 MSG: motion_planning_msgs/OrientationConstraint\n\
00471 # This message contains the definition of an orientation constraint.\n\
00472 Header header\n\
00473 \n\
00474 # The robot link this constraint refers to\n\
00475 string link_name\n\
00476 \n\
00477 # The type of the constraint\n\
00478 int32 type\n\
00479 int32 LINK_FRAME=0\n\
00480 int32 HEADER_FRAME=1\n\
00481 \n\
00482 # The desired orientation of the robot link specified as a quaternion\n\
00483 geometry_msgs/Quaternion orientation\n\
00484 \n\
00485 # optional RPY error tolerances specified if \n\
00486 float64 absolute_roll_tolerance\n\
00487 float64 absolute_pitch_tolerance\n\
00488 float64 absolute_yaw_tolerance\n\
00489 \n\
00490 # Constraint weighting factor - a weight for this constraint\n\
00491 float64 weight\n\
00492 \n\
00493 ================================================================================\n\
00494 MSG: motion_planning_msgs/VisibilityConstraint\n\
00495 # This message contains the definition of a visibility constraint.\n\
00496 Header header\n\
00497 \n\
00498 # The point stamped target that needs to be kept within view of the sensor\n\
00499 geometry_msgs/PointStamped target\n\
00500 \n\
00501 # The local pose of the frame in which visibility is to be maintained\n\
00502 # The frame id should represent the robot link to which the sensor is attached\n\
00503 # The visual axis of the sensor is assumed to be along the X axis of this frame\n\
00504 geometry_msgs/PoseStamped sensor_pose\n\
00505 \n\
00506 # The deviation (in radians) that will be tolerated\n\
00507 # Constraint error will be measured as the solid angle between the \n\
00508 # X axis of the frame defined above and the vector between the origin \n\
00509 # of the frame defined above and the target location\n\
00510 float64 absolute_tolerance\n\
00511 \n\
00512 \n\
00513 ================================================================================\n\
00514 MSG: geometry_msgs/PointStamped\n\
00515 # This represents a Point with reference coordinate frame and timestamp\n\
00516 Header header\n\
00517 Point point\n\
00518 \n\
00519 ================================================================================\n\
00520 MSG: geometry_msgs/PoseStamped\n\
00521 # A Pose with reference coordinate frame and timestamp\n\
00522 Header header\n\
00523 Pose pose\n\
00524 \n\
00525 ================================================================================\n\
00526 MSG: geometry_msgs/Pose\n\
00527 # A representation of pose in free space, composed of postion and orientation. \n\
00528 Point position\n\
00529 Quaternion orientation\n\
00530 \n\
00531 ================================================================================\n\
00532 MSG: motion_planning_msgs/ArmNavigationErrorCodes\n\
00533 int32 val\n\
00534 \n\
00535 # overall behavior\n\
00536 int32 PLANNING_FAILED=-1\n\
00537 int32 SUCCESS=1\n\
00538 int32 TIMED_OUT=-2\n\
00539 \n\
00540 # start state errors\n\
00541 int32 START_STATE_IN_COLLISION=-3\n\
00542 int32 START_STATE_VIOLATES_PATH_CONSTRAINTS=-4\n\
00543 \n\
00544 # goal errors\n\
00545 int32 GOAL_IN_COLLISION=-5\n\
00546 int32 GOAL_VIOLATES_PATH_CONSTRAINTS=-6\n\
00547 \n\
00548 # robot state\n\
00549 int32 INVALID_ROBOT_STATE=-7\n\
00550 int32 INCOMPLETE_ROBOT_STATE=-8\n\
00551 \n\
00552 # planning request errors\n\
00553 int32 INVALID_PLANNER_ID=-9\n\
00554 int32 INVALID_NUM_PLANNING_ATTEMPTS=-10\n\
00555 int32 INVALID_ALLOWED_PLANNING_TIME=-11\n\
00556 int32 INVALID_GROUP_NAME=-12\n\
00557 int32 INVALID_GOAL_JOINT_CONSTRAINTS=-13\n\
00558 int32 INVALID_GOAL_POSITION_CONSTRAINTS=-14\n\
00559 int32 INVALID_GOAL_ORIENTATION_CONSTRAINTS=-15\n\
00560 int32 INVALID_PATH_JOINT_CONSTRAINTS=-16\n\
00561 int32 INVALID_PATH_POSITION_CONSTRAINTS=-17\n\
00562 int32 INVALID_PATH_ORIENTATION_CONSTRAINTS=-18\n\
00563 \n\
00564 # state/trajectory monitor errors\n\
00565 int32 INVALID_TRAJECTORY=-19\n\
00566 int32 INVALID_INDEX=-20\n\
00567 int32 JOINT_LIMITS_VIOLATED=-21\n\
00568 int32 PATH_CONSTRAINTS_VIOLATED=-22\n\
00569 int32 COLLISION_CONSTRAINTS_VIOLATED=-23\n\
00570 int32 GOAL_CONSTRAINTS_VIOLATED=-24\n\
00571 int32 JOINTS_NOT_MOVING=-25\n\
00572 int32 TRAJECTORY_CONTROLLER_FAILED=-26\n\
00573 \n\
00574 # system errors\n\
00575 int32 FRAME_TRANSFORM_FAILURE=-27\n\
00576 int32 COLLISION_CHECKING_UNAVAILABLE=-28\n\
00577 int32 ROBOT_STATE_STALE=-29\n\
00578 int32 SENSOR_INFO_STALE=-30\n\
00579 \n\
00580 # kinematics errors\n\
00581 int32 NO_IK_SOLUTION=-31\n\
00582 int32 INVALID_LINK_NAME=-32\n\
00583 int32 IK_LINK_IN_COLLISION=-33\n\
00584 int32 NO_FK_SOLUTION=-34\n\
00585 int32 KINEMATICS_STATE_IN_COLLISION=-35\n\
00586 \n\
00587 # general errors\n\
00588 int32 INVALID_TIMEOUT=-36\n\
00589 \n\
00590 \n\
00591 "; }
00592 public:
00593 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00594
00595 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00596
00597 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00598 {
00599 ros::serialization::OStream stream(write_ptr, 1000000000);
00600 ros::serialization::serialize(stream, path_constraints);
00601 ros::serialization::serialize(stream, goal_constraints);
00602 ros::serialization::serialize(stream, error_code);
00603 return stream.getData();
00604 }
00605
00606 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00607 {
00608 ros::serialization::IStream stream(read_ptr, 1000000000);
00609 ros::serialization::deserialize(stream, path_constraints);
00610 ros::serialization::deserialize(stream, goal_constraints);
00611 ros::serialization::deserialize(stream, error_code);
00612 return stream.getData();
00613 }
00614
00615 ROS_DEPRECATED virtual uint32_t serializationLength() const
00616 {
00617 uint32_t size = 0;
00618 size += ros::serialization::serializationLength(path_constraints);
00619 size += ros::serialization::serializationLength(goal_constraints);
00620 size += ros::serialization::serializationLength(error_code);
00621 return size;
00622 }
00623
00624 typedef boost::shared_ptr< ::planning_environment_msgs::SetConstraintsResponse_<ContainerAllocator> > Ptr;
00625 typedef boost::shared_ptr< ::planning_environment_msgs::SetConstraintsResponse_<ContainerAllocator> const> ConstPtr;
00626 };
00627 typedef ::planning_environment_msgs::SetConstraintsResponse_<std::allocator<void> > SetConstraintsResponse;
00628
00629 typedef boost::shared_ptr< ::planning_environment_msgs::SetConstraintsResponse> SetConstraintsResponsePtr;
00630 typedef boost::shared_ptr< ::planning_environment_msgs::SetConstraintsResponse const> SetConstraintsResponseConstPtr;
00631
00632 struct SetConstraints
00633 {
00634
00635 typedef SetConstraintsRequest Request;
00636 typedef SetConstraintsResponse Response;
00637 Request request;
00638 Response response;
00639
00640 typedef Request RequestType;
00641 typedef Response ResponseType;
00642 };
00643 }
00644
00645 namespace ros
00646 {
00647 namespace message_traits
00648 {
00649 template<class ContainerAllocator>
00650 struct MD5Sum< ::planning_environment_msgs::SetConstraintsRequest_<ContainerAllocator> > {
00651 static const char* value()
00652 {
00653 return "6d13bc5e83c4c2ef090eae3053dfae3a";
00654 }
00655
00656 static const char* value(const ::planning_environment_msgs::SetConstraintsRequest_<ContainerAllocator> &) { return value(); }
00657 static const uint64_t static_value1 = 0x6d13bc5e83c4c2efULL;
00658 static const uint64_t static_value2 = 0x090eae3053dfae3aULL;
00659 };
00660
00661 template<class ContainerAllocator>
00662 struct DataType< ::planning_environment_msgs::SetConstraintsRequest_<ContainerAllocator> > {
00663 static const char* value()
00664 {
00665 return "planning_environment_msgs/SetConstraintsRequest";
00666 }
00667
00668 static const char* value(const ::planning_environment_msgs::SetConstraintsRequest_<ContainerAllocator> &) { return value(); }
00669 };
00670
00671 template<class ContainerAllocator>
00672 struct Definition< ::planning_environment_msgs::SetConstraintsRequest_<ContainerAllocator> > {
00673 static const char* value()
00674 {
00675 return "\n\
00676 \n\
00677 \n\
00678 \n\
00679 \n\
00680 \n\
00681 motion_planning_msgs/Constraints path_constraints\n\
00682 motion_planning_msgs/Constraints goal_constraints\n\
00683 \n\
00684 \n\
00685 ================================================================================\n\
00686 MSG: motion_planning_msgs/Constraints\n\
00687 # This message contains a list of motion planning constraints.\n\
00688 \n\
00689 motion_planning_msgs/JointConstraint[] joint_constraints\n\
00690 motion_planning_msgs/PositionConstraint[] position_constraints\n\
00691 motion_planning_msgs/OrientationConstraint[] orientation_constraints\n\
00692 motion_planning_msgs/VisibilityConstraint[] visibility_constraints\n\
00693 \n\
00694 ================================================================================\n\
00695 MSG: motion_planning_msgs/JointConstraint\n\
00696 # Constrain the position of a joint to be within a certain bound\n\
00697 string joint_name\n\
00698 \n\
00699 # the bound to be achieved is [position - tolerance_below, position + tolerance_above]\n\
00700 float64 position\n\
00701 float64 tolerance_above\n\
00702 float64 tolerance_below\n\
00703 \n\
00704 # A weighting factor for this constraint\n\
00705 float64 weight\n\
00706 ================================================================================\n\
00707 MSG: motion_planning_msgs/PositionConstraint\n\
00708 # This message contains the definition of a position constraint.\n\
00709 Header header\n\
00710 \n\
00711 # The robot link this constraint refers to\n\
00712 string link_name\n\
00713 \n\
00714 # The offset (in the link frame) for the target point on the link we are planning for\n\
00715 geometry_msgs/Point target_point_offset\n\
00716 \n\
00717 # The nominal/target position for the point we are planning for\n\
00718 geometry_msgs/Point position\n\
00719 \n\
00720 # The shape of the bounded region that constrains the position of the end-effector\n\
00721 # This region is always centered at the position defined above\n\
00722 geometric_shapes_msgs/Shape constraint_region_shape\n\
00723 \n\
00724 # The orientation of the bounded region that constrains the position of the end-effector. \n\
00725 # This allows the specification of non-axis aligned constraints\n\
00726 geometry_msgs/Quaternion constraint_region_orientation\n\
00727 \n\
00728 # Constraint weighting factor - a weight for this constraint\n\
00729 float64 weight\n\
00730 ================================================================================\n\
00731 MSG: std_msgs/Header\n\
00732 # Standard metadata for higher-level stamped data types.\n\
00733 # This is generally used to communicate timestamped data \n\
00734 # in a particular coordinate frame.\n\
00735 # \n\
00736 # sequence ID: consecutively increasing ID \n\
00737 uint32 seq\n\
00738 #Two-integer timestamp that is expressed as:\n\
00739 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00740 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00741 # time-handling sugar is provided by the client library\n\
00742 time stamp\n\
00743 #Frame this data is associated with\n\
00744 # 0: no frame\n\
00745 # 1: global frame\n\
00746 string frame_id\n\
00747 \n\
00748 ================================================================================\n\
00749 MSG: geometry_msgs/Point\n\
00750 # This contains the position of a point in free space\n\
00751 float64 x\n\
00752 float64 y\n\
00753 float64 z\n\
00754 \n\
00755 ================================================================================\n\
00756 MSG: geometric_shapes_msgs/Shape\n\
00757 byte SPHERE=0\n\
00758 byte BOX=1\n\
00759 byte CYLINDER=2\n\
00760 byte MESH=3\n\
00761 \n\
00762 byte type\n\
00763 \n\
00764 \n\
00765 #### define sphere, box, cylinder ####\n\
00766 # the origin of each shape is considered at the shape's center\n\
00767 \n\
00768 # for sphere\n\
00769 # radius := dimensions[0]\n\
00770 \n\
00771 # for cylinder\n\
00772 # radius := dimensions[0]\n\
00773 # length := dimensions[1]\n\
00774 # the length is along the Z axis\n\
00775 \n\
00776 # for box\n\
00777 # size_x := dimensions[0]\n\
00778 # size_y := dimensions[1]\n\
00779 # size_z := dimensions[2]\n\
00780 float64[] dimensions\n\
00781 \n\
00782 \n\
00783 #### define mesh ####\n\
00784 \n\
00785 # list of triangles; triangle k is defined by tre vertices located\n\
00786 # at indices triangles[3k], triangles[3k+1], triangles[3k+2]\n\
00787 int32[] triangles\n\
00788 geometry_msgs/Point[] vertices\n\
00789 \n\
00790 ================================================================================\n\
00791 MSG: geometry_msgs/Quaternion\n\
00792 # This represents an orientation in free space in quaternion form.\n\
00793 \n\
00794 float64 x\n\
00795 float64 y\n\
00796 float64 z\n\
00797 float64 w\n\
00798 \n\
00799 ================================================================================\n\
00800 MSG: motion_planning_msgs/OrientationConstraint\n\
00801 # This message contains the definition of an orientation constraint.\n\
00802 Header header\n\
00803 \n\
00804 # The robot link this constraint refers to\n\
00805 string link_name\n\
00806 \n\
00807 # The type of the constraint\n\
00808 int32 type\n\
00809 int32 LINK_FRAME=0\n\
00810 int32 HEADER_FRAME=1\n\
00811 \n\
00812 # The desired orientation of the robot link specified as a quaternion\n\
00813 geometry_msgs/Quaternion orientation\n\
00814 \n\
00815 # optional RPY error tolerances specified if \n\
00816 float64 absolute_roll_tolerance\n\
00817 float64 absolute_pitch_tolerance\n\
00818 float64 absolute_yaw_tolerance\n\
00819 \n\
00820 # Constraint weighting factor - a weight for this constraint\n\
00821 float64 weight\n\
00822 \n\
00823 ================================================================================\n\
00824 MSG: motion_planning_msgs/VisibilityConstraint\n\
00825 # This message contains the definition of a visibility constraint.\n\
00826 Header header\n\
00827 \n\
00828 # The point stamped target that needs to be kept within view of the sensor\n\
00829 geometry_msgs/PointStamped target\n\
00830 \n\
00831 # The local pose of the frame in which visibility is to be maintained\n\
00832 # The frame id should represent the robot link to which the sensor is attached\n\
00833 # The visual axis of the sensor is assumed to be along the X axis of this frame\n\
00834 geometry_msgs/PoseStamped sensor_pose\n\
00835 \n\
00836 # The deviation (in radians) that will be tolerated\n\
00837 # Constraint error will be measured as the solid angle between the \n\
00838 # X axis of the frame defined above and the vector between the origin \n\
00839 # of the frame defined above and the target location\n\
00840 float64 absolute_tolerance\n\
00841 \n\
00842 \n\
00843 ================================================================================\n\
00844 MSG: geometry_msgs/PointStamped\n\
00845 # This represents a Point with reference coordinate frame and timestamp\n\
00846 Header header\n\
00847 Point point\n\
00848 \n\
00849 ================================================================================\n\
00850 MSG: geometry_msgs/PoseStamped\n\
00851 # A Pose with reference coordinate frame and timestamp\n\
00852 Header header\n\
00853 Pose pose\n\
00854 \n\
00855 ================================================================================\n\
00856 MSG: geometry_msgs/Pose\n\
00857 # A representation of pose in free space, composed of postion and orientation. \n\
00858 Point position\n\
00859 Quaternion orientation\n\
00860 \n\
00861 ";
00862 }
00863
00864 static const char* value(const ::planning_environment_msgs::SetConstraintsRequest_<ContainerAllocator> &) { return value(); }
00865 };
00866
00867 }
00868 }
00869
00870
00871 namespace ros
00872 {
00873 namespace message_traits
00874 {
00875 template<class ContainerAllocator>
00876 struct MD5Sum< ::planning_environment_msgs::SetConstraintsResponse_<ContainerAllocator> > {
00877 static const char* value()
00878 {
00879 return "02fb232aac2c27a28d6a5482c3fbefef";
00880 }
00881
00882 static const char* value(const ::planning_environment_msgs::SetConstraintsResponse_<ContainerAllocator> &) { return value(); }
00883 static const uint64_t static_value1 = 0x02fb232aac2c27a2ULL;
00884 static const uint64_t static_value2 = 0x8d6a5482c3fbefefULL;
00885 };
00886
00887 template<class ContainerAllocator>
00888 struct DataType< ::planning_environment_msgs::SetConstraintsResponse_<ContainerAllocator> > {
00889 static const char* value()
00890 {
00891 return "planning_environment_msgs/SetConstraintsResponse";
00892 }
00893
00894 static const char* value(const ::planning_environment_msgs::SetConstraintsResponse_<ContainerAllocator> &) { return value(); }
00895 };
00896
00897 template<class ContainerAllocator>
00898 struct Definition< ::planning_environment_msgs::SetConstraintsResponse_<ContainerAllocator> > {
00899 static const char* value()
00900 {
00901 return "\n\
00902 \n\
00903 \n\
00904 motion_planning_msgs/Constraints path_constraints\n\
00905 motion_planning_msgs/Constraints goal_constraints\n\
00906 \n\
00907 motion_planning_msgs/ArmNavigationErrorCodes error_code\n\
00908 \n\
00909 ================================================================================\n\
00910 MSG: motion_planning_msgs/Constraints\n\
00911 # This message contains a list of motion planning constraints.\n\
00912 \n\
00913 motion_planning_msgs/JointConstraint[] joint_constraints\n\
00914 motion_planning_msgs/PositionConstraint[] position_constraints\n\
00915 motion_planning_msgs/OrientationConstraint[] orientation_constraints\n\
00916 motion_planning_msgs/VisibilityConstraint[] visibility_constraints\n\
00917 \n\
00918 ================================================================================\n\
00919 MSG: motion_planning_msgs/JointConstraint\n\
00920 # Constrain the position of a joint to be within a certain bound\n\
00921 string joint_name\n\
00922 \n\
00923 # the bound to be achieved is [position - tolerance_below, position + tolerance_above]\n\
00924 float64 position\n\
00925 float64 tolerance_above\n\
00926 float64 tolerance_below\n\
00927 \n\
00928 # A weighting factor for this constraint\n\
00929 float64 weight\n\
00930 ================================================================================\n\
00931 MSG: motion_planning_msgs/PositionConstraint\n\
00932 # This message contains the definition of a position constraint.\n\
00933 Header header\n\
00934 \n\
00935 # The robot link this constraint refers to\n\
00936 string link_name\n\
00937 \n\
00938 # The offset (in the link frame) for the target point on the link we are planning for\n\
00939 geometry_msgs/Point target_point_offset\n\
00940 \n\
00941 # The nominal/target position for the point we are planning for\n\
00942 geometry_msgs/Point position\n\
00943 \n\
00944 # The shape of the bounded region that constrains the position of the end-effector\n\
00945 # This region is always centered at the position defined above\n\
00946 geometric_shapes_msgs/Shape constraint_region_shape\n\
00947 \n\
00948 # The orientation of the bounded region that constrains the position of the end-effector. \n\
00949 # This allows the specification of non-axis aligned constraints\n\
00950 geometry_msgs/Quaternion constraint_region_orientation\n\
00951 \n\
00952 # Constraint weighting factor - a weight for this constraint\n\
00953 float64 weight\n\
00954 ================================================================================\n\
00955 MSG: std_msgs/Header\n\
00956 # Standard metadata for higher-level stamped data types.\n\
00957 # This is generally used to communicate timestamped data \n\
00958 # in a particular coordinate frame.\n\
00959 # \n\
00960 # sequence ID: consecutively increasing ID \n\
00961 uint32 seq\n\
00962 #Two-integer timestamp that is expressed as:\n\
00963 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00964 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00965 # time-handling sugar is provided by the client library\n\
00966 time stamp\n\
00967 #Frame this data is associated with\n\
00968 # 0: no frame\n\
00969 # 1: global frame\n\
00970 string frame_id\n\
00971 \n\
00972 ================================================================================\n\
00973 MSG: geometry_msgs/Point\n\
00974 # This contains the position of a point in free space\n\
00975 float64 x\n\
00976 float64 y\n\
00977 float64 z\n\
00978 \n\
00979 ================================================================================\n\
00980 MSG: geometric_shapes_msgs/Shape\n\
00981 byte SPHERE=0\n\
00982 byte BOX=1\n\
00983 byte CYLINDER=2\n\
00984 byte MESH=3\n\
00985 \n\
00986 byte type\n\
00987 \n\
00988 \n\
00989 #### define sphere, box, cylinder ####\n\
00990 # the origin of each shape is considered at the shape's center\n\
00991 \n\
00992 # for sphere\n\
00993 # radius := dimensions[0]\n\
00994 \n\
00995 # for cylinder\n\
00996 # radius := dimensions[0]\n\
00997 # length := dimensions[1]\n\
00998 # the length is along the Z axis\n\
00999 \n\
01000 # for box\n\
01001 # size_x := dimensions[0]\n\
01002 # size_y := dimensions[1]\n\
01003 # size_z := dimensions[2]\n\
01004 float64[] dimensions\n\
01005 \n\
01006 \n\
01007 #### define mesh ####\n\
01008 \n\
01009 # list of triangles; triangle k is defined by tre vertices located\n\
01010 # at indices triangles[3k], triangles[3k+1], triangles[3k+2]\n\
01011 int32[] triangles\n\
01012 geometry_msgs/Point[] vertices\n\
01013 \n\
01014 ================================================================================\n\
01015 MSG: geometry_msgs/Quaternion\n\
01016 # This represents an orientation in free space in quaternion form.\n\
01017 \n\
01018 float64 x\n\
01019 float64 y\n\
01020 float64 z\n\
01021 float64 w\n\
01022 \n\
01023 ================================================================================\n\
01024 MSG: motion_planning_msgs/OrientationConstraint\n\
01025 # This message contains the definition of an orientation constraint.\n\
01026 Header header\n\
01027 \n\
01028 # The robot link this constraint refers to\n\
01029 string link_name\n\
01030 \n\
01031 # The type of the constraint\n\
01032 int32 type\n\
01033 int32 LINK_FRAME=0\n\
01034 int32 HEADER_FRAME=1\n\
01035 \n\
01036 # The desired orientation of the robot link specified as a quaternion\n\
01037 geometry_msgs/Quaternion orientation\n\
01038 \n\
01039 # optional RPY error tolerances specified if \n\
01040 float64 absolute_roll_tolerance\n\
01041 float64 absolute_pitch_tolerance\n\
01042 float64 absolute_yaw_tolerance\n\
01043 \n\
01044 # Constraint weighting factor - a weight for this constraint\n\
01045 float64 weight\n\
01046 \n\
01047 ================================================================================\n\
01048 MSG: motion_planning_msgs/VisibilityConstraint\n\
01049 # This message contains the definition of a visibility constraint.\n\
01050 Header header\n\
01051 \n\
01052 # The point stamped target that needs to be kept within view of the sensor\n\
01053 geometry_msgs/PointStamped target\n\
01054 \n\
01055 # The local pose of the frame in which visibility is to be maintained\n\
01056 # The frame id should represent the robot link to which the sensor is attached\n\
01057 # The visual axis of the sensor is assumed to be along the X axis of this frame\n\
01058 geometry_msgs/PoseStamped sensor_pose\n\
01059 \n\
01060 # The deviation (in radians) that will be tolerated\n\
01061 # Constraint error will be measured as the solid angle between the \n\
01062 # X axis of the frame defined above and the vector between the origin \n\
01063 # of the frame defined above and the target location\n\
01064 float64 absolute_tolerance\n\
01065 \n\
01066 \n\
01067 ================================================================================\n\
01068 MSG: geometry_msgs/PointStamped\n\
01069 # This represents a Point with reference coordinate frame and timestamp\n\
01070 Header header\n\
01071 Point point\n\
01072 \n\
01073 ================================================================================\n\
01074 MSG: geometry_msgs/PoseStamped\n\
01075 # A Pose with reference coordinate frame and timestamp\n\
01076 Header header\n\
01077 Pose pose\n\
01078 \n\
01079 ================================================================================\n\
01080 MSG: geometry_msgs/Pose\n\
01081 # A representation of pose in free space, composed of postion and orientation. \n\
01082 Point position\n\
01083 Quaternion orientation\n\
01084 \n\
01085 ================================================================================\n\
01086 MSG: motion_planning_msgs/ArmNavigationErrorCodes\n\
01087 int32 val\n\
01088 \n\
01089 # overall behavior\n\
01090 int32 PLANNING_FAILED=-1\n\
01091 int32 SUCCESS=1\n\
01092 int32 TIMED_OUT=-2\n\
01093 \n\
01094 # start state errors\n\
01095 int32 START_STATE_IN_COLLISION=-3\n\
01096 int32 START_STATE_VIOLATES_PATH_CONSTRAINTS=-4\n\
01097 \n\
01098 # goal errors\n\
01099 int32 GOAL_IN_COLLISION=-5\n\
01100 int32 GOAL_VIOLATES_PATH_CONSTRAINTS=-6\n\
01101 \n\
01102 # robot state\n\
01103 int32 INVALID_ROBOT_STATE=-7\n\
01104 int32 INCOMPLETE_ROBOT_STATE=-8\n\
01105 \n\
01106 # planning request errors\n\
01107 int32 INVALID_PLANNER_ID=-9\n\
01108 int32 INVALID_NUM_PLANNING_ATTEMPTS=-10\n\
01109 int32 INVALID_ALLOWED_PLANNING_TIME=-11\n\
01110 int32 INVALID_GROUP_NAME=-12\n\
01111 int32 INVALID_GOAL_JOINT_CONSTRAINTS=-13\n\
01112 int32 INVALID_GOAL_POSITION_CONSTRAINTS=-14\n\
01113 int32 INVALID_GOAL_ORIENTATION_CONSTRAINTS=-15\n\
01114 int32 INVALID_PATH_JOINT_CONSTRAINTS=-16\n\
01115 int32 INVALID_PATH_POSITION_CONSTRAINTS=-17\n\
01116 int32 INVALID_PATH_ORIENTATION_CONSTRAINTS=-18\n\
01117 \n\
01118 # state/trajectory monitor errors\n\
01119 int32 INVALID_TRAJECTORY=-19\n\
01120 int32 INVALID_INDEX=-20\n\
01121 int32 JOINT_LIMITS_VIOLATED=-21\n\
01122 int32 PATH_CONSTRAINTS_VIOLATED=-22\n\
01123 int32 COLLISION_CONSTRAINTS_VIOLATED=-23\n\
01124 int32 GOAL_CONSTRAINTS_VIOLATED=-24\n\
01125 int32 JOINTS_NOT_MOVING=-25\n\
01126 int32 TRAJECTORY_CONTROLLER_FAILED=-26\n\
01127 \n\
01128 # system errors\n\
01129 int32 FRAME_TRANSFORM_FAILURE=-27\n\
01130 int32 COLLISION_CHECKING_UNAVAILABLE=-28\n\
01131 int32 ROBOT_STATE_STALE=-29\n\
01132 int32 SENSOR_INFO_STALE=-30\n\
01133 \n\
01134 # kinematics errors\n\
01135 int32 NO_IK_SOLUTION=-31\n\
01136 int32 INVALID_LINK_NAME=-32\n\
01137 int32 IK_LINK_IN_COLLISION=-33\n\
01138 int32 NO_FK_SOLUTION=-34\n\
01139 int32 KINEMATICS_STATE_IN_COLLISION=-35\n\
01140 \n\
01141 # general errors\n\
01142 int32 INVALID_TIMEOUT=-36\n\
01143 \n\
01144 \n\
01145 ";
01146 }
01147
01148 static const char* value(const ::planning_environment_msgs::SetConstraintsResponse_<ContainerAllocator> &) { return value(); }
01149 };
01150
01151 }
01152 }
01153
01154 namespace ros
01155 {
01156 namespace serialization
01157 {
01158
01159 template<class ContainerAllocator> struct Serializer< ::planning_environment_msgs::SetConstraintsRequest_<ContainerAllocator> >
01160 {
01161 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
01162 {
01163 stream.next(m.path_constraints);
01164 stream.next(m.goal_constraints);
01165 }
01166
01167 ROS_DECLARE_ALLINONE_SERIALIZER;
01168 };
01169 }
01170 }
01171
01172
01173 namespace ros
01174 {
01175 namespace serialization
01176 {
01177
01178 template<class ContainerAllocator> struct Serializer< ::planning_environment_msgs::SetConstraintsResponse_<ContainerAllocator> >
01179 {
01180 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
01181 {
01182 stream.next(m.path_constraints);
01183 stream.next(m.goal_constraints);
01184 stream.next(m.error_code);
01185 }
01186
01187 ROS_DECLARE_ALLINONE_SERIALIZER;
01188 };
01189 }
01190 }
01191
01192 namespace ros
01193 {
01194 namespace service_traits
01195 {
01196 template<>
01197 struct MD5Sum<planning_environment_msgs::SetConstraints> {
01198 static const char* value()
01199 {
01200 return "60cfcfae4d588cf6b9a94199b57d97db";
01201 }
01202
01203 static const char* value(const planning_environment_msgs::SetConstraints&) { return value(); }
01204 };
01205
01206 template<>
01207 struct DataType<planning_environment_msgs::SetConstraints> {
01208 static const char* value()
01209 {
01210 return "planning_environment_msgs/SetConstraints";
01211 }
01212
01213 static const char* value(const planning_environment_msgs::SetConstraints&) { return value(); }
01214 };
01215
01216 template<class ContainerAllocator>
01217 struct MD5Sum<planning_environment_msgs::SetConstraintsRequest_<ContainerAllocator> > {
01218 static const char* value()
01219 {
01220 return "60cfcfae4d588cf6b9a94199b57d97db";
01221 }
01222
01223 static const char* value(const planning_environment_msgs::SetConstraintsRequest_<ContainerAllocator> &) { return value(); }
01224 };
01225
01226 template<class ContainerAllocator>
01227 struct DataType<planning_environment_msgs::SetConstraintsRequest_<ContainerAllocator> > {
01228 static const char* value()
01229 {
01230 return "planning_environment_msgs/SetConstraints";
01231 }
01232
01233 static const char* value(const planning_environment_msgs::SetConstraintsRequest_<ContainerAllocator> &) { return value(); }
01234 };
01235
01236 template<class ContainerAllocator>
01237 struct MD5Sum<planning_environment_msgs::SetConstraintsResponse_<ContainerAllocator> > {
01238 static const char* value()
01239 {
01240 return "60cfcfae4d588cf6b9a94199b57d97db";
01241 }
01242
01243 static const char* value(const planning_environment_msgs::SetConstraintsResponse_<ContainerAllocator> &) { return value(); }
01244 };
01245
01246 template<class ContainerAllocator>
01247 struct DataType<planning_environment_msgs::SetConstraintsResponse_<ContainerAllocator> > {
01248 static const char* value()
01249 {
01250 return "planning_environment_msgs/SetConstraints";
01251 }
01252
01253 static const char* value(const planning_environment_msgs::SetConstraintsResponse_<ContainerAllocator> &) { return value(); }
01254 };
01255
01256 }
01257 }
01258
01259 #endif // PLANNING_ENVIRONMENT_MSGS_SERVICE_SETCONSTRAINTS_H
01260