$search
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-electric-cob_common/doc_stacks/2013-03-01_14-38-37.978792/cob_common/cob_srvs/srv/GetPoseStampedTransformed.srv */ 00002 #ifndef COB_SRVS_SERVICE_GETPOSESTAMPEDTRANSFORMED_H 00003 #define COB_SRVS_SERVICE_GETPOSESTAMPEDTRANSFORMED_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 "geometry_msgs/PoseStamped.h" 00020 #include "geometry_msgs/PoseStamped.h" 00021 #include "geometry_msgs/Quaternion.h" 00022 00023 00024 #include "geometry_msgs/PoseStamped.h" 00025 00026 namespace cob_srvs 00027 { 00028 template <class ContainerAllocator> 00029 struct GetPoseStampedTransformedRequest_ { 00030 typedef GetPoseStampedTransformedRequest_<ContainerAllocator> Type; 00031 00032 GetPoseStampedTransformedRequest_() 00033 : target() 00034 , origin() 00035 , orientation_override() 00036 , root_name() 00037 , tip_name() 00038 { 00039 } 00040 00041 GetPoseStampedTransformedRequest_(const ContainerAllocator& _alloc) 00042 : target(_alloc) 00043 , origin(_alloc) 00044 , orientation_override(_alloc) 00045 , root_name(_alloc) 00046 , tip_name(_alloc) 00047 { 00048 } 00049 00050 typedef ::geometry_msgs::PoseStamped_<ContainerAllocator> _target_type; 00051 ::geometry_msgs::PoseStamped_<ContainerAllocator> target; 00052 00053 typedef ::geometry_msgs::PoseStamped_<ContainerAllocator> _origin_type; 00054 ::geometry_msgs::PoseStamped_<ContainerAllocator> origin; 00055 00056 typedef ::geometry_msgs::Quaternion_<ContainerAllocator> _orientation_override_type; 00057 ::geometry_msgs::Quaternion_<ContainerAllocator> orientation_override; 00058 00059 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _root_name_type; 00060 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > root_name; 00061 00062 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _tip_name_type; 00063 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > tip_name; 00064 00065 00066 private: 00067 static const char* __s_getDataType_() { return "cob_srvs/GetPoseStampedTransformedRequest"; } 00068 public: 00069 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00070 00071 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00072 00073 private: 00074 static const char* __s_getMD5Sum_() { return "7f6050054c7441aa5c8e1b131c78c448"; } 00075 public: 00076 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00077 00078 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00079 00080 private: 00081 static const char* __s_getServerMD5Sum_() { return "ed0069a0a6ce5102fc39c3328eef052f"; } 00082 public: 00083 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); } 00084 00085 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); } 00086 00087 private: 00088 static const char* __s_getMessageDefinition_() { return "geometry_msgs/PoseStamped target\n\ 00089 geometry_msgs/PoseStamped origin\n\ 00090 geometry_msgs/Quaternion orientation_override\n\ 00091 string root_name\n\ 00092 string tip_name\n\ 00093 \n\ 00094 ================================================================================\n\ 00095 MSG: geometry_msgs/PoseStamped\n\ 00096 # A Pose with reference coordinate frame and timestamp\n\ 00097 Header header\n\ 00098 Pose pose\n\ 00099 \n\ 00100 ================================================================================\n\ 00101 MSG: std_msgs/Header\n\ 00102 # Standard metadata for higher-level stamped data types.\n\ 00103 # This is generally used to communicate timestamped data \n\ 00104 # in a particular coordinate frame.\n\ 00105 # \n\ 00106 # sequence ID: consecutively increasing ID \n\ 00107 uint32 seq\n\ 00108 #Two-integer timestamp that is expressed as:\n\ 00109 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00110 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00111 # time-handling sugar is provided by the client library\n\ 00112 time stamp\n\ 00113 #Frame this data is associated with\n\ 00114 # 0: no frame\n\ 00115 # 1: global frame\n\ 00116 string frame_id\n\ 00117 \n\ 00118 ================================================================================\n\ 00119 MSG: geometry_msgs/Pose\n\ 00120 # A representation of pose in free space, composed of postion and orientation. \n\ 00121 Point position\n\ 00122 Quaternion orientation\n\ 00123 \n\ 00124 ================================================================================\n\ 00125 MSG: geometry_msgs/Point\n\ 00126 # This contains the position of a point in free space\n\ 00127 float64 x\n\ 00128 float64 y\n\ 00129 float64 z\n\ 00130 \n\ 00131 ================================================================================\n\ 00132 MSG: geometry_msgs/Quaternion\n\ 00133 # This represents an orientation in free space in quaternion form.\n\ 00134 \n\ 00135 float64 x\n\ 00136 float64 y\n\ 00137 float64 z\n\ 00138 float64 w\n\ 00139 \n\ 00140 "; } 00141 public: 00142 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00143 00144 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00145 00146 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00147 { 00148 ros::serialization::OStream stream(write_ptr, 1000000000); 00149 ros::serialization::serialize(stream, target); 00150 ros::serialization::serialize(stream, origin); 00151 ros::serialization::serialize(stream, orientation_override); 00152 ros::serialization::serialize(stream, root_name); 00153 ros::serialization::serialize(stream, tip_name); 00154 return stream.getData(); 00155 } 00156 00157 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00158 { 00159 ros::serialization::IStream stream(read_ptr, 1000000000); 00160 ros::serialization::deserialize(stream, target); 00161 ros::serialization::deserialize(stream, origin); 00162 ros::serialization::deserialize(stream, orientation_override); 00163 ros::serialization::deserialize(stream, root_name); 00164 ros::serialization::deserialize(stream, tip_name); 00165 return stream.getData(); 00166 } 00167 00168 ROS_DEPRECATED virtual uint32_t serializationLength() const 00169 { 00170 uint32_t size = 0; 00171 size += ros::serialization::serializationLength(target); 00172 size += ros::serialization::serializationLength(origin); 00173 size += ros::serialization::serializationLength(orientation_override); 00174 size += ros::serialization::serializationLength(root_name); 00175 size += ros::serialization::serializationLength(tip_name); 00176 return size; 00177 } 00178 00179 typedef boost::shared_ptr< ::cob_srvs::GetPoseStampedTransformedRequest_<ContainerAllocator> > Ptr; 00180 typedef boost::shared_ptr< ::cob_srvs::GetPoseStampedTransformedRequest_<ContainerAllocator> const> ConstPtr; 00181 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00182 }; // struct GetPoseStampedTransformedRequest 00183 typedef ::cob_srvs::GetPoseStampedTransformedRequest_<std::allocator<void> > GetPoseStampedTransformedRequest; 00184 00185 typedef boost::shared_ptr< ::cob_srvs::GetPoseStampedTransformedRequest> GetPoseStampedTransformedRequestPtr; 00186 typedef boost::shared_ptr< ::cob_srvs::GetPoseStampedTransformedRequest const> GetPoseStampedTransformedRequestConstPtr; 00187 00188 00189 template <class ContainerAllocator> 00190 struct GetPoseStampedTransformedResponse_ { 00191 typedef GetPoseStampedTransformedResponse_<ContainerAllocator> Type; 00192 00193 GetPoseStampedTransformedResponse_() 00194 : success(false) 00195 , result() 00196 { 00197 } 00198 00199 GetPoseStampedTransformedResponse_(const ContainerAllocator& _alloc) 00200 : success(false) 00201 , result(_alloc) 00202 { 00203 } 00204 00205 typedef uint8_t _success_type; 00206 uint8_t success; 00207 00208 typedef ::geometry_msgs::PoseStamped_<ContainerAllocator> _result_type; 00209 ::geometry_msgs::PoseStamped_<ContainerAllocator> result; 00210 00211 00212 private: 00213 static const char* __s_getDataType_() { return "cob_srvs/GetPoseStampedTransformedResponse"; } 00214 public: 00215 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00216 00217 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00218 00219 private: 00220 static const char* __s_getMD5Sum_() { return "aa1ecfaaa2557395e49e336255c7a317"; } 00221 public: 00222 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00223 00224 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00225 00226 private: 00227 static const char* __s_getServerMD5Sum_() { return "ed0069a0a6ce5102fc39c3328eef052f"; } 00228 public: 00229 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); } 00230 00231 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); } 00232 00233 private: 00234 static const char* __s_getMessageDefinition_() { return "bool success\n\ 00235 geometry_msgs/PoseStamped result\n\ 00236 \n\ 00237 \n\ 00238 ================================================================================\n\ 00239 MSG: geometry_msgs/PoseStamped\n\ 00240 # A Pose with reference coordinate frame and timestamp\n\ 00241 Header header\n\ 00242 Pose pose\n\ 00243 \n\ 00244 ================================================================================\n\ 00245 MSG: std_msgs/Header\n\ 00246 # Standard metadata for higher-level stamped data types.\n\ 00247 # This is generally used to communicate timestamped data \n\ 00248 # in a particular coordinate frame.\n\ 00249 # \n\ 00250 # sequence ID: consecutively increasing ID \n\ 00251 uint32 seq\n\ 00252 #Two-integer timestamp that is expressed as:\n\ 00253 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00254 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00255 # time-handling sugar is provided by the client library\n\ 00256 time stamp\n\ 00257 #Frame this data is associated with\n\ 00258 # 0: no frame\n\ 00259 # 1: global frame\n\ 00260 string frame_id\n\ 00261 \n\ 00262 ================================================================================\n\ 00263 MSG: geometry_msgs/Pose\n\ 00264 # A representation of pose in free space, composed of postion and orientation. \n\ 00265 Point position\n\ 00266 Quaternion orientation\n\ 00267 \n\ 00268 ================================================================================\n\ 00269 MSG: geometry_msgs/Point\n\ 00270 # This contains the position of a point in free space\n\ 00271 float64 x\n\ 00272 float64 y\n\ 00273 float64 z\n\ 00274 \n\ 00275 ================================================================================\n\ 00276 MSG: geometry_msgs/Quaternion\n\ 00277 # This represents an orientation in free space in quaternion form.\n\ 00278 \n\ 00279 float64 x\n\ 00280 float64 y\n\ 00281 float64 z\n\ 00282 float64 w\n\ 00283 \n\ 00284 "; } 00285 public: 00286 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00287 00288 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00289 00290 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00291 { 00292 ros::serialization::OStream stream(write_ptr, 1000000000); 00293 ros::serialization::serialize(stream, success); 00294 ros::serialization::serialize(stream, result); 00295 return stream.getData(); 00296 } 00297 00298 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00299 { 00300 ros::serialization::IStream stream(read_ptr, 1000000000); 00301 ros::serialization::deserialize(stream, success); 00302 ros::serialization::deserialize(stream, result); 00303 return stream.getData(); 00304 } 00305 00306 ROS_DEPRECATED virtual uint32_t serializationLength() const 00307 { 00308 uint32_t size = 0; 00309 size += ros::serialization::serializationLength(success); 00310 size += ros::serialization::serializationLength(result); 00311 return size; 00312 } 00313 00314 typedef boost::shared_ptr< ::cob_srvs::GetPoseStampedTransformedResponse_<ContainerAllocator> > Ptr; 00315 typedef boost::shared_ptr< ::cob_srvs::GetPoseStampedTransformedResponse_<ContainerAllocator> const> ConstPtr; 00316 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00317 }; // struct GetPoseStampedTransformedResponse 00318 typedef ::cob_srvs::GetPoseStampedTransformedResponse_<std::allocator<void> > GetPoseStampedTransformedResponse; 00319 00320 typedef boost::shared_ptr< ::cob_srvs::GetPoseStampedTransformedResponse> GetPoseStampedTransformedResponsePtr; 00321 typedef boost::shared_ptr< ::cob_srvs::GetPoseStampedTransformedResponse const> GetPoseStampedTransformedResponseConstPtr; 00322 00323 struct GetPoseStampedTransformed 00324 { 00325 00326 typedef GetPoseStampedTransformedRequest Request; 00327 typedef GetPoseStampedTransformedResponse Response; 00328 Request request; 00329 Response response; 00330 00331 typedef Request RequestType; 00332 typedef Response ResponseType; 00333 }; // struct GetPoseStampedTransformed 00334 } // namespace cob_srvs 00335 00336 namespace ros 00337 { 00338 namespace message_traits 00339 { 00340 template<class ContainerAllocator> struct IsMessage< ::cob_srvs::GetPoseStampedTransformedRequest_<ContainerAllocator> > : public TrueType {}; 00341 template<class ContainerAllocator> struct IsMessage< ::cob_srvs::GetPoseStampedTransformedRequest_<ContainerAllocator> const> : public TrueType {}; 00342 template<class ContainerAllocator> 00343 struct MD5Sum< ::cob_srvs::GetPoseStampedTransformedRequest_<ContainerAllocator> > { 00344 static const char* value() 00345 { 00346 return "7f6050054c7441aa5c8e1b131c78c448"; 00347 } 00348 00349 static const char* value(const ::cob_srvs::GetPoseStampedTransformedRequest_<ContainerAllocator> &) { return value(); } 00350 static const uint64_t static_value1 = 0x7f6050054c7441aaULL; 00351 static const uint64_t static_value2 = 0x5c8e1b131c78c448ULL; 00352 }; 00353 00354 template<class ContainerAllocator> 00355 struct DataType< ::cob_srvs::GetPoseStampedTransformedRequest_<ContainerAllocator> > { 00356 static const char* value() 00357 { 00358 return "cob_srvs/GetPoseStampedTransformedRequest"; 00359 } 00360 00361 static const char* value(const ::cob_srvs::GetPoseStampedTransformedRequest_<ContainerAllocator> &) { return value(); } 00362 }; 00363 00364 template<class ContainerAllocator> 00365 struct Definition< ::cob_srvs::GetPoseStampedTransformedRequest_<ContainerAllocator> > { 00366 static const char* value() 00367 { 00368 return "geometry_msgs/PoseStamped target\n\ 00369 geometry_msgs/PoseStamped origin\n\ 00370 geometry_msgs/Quaternion orientation_override\n\ 00371 string root_name\n\ 00372 string tip_name\n\ 00373 \n\ 00374 ================================================================================\n\ 00375 MSG: geometry_msgs/PoseStamped\n\ 00376 # A Pose with reference coordinate frame and timestamp\n\ 00377 Header header\n\ 00378 Pose pose\n\ 00379 \n\ 00380 ================================================================================\n\ 00381 MSG: std_msgs/Header\n\ 00382 # Standard metadata for higher-level stamped data types.\n\ 00383 # This is generally used to communicate timestamped data \n\ 00384 # in a particular coordinate frame.\n\ 00385 # \n\ 00386 # sequence ID: consecutively increasing ID \n\ 00387 uint32 seq\n\ 00388 #Two-integer timestamp that is expressed as:\n\ 00389 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00390 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00391 # time-handling sugar is provided by the client library\n\ 00392 time stamp\n\ 00393 #Frame this data is associated with\n\ 00394 # 0: no frame\n\ 00395 # 1: global frame\n\ 00396 string frame_id\n\ 00397 \n\ 00398 ================================================================================\n\ 00399 MSG: geometry_msgs/Pose\n\ 00400 # A representation of pose in free space, composed of postion and orientation. \n\ 00401 Point position\n\ 00402 Quaternion orientation\n\ 00403 \n\ 00404 ================================================================================\n\ 00405 MSG: geometry_msgs/Point\n\ 00406 # This contains the position of a point in free space\n\ 00407 float64 x\n\ 00408 float64 y\n\ 00409 float64 z\n\ 00410 \n\ 00411 ================================================================================\n\ 00412 MSG: geometry_msgs/Quaternion\n\ 00413 # This represents an orientation in free space in quaternion form.\n\ 00414 \n\ 00415 float64 x\n\ 00416 float64 y\n\ 00417 float64 z\n\ 00418 float64 w\n\ 00419 \n\ 00420 "; 00421 } 00422 00423 static const char* value(const ::cob_srvs::GetPoseStampedTransformedRequest_<ContainerAllocator> &) { return value(); } 00424 }; 00425 00426 } // namespace message_traits 00427 } // namespace ros 00428 00429 00430 namespace ros 00431 { 00432 namespace message_traits 00433 { 00434 template<class ContainerAllocator> struct IsMessage< ::cob_srvs::GetPoseStampedTransformedResponse_<ContainerAllocator> > : public TrueType {}; 00435 template<class ContainerAllocator> struct IsMessage< ::cob_srvs::GetPoseStampedTransformedResponse_<ContainerAllocator> const> : public TrueType {}; 00436 template<class ContainerAllocator> 00437 struct MD5Sum< ::cob_srvs::GetPoseStampedTransformedResponse_<ContainerAllocator> > { 00438 static const char* value() 00439 { 00440 return "aa1ecfaaa2557395e49e336255c7a317"; 00441 } 00442 00443 static const char* value(const ::cob_srvs::GetPoseStampedTransformedResponse_<ContainerAllocator> &) { return value(); } 00444 static const uint64_t static_value1 = 0xaa1ecfaaa2557395ULL; 00445 static const uint64_t static_value2 = 0xe49e336255c7a317ULL; 00446 }; 00447 00448 template<class ContainerAllocator> 00449 struct DataType< ::cob_srvs::GetPoseStampedTransformedResponse_<ContainerAllocator> > { 00450 static const char* value() 00451 { 00452 return "cob_srvs/GetPoseStampedTransformedResponse"; 00453 } 00454 00455 static const char* value(const ::cob_srvs::GetPoseStampedTransformedResponse_<ContainerAllocator> &) { return value(); } 00456 }; 00457 00458 template<class ContainerAllocator> 00459 struct Definition< ::cob_srvs::GetPoseStampedTransformedResponse_<ContainerAllocator> > { 00460 static const char* value() 00461 { 00462 return "bool success\n\ 00463 geometry_msgs/PoseStamped result\n\ 00464 \n\ 00465 \n\ 00466 ================================================================================\n\ 00467 MSG: geometry_msgs/PoseStamped\n\ 00468 # A Pose with reference coordinate frame and timestamp\n\ 00469 Header header\n\ 00470 Pose pose\n\ 00471 \n\ 00472 ================================================================================\n\ 00473 MSG: std_msgs/Header\n\ 00474 # Standard metadata for higher-level stamped data types.\n\ 00475 # This is generally used to communicate timestamped data \n\ 00476 # in a particular coordinate frame.\n\ 00477 # \n\ 00478 # sequence ID: consecutively increasing ID \n\ 00479 uint32 seq\n\ 00480 #Two-integer timestamp that is expressed as:\n\ 00481 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00482 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00483 # time-handling sugar is provided by the client library\n\ 00484 time stamp\n\ 00485 #Frame this data is associated with\n\ 00486 # 0: no frame\n\ 00487 # 1: global frame\n\ 00488 string frame_id\n\ 00489 \n\ 00490 ================================================================================\n\ 00491 MSG: geometry_msgs/Pose\n\ 00492 # A representation of pose in free space, composed of postion and orientation. \n\ 00493 Point position\n\ 00494 Quaternion orientation\n\ 00495 \n\ 00496 ================================================================================\n\ 00497 MSG: geometry_msgs/Point\n\ 00498 # This contains the position of a point in free space\n\ 00499 float64 x\n\ 00500 float64 y\n\ 00501 float64 z\n\ 00502 \n\ 00503 ================================================================================\n\ 00504 MSG: geometry_msgs/Quaternion\n\ 00505 # This represents an orientation in free space in quaternion form.\n\ 00506 \n\ 00507 float64 x\n\ 00508 float64 y\n\ 00509 float64 z\n\ 00510 float64 w\n\ 00511 \n\ 00512 "; 00513 } 00514 00515 static const char* value(const ::cob_srvs::GetPoseStampedTransformedResponse_<ContainerAllocator> &) { return value(); } 00516 }; 00517 00518 } // namespace message_traits 00519 } // namespace ros 00520 00521 namespace ros 00522 { 00523 namespace serialization 00524 { 00525 00526 template<class ContainerAllocator> struct Serializer< ::cob_srvs::GetPoseStampedTransformedRequest_<ContainerAllocator> > 00527 { 00528 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00529 { 00530 stream.next(m.target); 00531 stream.next(m.origin); 00532 stream.next(m.orientation_override); 00533 stream.next(m.root_name); 00534 stream.next(m.tip_name); 00535 } 00536 00537 ROS_DECLARE_ALLINONE_SERIALIZER; 00538 }; // struct GetPoseStampedTransformedRequest_ 00539 } // namespace serialization 00540 } // namespace ros 00541 00542 00543 namespace ros 00544 { 00545 namespace serialization 00546 { 00547 00548 template<class ContainerAllocator> struct Serializer< ::cob_srvs::GetPoseStampedTransformedResponse_<ContainerAllocator> > 00549 { 00550 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00551 { 00552 stream.next(m.success); 00553 stream.next(m.result); 00554 } 00555 00556 ROS_DECLARE_ALLINONE_SERIALIZER; 00557 }; // struct GetPoseStampedTransformedResponse_ 00558 } // namespace serialization 00559 } // namespace ros 00560 00561 namespace ros 00562 { 00563 namespace service_traits 00564 { 00565 template<> 00566 struct MD5Sum<cob_srvs::GetPoseStampedTransformed> { 00567 static const char* value() 00568 { 00569 return "ed0069a0a6ce5102fc39c3328eef052f"; 00570 } 00571 00572 static const char* value(const cob_srvs::GetPoseStampedTransformed&) { return value(); } 00573 }; 00574 00575 template<> 00576 struct DataType<cob_srvs::GetPoseStampedTransformed> { 00577 static const char* value() 00578 { 00579 return "cob_srvs/GetPoseStampedTransformed"; 00580 } 00581 00582 static const char* value(const cob_srvs::GetPoseStampedTransformed&) { return value(); } 00583 }; 00584 00585 template<class ContainerAllocator> 00586 struct MD5Sum<cob_srvs::GetPoseStampedTransformedRequest_<ContainerAllocator> > { 00587 static const char* value() 00588 { 00589 return "ed0069a0a6ce5102fc39c3328eef052f"; 00590 } 00591 00592 static const char* value(const cob_srvs::GetPoseStampedTransformedRequest_<ContainerAllocator> &) { return value(); } 00593 }; 00594 00595 template<class ContainerAllocator> 00596 struct DataType<cob_srvs::GetPoseStampedTransformedRequest_<ContainerAllocator> > { 00597 static const char* value() 00598 { 00599 return "cob_srvs/GetPoseStampedTransformed"; 00600 } 00601 00602 static const char* value(const cob_srvs::GetPoseStampedTransformedRequest_<ContainerAllocator> &) { return value(); } 00603 }; 00604 00605 template<class ContainerAllocator> 00606 struct MD5Sum<cob_srvs::GetPoseStampedTransformedResponse_<ContainerAllocator> > { 00607 static const char* value() 00608 { 00609 return "ed0069a0a6ce5102fc39c3328eef052f"; 00610 } 00611 00612 static const char* value(const cob_srvs::GetPoseStampedTransformedResponse_<ContainerAllocator> &) { return value(); } 00613 }; 00614 00615 template<class ContainerAllocator> 00616 struct DataType<cob_srvs::GetPoseStampedTransformedResponse_<ContainerAllocator> > { 00617 static const char* value() 00618 { 00619 return "cob_srvs/GetPoseStampedTransformed"; 00620 } 00621 00622 static const char* value(const cob_srvs::GetPoseStampedTransformedResponse_<ContainerAllocator> &) { return value(); } 00623 }; 00624 00625 } // namespace service_traits 00626 } // namespace ros 00627 00628 #endif // COB_SRVS_SERVICE_GETPOSESTAMPEDTRANSFORMED_H 00629