Go to the documentation of this file.00001
00002 #ifndef ARM_NAVIGATION_MSGS_SERVICE_GETSTATEVALIDITY_H
00003 #define ARM_NAVIGATION_MSGS_SERVICE_GETSTATEVALIDITY_H
00004 #include <string>
00005 #include <vector>
00006 #include <map>
00007 #include <ostream>
00008 #include "ros/serialization.h"
00009 #include "ros/builtin_message_traits.h"
00010 #include "ros/message_operations.h"
00011 #include "ros/time.h"
00012
00013 #include "ros/macros.h"
00014
00015 #include "ros/assert.h"
00016
00017 #include "ros/service_traits.h"
00018
00019 #include "arm_navigation_msgs/RobotState.h"
00020 #include "arm_navigation_msgs/Constraints.h"
00021 #include "arm_navigation_msgs/Constraints.h"
00022
00023
00024 #include "arm_navigation_msgs/ArmNavigationErrorCodes.h"
00025 #include "arm_navigation_msgs/ContactInformation.h"
00026
00027 namespace arm_navigation_msgs
00028 {
00029 template <class ContainerAllocator>
00030 struct GetStateValidityRequest_ {
00031 typedef GetStateValidityRequest_<ContainerAllocator> Type;
00032
00033 GetStateValidityRequest_()
00034 : robot_state()
00035 , check_collisions(false)
00036 , check_path_constraints(false)
00037 , check_goal_constraints(false)
00038 , check_joint_limits(false)
00039 , group_name()
00040 , path_constraints()
00041 , goal_constraints()
00042 {
00043 }
00044
00045 GetStateValidityRequest_(const ContainerAllocator& _alloc)
00046 : robot_state(_alloc)
00047 , check_collisions(false)
00048 , check_path_constraints(false)
00049 , check_goal_constraints(false)
00050 , check_joint_limits(false)
00051 , group_name(_alloc)
00052 , path_constraints(_alloc)
00053 , goal_constraints(_alloc)
00054 {
00055 }
00056
00057 typedef ::arm_navigation_msgs::RobotState_<ContainerAllocator> _robot_state_type;
00058 ::arm_navigation_msgs::RobotState_<ContainerAllocator> robot_state;
00059
00060 typedef uint8_t _check_collisions_type;
00061 uint8_t check_collisions;
00062
00063 typedef uint8_t _check_path_constraints_type;
00064 uint8_t check_path_constraints;
00065
00066 typedef uint8_t _check_goal_constraints_type;
00067 uint8_t check_goal_constraints;
00068
00069 typedef uint8_t _check_joint_limits_type;
00070 uint8_t check_joint_limits;
00071
00072 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _group_name_type;
00073 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > group_name;
00074
00075 typedef ::arm_navigation_msgs::Constraints_<ContainerAllocator> _path_constraints_type;
00076 ::arm_navigation_msgs::Constraints_<ContainerAllocator> path_constraints;
00077
00078 typedef ::arm_navigation_msgs::Constraints_<ContainerAllocator> _goal_constraints_type;
00079 ::arm_navigation_msgs::Constraints_<ContainerAllocator> goal_constraints;
00080
00081
00082 typedef boost::shared_ptr< ::arm_navigation_msgs::GetStateValidityRequest_<ContainerAllocator> > Ptr;
00083 typedef boost::shared_ptr< ::arm_navigation_msgs::GetStateValidityRequest_<ContainerAllocator> const> ConstPtr;
00084 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00085 };
00086 typedef ::arm_navigation_msgs::GetStateValidityRequest_<std::allocator<void> > GetStateValidityRequest;
00087
00088 typedef boost::shared_ptr< ::arm_navigation_msgs::GetStateValidityRequest> GetStateValidityRequestPtr;
00089 typedef boost::shared_ptr< ::arm_navigation_msgs::GetStateValidityRequest const> GetStateValidityRequestConstPtr;
00090
00091
00092 template <class ContainerAllocator>
00093 struct GetStateValidityResponse_ {
00094 typedef GetStateValidityResponse_<ContainerAllocator> Type;
00095
00096 GetStateValidityResponse_()
00097 : error_code()
00098 , contacts()
00099 {
00100 }
00101
00102 GetStateValidityResponse_(const ContainerAllocator& _alloc)
00103 : error_code(_alloc)
00104 , contacts(_alloc)
00105 {
00106 }
00107
00108 typedef ::arm_navigation_msgs::ArmNavigationErrorCodes_<ContainerAllocator> _error_code_type;
00109 ::arm_navigation_msgs::ArmNavigationErrorCodes_<ContainerAllocator> error_code;
00110
00111 typedef std::vector< ::arm_navigation_msgs::ContactInformation_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::arm_navigation_msgs::ContactInformation_<ContainerAllocator> >::other > _contacts_type;
00112 std::vector< ::arm_navigation_msgs::ContactInformation_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::arm_navigation_msgs::ContactInformation_<ContainerAllocator> >::other > contacts;
00113
00114
00115 typedef boost::shared_ptr< ::arm_navigation_msgs::GetStateValidityResponse_<ContainerAllocator> > Ptr;
00116 typedef boost::shared_ptr< ::arm_navigation_msgs::GetStateValidityResponse_<ContainerAllocator> const> ConstPtr;
00117 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00118 };
00119 typedef ::arm_navigation_msgs::GetStateValidityResponse_<std::allocator<void> > GetStateValidityResponse;
00120
00121 typedef boost::shared_ptr< ::arm_navigation_msgs::GetStateValidityResponse> GetStateValidityResponsePtr;
00122 typedef boost::shared_ptr< ::arm_navigation_msgs::GetStateValidityResponse const> GetStateValidityResponseConstPtr;
00123
00124 struct GetStateValidity
00125 {
00126
00127 typedef GetStateValidityRequest Request;
00128 typedef GetStateValidityResponse Response;
00129 Request request;
00130 Response response;
00131
00132 typedef Request RequestType;
00133 typedef Response ResponseType;
00134 };
00135 }
00136
00137 namespace ros
00138 {
00139 namespace message_traits
00140 {
00141 template<class ContainerAllocator> struct IsMessage< ::arm_navigation_msgs::GetStateValidityRequest_<ContainerAllocator> > : public TrueType {};
00142 template<class ContainerAllocator> struct IsMessage< ::arm_navigation_msgs::GetStateValidityRequest_<ContainerAllocator> const> : public TrueType {};
00143 template<class ContainerAllocator>
00144 struct MD5Sum< ::arm_navigation_msgs::GetStateValidityRequest_<ContainerAllocator> > {
00145 static const char* value()
00146 {
00147 return "fe05d730cc03ecb8a8dff34774a12c59";
00148 }
00149
00150 static const char* value(const ::arm_navigation_msgs::GetStateValidityRequest_<ContainerAllocator> &) { return value(); }
00151 static const uint64_t static_value1 = 0xfe05d730cc03ecb8ULL;
00152 static const uint64_t static_value2 = 0xa8dff34774a12c59ULL;
00153 };
00154
00155 template<class ContainerAllocator>
00156 struct DataType< ::arm_navigation_msgs::GetStateValidityRequest_<ContainerAllocator> > {
00157 static const char* value()
00158 {
00159 return "arm_navigation_msgs/GetStateValidityRequest";
00160 }
00161
00162 static const char* value(const ::arm_navigation_msgs::GetStateValidityRequest_<ContainerAllocator> &) { return value(); }
00163 };
00164
00165 template<class ContainerAllocator>
00166 struct Definition< ::arm_navigation_msgs::GetStateValidityRequest_<ContainerAllocator> > {
00167 static const char* value()
00168 {
00169 return "\n\
00170 \n\
00171 arm_navigation_msgs/RobotState robot_state\n\
00172 \n\
00173 \n\
00174 bool check_collisions\n\
00175 \n\
00176 \n\
00177 bool check_path_constraints\n\
00178 \n\
00179 \n\
00180 bool check_goal_constraints\n\
00181 \n\
00182 \n\
00183 bool check_joint_limits\n\
00184 \n\
00185 \n\
00186 string group_name\n\
00187 \n\
00188 \n\
00189 \n\
00190 \n\
00191 arm_navigation_msgs/Constraints path_constraints\n\
00192 \n\
00193 \n\
00194 \n\
00195 \n\
00196 arm_navigation_msgs/Constraints goal_constraints\n\
00197 \n\
00198 \n\
00199 ================================================================================\n\
00200 MSG: arm_navigation_msgs/RobotState\n\
00201 # This message contains information about the robot state, i.e. the positions of its joints and links\n\
00202 sensor_msgs/JointState joint_state\n\
00203 arm_navigation_msgs/MultiDOFJointState multi_dof_joint_state\n\
00204 \n\
00205 ================================================================================\n\
00206 MSG: sensor_msgs/JointState\n\
00207 # This is a message that holds data to describe the state of a set of torque controlled joints. \n\
00208 #\n\
00209 # The state of each joint (revolute or prismatic) is defined by:\n\
00210 # * the position of the joint (rad or m),\n\
00211 # * the velocity of the joint (rad/s or m/s) and \n\
00212 # * the effort that is applied in the joint (Nm or N).\n\
00213 #\n\
00214 # Each joint is uniquely identified by its name\n\
00215 # The header specifies the time at which the joint states were recorded. All the joint states\n\
00216 # in one message have to be recorded at the same time.\n\
00217 #\n\
00218 # This message consists of a multiple arrays, one for each part of the joint state. \n\
00219 # The goal is to make each of the fields optional. When e.g. your joints have no\n\
00220 # effort associated with them, you can leave the effort array empty. \n\
00221 #\n\
00222 # All arrays in this message should have the same size, or be empty.\n\
00223 # This is the only way to uniquely associate the joint name with the correct\n\
00224 # states.\n\
00225 \n\
00226 \n\
00227 Header header\n\
00228 \n\
00229 string[] name\n\
00230 float64[] position\n\
00231 float64[] velocity\n\
00232 float64[] effort\n\
00233 \n\
00234 ================================================================================\n\
00235 MSG: std_msgs/Header\n\
00236 # Standard metadata for higher-level stamped data types.\n\
00237 # This is generally used to communicate timestamped data \n\
00238 # in a particular coordinate frame.\n\
00239 # \n\
00240 # sequence ID: consecutively increasing ID \n\
00241 uint32 seq\n\
00242 #Two-integer timestamp that is expressed as:\n\
00243 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00244 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00245 # time-handling sugar is provided by the client library\n\
00246 time stamp\n\
00247 #Frame this data is associated with\n\
00248 # 0: no frame\n\
00249 # 1: global frame\n\
00250 string frame_id\n\
00251 \n\
00252 ================================================================================\n\
00253 MSG: arm_navigation_msgs/MultiDOFJointState\n\
00254 #A representation of a multi-dof joint state\n\
00255 time stamp\n\
00256 string[] joint_names\n\
00257 string[] frame_ids\n\
00258 string[] child_frame_ids\n\
00259 geometry_msgs/Pose[] poses\n\
00260 \n\
00261 ================================================================================\n\
00262 MSG: geometry_msgs/Pose\n\
00263 # A representation of pose in free space, composed of postion and orientation. \n\
00264 Point position\n\
00265 Quaternion orientation\n\
00266 \n\
00267 ================================================================================\n\
00268 MSG: geometry_msgs/Point\n\
00269 # This contains the position of a point in free space\n\
00270 float64 x\n\
00271 float64 y\n\
00272 float64 z\n\
00273 \n\
00274 ================================================================================\n\
00275 MSG: geometry_msgs/Quaternion\n\
00276 # This represents an orientation in free space in quaternion form.\n\
00277 \n\
00278 float64 x\n\
00279 float64 y\n\
00280 float64 z\n\
00281 float64 w\n\
00282 \n\
00283 ================================================================================\n\
00284 MSG: arm_navigation_msgs/Constraints\n\
00285 # This message contains a list of motion planning constraints.\n\
00286 \n\
00287 arm_navigation_msgs/JointConstraint[] joint_constraints\n\
00288 arm_navigation_msgs/PositionConstraint[] position_constraints\n\
00289 arm_navigation_msgs/OrientationConstraint[] orientation_constraints\n\
00290 arm_navigation_msgs/VisibilityConstraint[] visibility_constraints\n\
00291 \n\
00292 ================================================================================\n\
00293 MSG: arm_navigation_msgs/JointConstraint\n\
00294 # Constrain the position of a joint to be within a certain bound\n\
00295 string joint_name\n\
00296 \n\
00297 # the bound to be achieved is [position - tolerance_below, position + tolerance_above]\n\
00298 float64 position\n\
00299 float64 tolerance_above\n\
00300 float64 tolerance_below\n\
00301 \n\
00302 # A weighting factor for this constraint\n\
00303 float64 weight\n\
00304 ================================================================================\n\
00305 MSG: arm_navigation_msgs/PositionConstraint\n\
00306 # This message contains the definition of a position constraint.\n\
00307 Header header\n\
00308 \n\
00309 # The robot link this constraint refers to\n\
00310 string link_name\n\
00311 \n\
00312 # The offset (in the link frame) for the target point on the link we are planning for\n\
00313 geometry_msgs/Point target_point_offset\n\
00314 \n\
00315 # The nominal/target position for the point we are planning for\n\
00316 geometry_msgs/Point position\n\
00317 \n\
00318 # The shape of the bounded region that constrains the position of the end-effector\n\
00319 # This region is always centered at the position defined above\n\
00320 arm_navigation_msgs/Shape constraint_region_shape\n\
00321 \n\
00322 # The orientation of the bounded region that constrains the position of the end-effector. \n\
00323 # This allows the specification of non-axis aligned constraints\n\
00324 geometry_msgs/Quaternion constraint_region_orientation\n\
00325 \n\
00326 # Constraint weighting factor - a weight for this constraint\n\
00327 float64 weight\n\
00328 \n\
00329 ================================================================================\n\
00330 MSG: arm_navigation_msgs/Shape\n\
00331 byte SPHERE=0\n\
00332 byte BOX=1\n\
00333 byte CYLINDER=2\n\
00334 byte MESH=3\n\
00335 \n\
00336 byte type\n\
00337 \n\
00338 \n\
00339 #### define sphere, box, cylinder ####\n\
00340 # the origin of each shape is considered at the shape's center\n\
00341 \n\
00342 # for sphere\n\
00343 # radius := dimensions[0]\n\
00344 \n\
00345 # for cylinder\n\
00346 # radius := dimensions[0]\n\
00347 # length := dimensions[1]\n\
00348 # the length is along the Z axis\n\
00349 \n\
00350 # for box\n\
00351 # size_x := dimensions[0]\n\
00352 # size_y := dimensions[1]\n\
00353 # size_z := dimensions[2]\n\
00354 float64[] dimensions\n\
00355 \n\
00356 \n\
00357 #### define mesh ####\n\
00358 \n\
00359 # list of triangles; triangle k is defined by tre vertices located\n\
00360 # at indices triangles[3k], triangles[3k+1], triangles[3k+2]\n\
00361 int32[] triangles\n\
00362 geometry_msgs/Point[] vertices\n\
00363 \n\
00364 ================================================================================\n\
00365 MSG: arm_navigation_msgs/OrientationConstraint\n\
00366 # This message contains the definition of an orientation constraint.\n\
00367 Header header\n\
00368 \n\
00369 # The robot link this constraint refers to\n\
00370 string link_name\n\
00371 \n\
00372 # The type of the constraint\n\
00373 int32 type\n\
00374 int32 LINK_FRAME=0\n\
00375 int32 HEADER_FRAME=1\n\
00376 \n\
00377 # The desired orientation of the robot link specified as a quaternion\n\
00378 geometry_msgs/Quaternion orientation\n\
00379 \n\
00380 # optional RPY error tolerances specified if \n\
00381 float64 absolute_roll_tolerance\n\
00382 float64 absolute_pitch_tolerance\n\
00383 float64 absolute_yaw_tolerance\n\
00384 \n\
00385 # Constraint weighting factor - a weight for this constraint\n\
00386 float64 weight\n\
00387 \n\
00388 ================================================================================\n\
00389 MSG: arm_navigation_msgs/VisibilityConstraint\n\
00390 # This message contains the definition of a visibility constraint.\n\
00391 Header header\n\
00392 \n\
00393 # The point stamped target that needs to be kept within view of the sensor\n\
00394 geometry_msgs/PointStamped target\n\
00395 \n\
00396 # The local pose of the frame in which visibility is to be maintained\n\
00397 # The frame id should represent the robot link to which the sensor is attached\n\
00398 # The visual axis of the sensor is assumed to be along the X axis of this frame\n\
00399 geometry_msgs/PoseStamped sensor_pose\n\
00400 \n\
00401 # The deviation (in radians) that will be tolerated\n\
00402 # Constraint error will be measured as the solid angle between the \n\
00403 # X axis of the frame defined above and the vector between the origin \n\
00404 # of the frame defined above and the target location\n\
00405 float64 absolute_tolerance\n\
00406 \n\
00407 \n\
00408 ================================================================================\n\
00409 MSG: geometry_msgs/PointStamped\n\
00410 # This represents a Point with reference coordinate frame and timestamp\n\
00411 Header header\n\
00412 Point point\n\
00413 \n\
00414 ================================================================================\n\
00415 MSG: geometry_msgs/PoseStamped\n\
00416 # A Pose with reference coordinate frame and timestamp\n\
00417 Header header\n\
00418 Pose pose\n\
00419 \n\
00420 ";
00421 }
00422
00423 static const char* value(const ::arm_navigation_msgs::GetStateValidityRequest_<ContainerAllocator> &) { return value(); }
00424 };
00425
00426 }
00427 }
00428
00429
00430 namespace ros
00431 {
00432 namespace message_traits
00433 {
00434 template<class ContainerAllocator> struct IsMessage< ::arm_navigation_msgs::GetStateValidityResponse_<ContainerAllocator> > : public TrueType {};
00435 template<class ContainerAllocator> struct IsMessage< ::arm_navigation_msgs::GetStateValidityResponse_<ContainerAllocator> const> : public TrueType {};
00436 template<class ContainerAllocator>
00437 struct MD5Sum< ::arm_navigation_msgs::GetStateValidityResponse_<ContainerAllocator> > {
00438 static const char* value()
00439 {
00440 return "3229301226a0605e3ffc9dfdaeac662f";
00441 }
00442
00443 static const char* value(const ::arm_navigation_msgs::GetStateValidityResponse_<ContainerAllocator> &) { return value(); }
00444 static const uint64_t static_value1 = 0x3229301226a0605eULL;
00445 static const uint64_t static_value2 = 0x3ffc9dfdaeac662fULL;
00446 };
00447
00448 template<class ContainerAllocator>
00449 struct DataType< ::arm_navigation_msgs::GetStateValidityResponse_<ContainerAllocator> > {
00450 static const char* value()
00451 {
00452 return "arm_navigation_msgs/GetStateValidityResponse";
00453 }
00454
00455 static const char* value(const ::arm_navigation_msgs::GetStateValidityResponse_<ContainerAllocator> &) { return value(); }
00456 };
00457
00458 template<class ContainerAllocator>
00459 struct Definition< ::arm_navigation_msgs::GetStateValidityResponse_<ContainerAllocator> > {
00460 static const char* value()
00461 {
00462 return "\n\
00463 \n\
00464 \n\
00465 \n\
00466 arm_navigation_msgs/ArmNavigationErrorCodes error_code\n\
00467 \n\
00468 \n\
00469 arm_navigation_msgs/ContactInformation[] contacts\n\
00470 \n\
00471 \n\
00472 ================================================================================\n\
00473 MSG: arm_navigation_msgs/ArmNavigationErrorCodes\n\
00474 int32 val\n\
00475 \n\
00476 # overall behavior\n\
00477 int32 PLANNING_FAILED=-1\n\
00478 int32 SUCCESS=1\n\
00479 int32 TIMED_OUT=-2\n\
00480 \n\
00481 # start state errors\n\
00482 int32 START_STATE_IN_COLLISION=-3\n\
00483 int32 START_STATE_VIOLATES_PATH_CONSTRAINTS=-4\n\
00484 \n\
00485 # goal errors\n\
00486 int32 GOAL_IN_COLLISION=-5\n\
00487 int32 GOAL_VIOLATES_PATH_CONSTRAINTS=-6\n\
00488 \n\
00489 # robot state\n\
00490 int32 INVALID_ROBOT_STATE=-7\n\
00491 int32 INCOMPLETE_ROBOT_STATE=-8\n\
00492 \n\
00493 # planning request errors\n\
00494 int32 INVALID_PLANNER_ID=-9\n\
00495 int32 INVALID_NUM_PLANNING_ATTEMPTS=-10\n\
00496 int32 INVALID_ALLOWED_PLANNING_TIME=-11\n\
00497 int32 INVALID_GROUP_NAME=-12\n\
00498 int32 INVALID_GOAL_JOINT_CONSTRAINTS=-13\n\
00499 int32 INVALID_GOAL_POSITION_CONSTRAINTS=-14\n\
00500 int32 INVALID_GOAL_ORIENTATION_CONSTRAINTS=-15\n\
00501 int32 INVALID_PATH_JOINT_CONSTRAINTS=-16\n\
00502 int32 INVALID_PATH_POSITION_CONSTRAINTS=-17\n\
00503 int32 INVALID_PATH_ORIENTATION_CONSTRAINTS=-18\n\
00504 \n\
00505 # state/trajectory monitor errors\n\
00506 int32 INVALID_TRAJECTORY=-19\n\
00507 int32 INVALID_INDEX=-20\n\
00508 int32 JOINT_LIMITS_VIOLATED=-21\n\
00509 int32 PATH_CONSTRAINTS_VIOLATED=-22\n\
00510 int32 COLLISION_CONSTRAINTS_VIOLATED=-23\n\
00511 int32 GOAL_CONSTRAINTS_VIOLATED=-24\n\
00512 int32 JOINTS_NOT_MOVING=-25\n\
00513 int32 TRAJECTORY_CONTROLLER_FAILED=-26\n\
00514 \n\
00515 # system errors\n\
00516 int32 FRAME_TRANSFORM_FAILURE=-27\n\
00517 int32 COLLISION_CHECKING_UNAVAILABLE=-28\n\
00518 int32 ROBOT_STATE_STALE=-29\n\
00519 int32 SENSOR_INFO_STALE=-30\n\
00520 \n\
00521 # kinematics errors\n\
00522 int32 NO_IK_SOLUTION=-31\n\
00523 int32 INVALID_LINK_NAME=-32\n\
00524 int32 IK_LINK_IN_COLLISION=-33\n\
00525 int32 NO_FK_SOLUTION=-34\n\
00526 int32 KINEMATICS_STATE_IN_COLLISION=-35\n\
00527 \n\
00528 # general errors\n\
00529 int32 INVALID_TIMEOUT=-36\n\
00530 \n\
00531 \n\
00532 ================================================================================\n\
00533 MSG: arm_navigation_msgs/ContactInformation\n\
00534 # Standard ROS header contains information \n\
00535 # about the frame in which this \n\
00536 # contact is specified\n\
00537 Header header\n\
00538 \n\
00539 # Position of the contact point\n\
00540 geometry_msgs/Point position\n\
00541 \n\
00542 # Normal corresponding to the contact point\n\
00543 geometry_msgs/Vector3 normal \n\
00544 \n\
00545 # Depth of contact point\n\
00546 float64 depth\n\
00547 \n\
00548 # Name of the first body that is in contact\n\
00549 # This could be a link or a namespace that represents a body\n\
00550 string contact_body_1\n\
00551 string attached_body_1\n\
00552 uint32 body_type_1\n\
00553 \n\
00554 # Name of the second body that is in contact\n\
00555 # This could be a link or a namespace that represents a body\n\
00556 string contact_body_2\n\
00557 string attached_body_2\n\
00558 uint32 body_type_2\n\
00559 \n\
00560 uint32 ROBOT_LINK=0\n\
00561 uint32 OBJECT=1\n\
00562 uint32 ATTACHED_BODY=2\n\
00563 ================================================================================\n\
00564 MSG: std_msgs/Header\n\
00565 # Standard metadata for higher-level stamped data types.\n\
00566 # This is generally used to communicate timestamped data \n\
00567 # in a particular coordinate frame.\n\
00568 # \n\
00569 # sequence ID: consecutively increasing ID \n\
00570 uint32 seq\n\
00571 #Two-integer timestamp that is expressed as:\n\
00572 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00573 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00574 # time-handling sugar is provided by the client library\n\
00575 time stamp\n\
00576 #Frame this data is associated with\n\
00577 # 0: no frame\n\
00578 # 1: global frame\n\
00579 string frame_id\n\
00580 \n\
00581 ================================================================================\n\
00582 MSG: geometry_msgs/Point\n\
00583 # This contains the position of a point in free space\n\
00584 float64 x\n\
00585 float64 y\n\
00586 float64 z\n\
00587 \n\
00588 ================================================================================\n\
00589 MSG: geometry_msgs/Vector3\n\
00590 # This represents a vector in free space. \n\
00591 \n\
00592 float64 x\n\
00593 float64 y\n\
00594 float64 z\n\
00595 ";
00596 }
00597
00598 static const char* value(const ::arm_navigation_msgs::GetStateValidityResponse_<ContainerAllocator> &) { return value(); }
00599 };
00600
00601 }
00602 }
00603
00604 namespace ros
00605 {
00606 namespace serialization
00607 {
00608
00609 template<class ContainerAllocator> struct Serializer< ::arm_navigation_msgs::GetStateValidityRequest_<ContainerAllocator> >
00610 {
00611 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00612 {
00613 stream.next(m.robot_state);
00614 stream.next(m.check_collisions);
00615 stream.next(m.check_path_constraints);
00616 stream.next(m.check_goal_constraints);
00617 stream.next(m.check_joint_limits);
00618 stream.next(m.group_name);
00619 stream.next(m.path_constraints);
00620 stream.next(m.goal_constraints);
00621 }
00622
00623 ROS_DECLARE_ALLINONE_SERIALIZER;
00624 };
00625 }
00626 }
00627
00628
00629 namespace ros
00630 {
00631 namespace serialization
00632 {
00633
00634 template<class ContainerAllocator> struct Serializer< ::arm_navigation_msgs::GetStateValidityResponse_<ContainerAllocator> >
00635 {
00636 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00637 {
00638 stream.next(m.error_code);
00639 stream.next(m.contacts);
00640 }
00641
00642 ROS_DECLARE_ALLINONE_SERIALIZER;
00643 };
00644 }
00645 }
00646
00647 namespace ros
00648 {
00649 namespace service_traits
00650 {
00651 template<>
00652 struct MD5Sum<arm_navigation_msgs::GetStateValidity> {
00653 static const char* value()
00654 {
00655 return "05125b9572f64feb9a7f590a8674e9ee";
00656 }
00657
00658 static const char* value(const arm_navigation_msgs::GetStateValidity&) { return value(); }
00659 };
00660
00661 template<>
00662 struct DataType<arm_navigation_msgs::GetStateValidity> {
00663 static const char* value()
00664 {
00665 return "arm_navigation_msgs/GetStateValidity";
00666 }
00667
00668 static const char* value(const arm_navigation_msgs::GetStateValidity&) { return value(); }
00669 };
00670
00671 template<class ContainerAllocator>
00672 struct MD5Sum<arm_navigation_msgs::GetStateValidityRequest_<ContainerAllocator> > {
00673 static const char* value()
00674 {
00675 return "05125b9572f64feb9a7f590a8674e9ee";
00676 }
00677
00678 static const char* value(const arm_navigation_msgs::GetStateValidityRequest_<ContainerAllocator> &) { return value(); }
00679 };
00680
00681 template<class ContainerAllocator>
00682 struct DataType<arm_navigation_msgs::GetStateValidityRequest_<ContainerAllocator> > {
00683 static const char* value()
00684 {
00685 return "arm_navigation_msgs/GetStateValidity";
00686 }
00687
00688 static const char* value(const arm_navigation_msgs::GetStateValidityRequest_<ContainerAllocator> &) { return value(); }
00689 };
00690
00691 template<class ContainerAllocator>
00692 struct MD5Sum<arm_navigation_msgs::GetStateValidityResponse_<ContainerAllocator> > {
00693 static const char* value()
00694 {
00695 return "05125b9572f64feb9a7f590a8674e9ee";
00696 }
00697
00698 static const char* value(const arm_navigation_msgs::GetStateValidityResponse_<ContainerAllocator> &) { return value(); }
00699 };
00700
00701 template<class ContainerAllocator>
00702 struct DataType<arm_navigation_msgs::GetStateValidityResponse_<ContainerAllocator> > {
00703 static const char* value()
00704 {
00705 return "arm_navigation_msgs/GetStateValidity";
00706 }
00707
00708 static const char* value(const arm_navigation_msgs::GetStateValidityResponse_<ContainerAllocator> &) { return value(); }
00709 };
00710
00711 }
00712 }
00713
00714 #endif // ARM_NAVIGATION_MSGS_SERVICE_GETSTATEVALIDITY_H
00715