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 private:
00083 static const char* __s_getDataType_() { return "arm_navigation_msgs/GetStateValidityRequest"; }
00084 public:
00085 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00086
00087 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00088
00089 private:
00090 static const char* __s_getMD5Sum_() { return "fe05d730cc03ecb8a8dff34774a12c59"; }
00091 public:
00092 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00093
00094 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00095
00096 private:
00097 static const char* __s_getServerMD5Sum_() { return "05125b9572f64feb9a7f590a8674e9ee"; }
00098 public:
00099 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); }
00100
00101 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); }
00102
00103 private:
00104 static const char* __s_getMessageDefinition_() { return "\n\
00105 \n\
00106 arm_navigation_msgs/RobotState robot_state\n\
00107 \n\
00108 \n\
00109 bool check_collisions\n\
00110 \n\
00111 \n\
00112 bool check_path_constraints\n\
00113 \n\
00114 \n\
00115 bool check_goal_constraints\n\
00116 \n\
00117 \n\
00118 bool check_joint_limits\n\
00119 \n\
00120 \n\
00121 string group_name\n\
00122 \n\
00123 \n\
00124 \n\
00125 \n\
00126 arm_navigation_msgs/Constraints path_constraints\n\
00127 \n\
00128 \n\
00129 \n\
00130 \n\
00131 arm_navigation_msgs/Constraints goal_constraints\n\
00132 \n\
00133 \n\
00134 ================================================================================\n\
00135 MSG: arm_navigation_msgs/RobotState\n\
00136 # This message contains information about the robot state, i.e. the positions of its joints and links\n\
00137 sensor_msgs/JointState joint_state\n\
00138 arm_navigation_msgs/MultiDOFJointState multi_dof_joint_state\n\
00139 \n\
00140 ================================================================================\n\
00141 MSG: sensor_msgs/JointState\n\
00142 # This is a message that holds data to describe the state of a set of torque controlled joints. \n\
00143 #\n\
00144 # The state of each joint (revolute or prismatic) is defined by:\n\
00145 # * the position of the joint (rad or m),\n\
00146 # * the velocity of the joint (rad/s or m/s) and \n\
00147 # * the effort that is applied in the joint (Nm or N).\n\
00148 #\n\
00149 # Each joint is uniquely identified by its name\n\
00150 # The header specifies the time at which the joint states were recorded. All the joint states\n\
00151 # in one message have to be recorded at the same time.\n\
00152 #\n\
00153 # This message consists of a multiple arrays, one for each part of the joint state. \n\
00154 # The goal is to make each of the fields optional. When e.g. your joints have no\n\
00155 # effort associated with them, you can leave the effort array empty. \n\
00156 #\n\
00157 # All arrays in this message should have the same size, or be empty.\n\
00158 # This is the only way to uniquely associate the joint name with the correct\n\
00159 # states.\n\
00160 \n\
00161 \n\
00162 Header header\n\
00163 \n\
00164 string[] name\n\
00165 float64[] position\n\
00166 float64[] velocity\n\
00167 float64[] effort\n\
00168 \n\
00169 ================================================================================\n\
00170 MSG: std_msgs/Header\n\
00171 # Standard metadata for higher-level stamped data types.\n\
00172 # This is generally used to communicate timestamped data \n\
00173 # in a particular coordinate frame.\n\
00174 # \n\
00175 # sequence ID: consecutively increasing ID \n\
00176 uint32 seq\n\
00177 #Two-integer timestamp that is expressed as:\n\
00178 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00179 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00180 # time-handling sugar is provided by the client library\n\
00181 time stamp\n\
00182 #Frame this data is associated with\n\
00183 # 0: no frame\n\
00184 # 1: global frame\n\
00185 string frame_id\n\
00186 \n\
00187 ================================================================================\n\
00188 MSG: arm_navigation_msgs/MultiDOFJointState\n\
00189 #A representation of a multi-dof joint state\n\
00190 time stamp\n\
00191 string[] joint_names\n\
00192 string[] frame_ids\n\
00193 string[] child_frame_ids\n\
00194 geometry_msgs/Pose[] poses\n\
00195 \n\
00196 ================================================================================\n\
00197 MSG: geometry_msgs/Pose\n\
00198 # A representation of pose in free space, composed of postion and orientation. \n\
00199 Point position\n\
00200 Quaternion orientation\n\
00201 \n\
00202 ================================================================================\n\
00203 MSG: geometry_msgs/Point\n\
00204 # This contains the position of a point in free space\n\
00205 float64 x\n\
00206 float64 y\n\
00207 float64 z\n\
00208 \n\
00209 ================================================================================\n\
00210 MSG: geometry_msgs/Quaternion\n\
00211 # This represents an orientation in free space in quaternion form.\n\
00212 \n\
00213 float64 x\n\
00214 float64 y\n\
00215 float64 z\n\
00216 float64 w\n\
00217 \n\
00218 ================================================================================\n\
00219 MSG: arm_navigation_msgs/Constraints\n\
00220 # This message contains a list of motion planning constraints.\n\
00221 \n\
00222 arm_navigation_msgs/JointConstraint[] joint_constraints\n\
00223 arm_navigation_msgs/PositionConstraint[] position_constraints\n\
00224 arm_navigation_msgs/OrientationConstraint[] orientation_constraints\n\
00225 arm_navigation_msgs/VisibilityConstraint[] visibility_constraints\n\
00226 \n\
00227 ================================================================================\n\
00228 MSG: arm_navigation_msgs/JointConstraint\n\
00229 # Constrain the position of a joint to be within a certain bound\n\
00230 string joint_name\n\
00231 \n\
00232 # the bound to be achieved is [position - tolerance_below, position + tolerance_above]\n\
00233 float64 position\n\
00234 float64 tolerance_above\n\
00235 float64 tolerance_below\n\
00236 \n\
00237 # A weighting factor for this constraint\n\
00238 float64 weight\n\
00239 ================================================================================\n\
00240 MSG: arm_navigation_msgs/PositionConstraint\n\
00241 # This message contains the definition of a position constraint.\n\
00242 Header header\n\
00243 \n\
00244 # The robot link this constraint refers to\n\
00245 string link_name\n\
00246 \n\
00247 # The offset (in the link frame) for the target point on the link we are planning for\n\
00248 geometry_msgs/Point target_point_offset\n\
00249 \n\
00250 # The nominal/target position for the point we are planning for\n\
00251 geometry_msgs/Point position\n\
00252 \n\
00253 # The shape of the bounded region that constrains the position of the end-effector\n\
00254 # This region is always centered at the position defined above\n\
00255 arm_navigation_msgs/Shape constraint_region_shape\n\
00256 \n\
00257 # The orientation of the bounded region that constrains the position of the end-effector. \n\
00258 # This allows the specification of non-axis aligned constraints\n\
00259 geometry_msgs/Quaternion constraint_region_orientation\n\
00260 \n\
00261 # Constraint weighting factor - a weight for this constraint\n\
00262 float64 weight\n\
00263 \n\
00264 ================================================================================\n\
00265 MSG: arm_navigation_msgs/Shape\n\
00266 byte SPHERE=0\n\
00267 byte BOX=1\n\
00268 byte CYLINDER=2\n\
00269 byte MESH=3\n\
00270 \n\
00271 byte type\n\
00272 \n\
00273 \n\
00274 #### define sphere, box, cylinder ####\n\
00275 # the origin of each shape is considered at the shape's center\n\
00276 \n\
00277 # for sphere\n\
00278 # radius := dimensions[0]\n\
00279 \n\
00280 # for cylinder\n\
00281 # radius := dimensions[0]\n\
00282 # length := dimensions[1]\n\
00283 # the length is along the Z axis\n\
00284 \n\
00285 # for box\n\
00286 # size_x := dimensions[0]\n\
00287 # size_y := dimensions[1]\n\
00288 # size_z := dimensions[2]\n\
00289 float64[] dimensions\n\
00290 \n\
00291 \n\
00292 #### define mesh ####\n\
00293 \n\
00294 # list of triangles; triangle k is defined by tre vertices located\n\
00295 # at indices triangles[3k], triangles[3k+1], triangles[3k+2]\n\
00296 int32[] triangles\n\
00297 geometry_msgs/Point[] vertices\n\
00298 \n\
00299 ================================================================================\n\
00300 MSG: arm_navigation_msgs/OrientationConstraint\n\
00301 # This message contains the definition of an orientation constraint.\n\
00302 Header header\n\
00303 \n\
00304 # The robot link this constraint refers to\n\
00305 string link_name\n\
00306 \n\
00307 # The type of the constraint\n\
00308 int32 type\n\
00309 int32 LINK_FRAME=0\n\
00310 int32 HEADER_FRAME=1\n\
00311 \n\
00312 # The desired orientation of the robot link specified as a quaternion\n\
00313 geometry_msgs/Quaternion orientation\n\
00314 \n\
00315 # optional RPY error tolerances specified if \n\
00316 float64 absolute_roll_tolerance\n\
00317 float64 absolute_pitch_tolerance\n\
00318 float64 absolute_yaw_tolerance\n\
00319 \n\
00320 # Constraint weighting factor - a weight for this constraint\n\
00321 float64 weight\n\
00322 \n\
00323 ================================================================================\n\
00324 MSG: arm_navigation_msgs/VisibilityConstraint\n\
00325 # This message contains the definition of a visibility constraint.\n\
00326 Header header\n\
00327 \n\
00328 # The point stamped target that needs to be kept within view of the sensor\n\
00329 geometry_msgs/PointStamped target\n\
00330 \n\
00331 # The local pose of the frame in which visibility is to be maintained\n\
00332 # The frame id should represent the robot link to which the sensor is attached\n\
00333 # The visual axis of the sensor is assumed to be along the X axis of this frame\n\
00334 geometry_msgs/PoseStamped sensor_pose\n\
00335 \n\
00336 # The deviation (in radians) that will be tolerated\n\
00337 # Constraint error will be measured as the solid angle between the \n\
00338 # X axis of the frame defined above and the vector between the origin \n\
00339 # of the frame defined above and the target location\n\
00340 float64 absolute_tolerance\n\
00341 \n\
00342 \n\
00343 ================================================================================\n\
00344 MSG: geometry_msgs/PointStamped\n\
00345 # This represents a Point with reference coordinate frame and timestamp\n\
00346 Header header\n\
00347 Point point\n\
00348 \n\
00349 ================================================================================\n\
00350 MSG: geometry_msgs/PoseStamped\n\
00351 # A Pose with reference coordinate frame and timestamp\n\
00352 Header header\n\
00353 Pose pose\n\
00354 \n\
00355 "; }
00356 public:
00357 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00358
00359 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00360
00361 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00362 {
00363 ros::serialization::OStream stream(write_ptr, 1000000000);
00364 ros::serialization::serialize(stream, robot_state);
00365 ros::serialization::serialize(stream, check_collisions);
00366 ros::serialization::serialize(stream, check_path_constraints);
00367 ros::serialization::serialize(stream, check_goal_constraints);
00368 ros::serialization::serialize(stream, check_joint_limits);
00369 ros::serialization::serialize(stream, group_name);
00370 ros::serialization::serialize(stream, path_constraints);
00371 ros::serialization::serialize(stream, goal_constraints);
00372 return stream.getData();
00373 }
00374
00375 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00376 {
00377 ros::serialization::IStream stream(read_ptr, 1000000000);
00378 ros::serialization::deserialize(stream, robot_state);
00379 ros::serialization::deserialize(stream, check_collisions);
00380 ros::serialization::deserialize(stream, check_path_constraints);
00381 ros::serialization::deserialize(stream, check_goal_constraints);
00382 ros::serialization::deserialize(stream, check_joint_limits);
00383 ros::serialization::deserialize(stream, group_name);
00384 ros::serialization::deserialize(stream, path_constraints);
00385 ros::serialization::deserialize(stream, goal_constraints);
00386 return stream.getData();
00387 }
00388
00389 ROS_DEPRECATED virtual uint32_t serializationLength() const
00390 {
00391 uint32_t size = 0;
00392 size += ros::serialization::serializationLength(robot_state);
00393 size += ros::serialization::serializationLength(check_collisions);
00394 size += ros::serialization::serializationLength(check_path_constraints);
00395 size += ros::serialization::serializationLength(check_goal_constraints);
00396 size += ros::serialization::serializationLength(check_joint_limits);
00397 size += ros::serialization::serializationLength(group_name);
00398 size += ros::serialization::serializationLength(path_constraints);
00399 size += ros::serialization::serializationLength(goal_constraints);
00400 return size;
00401 }
00402
00403 typedef boost::shared_ptr< ::arm_navigation_msgs::GetStateValidityRequest_<ContainerAllocator> > Ptr;
00404 typedef boost::shared_ptr< ::arm_navigation_msgs::GetStateValidityRequest_<ContainerAllocator> const> ConstPtr;
00405 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00406 };
00407 typedef ::arm_navigation_msgs::GetStateValidityRequest_<std::allocator<void> > GetStateValidityRequest;
00408
00409 typedef boost::shared_ptr< ::arm_navigation_msgs::GetStateValidityRequest> GetStateValidityRequestPtr;
00410 typedef boost::shared_ptr< ::arm_navigation_msgs::GetStateValidityRequest const> GetStateValidityRequestConstPtr;
00411
00412
00413 template <class ContainerAllocator>
00414 struct GetStateValidityResponse_ {
00415 typedef GetStateValidityResponse_<ContainerAllocator> Type;
00416
00417 GetStateValidityResponse_()
00418 : error_code()
00419 , contacts()
00420 {
00421 }
00422
00423 GetStateValidityResponse_(const ContainerAllocator& _alloc)
00424 : error_code(_alloc)
00425 , contacts(_alloc)
00426 {
00427 }
00428
00429 typedef ::arm_navigation_msgs::ArmNavigationErrorCodes_<ContainerAllocator> _error_code_type;
00430 ::arm_navigation_msgs::ArmNavigationErrorCodes_<ContainerAllocator> error_code;
00431
00432 typedef std::vector< ::arm_navigation_msgs::ContactInformation_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::arm_navigation_msgs::ContactInformation_<ContainerAllocator> >::other > _contacts_type;
00433 std::vector< ::arm_navigation_msgs::ContactInformation_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::arm_navigation_msgs::ContactInformation_<ContainerAllocator> >::other > contacts;
00434
00435
00436 ROS_DEPRECATED uint32_t get_contacts_size() const { return (uint32_t)contacts.size(); }
00437 ROS_DEPRECATED void set_contacts_size(uint32_t size) { contacts.resize((size_t)size); }
00438 ROS_DEPRECATED void get_contacts_vec(std::vector< ::arm_navigation_msgs::ContactInformation_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::arm_navigation_msgs::ContactInformation_<ContainerAllocator> >::other > & vec) const { vec = this->contacts; }
00439 ROS_DEPRECATED void set_contacts_vec(const std::vector< ::arm_navigation_msgs::ContactInformation_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::arm_navigation_msgs::ContactInformation_<ContainerAllocator> >::other > & vec) { this->contacts = vec; }
00440 private:
00441 static const char* __s_getDataType_() { return "arm_navigation_msgs/GetStateValidityResponse"; }
00442 public:
00443 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00444
00445 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00446
00447 private:
00448 static const char* __s_getMD5Sum_() { return "3229301226a0605e3ffc9dfdaeac662f"; }
00449 public:
00450 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00451
00452 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00453
00454 private:
00455 static const char* __s_getServerMD5Sum_() { return "05125b9572f64feb9a7f590a8674e9ee"; }
00456 public:
00457 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); }
00458
00459 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); }
00460
00461 private:
00462 static const char* __s_getMessageDefinition_() { 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 public:
00597 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00598
00599 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00600
00601 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00602 {
00603 ros::serialization::OStream stream(write_ptr, 1000000000);
00604 ros::serialization::serialize(stream, error_code);
00605 ros::serialization::serialize(stream, contacts);
00606 return stream.getData();
00607 }
00608
00609 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00610 {
00611 ros::serialization::IStream stream(read_ptr, 1000000000);
00612 ros::serialization::deserialize(stream, error_code);
00613 ros::serialization::deserialize(stream, contacts);
00614 return stream.getData();
00615 }
00616
00617 ROS_DEPRECATED virtual uint32_t serializationLength() const
00618 {
00619 uint32_t size = 0;
00620 size += ros::serialization::serializationLength(error_code);
00621 size += ros::serialization::serializationLength(contacts);
00622 return size;
00623 }
00624
00625 typedef boost::shared_ptr< ::arm_navigation_msgs::GetStateValidityResponse_<ContainerAllocator> > Ptr;
00626 typedef boost::shared_ptr< ::arm_navigation_msgs::GetStateValidityResponse_<ContainerAllocator> const> ConstPtr;
00627 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00628 };
00629 typedef ::arm_navigation_msgs::GetStateValidityResponse_<std::allocator<void> > GetStateValidityResponse;
00630
00631 typedef boost::shared_ptr< ::arm_navigation_msgs::GetStateValidityResponse> GetStateValidityResponsePtr;
00632 typedef boost::shared_ptr< ::arm_navigation_msgs::GetStateValidityResponse const> GetStateValidityResponseConstPtr;
00633
00634 struct GetStateValidity
00635 {
00636
00637 typedef GetStateValidityRequest Request;
00638 typedef GetStateValidityResponse Response;
00639 Request request;
00640 Response response;
00641
00642 typedef Request RequestType;
00643 typedef Response ResponseType;
00644 };
00645 }
00646
00647 namespace ros
00648 {
00649 namespace message_traits
00650 {
00651 template<class ContainerAllocator> struct IsMessage< ::arm_navigation_msgs::GetStateValidityRequest_<ContainerAllocator> > : public TrueType {};
00652 template<class ContainerAllocator> struct IsMessage< ::arm_navigation_msgs::GetStateValidityRequest_<ContainerAllocator> const> : public TrueType {};
00653 template<class ContainerAllocator>
00654 struct MD5Sum< ::arm_navigation_msgs::GetStateValidityRequest_<ContainerAllocator> > {
00655 static const char* value()
00656 {
00657 return "fe05d730cc03ecb8a8dff34774a12c59";
00658 }
00659
00660 static const char* value(const ::arm_navigation_msgs::GetStateValidityRequest_<ContainerAllocator> &) { return value(); }
00661 static const uint64_t static_value1 = 0xfe05d730cc03ecb8ULL;
00662 static const uint64_t static_value2 = 0xa8dff34774a12c59ULL;
00663 };
00664
00665 template<class ContainerAllocator>
00666 struct DataType< ::arm_navigation_msgs::GetStateValidityRequest_<ContainerAllocator> > {
00667 static const char* value()
00668 {
00669 return "arm_navigation_msgs/GetStateValidityRequest";
00670 }
00671
00672 static const char* value(const ::arm_navigation_msgs::GetStateValidityRequest_<ContainerAllocator> &) { return value(); }
00673 };
00674
00675 template<class ContainerAllocator>
00676 struct Definition< ::arm_navigation_msgs::GetStateValidityRequest_<ContainerAllocator> > {
00677 static const char* value()
00678 {
00679 return "\n\
00680 \n\
00681 arm_navigation_msgs/RobotState robot_state\n\
00682 \n\
00683 \n\
00684 bool check_collisions\n\
00685 \n\
00686 \n\
00687 bool check_path_constraints\n\
00688 \n\
00689 \n\
00690 bool check_goal_constraints\n\
00691 \n\
00692 \n\
00693 bool check_joint_limits\n\
00694 \n\
00695 \n\
00696 string group_name\n\
00697 \n\
00698 \n\
00699 \n\
00700 \n\
00701 arm_navigation_msgs/Constraints path_constraints\n\
00702 \n\
00703 \n\
00704 \n\
00705 \n\
00706 arm_navigation_msgs/Constraints goal_constraints\n\
00707 \n\
00708 \n\
00709 ================================================================================\n\
00710 MSG: arm_navigation_msgs/RobotState\n\
00711 # This message contains information about the robot state, i.e. the positions of its joints and links\n\
00712 sensor_msgs/JointState joint_state\n\
00713 arm_navigation_msgs/MultiDOFJointState multi_dof_joint_state\n\
00714 \n\
00715 ================================================================================\n\
00716 MSG: sensor_msgs/JointState\n\
00717 # This is a message that holds data to describe the state of a set of torque controlled joints. \n\
00718 #\n\
00719 # The state of each joint (revolute or prismatic) is defined by:\n\
00720 # * the position of the joint (rad or m),\n\
00721 # * the velocity of the joint (rad/s or m/s) and \n\
00722 # * the effort that is applied in the joint (Nm or N).\n\
00723 #\n\
00724 # Each joint is uniquely identified by its name\n\
00725 # The header specifies the time at which the joint states were recorded. All the joint states\n\
00726 # in one message have to be recorded at the same time.\n\
00727 #\n\
00728 # This message consists of a multiple arrays, one for each part of the joint state. \n\
00729 # The goal is to make each of the fields optional. When e.g. your joints have no\n\
00730 # effort associated with them, you can leave the effort array empty. \n\
00731 #\n\
00732 # All arrays in this message should have the same size, or be empty.\n\
00733 # This is the only way to uniquely associate the joint name with the correct\n\
00734 # states.\n\
00735 \n\
00736 \n\
00737 Header header\n\
00738 \n\
00739 string[] name\n\
00740 float64[] position\n\
00741 float64[] velocity\n\
00742 float64[] effort\n\
00743 \n\
00744 ================================================================================\n\
00745 MSG: std_msgs/Header\n\
00746 # Standard metadata for higher-level stamped data types.\n\
00747 # This is generally used to communicate timestamped data \n\
00748 # in a particular coordinate frame.\n\
00749 # \n\
00750 # sequence ID: consecutively increasing ID \n\
00751 uint32 seq\n\
00752 #Two-integer timestamp that is expressed as:\n\
00753 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00754 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00755 # time-handling sugar is provided by the client library\n\
00756 time stamp\n\
00757 #Frame this data is associated with\n\
00758 # 0: no frame\n\
00759 # 1: global frame\n\
00760 string frame_id\n\
00761 \n\
00762 ================================================================================\n\
00763 MSG: arm_navigation_msgs/MultiDOFJointState\n\
00764 #A representation of a multi-dof joint state\n\
00765 time stamp\n\
00766 string[] joint_names\n\
00767 string[] frame_ids\n\
00768 string[] child_frame_ids\n\
00769 geometry_msgs/Pose[] poses\n\
00770 \n\
00771 ================================================================================\n\
00772 MSG: geometry_msgs/Pose\n\
00773 # A representation of pose in free space, composed of postion and orientation. \n\
00774 Point position\n\
00775 Quaternion orientation\n\
00776 \n\
00777 ================================================================================\n\
00778 MSG: geometry_msgs/Point\n\
00779 # This contains the position of a point in free space\n\
00780 float64 x\n\
00781 float64 y\n\
00782 float64 z\n\
00783 \n\
00784 ================================================================================\n\
00785 MSG: geometry_msgs/Quaternion\n\
00786 # This represents an orientation in free space in quaternion form.\n\
00787 \n\
00788 float64 x\n\
00789 float64 y\n\
00790 float64 z\n\
00791 float64 w\n\
00792 \n\
00793 ================================================================================\n\
00794 MSG: arm_navigation_msgs/Constraints\n\
00795 # This message contains a list of motion planning constraints.\n\
00796 \n\
00797 arm_navigation_msgs/JointConstraint[] joint_constraints\n\
00798 arm_navigation_msgs/PositionConstraint[] position_constraints\n\
00799 arm_navigation_msgs/OrientationConstraint[] orientation_constraints\n\
00800 arm_navigation_msgs/VisibilityConstraint[] visibility_constraints\n\
00801 \n\
00802 ================================================================================\n\
00803 MSG: arm_navigation_msgs/JointConstraint\n\
00804 # Constrain the position of a joint to be within a certain bound\n\
00805 string joint_name\n\
00806 \n\
00807 # the bound to be achieved is [position - tolerance_below, position + tolerance_above]\n\
00808 float64 position\n\
00809 float64 tolerance_above\n\
00810 float64 tolerance_below\n\
00811 \n\
00812 # A weighting factor for this constraint\n\
00813 float64 weight\n\
00814 ================================================================================\n\
00815 MSG: arm_navigation_msgs/PositionConstraint\n\
00816 # This message contains the definition of a position constraint.\n\
00817 Header header\n\
00818 \n\
00819 # The robot link this constraint refers to\n\
00820 string link_name\n\
00821 \n\
00822 # The offset (in the link frame) for the target point on the link we are planning for\n\
00823 geometry_msgs/Point target_point_offset\n\
00824 \n\
00825 # The nominal/target position for the point we are planning for\n\
00826 geometry_msgs/Point position\n\
00827 \n\
00828 # The shape of the bounded region that constrains the position of the end-effector\n\
00829 # This region is always centered at the position defined above\n\
00830 arm_navigation_msgs/Shape constraint_region_shape\n\
00831 \n\
00832 # The orientation of the bounded region that constrains the position of the end-effector. \n\
00833 # This allows the specification of non-axis aligned constraints\n\
00834 geometry_msgs/Quaternion constraint_region_orientation\n\
00835 \n\
00836 # Constraint weighting factor - a weight for this constraint\n\
00837 float64 weight\n\
00838 \n\
00839 ================================================================================\n\
00840 MSG: arm_navigation_msgs/Shape\n\
00841 byte SPHERE=0\n\
00842 byte BOX=1\n\
00843 byte CYLINDER=2\n\
00844 byte MESH=3\n\
00845 \n\
00846 byte type\n\
00847 \n\
00848 \n\
00849 #### define sphere, box, cylinder ####\n\
00850 # the origin of each shape is considered at the shape's center\n\
00851 \n\
00852 # for sphere\n\
00853 # radius := dimensions[0]\n\
00854 \n\
00855 # for cylinder\n\
00856 # radius := dimensions[0]\n\
00857 # length := dimensions[1]\n\
00858 # the length is along the Z axis\n\
00859 \n\
00860 # for box\n\
00861 # size_x := dimensions[0]\n\
00862 # size_y := dimensions[1]\n\
00863 # size_z := dimensions[2]\n\
00864 float64[] dimensions\n\
00865 \n\
00866 \n\
00867 #### define mesh ####\n\
00868 \n\
00869 # list of triangles; triangle k is defined by tre vertices located\n\
00870 # at indices triangles[3k], triangles[3k+1], triangles[3k+2]\n\
00871 int32[] triangles\n\
00872 geometry_msgs/Point[] vertices\n\
00873 \n\
00874 ================================================================================\n\
00875 MSG: arm_navigation_msgs/OrientationConstraint\n\
00876 # This message contains the definition of an orientation constraint.\n\
00877 Header header\n\
00878 \n\
00879 # The robot link this constraint refers to\n\
00880 string link_name\n\
00881 \n\
00882 # The type of the constraint\n\
00883 int32 type\n\
00884 int32 LINK_FRAME=0\n\
00885 int32 HEADER_FRAME=1\n\
00886 \n\
00887 # The desired orientation of the robot link specified as a quaternion\n\
00888 geometry_msgs/Quaternion orientation\n\
00889 \n\
00890 # optional RPY error tolerances specified if \n\
00891 float64 absolute_roll_tolerance\n\
00892 float64 absolute_pitch_tolerance\n\
00893 float64 absolute_yaw_tolerance\n\
00894 \n\
00895 # Constraint weighting factor - a weight for this constraint\n\
00896 float64 weight\n\
00897 \n\
00898 ================================================================================\n\
00899 MSG: arm_navigation_msgs/VisibilityConstraint\n\
00900 # This message contains the definition of a visibility constraint.\n\
00901 Header header\n\
00902 \n\
00903 # The point stamped target that needs to be kept within view of the sensor\n\
00904 geometry_msgs/PointStamped target\n\
00905 \n\
00906 # The local pose of the frame in which visibility is to be maintained\n\
00907 # The frame id should represent the robot link to which the sensor is attached\n\
00908 # The visual axis of the sensor is assumed to be along the X axis of this frame\n\
00909 geometry_msgs/PoseStamped sensor_pose\n\
00910 \n\
00911 # The deviation (in radians) that will be tolerated\n\
00912 # Constraint error will be measured as the solid angle between the \n\
00913 # X axis of the frame defined above and the vector between the origin \n\
00914 # of the frame defined above and the target location\n\
00915 float64 absolute_tolerance\n\
00916 \n\
00917 \n\
00918 ================================================================================\n\
00919 MSG: geometry_msgs/PointStamped\n\
00920 # This represents a Point with reference coordinate frame and timestamp\n\
00921 Header header\n\
00922 Point point\n\
00923 \n\
00924 ================================================================================\n\
00925 MSG: geometry_msgs/PoseStamped\n\
00926 # A Pose with reference coordinate frame and timestamp\n\
00927 Header header\n\
00928 Pose pose\n\
00929 \n\
00930 ";
00931 }
00932
00933 static const char* value(const ::arm_navigation_msgs::GetStateValidityRequest_<ContainerAllocator> &) { return value(); }
00934 };
00935
00936 }
00937 }
00938
00939
00940 namespace ros
00941 {
00942 namespace message_traits
00943 {
00944 template<class ContainerAllocator> struct IsMessage< ::arm_navigation_msgs::GetStateValidityResponse_<ContainerAllocator> > : public TrueType {};
00945 template<class ContainerAllocator> struct IsMessage< ::arm_navigation_msgs::GetStateValidityResponse_<ContainerAllocator> const> : public TrueType {};
00946 template<class ContainerAllocator>
00947 struct MD5Sum< ::arm_navigation_msgs::GetStateValidityResponse_<ContainerAllocator> > {
00948 static const char* value()
00949 {
00950 return "3229301226a0605e3ffc9dfdaeac662f";
00951 }
00952
00953 static const char* value(const ::arm_navigation_msgs::GetStateValidityResponse_<ContainerAllocator> &) { return value(); }
00954 static const uint64_t static_value1 = 0x3229301226a0605eULL;
00955 static const uint64_t static_value2 = 0x3ffc9dfdaeac662fULL;
00956 };
00957
00958 template<class ContainerAllocator>
00959 struct DataType< ::arm_navigation_msgs::GetStateValidityResponse_<ContainerAllocator> > {
00960 static const char* value()
00961 {
00962 return "arm_navigation_msgs/GetStateValidityResponse";
00963 }
00964
00965 static const char* value(const ::arm_navigation_msgs::GetStateValidityResponse_<ContainerAllocator> &) { return value(); }
00966 };
00967
00968 template<class ContainerAllocator>
00969 struct Definition< ::arm_navigation_msgs::GetStateValidityResponse_<ContainerAllocator> > {
00970 static const char* value()
00971 {
00972 return "\n\
00973 \n\
00974 \n\
00975 \n\
00976 arm_navigation_msgs/ArmNavigationErrorCodes error_code\n\
00977 \n\
00978 \n\
00979 arm_navigation_msgs/ContactInformation[] contacts\n\
00980 \n\
00981 \n\
00982 ================================================================================\n\
00983 MSG: arm_navigation_msgs/ArmNavigationErrorCodes\n\
00984 int32 val\n\
00985 \n\
00986 # overall behavior\n\
00987 int32 PLANNING_FAILED=-1\n\
00988 int32 SUCCESS=1\n\
00989 int32 TIMED_OUT=-2\n\
00990 \n\
00991 # start state errors\n\
00992 int32 START_STATE_IN_COLLISION=-3\n\
00993 int32 START_STATE_VIOLATES_PATH_CONSTRAINTS=-4\n\
00994 \n\
00995 # goal errors\n\
00996 int32 GOAL_IN_COLLISION=-5\n\
00997 int32 GOAL_VIOLATES_PATH_CONSTRAINTS=-6\n\
00998 \n\
00999 # robot state\n\
01000 int32 INVALID_ROBOT_STATE=-7\n\
01001 int32 INCOMPLETE_ROBOT_STATE=-8\n\
01002 \n\
01003 # planning request errors\n\
01004 int32 INVALID_PLANNER_ID=-9\n\
01005 int32 INVALID_NUM_PLANNING_ATTEMPTS=-10\n\
01006 int32 INVALID_ALLOWED_PLANNING_TIME=-11\n\
01007 int32 INVALID_GROUP_NAME=-12\n\
01008 int32 INVALID_GOAL_JOINT_CONSTRAINTS=-13\n\
01009 int32 INVALID_GOAL_POSITION_CONSTRAINTS=-14\n\
01010 int32 INVALID_GOAL_ORIENTATION_CONSTRAINTS=-15\n\
01011 int32 INVALID_PATH_JOINT_CONSTRAINTS=-16\n\
01012 int32 INVALID_PATH_POSITION_CONSTRAINTS=-17\n\
01013 int32 INVALID_PATH_ORIENTATION_CONSTRAINTS=-18\n\
01014 \n\
01015 # state/trajectory monitor errors\n\
01016 int32 INVALID_TRAJECTORY=-19\n\
01017 int32 INVALID_INDEX=-20\n\
01018 int32 JOINT_LIMITS_VIOLATED=-21\n\
01019 int32 PATH_CONSTRAINTS_VIOLATED=-22\n\
01020 int32 COLLISION_CONSTRAINTS_VIOLATED=-23\n\
01021 int32 GOAL_CONSTRAINTS_VIOLATED=-24\n\
01022 int32 JOINTS_NOT_MOVING=-25\n\
01023 int32 TRAJECTORY_CONTROLLER_FAILED=-26\n\
01024 \n\
01025 # system errors\n\
01026 int32 FRAME_TRANSFORM_FAILURE=-27\n\
01027 int32 COLLISION_CHECKING_UNAVAILABLE=-28\n\
01028 int32 ROBOT_STATE_STALE=-29\n\
01029 int32 SENSOR_INFO_STALE=-30\n\
01030 \n\
01031 # kinematics errors\n\
01032 int32 NO_IK_SOLUTION=-31\n\
01033 int32 INVALID_LINK_NAME=-32\n\
01034 int32 IK_LINK_IN_COLLISION=-33\n\
01035 int32 NO_FK_SOLUTION=-34\n\
01036 int32 KINEMATICS_STATE_IN_COLLISION=-35\n\
01037 \n\
01038 # general errors\n\
01039 int32 INVALID_TIMEOUT=-36\n\
01040 \n\
01041 \n\
01042 ================================================================================\n\
01043 MSG: arm_navigation_msgs/ContactInformation\n\
01044 # Standard ROS header contains information \n\
01045 # about the frame in which this \n\
01046 # contact is specified\n\
01047 Header header\n\
01048 \n\
01049 # Position of the contact point\n\
01050 geometry_msgs/Point position\n\
01051 \n\
01052 # Normal corresponding to the contact point\n\
01053 geometry_msgs/Vector3 normal \n\
01054 \n\
01055 # Depth of contact point\n\
01056 float64 depth\n\
01057 \n\
01058 # Name of the first body that is in contact\n\
01059 # This could be a link or a namespace that represents a body\n\
01060 string contact_body_1\n\
01061 string attached_body_1\n\
01062 uint32 body_type_1\n\
01063 \n\
01064 # Name of the second body that is in contact\n\
01065 # This could be a link or a namespace that represents a body\n\
01066 string contact_body_2\n\
01067 string attached_body_2\n\
01068 uint32 body_type_2\n\
01069 \n\
01070 uint32 ROBOT_LINK=0\n\
01071 uint32 OBJECT=1\n\
01072 uint32 ATTACHED_BODY=2\n\
01073 ================================================================================\n\
01074 MSG: std_msgs/Header\n\
01075 # Standard metadata for higher-level stamped data types.\n\
01076 # This is generally used to communicate timestamped data \n\
01077 # in a particular coordinate frame.\n\
01078 # \n\
01079 # sequence ID: consecutively increasing ID \n\
01080 uint32 seq\n\
01081 #Two-integer timestamp that is expressed as:\n\
01082 # * stamp.secs: seconds (stamp_secs) since epoch\n\
01083 # * stamp.nsecs: nanoseconds since stamp_secs\n\
01084 # time-handling sugar is provided by the client library\n\
01085 time stamp\n\
01086 #Frame this data is associated with\n\
01087 # 0: no frame\n\
01088 # 1: global frame\n\
01089 string frame_id\n\
01090 \n\
01091 ================================================================================\n\
01092 MSG: geometry_msgs/Point\n\
01093 # This contains the position of a point in free space\n\
01094 float64 x\n\
01095 float64 y\n\
01096 float64 z\n\
01097 \n\
01098 ================================================================================\n\
01099 MSG: geometry_msgs/Vector3\n\
01100 # This represents a vector in free space. \n\
01101 \n\
01102 float64 x\n\
01103 float64 y\n\
01104 float64 z\n\
01105 ";
01106 }
01107
01108 static const char* value(const ::arm_navigation_msgs::GetStateValidityResponse_<ContainerAllocator> &) { return value(); }
01109 };
01110
01111 }
01112 }
01113
01114 namespace ros
01115 {
01116 namespace serialization
01117 {
01118
01119 template<class ContainerAllocator> struct Serializer< ::arm_navigation_msgs::GetStateValidityRequest_<ContainerAllocator> >
01120 {
01121 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
01122 {
01123 stream.next(m.robot_state);
01124 stream.next(m.check_collisions);
01125 stream.next(m.check_path_constraints);
01126 stream.next(m.check_goal_constraints);
01127 stream.next(m.check_joint_limits);
01128 stream.next(m.group_name);
01129 stream.next(m.path_constraints);
01130 stream.next(m.goal_constraints);
01131 }
01132
01133 ROS_DECLARE_ALLINONE_SERIALIZER;
01134 };
01135 }
01136 }
01137
01138
01139 namespace ros
01140 {
01141 namespace serialization
01142 {
01143
01144 template<class ContainerAllocator> struct Serializer< ::arm_navigation_msgs::GetStateValidityResponse_<ContainerAllocator> >
01145 {
01146 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
01147 {
01148 stream.next(m.error_code);
01149 stream.next(m.contacts);
01150 }
01151
01152 ROS_DECLARE_ALLINONE_SERIALIZER;
01153 };
01154 }
01155 }
01156
01157 namespace ros
01158 {
01159 namespace service_traits
01160 {
01161 template<>
01162 struct MD5Sum<arm_navigation_msgs::GetStateValidity> {
01163 static const char* value()
01164 {
01165 return "05125b9572f64feb9a7f590a8674e9ee";
01166 }
01167
01168 static const char* value(const arm_navigation_msgs::GetStateValidity&) { return value(); }
01169 };
01170
01171 template<>
01172 struct DataType<arm_navigation_msgs::GetStateValidity> {
01173 static const char* value()
01174 {
01175 return "arm_navigation_msgs/GetStateValidity";
01176 }
01177
01178 static const char* value(const arm_navigation_msgs::GetStateValidity&) { return value(); }
01179 };
01180
01181 template<class ContainerAllocator>
01182 struct MD5Sum<arm_navigation_msgs::GetStateValidityRequest_<ContainerAllocator> > {
01183 static const char* value()
01184 {
01185 return "05125b9572f64feb9a7f590a8674e9ee";
01186 }
01187
01188 static const char* value(const arm_navigation_msgs::GetStateValidityRequest_<ContainerAllocator> &) { return value(); }
01189 };
01190
01191 template<class ContainerAllocator>
01192 struct DataType<arm_navigation_msgs::GetStateValidityRequest_<ContainerAllocator> > {
01193 static const char* value()
01194 {
01195 return "arm_navigation_msgs/GetStateValidity";
01196 }
01197
01198 static const char* value(const arm_navigation_msgs::GetStateValidityRequest_<ContainerAllocator> &) { return value(); }
01199 };
01200
01201 template<class ContainerAllocator>
01202 struct MD5Sum<arm_navigation_msgs::GetStateValidityResponse_<ContainerAllocator> > {
01203 static const char* value()
01204 {
01205 return "05125b9572f64feb9a7f590a8674e9ee";
01206 }
01207
01208 static const char* value(const arm_navigation_msgs::GetStateValidityResponse_<ContainerAllocator> &) { return value(); }
01209 };
01210
01211 template<class ContainerAllocator>
01212 struct DataType<arm_navigation_msgs::GetStateValidityResponse_<ContainerAllocator> > {
01213 static const char* value()
01214 {
01215 return "arm_navigation_msgs/GetStateValidity";
01216 }
01217
01218 static const char* value(const arm_navigation_msgs::GetStateValidityResponse_<ContainerAllocator> &) { return value(); }
01219 };
01220
01221 }
01222 }
01223
01224 #endif // ARM_NAVIGATION_MSGS_SERVICE_GETSTATEVALIDITY_H
01225