00001
00002 #ifndef KINEMATICS_MSGS_SERVICE_GETPOSITIONIK_H
00003 #define KINEMATICS_MSGS_SERVICE_GETPOSITIONIK_H
00004 #include <string>
00005 #include <vector>
00006 #include <ostream>
00007 #include "ros/serialization.h"
00008 #include "ros/builtin_message_traits.h"
00009 #include "ros/message_operations.h"
00010 #include "ros/message.h"
00011 #include "ros/time.h"
00012
00013 #include "ros/service_traits.h"
00014
00015 #include "kinematics_msgs/PositionIKRequest.h"
00016
00017
00018 #include "motion_planning_msgs/RobotState.h"
00019 #include "motion_planning_msgs/ArmNavigationErrorCodes.h"
00020
00021 namespace kinematics_msgs
00022 {
00023 template <class ContainerAllocator>
00024 struct GetPositionIKRequest_ : public ros::Message
00025 {
00026 typedef GetPositionIKRequest_<ContainerAllocator> Type;
00027
00028 GetPositionIKRequest_()
00029 : ik_request()
00030 , timeout()
00031 {
00032 }
00033
00034 GetPositionIKRequest_(const ContainerAllocator& _alloc)
00035 : ik_request(_alloc)
00036 , timeout()
00037 {
00038 }
00039
00040 typedef ::kinematics_msgs::PositionIKRequest_<ContainerAllocator> _ik_request_type;
00041 ::kinematics_msgs::PositionIKRequest_<ContainerAllocator> ik_request;
00042
00043 typedef ros::Duration _timeout_type;
00044 ros::Duration timeout;
00045
00046
00047 private:
00048 static const char* __s_getDataType_() { return "kinematics_msgs/GetPositionIKRequest"; }
00049 public:
00050 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00051
00052 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00053
00054 private:
00055 static const char* __s_getMD5Sum_() { return "bf9ee33930d9eaff390b8af4a213ba62"; }
00056 public:
00057 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00058
00059 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00060
00061 private:
00062 static const char* __s_getServerMD5Sum_() { return "6d82fcb918d48c6d8a708bc55e34ace2"; }
00063 public:
00064 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); }
00065
00066 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); }
00067
00068 private:
00069 static const char* __s_getMessageDefinition_() { return "\n\
00070 \n\
00071 kinematics_msgs/PositionIKRequest ik_request\n\
00072 \n\
00073 duration timeout\n\
00074 \n\
00075 ================================================================================\n\
00076 MSG: kinematics_msgs/PositionIKRequest\n\
00077 # A Position IK request message\n\
00078 # The name of the link for which we are computing IK\n\
00079 string ik_link_name\n\
00080 \n\
00081 # The (stamped) pose of the link\n\
00082 geometry_msgs/PoseStamped pose_stamped\n\
00083 \n\
00084 # A RobotState consisting of hint/seed positions for the IK computation. \n\
00085 # These may be used to seed the IK search. \n\
00086 # The seed state MUST contain state for all joints to be used by the IK solver\n\
00087 # to compute IK. The list of joints that the IK solver deals with can be found using\n\
00088 # the kinematics_msgs/GetKinematicSolverInfo\n\
00089 motion_planning_msgs/RobotState ik_seed_state\n\
00090 \n\
00091 # Additional state information can be provided here to specify the starting positions \n\
00092 # of other joints/links on the robot.\n\
00093 motion_planning_msgs/RobotState robot_state\n\
00094 \n\
00095 ================================================================================\n\
00096 MSG: geometry_msgs/PoseStamped\n\
00097 # A Pose with reference coordinate frame and timestamp\n\
00098 Header header\n\
00099 Pose pose\n\
00100 \n\
00101 ================================================================================\n\
00102 MSG: std_msgs/Header\n\
00103 # Standard metadata for higher-level stamped data types.\n\
00104 # This is generally used to communicate timestamped data \n\
00105 # in a particular coordinate frame.\n\
00106 # \n\
00107 # sequence ID: consecutively increasing ID \n\
00108 uint32 seq\n\
00109 #Two-integer timestamp that is expressed as:\n\
00110 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00111 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00112 # time-handling sugar is provided by the client library\n\
00113 time stamp\n\
00114 #Frame this data is associated with\n\
00115 # 0: no frame\n\
00116 # 1: global frame\n\
00117 string frame_id\n\
00118 \n\
00119 ================================================================================\n\
00120 MSG: geometry_msgs/Pose\n\
00121 # A representation of pose in free space, composed of postion and orientation. \n\
00122 Point position\n\
00123 Quaternion orientation\n\
00124 \n\
00125 ================================================================================\n\
00126 MSG: geometry_msgs/Point\n\
00127 # This contains the position of a point in free space\n\
00128 float64 x\n\
00129 float64 y\n\
00130 float64 z\n\
00131 \n\
00132 ================================================================================\n\
00133 MSG: geometry_msgs/Quaternion\n\
00134 # This represents an orientation in free space in quaternion form.\n\
00135 \n\
00136 float64 x\n\
00137 float64 y\n\
00138 float64 z\n\
00139 float64 w\n\
00140 \n\
00141 ================================================================================\n\
00142 MSG: motion_planning_msgs/RobotState\n\
00143 # This message contains information about the robot state, i.e. the positions of its joints and links\n\
00144 sensor_msgs/JointState joint_state\n\
00145 motion_planning_msgs/MultiDOFJointState multi_dof_joint_state\n\
00146 ================================================================================\n\
00147 MSG: sensor_msgs/JointState\n\
00148 # This is a message that holds data to describe the state of a set of torque controlled joints. \n\
00149 #\n\
00150 # The state of each joint (revolute or prismatic) is defined by:\n\
00151 # * the position of the joint (rad or m),\n\
00152 # * the velocity of the joint (rad/s or m/s) and \n\
00153 # * the effort that is applied in the joint (Nm or N).\n\
00154 #\n\
00155 # Each joint is uniquely identified by its name\n\
00156 # The header specifies the time at which the joint states were recorded. All the joint states\n\
00157 # in one message have to be recorded at the same time.\n\
00158 #\n\
00159 # This message consists of a multiple arrays, one for each part of the joint state. \n\
00160 # The goal is to make each of the fields optional. When e.g. your joints have no\n\
00161 # effort associated with them, you can leave the effort array empty. \n\
00162 #\n\
00163 # All arrays in this message should have the same size, or be empty.\n\
00164 # This is the only way to uniquely associate the joint name with the correct\n\
00165 # states.\n\
00166 \n\
00167 \n\
00168 Header header\n\
00169 \n\
00170 string[] name\n\
00171 float64[] position\n\
00172 float64[] velocity\n\
00173 float64[] effort\n\
00174 \n\
00175 ================================================================================\n\
00176 MSG: motion_planning_msgs/MultiDOFJointState\n\
00177 #A representation of a multi-dof joint state\n\
00178 time stamp\n\
00179 string[] joint_names\n\
00180 string[] frame_ids\n\
00181 string[] child_frame_ids\n\
00182 geometry_msgs/Pose[] poses\n\
00183 \n\
00184 "; }
00185 public:
00186 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00187
00188 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00189
00190 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00191 {
00192 ros::serialization::OStream stream(write_ptr, 1000000000);
00193 ros::serialization::serialize(stream, ik_request);
00194 ros::serialization::serialize(stream, timeout);
00195 return stream.getData();
00196 }
00197
00198 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00199 {
00200 ros::serialization::IStream stream(read_ptr, 1000000000);
00201 ros::serialization::deserialize(stream, ik_request);
00202 ros::serialization::deserialize(stream, timeout);
00203 return stream.getData();
00204 }
00205
00206 ROS_DEPRECATED virtual uint32_t serializationLength() const
00207 {
00208 uint32_t size = 0;
00209 size += ros::serialization::serializationLength(ik_request);
00210 size += ros::serialization::serializationLength(timeout);
00211 return size;
00212 }
00213
00214 typedef boost::shared_ptr< ::kinematics_msgs::GetPositionIKRequest_<ContainerAllocator> > Ptr;
00215 typedef boost::shared_ptr< ::kinematics_msgs::GetPositionIKRequest_<ContainerAllocator> const> ConstPtr;
00216 };
00217 typedef ::kinematics_msgs::GetPositionIKRequest_<std::allocator<void> > GetPositionIKRequest;
00218
00219 typedef boost::shared_ptr< ::kinematics_msgs::GetPositionIKRequest> GetPositionIKRequestPtr;
00220 typedef boost::shared_ptr< ::kinematics_msgs::GetPositionIKRequest const> GetPositionIKRequestConstPtr;
00221
00222
00223 template <class ContainerAllocator>
00224 struct GetPositionIKResponse_ : public ros::Message
00225 {
00226 typedef GetPositionIKResponse_<ContainerAllocator> Type;
00227
00228 GetPositionIKResponse_()
00229 : solution()
00230 , error_code()
00231 {
00232 }
00233
00234 GetPositionIKResponse_(const ContainerAllocator& _alloc)
00235 : solution(_alloc)
00236 , error_code(_alloc)
00237 {
00238 }
00239
00240 typedef ::motion_planning_msgs::RobotState_<ContainerAllocator> _solution_type;
00241 ::motion_planning_msgs::RobotState_<ContainerAllocator> solution;
00242
00243 typedef ::motion_planning_msgs::ArmNavigationErrorCodes_<ContainerAllocator> _error_code_type;
00244 ::motion_planning_msgs::ArmNavigationErrorCodes_<ContainerAllocator> error_code;
00245
00246
00247 private:
00248 static const char* __s_getDataType_() { return "kinematics_msgs/GetPositionIKResponse"; }
00249 public:
00250 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00251
00252 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00253
00254 private:
00255 static const char* __s_getMD5Sum_() { return "5a8bbc4eb2775fe00cbd09858fd3dc65"; }
00256 public:
00257 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00258
00259 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00260
00261 private:
00262 static const char* __s_getServerMD5Sum_() { return "6d82fcb918d48c6d8a708bc55e34ace2"; }
00263 public:
00264 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); }
00265
00266 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); }
00267
00268 private:
00269 static const char* __s_getMessageDefinition_() { return "\n\
00270 \n\
00271 motion_planning_msgs/RobotState solution\n\
00272 \n\
00273 motion_planning_msgs/ArmNavigationErrorCodes error_code\n\
00274 \n\
00275 \n\
00276 \n\
00277 ================================================================================\n\
00278 MSG: motion_planning_msgs/RobotState\n\
00279 # This message contains information about the robot state, i.e. the positions of its joints and links\n\
00280 sensor_msgs/JointState joint_state\n\
00281 motion_planning_msgs/MultiDOFJointState multi_dof_joint_state\n\
00282 ================================================================================\n\
00283 MSG: sensor_msgs/JointState\n\
00284 # This is a message that holds data to describe the state of a set of torque controlled joints. \n\
00285 #\n\
00286 # The state of each joint (revolute or prismatic) is defined by:\n\
00287 # * the position of the joint (rad or m),\n\
00288 # * the velocity of the joint (rad/s or m/s) and \n\
00289 # * the effort that is applied in the joint (Nm or N).\n\
00290 #\n\
00291 # Each joint is uniquely identified by its name\n\
00292 # The header specifies the time at which the joint states were recorded. All the joint states\n\
00293 # in one message have to be recorded at the same time.\n\
00294 #\n\
00295 # This message consists of a multiple arrays, one for each part of the joint state. \n\
00296 # The goal is to make each of the fields optional. When e.g. your joints have no\n\
00297 # effort associated with them, you can leave the effort array empty. \n\
00298 #\n\
00299 # All arrays in this message should have the same size, or be empty.\n\
00300 # This is the only way to uniquely associate the joint name with the correct\n\
00301 # states.\n\
00302 \n\
00303 \n\
00304 Header header\n\
00305 \n\
00306 string[] name\n\
00307 float64[] position\n\
00308 float64[] velocity\n\
00309 float64[] effort\n\
00310 \n\
00311 ================================================================================\n\
00312 MSG: std_msgs/Header\n\
00313 # Standard metadata for higher-level stamped data types.\n\
00314 # This is generally used to communicate timestamped data \n\
00315 # in a particular coordinate frame.\n\
00316 # \n\
00317 # sequence ID: consecutively increasing ID \n\
00318 uint32 seq\n\
00319 #Two-integer timestamp that is expressed as:\n\
00320 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00321 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00322 # time-handling sugar is provided by the client library\n\
00323 time stamp\n\
00324 #Frame this data is associated with\n\
00325 # 0: no frame\n\
00326 # 1: global frame\n\
00327 string frame_id\n\
00328 \n\
00329 ================================================================================\n\
00330 MSG: motion_planning_msgs/MultiDOFJointState\n\
00331 #A representation of a multi-dof joint state\n\
00332 time stamp\n\
00333 string[] joint_names\n\
00334 string[] frame_ids\n\
00335 string[] child_frame_ids\n\
00336 geometry_msgs/Pose[] poses\n\
00337 \n\
00338 ================================================================================\n\
00339 MSG: geometry_msgs/Pose\n\
00340 # A representation of pose in free space, composed of postion and orientation. \n\
00341 Point position\n\
00342 Quaternion orientation\n\
00343 \n\
00344 ================================================================================\n\
00345 MSG: geometry_msgs/Point\n\
00346 # This contains the position of a point in free space\n\
00347 float64 x\n\
00348 float64 y\n\
00349 float64 z\n\
00350 \n\
00351 ================================================================================\n\
00352 MSG: geometry_msgs/Quaternion\n\
00353 # This represents an orientation in free space in quaternion form.\n\
00354 \n\
00355 float64 x\n\
00356 float64 y\n\
00357 float64 z\n\
00358 float64 w\n\
00359 \n\
00360 ================================================================================\n\
00361 MSG: motion_planning_msgs/ArmNavigationErrorCodes\n\
00362 int32 val\n\
00363 \n\
00364 # overall behavior\n\
00365 int32 PLANNING_FAILED=-1\n\
00366 int32 SUCCESS=1\n\
00367 int32 TIMED_OUT=-2\n\
00368 \n\
00369 # start state errors\n\
00370 int32 START_STATE_IN_COLLISION=-3\n\
00371 int32 START_STATE_VIOLATES_PATH_CONSTRAINTS=-4\n\
00372 \n\
00373 # goal errors\n\
00374 int32 GOAL_IN_COLLISION=-5\n\
00375 int32 GOAL_VIOLATES_PATH_CONSTRAINTS=-6\n\
00376 \n\
00377 # robot state\n\
00378 int32 INVALID_ROBOT_STATE=-7\n\
00379 int32 INCOMPLETE_ROBOT_STATE=-8\n\
00380 \n\
00381 # planning request errors\n\
00382 int32 INVALID_PLANNER_ID=-9\n\
00383 int32 INVALID_NUM_PLANNING_ATTEMPTS=-10\n\
00384 int32 INVALID_ALLOWED_PLANNING_TIME=-11\n\
00385 int32 INVALID_GROUP_NAME=-12\n\
00386 int32 INVALID_GOAL_JOINT_CONSTRAINTS=-13\n\
00387 int32 INVALID_GOAL_POSITION_CONSTRAINTS=-14\n\
00388 int32 INVALID_GOAL_ORIENTATION_CONSTRAINTS=-15\n\
00389 int32 INVALID_PATH_JOINT_CONSTRAINTS=-16\n\
00390 int32 INVALID_PATH_POSITION_CONSTRAINTS=-17\n\
00391 int32 INVALID_PATH_ORIENTATION_CONSTRAINTS=-18\n\
00392 \n\
00393 # state/trajectory monitor errors\n\
00394 int32 INVALID_TRAJECTORY=-19\n\
00395 int32 INVALID_INDEX=-20\n\
00396 int32 JOINT_LIMITS_VIOLATED=-21\n\
00397 int32 PATH_CONSTRAINTS_VIOLATED=-22\n\
00398 int32 COLLISION_CONSTRAINTS_VIOLATED=-23\n\
00399 int32 GOAL_CONSTRAINTS_VIOLATED=-24\n\
00400 int32 JOINTS_NOT_MOVING=-25\n\
00401 int32 TRAJECTORY_CONTROLLER_FAILED=-26\n\
00402 \n\
00403 # system errors\n\
00404 int32 FRAME_TRANSFORM_FAILURE=-27\n\
00405 int32 COLLISION_CHECKING_UNAVAILABLE=-28\n\
00406 int32 ROBOT_STATE_STALE=-29\n\
00407 int32 SENSOR_INFO_STALE=-30\n\
00408 \n\
00409 # kinematics errors\n\
00410 int32 NO_IK_SOLUTION=-31\n\
00411 int32 INVALID_LINK_NAME=-32\n\
00412 int32 IK_LINK_IN_COLLISION=-33\n\
00413 int32 NO_FK_SOLUTION=-34\n\
00414 int32 KINEMATICS_STATE_IN_COLLISION=-35\n\
00415 \n\
00416 # general errors\n\
00417 int32 INVALID_TIMEOUT=-36\n\
00418 \n\
00419 \n\
00420 "; }
00421 public:
00422 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00423
00424 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00425
00426 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00427 {
00428 ros::serialization::OStream stream(write_ptr, 1000000000);
00429 ros::serialization::serialize(stream, solution);
00430 ros::serialization::serialize(stream, error_code);
00431 return stream.getData();
00432 }
00433
00434 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00435 {
00436 ros::serialization::IStream stream(read_ptr, 1000000000);
00437 ros::serialization::deserialize(stream, solution);
00438 ros::serialization::deserialize(stream, error_code);
00439 return stream.getData();
00440 }
00441
00442 ROS_DEPRECATED virtual uint32_t serializationLength() const
00443 {
00444 uint32_t size = 0;
00445 size += ros::serialization::serializationLength(solution);
00446 size += ros::serialization::serializationLength(error_code);
00447 return size;
00448 }
00449
00450 typedef boost::shared_ptr< ::kinematics_msgs::GetPositionIKResponse_<ContainerAllocator> > Ptr;
00451 typedef boost::shared_ptr< ::kinematics_msgs::GetPositionIKResponse_<ContainerAllocator> const> ConstPtr;
00452 };
00453 typedef ::kinematics_msgs::GetPositionIKResponse_<std::allocator<void> > GetPositionIKResponse;
00454
00455 typedef boost::shared_ptr< ::kinematics_msgs::GetPositionIKResponse> GetPositionIKResponsePtr;
00456 typedef boost::shared_ptr< ::kinematics_msgs::GetPositionIKResponse const> GetPositionIKResponseConstPtr;
00457
00458 struct GetPositionIK
00459 {
00460
00461 typedef GetPositionIKRequest Request;
00462 typedef GetPositionIKResponse Response;
00463 Request request;
00464 Response response;
00465
00466 typedef Request RequestType;
00467 typedef Response ResponseType;
00468 };
00469 }
00470
00471 namespace ros
00472 {
00473 namespace message_traits
00474 {
00475 template<class ContainerAllocator>
00476 struct MD5Sum< ::kinematics_msgs::GetPositionIKRequest_<ContainerAllocator> > {
00477 static const char* value()
00478 {
00479 return "bf9ee33930d9eaff390b8af4a213ba62";
00480 }
00481
00482 static const char* value(const ::kinematics_msgs::GetPositionIKRequest_<ContainerAllocator> &) { return value(); }
00483 static const uint64_t static_value1 = 0xbf9ee33930d9eaffULL;
00484 static const uint64_t static_value2 = 0x390b8af4a213ba62ULL;
00485 };
00486
00487 template<class ContainerAllocator>
00488 struct DataType< ::kinematics_msgs::GetPositionIKRequest_<ContainerAllocator> > {
00489 static const char* value()
00490 {
00491 return "kinematics_msgs/GetPositionIKRequest";
00492 }
00493
00494 static const char* value(const ::kinematics_msgs::GetPositionIKRequest_<ContainerAllocator> &) { return value(); }
00495 };
00496
00497 template<class ContainerAllocator>
00498 struct Definition< ::kinematics_msgs::GetPositionIKRequest_<ContainerAllocator> > {
00499 static const char* value()
00500 {
00501 return "\n\
00502 \n\
00503 kinematics_msgs/PositionIKRequest ik_request\n\
00504 \n\
00505 duration timeout\n\
00506 \n\
00507 ================================================================================\n\
00508 MSG: kinematics_msgs/PositionIKRequest\n\
00509 # A Position IK request message\n\
00510 # The name of the link for which we are computing IK\n\
00511 string ik_link_name\n\
00512 \n\
00513 # The (stamped) pose of the link\n\
00514 geometry_msgs/PoseStamped pose_stamped\n\
00515 \n\
00516 # A RobotState consisting of hint/seed positions for the IK computation. \n\
00517 # These may be used to seed the IK search. \n\
00518 # The seed state MUST contain state for all joints to be used by the IK solver\n\
00519 # to compute IK. The list of joints that the IK solver deals with can be found using\n\
00520 # the kinematics_msgs/GetKinematicSolverInfo\n\
00521 motion_planning_msgs/RobotState ik_seed_state\n\
00522 \n\
00523 # Additional state information can be provided here to specify the starting positions \n\
00524 # of other joints/links on the robot.\n\
00525 motion_planning_msgs/RobotState robot_state\n\
00526 \n\
00527 ================================================================================\n\
00528 MSG: geometry_msgs/PoseStamped\n\
00529 # A Pose with reference coordinate frame and timestamp\n\
00530 Header header\n\
00531 Pose pose\n\
00532 \n\
00533 ================================================================================\n\
00534 MSG: std_msgs/Header\n\
00535 # Standard metadata for higher-level stamped data types.\n\
00536 # This is generally used to communicate timestamped data \n\
00537 # in a particular coordinate frame.\n\
00538 # \n\
00539 # sequence ID: consecutively increasing ID \n\
00540 uint32 seq\n\
00541 #Two-integer timestamp that is expressed as:\n\
00542 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00543 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00544 # time-handling sugar is provided by the client library\n\
00545 time stamp\n\
00546 #Frame this data is associated with\n\
00547 # 0: no frame\n\
00548 # 1: global frame\n\
00549 string frame_id\n\
00550 \n\
00551 ================================================================================\n\
00552 MSG: geometry_msgs/Pose\n\
00553 # A representation of pose in free space, composed of postion and orientation. \n\
00554 Point position\n\
00555 Quaternion orientation\n\
00556 \n\
00557 ================================================================================\n\
00558 MSG: geometry_msgs/Point\n\
00559 # This contains the position of a point in free space\n\
00560 float64 x\n\
00561 float64 y\n\
00562 float64 z\n\
00563 \n\
00564 ================================================================================\n\
00565 MSG: geometry_msgs/Quaternion\n\
00566 # This represents an orientation in free space in quaternion form.\n\
00567 \n\
00568 float64 x\n\
00569 float64 y\n\
00570 float64 z\n\
00571 float64 w\n\
00572 \n\
00573 ================================================================================\n\
00574 MSG: motion_planning_msgs/RobotState\n\
00575 # This message contains information about the robot state, i.e. the positions of its joints and links\n\
00576 sensor_msgs/JointState joint_state\n\
00577 motion_planning_msgs/MultiDOFJointState multi_dof_joint_state\n\
00578 ================================================================================\n\
00579 MSG: sensor_msgs/JointState\n\
00580 # This is a message that holds data to describe the state of a set of torque controlled joints. \n\
00581 #\n\
00582 # The state of each joint (revolute or prismatic) is defined by:\n\
00583 # * the position of the joint (rad or m),\n\
00584 # * the velocity of the joint (rad/s or m/s) and \n\
00585 # * the effort that is applied in the joint (Nm or N).\n\
00586 #\n\
00587 # Each joint is uniquely identified by its name\n\
00588 # The header specifies the time at which the joint states were recorded. All the joint states\n\
00589 # in one message have to be recorded at the same time.\n\
00590 #\n\
00591 # This message consists of a multiple arrays, one for each part of the joint state. \n\
00592 # The goal is to make each of the fields optional. When e.g. your joints have no\n\
00593 # effort associated with them, you can leave the effort array empty. \n\
00594 #\n\
00595 # All arrays in this message should have the same size, or be empty.\n\
00596 # This is the only way to uniquely associate the joint name with the correct\n\
00597 # states.\n\
00598 \n\
00599 \n\
00600 Header header\n\
00601 \n\
00602 string[] name\n\
00603 float64[] position\n\
00604 float64[] velocity\n\
00605 float64[] effort\n\
00606 \n\
00607 ================================================================================\n\
00608 MSG: motion_planning_msgs/MultiDOFJointState\n\
00609 #A representation of a multi-dof joint state\n\
00610 time stamp\n\
00611 string[] joint_names\n\
00612 string[] frame_ids\n\
00613 string[] child_frame_ids\n\
00614 geometry_msgs/Pose[] poses\n\
00615 \n\
00616 ";
00617 }
00618
00619 static const char* value(const ::kinematics_msgs::GetPositionIKRequest_<ContainerAllocator> &) { return value(); }
00620 };
00621
00622 }
00623 }
00624
00625
00626 namespace ros
00627 {
00628 namespace message_traits
00629 {
00630 template<class ContainerAllocator>
00631 struct MD5Sum< ::kinematics_msgs::GetPositionIKResponse_<ContainerAllocator> > {
00632 static const char* value()
00633 {
00634 return "5a8bbc4eb2775fe00cbd09858fd3dc65";
00635 }
00636
00637 static const char* value(const ::kinematics_msgs::GetPositionIKResponse_<ContainerAllocator> &) { return value(); }
00638 static const uint64_t static_value1 = 0x5a8bbc4eb2775fe0ULL;
00639 static const uint64_t static_value2 = 0x0cbd09858fd3dc65ULL;
00640 };
00641
00642 template<class ContainerAllocator>
00643 struct DataType< ::kinematics_msgs::GetPositionIKResponse_<ContainerAllocator> > {
00644 static const char* value()
00645 {
00646 return "kinematics_msgs/GetPositionIKResponse";
00647 }
00648
00649 static const char* value(const ::kinematics_msgs::GetPositionIKResponse_<ContainerAllocator> &) { return value(); }
00650 };
00651
00652 template<class ContainerAllocator>
00653 struct Definition< ::kinematics_msgs::GetPositionIKResponse_<ContainerAllocator> > {
00654 static const char* value()
00655 {
00656 return "\n\
00657 \n\
00658 motion_planning_msgs/RobotState solution\n\
00659 \n\
00660 motion_planning_msgs/ArmNavigationErrorCodes error_code\n\
00661 \n\
00662 \n\
00663 \n\
00664 ================================================================================\n\
00665 MSG: motion_planning_msgs/RobotState\n\
00666 # This message contains information about the robot state, i.e. the positions of its joints and links\n\
00667 sensor_msgs/JointState joint_state\n\
00668 motion_planning_msgs/MultiDOFJointState multi_dof_joint_state\n\
00669 ================================================================================\n\
00670 MSG: sensor_msgs/JointState\n\
00671 # This is a message that holds data to describe the state of a set of torque controlled joints. \n\
00672 #\n\
00673 # The state of each joint (revolute or prismatic) is defined by:\n\
00674 # * the position of the joint (rad or m),\n\
00675 # * the velocity of the joint (rad/s or m/s) and \n\
00676 # * the effort that is applied in the joint (Nm or N).\n\
00677 #\n\
00678 # Each joint is uniquely identified by its name\n\
00679 # The header specifies the time at which the joint states were recorded. All the joint states\n\
00680 # in one message have to be recorded at the same time.\n\
00681 #\n\
00682 # This message consists of a multiple arrays, one for each part of the joint state. \n\
00683 # The goal is to make each of the fields optional. When e.g. your joints have no\n\
00684 # effort associated with them, you can leave the effort array empty. \n\
00685 #\n\
00686 # All arrays in this message should have the same size, or be empty.\n\
00687 # This is the only way to uniquely associate the joint name with the correct\n\
00688 # states.\n\
00689 \n\
00690 \n\
00691 Header header\n\
00692 \n\
00693 string[] name\n\
00694 float64[] position\n\
00695 float64[] velocity\n\
00696 float64[] effort\n\
00697 \n\
00698 ================================================================================\n\
00699 MSG: std_msgs/Header\n\
00700 # Standard metadata for higher-level stamped data types.\n\
00701 # This is generally used to communicate timestamped data \n\
00702 # in a particular coordinate frame.\n\
00703 # \n\
00704 # sequence ID: consecutively increasing ID \n\
00705 uint32 seq\n\
00706 #Two-integer timestamp that is expressed as:\n\
00707 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00708 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00709 # time-handling sugar is provided by the client library\n\
00710 time stamp\n\
00711 #Frame this data is associated with\n\
00712 # 0: no frame\n\
00713 # 1: global frame\n\
00714 string frame_id\n\
00715 \n\
00716 ================================================================================\n\
00717 MSG: motion_planning_msgs/MultiDOFJointState\n\
00718 #A representation of a multi-dof joint state\n\
00719 time stamp\n\
00720 string[] joint_names\n\
00721 string[] frame_ids\n\
00722 string[] child_frame_ids\n\
00723 geometry_msgs/Pose[] poses\n\
00724 \n\
00725 ================================================================================\n\
00726 MSG: geometry_msgs/Pose\n\
00727 # A representation of pose in free space, composed of postion and orientation. \n\
00728 Point position\n\
00729 Quaternion orientation\n\
00730 \n\
00731 ================================================================================\n\
00732 MSG: geometry_msgs/Point\n\
00733 # This contains the position of a point in free space\n\
00734 float64 x\n\
00735 float64 y\n\
00736 float64 z\n\
00737 \n\
00738 ================================================================================\n\
00739 MSG: geometry_msgs/Quaternion\n\
00740 # This represents an orientation in free space in quaternion form.\n\
00741 \n\
00742 float64 x\n\
00743 float64 y\n\
00744 float64 z\n\
00745 float64 w\n\
00746 \n\
00747 ================================================================================\n\
00748 MSG: motion_planning_msgs/ArmNavigationErrorCodes\n\
00749 int32 val\n\
00750 \n\
00751 # overall behavior\n\
00752 int32 PLANNING_FAILED=-1\n\
00753 int32 SUCCESS=1\n\
00754 int32 TIMED_OUT=-2\n\
00755 \n\
00756 # start state errors\n\
00757 int32 START_STATE_IN_COLLISION=-3\n\
00758 int32 START_STATE_VIOLATES_PATH_CONSTRAINTS=-4\n\
00759 \n\
00760 # goal errors\n\
00761 int32 GOAL_IN_COLLISION=-5\n\
00762 int32 GOAL_VIOLATES_PATH_CONSTRAINTS=-6\n\
00763 \n\
00764 # robot state\n\
00765 int32 INVALID_ROBOT_STATE=-7\n\
00766 int32 INCOMPLETE_ROBOT_STATE=-8\n\
00767 \n\
00768 # planning request errors\n\
00769 int32 INVALID_PLANNER_ID=-9\n\
00770 int32 INVALID_NUM_PLANNING_ATTEMPTS=-10\n\
00771 int32 INVALID_ALLOWED_PLANNING_TIME=-11\n\
00772 int32 INVALID_GROUP_NAME=-12\n\
00773 int32 INVALID_GOAL_JOINT_CONSTRAINTS=-13\n\
00774 int32 INVALID_GOAL_POSITION_CONSTRAINTS=-14\n\
00775 int32 INVALID_GOAL_ORIENTATION_CONSTRAINTS=-15\n\
00776 int32 INVALID_PATH_JOINT_CONSTRAINTS=-16\n\
00777 int32 INVALID_PATH_POSITION_CONSTRAINTS=-17\n\
00778 int32 INVALID_PATH_ORIENTATION_CONSTRAINTS=-18\n\
00779 \n\
00780 # state/trajectory monitor errors\n\
00781 int32 INVALID_TRAJECTORY=-19\n\
00782 int32 INVALID_INDEX=-20\n\
00783 int32 JOINT_LIMITS_VIOLATED=-21\n\
00784 int32 PATH_CONSTRAINTS_VIOLATED=-22\n\
00785 int32 COLLISION_CONSTRAINTS_VIOLATED=-23\n\
00786 int32 GOAL_CONSTRAINTS_VIOLATED=-24\n\
00787 int32 JOINTS_NOT_MOVING=-25\n\
00788 int32 TRAJECTORY_CONTROLLER_FAILED=-26\n\
00789 \n\
00790 # system errors\n\
00791 int32 FRAME_TRANSFORM_FAILURE=-27\n\
00792 int32 COLLISION_CHECKING_UNAVAILABLE=-28\n\
00793 int32 ROBOT_STATE_STALE=-29\n\
00794 int32 SENSOR_INFO_STALE=-30\n\
00795 \n\
00796 # kinematics errors\n\
00797 int32 NO_IK_SOLUTION=-31\n\
00798 int32 INVALID_LINK_NAME=-32\n\
00799 int32 IK_LINK_IN_COLLISION=-33\n\
00800 int32 NO_FK_SOLUTION=-34\n\
00801 int32 KINEMATICS_STATE_IN_COLLISION=-35\n\
00802 \n\
00803 # general errors\n\
00804 int32 INVALID_TIMEOUT=-36\n\
00805 \n\
00806 \n\
00807 ";
00808 }
00809
00810 static const char* value(const ::kinematics_msgs::GetPositionIKResponse_<ContainerAllocator> &) { return value(); }
00811 };
00812
00813 }
00814 }
00815
00816 namespace ros
00817 {
00818 namespace serialization
00819 {
00820
00821 template<class ContainerAllocator> struct Serializer< ::kinematics_msgs::GetPositionIKRequest_<ContainerAllocator> >
00822 {
00823 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00824 {
00825 stream.next(m.ik_request);
00826 stream.next(m.timeout);
00827 }
00828
00829 ROS_DECLARE_ALLINONE_SERIALIZER;
00830 };
00831 }
00832 }
00833
00834
00835 namespace ros
00836 {
00837 namespace serialization
00838 {
00839
00840 template<class ContainerAllocator> struct Serializer< ::kinematics_msgs::GetPositionIKResponse_<ContainerAllocator> >
00841 {
00842 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00843 {
00844 stream.next(m.solution);
00845 stream.next(m.error_code);
00846 }
00847
00848 ROS_DECLARE_ALLINONE_SERIALIZER;
00849 };
00850 }
00851 }
00852
00853 namespace ros
00854 {
00855 namespace service_traits
00856 {
00857 template<>
00858 struct MD5Sum<kinematics_msgs::GetPositionIK> {
00859 static const char* value()
00860 {
00861 return "6d82fcb918d48c6d8a708bc55e34ace2";
00862 }
00863
00864 static const char* value(const kinematics_msgs::GetPositionIK&) { return value(); }
00865 };
00866
00867 template<>
00868 struct DataType<kinematics_msgs::GetPositionIK> {
00869 static const char* value()
00870 {
00871 return "kinematics_msgs/GetPositionIK";
00872 }
00873
00874 static const char* value(const kinematics_msgs::GetPositionIK&) { return value(); }
00875 };
00876
00877 template<class ContainerAllocator>
00878 struct MD5Sum<kinematics_msgs::GetPositionIKRequest_<ContainerAllocator> > {
00879 static const char* value()
00880 {
00881 return "6d82fcb918d48c6d8a708bc55e34ace2";
00882 }
00883
00884 static const char* value(const kinematics_msgs::GetPositionIKRequest_<ContainerAllocator> &) { return value(); }
00885 };
00886
00887 template<class ContainerAllocator>
00888 struct DataType<kinematics_msgs::GetPositionIKRequest_<ContainerAllocator> > {
00889 static const char* value()
00890 {
00891 return "kinematics_msgs/GetPositionIK";
00892 }
00893
00894 static const char* value(const kinematics_msgs::GetPositionIKRequest_<ContainerAllocator> &) { return value(); }
00895 };
00896
00897 template<class ContainerAllocator>
00898 struct MD5Sum<kinematics_msgs::GetPositionIKResponse_<ContainerAllocator> > {
00899 static const char* value()
00900 {
00901 return "6d82fcb918d48c6d8a708bc55e34ace2";
00902 }
00903
00904 static const char* value(const kinematics_msgs::GetPositionIKResponse_<ContainerAllocator> &) { return value(); }
00905 };
00906
00907 template<class ContainerAllocator>
00908 struct DataType<kinematics_msgs::GetPositionIKResponse_<ContainerAllocator> > {
00909 static const char* value()
00910 {
00911 return "kinematics_msgs/GetPositionIK";
00912 }
00913
00914 static const char* value(const kinematics_msgs::GetPositionIKResponse_<ContainerAllocator> &) { return value(); }
00915 };
00916
00917 }
00918 }
00919
00920 #endif // KINEMATICS_MSGS_SERVICE_GETPOSITIONIK_H
00921