$search
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-electric-arm_navigation/doc_stacks/2013-03-01_14-05-03.553953/arm_navigation/arm_navigation_msgs/srv/GetRobotState.srv */ 00002 #ifndef ARM_NAVIGATION_MSGS_SERVICE_GETROBOTSTATE_H 00003 #define ARM_NAVIGATION_MSGS_SERVICE_GETROBOTSTATE_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 00020 00021 #include "arm_navigation_msgs/RobotState.h" 00022 #include "arm_navigation_msgs/ArmNavigationErrorCodes.h" 00023 00024 namespace arm_navigation_msgs 00025 { 00026 template <class ContainerAllocator> 00027 struct GetRobotStateRequest_ { 00028 typedef GetRobotStateRequest_<ContainerAllocator> Type; 00029 00030 GetRobotStateRequest_() 00031 { 00032 } 00033 00034 GetRobotStateRequest_(const ContainerAllocator& _alloc) 00035 { 00036 } 00037 00038 00039 private: 00040 static const char* __s_getDataType_() { return "arm_navigation_msgs/GetRobotStateRequest"; } 00041 public: 00042 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00043 00044 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00045 00046 private: 00047 static const char* __s_getMD5Sum_() { return "d41d8cd98f00b204e9800998ecf8427e"; } 00048 public: 00049 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00050 00051 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00052 00053 private: 00054 static const char* __s_getServerMD5Sum_() { return "9799d82a26586bf3963962b7c3038f40"; } 00055 public: 00056 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); } 00057 00058 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); } 00059 00060 private: 00061 static const char* __s_getMessageDefinition_() { return "\n\ 00062 \n\ 00063 \n\ 00064 \n\ 00065 "; } 00066 public: 00067 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00068 00069 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00070 00071 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00072 { 00073 ros::serialization::OStream stream(write_ptr, 1000000000); 00074 return stream.getData(); 00075 } 00076 00077 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00078 { 00079 ros::serialization::IStream stream(read_ptr, 1000000000); 00080 return stream.getData(); 00081 } 00082 00083 ROS_DEPRECATED virtual uint32_t serializationLength() const 00084 { 00085 uint32_t size = 0; 00086 return size; 00087 } 00088 00089 typedef boost::shared_ptr< ::arm_navigation_msgs::GetRobotStateRequest_<ContainerAllocator> > Ptr; 00090 typedef boost::shared_ptr< ::arm_navigation_msgs::GetRobotStateRequest_<ContainerAllocator> const> ConstPtr; 00091 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00092 }; // struct GetRobotStateRequest 00093 typedef ::arm_navigation_msgs::GetRobotStateRequest_<std::allocator<void> > GetRobotStateRequest; 00094 00095 typedef boost::shared_ptr< ::arm_navigation_msgs::GetRobotStateRequest> GetRobotStateRequestPtr; 00096 typedef boost::shared_ptr< ::arm_navigation_msgs::GetRobotStateRequest const> GetRobotStateRequestConstPtr; 00097 00098 00099 template <class ContainerAllocator> 00100 struct GetRobotStateResponse_ { 00101 typedef GetRobotStateResponse_<ContainerAllocator> Type; 00102 00103 GetRobotStateResponse_() 00104 : robot_state() 00105 , error_code() 00106 { 00107 } 00108 00109 GetRobotStateResponse_(const ContainerAllocator& _alloc) 00110 : robot_state(_alloc) 00111 , error_code(_alloc) 00112 { 00113 } 00114 00115 typedef ::arm_navigation_msgs::RobotState_<ContainerAllocator> _robot_state_type; 00116 ::arm_navigation_msgs::RobotState_<ContainerAllocator> robot_state; 00117 00118 typedef ::arm_navigation_msgs::ArmNavigationErrorCodes_<ContainerAllocator> _error_code_type; 00119 ::arm_navigation_msgs::ArmNavigationErrorCodes_<ContainerAllocator> error_code; 00120 00121 00122 private: 00123 static const char* __s_getDataType_() { return "arm_navigation_msgs/GetRobotStateResponse"; } 00124 public: 00125 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00126 00127 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00128 00129 private: 00130 static const char* __s_getMD5Sum_() { return "9799d82a26586bf3963962b7c3038f40"; } 00131 public: 00132 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00133 00134 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00135 00136 private: 00137 static const char* __s_getServerMD5Sum_() { return "9799d82a26586bf3963962b7c3038f40"; } 00138 public: 00139 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); } 00140 00141 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); } 00142 00143 private: 00144 static const char* __s_getMessageDefinition_() { return "\n\ 00145 \n\ 00146 arm_navigation_msgs/RobotState robot_state\n\ 00147 \n\ 00148 \n\ 00149 \n\ 00150 \n\ 00151 arm_navigation_msgs/ArmNavigationErrorCodes error_code\n\ 00152 \n\ 00153 \n\ 00154 ================================================================================\n\ 00155 MSG: arm_navigation_msgs/RobotState\n\ 00156 # This message contains information about the robot state, i.e. the positions of its joints and links\n\ 00157 sensor_msgs/JointState joint_state\n\ 00158 arm_navigation_msgs/MultiDOFJointState multi_dof_joint_state\n\ 00159 \n\ 00160 ================================================================================\n\ 00161 MSG: sensor_msgs/JointState\n\ 00162 # This is a message that holds data to describe the state of a set of torque controlled joints. \n\ 00163 #\n\ 00164 # The state of each joint (revolute or prismatic) is defined by:\n\ 00165 # * the position of the joint (rad or m),\n\ 00166 # * the velocity of the joint (rad/s or m/s) and \n\ 00167 # * the effort that is applied in the joint (Nm or N).\n\ 00168 #\n\ 00169 # Each joint is uniquely identified by its name\n\ 00170 # The header specifies the time at which the joint states were recorded. All the joint states\n\ 00171 # in one message have to be recorded at the same time.\n\ 00172 #\n\ 00173 # This message consists of a multiple arrays, one for each part of the joint state. \n\ 00174 # The goal is to make each of the fields optional. When e.g. your joints have no\n\ 00175 # effort associated with them, you can leave the effort array empty. \n\ 00176 #\n\ 00177 # All arrays in this message should have the same size, or be empty.\n\ 00178 # This is the only way to uniquely associate the joint name with the correct\n\ 00179 # states.\n\ 00180 \n\ 00181 \n\ 00182 Header header\n\ 00183 \n\ 00184 string[] name\n\ 00185 float64[] position\n\ 00186 float64[] velocity\n\ 00187 float64[] effort\n\ 00188 \n\ 00189 ================================================================================\n\ 00190 MSG: std_msgs/Header\n\ 00191 # Standard metadata for higher-level stamped data types.\n\ 00192 # This is generally used to communicate timestamped data \n\ 00193 # in a particular coordinate frame.\n\ 00194 # \n\ 00195 # sequence ID: consecutively increasing ID \n\ 00196 uint32 seq\n\ 00197 #Two-integer timestamp that is expressed as:\n\ 00198 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00199 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00200 # time-handling sugar is provided by the client library\n\ 00201 time stamp\n\ 00202 #Frame this data is associated with\n\ 00203 # 0: no frame\n\ 00204 # 1: global frame\n\ 00205 string frame_id\n\ 00206 \n\ 00207 ================================================================================\n\ 00208 MSG: arm_navigation_msgs/MultiDOFJointState\n\ 00209 #A representation of a multi-dof joint state\n\ 00210 time stamp\n\ 00211 string[] joint_names\n\ 00212 string[] frame_ids\n\ 00213 string[] child_frame_ids\n\ 00214 geometry_msgs/Pose[] poses\n\ 00215 \n\ 00216 ================================================================================\n\ 00217 MSG: geometry_msgs/Pose\n\ 00218 # A representation of pose in free space, composed of postion and orientation. \n\ 00219 Point position\n\ 00220 Quaternion orientation\n\ 00221 \n\ 00222 ================================================================================\n\ 00223 MSG: geometry_msgs/Point\n\ 00224 # This contains the position of a point in free space\n\ 00225 float64 x\n\ 00226 float64 y\n\ 00227 float64 z\n\ 00228 \n\ 00229 ================================================================================\n\ 00230 MSG: geometry_msgs/Quaternion\n\ 00231 # This represents an orientation in free space in quaternion form.\n\ 00232 \n\ 00233 float64 x\n\ 00234 float64 y\n\ 00235 float64 z\n\ 00236 float64 w\n\ 00237 \n\ 00238 ================================================================================\n\ 00239 MSG: arm_navigation_msgs/ArmNavigationErrorCodes\n\ 00240 int32 val\n\ 00241 \n\ 00242 # overall behavior\n\ 00243 int32 PLANNING_FAILED=-1\n\ 00244 int32 SUCCESS=1\n\ 00245 int32 TIMED_OUT=-2\n\ 00246 \n\ 00247 # start state errors\n\ 00248 int32 START_STATE_IN_COLLISION=-3\n\ 00249 int32 START_STATE_VIOLATES_PATH_CONSTRAINTS=-4\n\ 00250 \n\ 00251 # goal errors\n\ 00252 int32 GOAL_IN_COLLISION=-5\n\ 00253 int32 GOAL_VIOLATES_PATH_CONSTRAINTS=-6\n\ 00254 \n\ 00255 # robot state\n\ 00256 int32 INVALID_ROBOT_STATE=-7\n\ 00257 int32 INCOMPLETE_ROBOT_STATE=-8\n\ 00258 \n\ 00259 # planning request errors\n\ 00260 int32 INVALID_PLANNER_ID=-9\n\ 00261 int32 INVALID_NUM_PLANNING_ATTEMPTS=-10\n\ 00262 int32 INVALID_ALLOWED_PLANNING_TIME=-11\n\ 00263 int32 INVALID_GROUP_NAME=-12\n\ 00264 int32 INVALID_GOAL_JOINT_CONSTRAINTS=-13\n\ 00265 int32 INVALID_GOAL_POSITION_CONSTRAINTS=-14\n\ 00266 int32 INVALID_GOAL_ORIENTATION_CONSTRAINTS=-15\n\ 00267 int32 INVALID_PATH_JOINT_CONSTRAINTS=-16\n\ 00268 int32 INVALID_PATH_POSITION_CONSTRAINTS=-17\n\ 00269 int32 INVALID_PATH_ORIENTATION_CONSTRAINTS=-18\n\ 00270 \n\ 00271 # state/trajectory monitor errors\n\ 00272 int32 INVALID_TRAJECTORY=-19\n\ 00273 int32 INVALID_INDEX=-20\n\ 00274 int32 JOINT_LIMITS_VIOLATED=-21\n\ 00275 int32 PATH_CONSTRAINTS_VIOLATED=-22\n\ 00276 int32 COLLISION_CONSTRAINTS_VIOLATED=-23\n\ 00277 int32 GOAL_CONSTRAINTS_VIOLATED=-24\n\ 00278 int32 JOINTS_NOT_MOVING=-25\n\ 00279 int32 TRAJECTORY_CONTROLLER_FAILED=-26\n\ 00280 \n\ 00281 # system errors\n\ 00282 int32 FRAME_TRANSFORM_FAILURE=-27\n\ 00283 int32 COLLISION_CHECKING_UNAVAILABLE=-28\n\ 00284 int32 ROBOT_STATE_STALE=-29\n\ 00285 int32 SENSOR_INFO_STALE=-30\n\ 00286 \n\ 00287 # kinematics errors\n\ 00288 int32 NO_IK_SOLUTION=-31\n\ 00289 int32 INVALID_LINK_NAME=-32\n\ 00290 int32 IK_LINK_IN_COLLISION=-33\n\ 00291 int32 NO_FK_SOLUTION=-34\n\ 00292 int32 KINEMATICS_STATE_IN_COLLISION=-35\n\ 00293 \n\ 00294 # general errors\n\ 00295 int32 INVALID_TIMEOUT=-36\n\ 00296 \n\ 00297 \n\ 00298 "; } 00299 public: 00300 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00301 00302 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00303 00304 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00305 { 00306 ros::serialization::OStream stream(write_ptr, 1000000000); 00307 ros::serialization::serialize(stream, robot_state); 00308 ros::serialization::serialize(stream, error_code); 00309 return stream.getData(); 00310 } 00311 00312 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00313 { 00314 ros::serialization::IStream stream(read_ptr, 1000000000); 00315 ros::serialization::deserialize(stream, robot_state); 00316 ros::serialization::deserialize(stream, error_code); 00317 return stream.getData(); 00318 } 00319 00320 ROS_DEPRECATED virtual uint32_t serializationLength() const 00321 { 00322 uint32_t size = 0; 00323 size += ros::serialization::serializationLength(robot_state); 00324 size += ros::serialization::serializationLength(error_code); 00325 return size; 00326 } 00327 00328 typedef boost::shared_ptr< ::arm_navigation_msgs::GetRobotStateResponse_<ContainerAllocator> > Ptr; 00329 typedef boost::shared_ptr< ::arm_navigation_msgs::GetRobotStateResponse_<ContainerAllocator> const> ConstPtr; 00330 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00331 }; // struct GetRobotStateResponse 00332 typedef ::arm_navigation_msgs::GetRobotStateResponse_<std::allocator<void> > GetRobotStateResponse; 00333 00334 typedef boost::shared_ptr< ::arm_navigation_msgs::GetRobotStateResponse> GetRobotStateResponsePtr; 00335 typedef boost::shared_ptr< ::arm_navigation_msgs::GetRobotStateResponse const> GetRobotStateResponseConstPtr; 00336 00337 struct GetRobotState 00338 { 00339 00340 typedef GetRobotStateRequest Request; 00341 typedef GetRobotStateResponse Response; 00342 Request request; 00343 Response response; 00344 00345 typedef Request RequestType; 00346 typedef Response ResponseType; 00347 }; // struct GetRobotState 00348 } // namespace arm_navigation_msgs 00349 00350 namespace ros 00351 { 00352 namespace message_traits 00353 { 00354 template<class ContainerAllocator> struct IsMessage< ::arm_navigation_msgs::GetRobotStateRequest_<ContainerAllocator> > : public TrueType {}; 00355 template<class ContainerAllocator> struct IsMessage< ::arm_navigation_msgs::GetRobotStateRequest_<ContainerAllocator> const> : public TrueType {}; 00356 template<class ContainerAllocator> 00357 struct MD5Sum< ::arm_navigation_msgs::GetRobotStateRequest_<ContainerAllocator> > { 00358 static const char* value() 00359 { 00360 return "d41d8cd98f00b204e9800998ecf8427e"; 00361 } 00362 00363 static const char* value(const ::arm_navigation_msgs::GetRobotStateRequest_<ContainerAllocator> &) { return value(); } 00364 static const uint64_t static_value1 = 0xd41d8cd98f00b204ULL; 00365 static const uint64_t static_value2 = 0xe9800998ecf8427eULL; 00366 }; 00367 00368 template<class ContainerAllocator> 00369 struct DataType< ::arm_navigation_msgs::GetRobotStateRequest_<ContainerAllocator> > { 00370 static const char* value() 00371 { 00372 return "arm_navigation_msgs/GetRobotStateRequest"; 00373 } 00374 00375 static const char* value(const ::arm_navigation_msgs::GetRobotStateRequest_<ContainerAllocator> &) { return value(); } 00376 }; 00377 00378 template<class ContainerAllocator> 00379 struct Definition< ::arm_navigation_msgs::GetRobotStateRequest_<ContainerAllocator> > { 00380 static const char* value() 00381 { 00382 return "\n\ 00383 \n\ 00384 \n\ 00385 \n\ 00386 "; 00387 } 00388 00389 static const char* value(const ::arm_navigation_msgs::GetRobotStateRequest_<ContainerAllocator> &) { return value(); } 00390 }; 00391 00392 template<class ContainerAllocator> struct IsFixedSize< ::arm_navigation_msgs::GetRobotStateRequest_<ContainerAllocator> > : public TrueType {}; 00393 } // namespace message_traits 00394 } // namespace ros 00395 00396 00397 namespace ros 00398 { 00399 namespace message_traits 00400 { 00401 template<class ContainerAllocator> struct IsMessage< ::arm_navigation_msgs::GetRobotStateResponse_<ContainerAllocator> > : public TrueType {}; 00402 template<class ContainerAllocator> struct IsMessage< ::arm_navigation_msgs::GetRobotStateResponse_<ContainerAllocator> const> : public TrueType {}; 00403 template<class ContainerAllocator> 00404 struct MD5Sum< ::arm_navigation_msgs::GetRobotStateResponse_<ContainerAllocator> > { 00405 static const char* value() 00406 { 00407 return "9799d82a26586bf3963962b7c3038f40"; 00408 } 00409 00410 static const char* value(const ::arm_navigation_msgs::GetRobotStateResponse_<ContainerAllocator> &) { return value(); } 00411 static const uint64_t static_value1 = 0x9799d82a26586bf3ULL; 00412 static const uint64_t static_value2 = 0x963962b7c3038f40ULL; 00413 }; 00414 00415 template<class ContainerAllocator> 00416 struct DataType< ::arm_navigation_msgs::GetRobotStateResponse_<ContainerAllocator> > { 00417 static const char* value() 00418 { 00419 return "arm_navigation_msgs/GetRobotStateResponse"; 00420 } 00421 00422 static const char* value(const ::arm_navigation_msgs::GetRobotStateResponse_<ContainerAllocator> &) { return value(); } 00423 }; 00424 00425 template<class ContainerAllocator> 00426 struct Definition< ::arm_navigation_msgs::GetRobotStateResponse_<ContainerAllocator> > { 00427 static const char* value() 00428 { 00429 return "\n\ 00430 \n\ 00431 arm_navigation_msgs/RobotState robot_state\n\ 00432 \n\ 00433 \n\ 00434 \n\ 00435 \n\ 00436 arm_navigation_msgs/ArmNavigationErrorCodes error_code\n\ 00437 \n\ 00438 \n\ 00439 ================================================================================\n\ 00440 MSG: arm_navigation_msgs/RobotState\n\ 00441 # This message contains information about the robot state, i.e. the positions of its joints and links\n\ 00442 sensor_msgs/JointState joint_state\n\ 00443 arm_navigation_msgs/MultiDOFJointState multi_dof_joint_state\n\ 00444 \n\ 00445 ================================================================================\n\ 00446 MSG: sensor_msgs/JointState\n\ 00447 # This is a message that holds data to describe the state of a set of torque controlled joints. \n\ 00448 #\n\ 00449 # The state of each joint (revolute or prismatic) is defined by:\n\ 00450 # * the position of the joint (rad or m),\n\ 00451 # * the velocity of the joint (rad/s or m/s) and \n\ 00452 # * the effort that is applied in the joint (Nm or N).\n\ 00453 #\n\ 00454 # Each joint is uniquely identified by its name\n\ 00455 # The header specifies the time at which the joint states were recorded. All the joint states\n\ 00456 # in one message have to be recorded at the same time.\n\ 00457 #\n\ 00458 # This message consists of a multiple arrays, one for each part of the joint state. \n\ 00459 # The goal is to make each of the fields optional. When e.g. your joints have no\n\ 00460 # effort associated with them, you can leave the effort array empty. \n\ 00461 #\n\ 00462 # All arrays in this message should have the same size, or be empty.\n\ 00463 # This is the only way to uniquely associate the joint name with the correct\n\ 00464 # states.\n\ 00465 \n\ 00466 \n\ 00467 Header header\n\ 00468 \n\ 00469 string[] name\n\ 00470 float64[] position\n\ 00471 float64[] velocity\n\ 00472 float64[] effort\n\ 00473 \n\ 00474 ================================================================================\n\ 00475 MSG: std_msgs/Header\n\ 00476 # Standard metadata for higher-level stamped data types.\n\ 00477 # This is generally used to communicate timestamped data \n\ 00478 # in a particular coordinate frame.\n\ 00479 # \n\ 00480 # sequence ID: consecutively increasing ID \n\ 00481 uint32 seq\n\ 00482 #Two-integer timestamp that is expressed as:\n\ 00483 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00484 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00485 # time-handling sugar is provided by the client library\n\ 00486 time stamp\n\ 00487 #Frame this data is associated with\n\ 00488 # 0: no frame\n\ 00489 # 1: global frame\n\ 00490 string frame_id\n\ 00491 \n\ 00492 ================================================================================\n\ 00493 MSG: arm_navigation_msgs/MultiDOFJointState\n\ 00494 #A representation of a multi-dof joint state\n\ 00495 time stamp\n\ 00496 string[] joint_names\n\ 00497 string[] frame_ids\n\ 00498 string[] child_frame_ids\n\ 00499 geometry_msgs/Pose[] poses\n\ 00500 \n\ 00501 ================================================================================\n\ 00502 MSG: geometry_msgs/Pose\n\ 00503 # A representation of pose in free space, composed of postion and orientation. \n\ 00504 Point position\n\ 00505 Quaternion orientation\n\ 00506 \n\ 00507 ================================================================================\n\ 00508 MSG: geometry_msgs/Point\n\ 00509 # This contains the position of a point in free space\n\ 00510 float64 x\n\ 00511 float64 y\n\ 00512 float64 z\n\ 00513 \n\ 00514 ================================================================================\n\ 00515 MSG: geometry_msgs/Quaternion\n\ 00516 # This represents an orientation in free space in quaternion form.\n\ 00517 \n\ 00518 float64 x\n\ 00519 float64 y\n\ 00520 float64 z\n\ 00521 float64 w\n\ 00522 \n\ 00523 ================================================================================\n\ 00524 MSG: arm_navigation_msgs/ArmNavigationErrorCodes\n\ 00525 int32 val\n\ 00526 \n\ 00527 # overall behavior\n\ 00528 int32 PLANNING_FAILED=-1\n\ 00529 int32 SUCCESS=1\n\ 00530 int32 TIMED_OUT=-2\n\ 00531 \n\ 00532 # start state errors\n\ 00533 int32 START_STATE_IN_COLLISION=-3\n\ 00534 int32 START_STATE_VIOLATES_PATH_CONSTRAINTS=-4\n\ 00535 \n\ 00536 # goal errors\n\ 00537 int32 GOAL_IN_COLLISION=-5\n\ 00538 int32 GOAL_VIOLATES_PATH_CONSTRAINTS=-6\n\ 00539 \n\ 00540 # robot state\n\ 00541 int32 INVALID_ROBOT_STATE=-7\n\ 00542 int32 INCOMPLETE_ROBOT_STATE=-8\n\ 00543 \n\ 00544 # planning request errors\n\ 00545 int32 INVALID_PLANNER_ID=-9\n\ 00546 int32 INVALID_NUM_PLANNING_ATTEMPTS=-10\n\ 00547 int32 INVALID_ALLOWED_PLANNING_TIME=-11\n\ 00548 int32 INVALID_GROUP_NAME=-12\n\ 00549 int32 INVALID_GOAL_JOINT_CONSTRAINTS=-13\n\ 00550 int32 INVALID_GOAL_POSITION_CONSTRAINTS=-14\n\ 00551 int32 INVALID_GOAL_ORIENTATION_CONSTRAINTS=-15\n\ 00552 int32 INVALID_PATH_JOINT_CONSTRAINTS=-16\n\ 00553 int32 INVALID_PATH_POSITION_CONSTRAINTS=-17\n\ 00554 int32 INVALID_PATH_ORIENTATION_CONSTRAINTS=-18\n\ 00555 \n\ 00556 # state/trajectory monitor errors\n\ 00557 int32 INVALID_TRAJECTORY=-19\n\ 00558 int32 INVALID_INDEX=-20\n\ 00559 int32 JOINT_LIMITS_VIOLATED=-21\n\ 00560 int32 PATH_CONSTRAINTS_VIOLATED=-22\n\ 00561 int32 COLLISION_CONSTRAINTS_VIOLATED=-23\n\ 00562 int32 GOAL_CONSTRAINTS_VIOLATED=-24\n\ 00563 int32 JOINTS_NOT_MOVING=-25\n\ 00564 int32 TRAJECTORY_CONTROLLER_FAILED=-26\n\ 00565 \n\ 00566 # system errors\n\ 00567 int32 FRAME_TRANSFORM_FAILURE=-27\n\ 00568 int32 COLLISION_CHECKING_UNAVAILABLE=-28\n\ 00569 int32 ROBOT_STATE_STALE=-29\n\ 00570 int32 SENSOR_INFO_STALE=-30\n\ 00571 \n\ 00572 # kinematics errors\n\ 00573 int32 NO_IK_SOLUTION=-31\n\ 00574 int32 INVALID_LINK_NAME=-32\n\ 00575 int32 IK_LINK_IN_COLLISION=-33\n\ 00576 int32 NO_FK_SOLUTION=-34\n\ 00577 int32 KINEMATICS_STATE_IN_COLLISION=-35\n\ 00578 \n\ 00579 # general errors\n\ 00580 int32 INVALID_TIMEOUT=-36\n\ 00581 \n\ 00582 \n\ 00583 "; 00584 } 00585 00586 static const char* value(const ::arm_navigation_msgs::GetRobotStateResponse_<ContainerAllocator> &) { return value(); } 00587 }; 00588 00589 } // namespace message_traits 00590 } // namespace ros 00591 00592 namespace ros 00593 { 00594 namespace serialization 00595 { 00596 00597 template<class ContainerAllocator> struct Serializer< ::arm_navigation_msgs::GetRobotStateRequest_<ContainerAllocator> > 00598 { 00599 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00600 { 00601 } 00602 00603 ROS_DECLARE_ALLINONE_SERIALIZER; 00604 }; // struct GetRobotStateRequest_ 00605 } // namespace serialization 00606 } // namespace ros 00607 00608 00609 namespace ros 00610 { 00611 namespace serialization 00612 { 00613 00614 template<class ContainerAllocator> struct Serializer< ::arm_navigation_msgs::GetRobotStateResponse_<ContainerAllocator> > 00615 { 00616 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00617 { 00618 stream.next(m.robot_state); 00619 stream.next(m.error_code); 00620 } 00621 00622 ROS_DECLARE_ALLINONE_SERIALIZER; 00623 }; // struct GetRobotStateResponse_ 00624 } // namespace serialization 00625 } // namespace ros 00626 00627 namespace ros 00628 { 00629 namespace service_traits 00630 { 00631 template<> 00632 struct MD5Sum<arm_navigation_msgs::GetRobotState> { 00633 static const char* value() 00634 { 00635 return "9799d82a26586bf3963962b7c3038f40"; 00636 } 00637 00638 static const char* value(const arm_navigation_msgs::GetRobotState&) { return value(); } 00639 }; 00640 00641 template<> 00642 struct DataType<arm_navigation_msgs::GetRobotState> { 00643 static const char* value() 00644 { 00645 return "arm_navigation_msgs/GetRobotState"; 00646 } 00647 00648 static const char* value(const arm_navigation_msgs::GetRobotState&) { return value(); } 00649 }; 00650 00651 template<class ContainerAllocator> 00652 struct MD5Sum<arm_navigation_msgs::GetRobotStateRequest_<ContainerAllocator> > { 00653 static const char* value() 00654 { 00655 return "9799d82a26586bf3963962b7c3038f40"; 00656 } 00657 00658 static const char* value(const arm_navigation_msgs::GetRobotStateRequest_<ContainerAllocator> &) { return value(); } 00659 }; 00660 00661 template<class ContainerAllocator> 00662 struct DataType<arm_navigation_msgs::GetRobotStateRequest_<ContainerAllocator> > { 00663 static const char* value() 00664 { 00665 return "arm_navigation_msgs/GetRobotState"; 00666 } 00667 00668 static const char* value(const arm_navigation_msgs::GetRobotStateRequest_<ContainerAllocator> &) { return value(); } 00669 }; 00670 00671 template<class ContainerAllocator> 00672 struct MD5Sum<arm_navigation_msgs::GetRobotStateResponse_<ContainerAllocator> > { 00673 static const char* value() 00674 { 00675 return "9799d82a26586bf3963962b7c3038f40"; 00676 } 00677 00678 static const char* value(const arm_navigation_msgs::GetRobotStateResponse_<ContainerAllocator> &) { return value(); } 00679 }; 00680 00681 template<class ContainerAllocator> 00682 struct DataType<arm_navigation_msgs::GetRobotStateResponse_<ContainerAllocator> > { 00683 static const char* value() 00684 { 00685 return "arm_navigation_msgs/GetRobotState"; 00686 } 00687 00688 static const char* value(const arm_navigation_msgs::GetRobotStateResponse_<ContainerAllocator> &) { return value(); } 00689 }; 00690 00691 } // namespace service_traits 00692 } // namespace ros 00693 00694 #endif // ARM_NAVIGATION_MSGS_SERVICE_GETROBOTSTATE_H 00695