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