$search
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-electric-tu-darmstadt-ros-pkg/doc_stacks/2013-03-05_12-22-58.304137/hector_slam/hector_nav_msgs/srv/GetRecoveryInfo.srv */ 00002 #ifndef HECTOR_NAV_MSGS_SERVICE_GETRECOVERYINFO_H 00003 #define HECTOR_NAV_MSGS_SERVICE_GETRECOVERYINFO_H 00004 #include <string> 00005 #include <vector> 00006 #include <map> 00007 #include <ostream> 00008 #include "ros/serialization.h" 00009 #include "ros/builtin_message_traits.h" 00010 #include "ros/message_operations.h" 00011 #include "ros/time.h" 00012 00013 #include "ros/macros.h" 00014 00015 #include "ros/assert.h" 00016 00017 #include "ros/service_traits.h" 00018 00019 00020 00021 #include "nav_msgs/Path.h" 00022 #include "geometry_msgs/PoseStamped.h" 00023 #include "geometry_msgs/PoseStamped.h" 00024 00025 namespace hector_nav_msgs 00026 { 00027 template <class ContainerAllocator> 00028 struct GetRecoveryInfoRequest_ { 00029 typedef GetRecoveryInfoRequest_<ContainerAllocator> Type; 00030 00031 GetRecoveryInfoRequest_() 00032 : request_time() 00033 , request_radius(0.0) 00034 { 00035 } 00036 00037 GetRecoveryInfoRequest_(const ContainerAllocator& _alloc) 00038 : request_time() 00039 , request_radius(0.0) 00040 { 00041 } 00042 00043 typedef ros::Time _request_time_type; 00044 ros::Time request_time; 00045 00046 typedef double _request_radius_type; 00047 double request_radius; 00048 00049 00050 private: 00051 static const char* __s_getDataType_() { return "hector_nav_msgs/GetRecoveryInfoRequest"; } 00052 public: 00053 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00054 00055 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00056 00057 private: 00058 static const char* __s_getMD5Sum_() { return "3916a0c55958d5dd43204cd2fe5608f6"; } 00059 public: 00060 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00061 00062 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00063 00064 private: 00065 static const char* __s_getServerMD5Sum_() { return "edd6e579a08e5c27f2b7fcfa4c39b7bb"; } 00066 public: 00067 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); } 00068 00069 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); } 00070 00071 private: 00072 static const char* __s_getMessageDefinition_() { return "\n\ 00073 \n\ 00074 \n\ 00075 \n\ 00076 time request_time\n\ 00077 float64 request_radius\n\ 00078 \n\ 00079 "; } 00080 public: 00081 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00082 00083 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00084 00085 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00086 { 00087 ros::serialization::OStream stream(write_ptr, 1000000000); 00088 ros::serialization::serialize(stream, request_time); 00089 ros::serialization::serialize(stream, request_radius); 00090 return stream.getData(); 00091 } 00092 00093 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00094 { 00095 ros::serialization::IStream stream(read_ptr, 1000000000); 00096 ros::serialization::deserialize(stream, request_time); 00097 ros::serialization::deserialize(stream, request_radius); 00098 return stream.getData(); 00099 } 00100 00101 ROS_DEPRECATED virtual uint32_t serializationLength() const 00102 { 00103 uint32_t size = 0; 00104 size += ros::serialization::serializationLength(request_time); 00105 size += ros::serialization::serializationLength(request_radius); 00106 return size; 00107 } 00108 00109 typedef boost::shared_ptr< ::hector_nav_msgs::GetRecoveryInfoRequest_<ContainerAllocator> > Ptr; 00110 typedef boost::shared_ptr< ::hector_nav_msgs::GetRecoveryInfoRequest_<ContainerAllocator> const> ConstPtr; 00111 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00112 }; // struct GetRecoveryInfoRequest 00113 typedef ::hector_nav_msgs::GetRecoveryInfoRequest_<std::allocator<void> > GetRecoveryInfoRequest; 00114 00115 typedef boost::shared_ptr< ::hector_nav_msgs::GetRecoveryInfoRequest> GetRecoveryInfoRequestPtr; 00116 typedef boost::shared_ptr< ::hector_nav_msgs::GetRecoveryInfoRequest const> GetRecoveryInfoRequestConstPtr; 00117 00118 00119 template <class ContainerAllocator> 00120 struct GetRecoveryInfoResponse_ { 00121 typedef GetRecoveryInfoResponse_<ContainerAllocator> Type; 00122 00123 GetRecoveryInfoResponse_() 00124 : trajectory_radius_entry_pose_to_req_pose() 00125 , radius_entry_pose() 00126 , req_pose() 00127 { 00128 } 00129 00130 GetRecoveryInfoResponse_(const ContainerAllocator& _alloc) 00131 : trajectory_radius_entry_pose_to_req_pose(_alloc) 00132 , radius_entry_pose(_alloc) 00133 , req_pose(_alloc) 00134 { 00135 } 00136 00137 typedef ::nav_msgs::Path_<ContainerAllocator> _trajectory_radius_entry_pose_to_req_pose_type; 00138 ::nav_msgs::Path_<ContainerAllocator> trajectory_radius_entry_pose_to_req_pose; 00139 00140 typedef ::geometry_msgs::PoseStamped_<ContainerAllocator> _radius_entry_pose_type; 00141 ::geometry_msgs::PoseStamped_<ContainerAllocator> radius_entry_pose; 00142 00143 typedef ::geometry_msgs::PoseStamped_<ContainerAllocator> _req_pose_type; 00144 ::geometry_msgs::PoseStamped_<ContainerAllocator> req_pose; 00145 00146 00147 private: 00148 static const char* __s_getDataType_() { return "hector_nav_msgs/GetRecoveryInfoResponse"; } 00149 public: 00150 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00151 00152 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00153 00154 private: 00155 static const char* __s_getMD5Sum_() { return "a93581be8e34e3c09aeafc6b9b990ad5"; } 00156 public: 00157 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00158 00159 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00160 00161 private: 00162 static const char* __s_getServerMD5Sum_() { return "edd6e579a08e5c27f2b7fcfa4c39b7bb"; } 00163 public: 00164 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); } 00165 00166 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); } 00167 00168 private: 00169 static const char* __s_getMessageDefinition_() { return "nav_msgs/Path trajectory_radius_entry_pose_to_req_pose\n\ 00170 geometry_msgs/PoseStamped radius_entry_pose\n\ 00171 geometry_msgs/PoseStamped req_pose\n\ 00172 \n\ 00173 \n\ 00174 \n\ 00175 ================================================================================\n\ 00176 MSG: nav_msgs/Path\n\ 00177 #An array of poses that represents a Path for a robot to follow\n\ 00178 Header header\n\ 00179 geometry_msgs/PoseStamped[] poses\n\ 00180 \n\ 00181 ================================================================================\n\ 00182 MSG: std_msgs/Header\n\ 00183 # Standard metadata for higher-level stamped data types.\n\ 00184 # This is generally used to communicate timestamped data \n\ 00185 # in a particular coordinate frame.\n\ 00186 # \n\ 00187 # sequence ID: consecutively increasing ID \n\ 00188 uint32 seq\n\ 00189 #Two-integer timestamp that is expressed as:\n\ 00190 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00191 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00192 # time-handling sugar is provided by the client library\n\ 00193 time stamp\n\ 00194 #Frame this data is associated with\n\ 00195 # 0: no frame\n\ 00196 # 1: global frame\n\ 00197 string frame_id\n\ 00198 \n\ 00199 ================================================================================\n\ 00200 MSG: geometry_msgs/PoseStamped\n\ 00201 # A Pose with reference coordinate frame and timestamp\n\ 00202 Header header\n\ 00203 Pose pose\n\ 00204 \n\ 00205 ================================================================================\n\ 00206 MSG: geometry_msgs/Pose\n\ 00207 # A representation of pose in free space, composed of postion and orientation. \n\ 00208 Point position\n\ 00209 Quaternion orientation\n\ 00210 \n\ 00211 ================================================================================\n\ 00212 MSG: geometry_msgs/Point\n\ 00213 # This contains the position of a point in free space\n\ 00214 float64 x\n\ 00215 float64 y\n\ 00216 float64 z\n\ 00217 \n\ 00218 ================================================================================\n\ 00219 MSG: geometry_msgs/Quaternion\n\ 00220 # This represents an orientation in free space in quaternion form.\n\ 00221 \n\ 00222 float64 x\n\ 00223 float64 y\n\ 00224 float64 z\n\ 00225 float64 w\n\ 00226 \n\ 00227 "; } 00228 public: 00229 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00230 00231 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00232 00233 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00234 { 00235 ros::serialization::OStream stream(write_ptr, 1000000000); 00236 ros::serialization::serialize(stream, trajectory_radius_entry_pose_to_req_pose); 00237 ros::serialization::serialize(stream, radius_entry_pose); 00238 ros::serialization::serialize(stream, req_pose); 00239 return stream.getData(); 00240 } 00241 00242 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00243 { 00244 ros::serialization::IStream stream(read_ptr, 1000000000); 00245 ros::serialization::deserialize(stream, trajectory_radius_entry_pose_to_req_pose); 00246 ros::serialization::deserialize(stream, radius_entry_pose); 00247 ros::serialization::deserialize(stream, req_pose); 00248 return stream.getData(); 00249 } 00250 00251 ROS_DEPRECATED virtual uint32_t serializationLength() const 00252 { 00253 uint32_t size = 0; 00254 size += ros::serialization::serializationLength(trajectory_radius_entry_pose_to_req_pose); 00255 size += ros::serialization::serializationLength(radius_entry_pose); 00256 size += ros::serialization::serializationLength(req_pose); 00257 return size; 00258 } 00259 00260 typedef boost::shared_ptr< ::hector_nav_msgs::GetRecoveryInfoResponse_<ContainerAllocator> > Ptr; 00261 typedef boost::shared_ptr< ::hector_nav_msgs::GetRecoveryInfoResponse_<ContainerAllocator> const> ConstPtr; 00262 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00263 }; // struct GetRecoveryInfoResponse 00264 typedef ::hector_nav_msgs::GetRecoveryInfoResponse_<std::allocator<void> > GetRecoveryInfoResponse; 00265 00266 typedef boost::shared_ptr< ::hector_nav_msgs::GetRecoveryInfoResponse> GetRecoveryInfoResponsePtr; 00267 typedef boost::shared_ptr< ::hector_nav_msgs::GetRecoveryInfoResponse const> GetRecoveryInfoResponseConstPtr; 00268 00269 struct GetRecoveryInfo 00270 { 00271 00272 typedef GetRecoveryInfoRequest Request; 00273 typedef GetRecoveryInfoResponse Response; 00274 Request request; 00275 Response response; 00276 00277 typedef Request RequestType; 00278 typedef Response ResponseType; 00279 }; // struct GetRecoveryInfo 00280 } // namespace hector_nav_msgs 00281 00282 namespace ros 00283 { 00284 namespace message_traits 00285 { 00286 template<class ContainerAllocator> struct IsMessage< ::hector_nav_msgs::GetRecoveryInfoRequest_<ContainerAllocator> > : public TrueType {}; 00287 template<class ContainerAllocator> struct IsMessage< ::hector_nav_msgs::GetRecoveryInfoRequest_<ContainerAllocator> const> : public TrueType {}; 00288 template<class ContainerAllocator> 00289 struct MD5Sum< ::hector_nav_msgs::GetRecoveryInfoRequest_<ContainerAllocator> > { 00290 static const char* value() 00291 { 00292 return "3916a0c55958d5dd43204cd2fe5608f6"; 00293 } 00294 00295 static const char* value(const ::hector_nav_msgs::GetRecoveryInfoRequest_<ContainerAllocator> &) { return value(); } 00296 static const uint64_t static_value1 = 0x3916a0c55958d5ddULL; 00297 static const uint64_t static_value2 = 0x43204cd2fe5608f6ULL; 00298 }; 00299 00300 template<class ContainerAllocator> 00301 struct DataType< ::hector_nav_msgs::GetRecoveryInfoRequest_<ContainerAllocator> > { 00302 static const char* value() 00303 { 00304 return "hector_nav_msgs/GetRecoveryInfoRequest"; 00305 } 00306 00307 static const char* value(const ::hector_nav_msgs::GetRecoveryInfoRequest_<ContainerAllocator> &) { return value(); } 00308 }; 00309 00310 template<class ContainerAllocator> 00311 struct Definition< ::hector_nav_msgs::GetRecoveryInfoRequest_<ContainerAllocator> > { 00312 static const char* value() 00313 { 00314 return "\n\ 00315 \n\ 00316 \n\ 00317 \n\ 00318 time request_time\n\ 00319 float64 request_radius\n\ 00320 \n\ 00321 "; 00322 } 00323 00324 static const char* value(const ::hector_nav_msgs::GetRecoveryInfoRequest_<ContainerAllocator> &) { return value(); } 00325 }; 00326 00327 template<class ContainerAllocator> struct IsFixedSize< ::hector_nav_msgs::GetRecoveryInfoRequest_<ContainerAllocator> > : public TrueType {}; 00328 } // namespace message_traits 00329 } // namespace ros 00330 00331 00332 namespace ros 00333 { 00334 namespace message_traits 00335 { 00336 template<class ContainerAllocator> struct IsMessage< ::hector_nav_msgs::GetRecoveryInfoResponse_<ContainerAllocator> > : public TrueType {}; 00337 template<class ContainerAllocator> struct IsMessage< ::hector_nav_msgs::GetRecoveryInfoResponse_<ContainerAllocator> const> : public TrueType {}; 00338 template<class ContainerAllocator> 00339 struct MD5Sum< ::hector_nav_msgs::GetRecoveryInfoResponse_<ContainerAllocator> > { 00340 static const char* value() 00341 { 00342 return "a93581be8e34e3c09aeafc6b9b990ad5"; 00343 } 00344 00345 static const char* value(const ::hector_nav_msgs::GetRecoveryInfoResponse_<ContainerAllocator> &) { return value(); } 00346 static const uint64_t static_value1 = 0xa93581be8e34e3c0ULL; 00347 static const uint64_t static_value2 = 0x9aeafc6b9b990ad5ULL; 00348 }; 00349 00350 template<class ContainerAllocator> 00351 struct DataType< ::hector_nav_msgs::GetRecoveryInfoResponse_<ContainerAllocator> > { 00352 static const char* value() 00353 { 00354 return "hector_nav_msgs/GetRecoveryInfoResponse"; 00355 } 00356 00357 static const char* value(const ::hector_nav_msgs::GetRecoveryInfoResponse_<ContainerAllocator> &) { return value(); } 00358 }; 00359 00360 template<class ContainerAllocator> 00361 struct Definition< ::hector_nav_msgs::GetRecoveryInfoResponse_<ContainerAllocator> > { 00362 static const char* value() 00363 { 00364 return "nav_msgs/Path trajectory_radius_entry_pose_to_req_pose\n\ 00365 geometry_msgs/PoseStamped radius_entry_pose\n\ 00366 geometry_msgs/PoseStamped req_pose\n\ 00367 \n\ 00368 \n\ 00369 \n\ 00370 ================================================================================\n\ 00371 MSG: nav_msgs/Path\n\ 00372 #An array of poses that represents a Path for a robot to follow\n\ 00373 Header header\n\ 00374 geometry_msgs/PoseStamped[] poses\n\ 00375 \n\ 00376 ================================================================================\n\ 00377 MSG: std_msgs/Header\n\ 00378 # Standard metadata for higher-level stamped data types.\n\ 00379 # This is generally used to communicate timestamped data \n\ 00380 # in a particular coordinate frame.\n\ 00381 # \n\ 00382 # sequence ID: consecutively increasing ID \n\ 00383 uint32 seq\n\ 00384 #Two-integer timestamp that is expressed as:\n\ 00385 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00386 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00387 # time-handling sugar is provided by the client library\n\ 00388 time stamp\n\ 00389 #Frame this data is associated with\n\ 00390 # 0: no frame\n\ 00391 # 1: global frame\n\ 00392 string frame_id\n\ 00393 \n\ 00394 ================================================================================\n\ 00395 MSG: geometry_msgs/PoseStamped\n\ 00396 # A Pose with reference coordinate frame and timestamp\n\ 00397 Header header\n\ 00398 Pose pose\n\ 00399 \n\ 00400 ================================================================================\n\ 00401 MSG: geometry_msgs/Pose\n\ 00402 # A representation of pose in free space, composed of postion and orientation. \n\ 00403 Point position\n\ 00404 Quaternion orientation\n\ 00405 \n\ 00406 ================================================================================\n\ 00407 MSG: geometry_msgs/Point\n\ 00408 # This contains the position of a point in free space\n\ 00409 float64 x\n\ 00410 float64 y\n\ 00411 float64 z\n\ 00412 \n\ 00413 ================================================================================\n\ 00414 MSG: geometry_msgs/Quaternion\n\ 00415 # This represents an orientation in free space in quaternion form.\n\ 00416 \n\ 00417 float64 x\n\ 00418 float64 y\n\ 00419 float64 z\n\ 00420 float64 w\n\ 00421 \n\ 00422 "; 00423 } 00424 00425 static const char* value(const ::hector_nav_msgs::GetRecoveryInfoResponse_<ContainerAllocator> &) { return value(); } 00426 }; 00427 00428 } // namespace message_traits 00429 } // namespace ros 00430 00431 namespace ros 00432 { 00433 namespace serialization 00434 { 00435 00436 template<class ContainerAllocator> struct Serializer< ::hector_nav_msgs::GetRecoveryInfoRequest_<ContainerAllocator> > 00437 { 00438 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00439 { 00440 stream.next(m.request_time); 00441 stream.next(m.request_radius); 00442 } 00443 00444 ROS_DECLARE_ALLINONE_SERIALIZER; 00445 }; // struct GetRecoveryInfoRequest_ 00446 } // namespace serialization 00447 } // namespace ros 00448 00449 00450 namespace ros 00451 { 00452 namespace serialization 00453 { 00454 00455 template<class ContainerAllocator> struct Serializer< ::hector_nav_msgs::GetRecoveryInfoResponse_<ContainerAllocator> > 00456 { 00457 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00458 { 00459 stream.next(m.trajectory_radius_entry_pose_to_req_pose); 00460 stream.next(m.radius_entry_pose); 00461 stream.next(m.req_pose); 00462 } 00463 00464 ROS_DECLARE_ALLINONE_SERIALIZER; 00465 }; // struct GetRecoveryInfoResponse_ 00466 } // namespace serialization 00467 } // namespace ros 00468 00469 namespace ros 00470 { 00471 namespace service_traits 00472 { 00473 template<> 00474 struct MD5Sum<hector_nav_msgs::GetRecoveryInfo> { 00475 static const char* value() 00476 { 00477 return "edd6e579a08e5c27f2b7fcfa4c39b7bb"; 00478 } 00479 00480 static const char* value(const hector_nav_msgs::GetRecoveryInfo&) { return value(); } 00481 }; 00482 00483 template<> 00484 struct DataType<hector_nav_msgs::GetRecoveryInfo> { 00485 static const char* value() 00486 { 00487 return "hector_nav_msgs/GetRecoveryInfo"; 00488 } 00489 00490 static const char* value(const hector_nav_msgs::GetRecoveryInfo&) { return value(); } 00491 }; 00492 00493 template<class ContainerAllocator> 00494 struct MD5Sum<hector_nav_msgs::GetRecoveryInfoRequest_<ContainerAllocator> > { 00495 static const char* value() 00496 { 00497 return "edd6e579a08e5c27f2b7fcfa4c39b7bb"; 00498 } 00499 00500 static const char* value(const hector_nav_msgs::GetRecoveryInfoRequest_<ContainerAllocator> &) { return value(); } 00501 }; 00502 00503 template<class ContainerAllocator> 00504 struct DataType<hector_nav_msgs::GetRecoveryInfoRequest_<ContainerAllocator> > { 00505 static const char* value() 00506 { 00507 return "hector_nav_msgs/GetRecoveryInfo"; 00508 } 00509 00510 static const char* value(const hector_nav_msgs::GetRecoveryInfoRequest_<ContainerAllocator> &) { return value(); } 00511 }; 00512 00513 template<class ContainerAllocator> 00514 struct MD5Sum<hector_nav_msgs::GetRecoveryInfoResponse_<ContainerAllocator> > { 00515 static const char* value() 00516 { 00517 return "edd6e579a08e5c27f2b7fcfa4c39b7bb"; 00518 } 00519 00520 static const char* value(const hector_nav_msgs::GetRecoveryInfoResponse_<ContainerAllocator> &) { return value(); } 00521 }; 00522 00523 template<class ContainerAllocator> 00524 struct DataType<hector_nav_msgs::GetRecoveryInfoResponse_<ContainerAllocator> > { 00525 static const char* value() 00526 { 00527 return "hector_nav_msgs/GetRecoveryInfo"; 00528 } 00529 00530 static const char* value(const hector_nav_msgs::GetRecoveryInfoResponse_<ContainerAllocator> &) { return value(); } 00531 }; 00532 00533 } // namespace service_traits 00534 } // namespace ros 00535 00536 #endif // HECTOR_NAV_MSGS_SERVICE_GETRECOVERYINFO_H 00537