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