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