GetMapROI.h
Go to the documentation of this file.
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-fuerte-map_msgs/doc_stacks/2013-05-31_08-20-41.450426/map_msgs/srv/GetMapROI.srv */
00002 #ifndef MAP_MSGS_SERVICE_GETMAPROI_H
00003 #define MAP_MSGS_SERVICE_GETMAPROI_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 map_msgs
00024 {
00025 template <class ContainerAllocator>
00026 struct GetMapROIRequest_ {
00027   typedef GetMapROIRequest_<ContainerAllocator> Type;
00028 
00029   GetMapROIRequest_()
00030   : x(0.0)
00031   , y(0.0)
00032   , l_x(0.0)
00033   , l_y(0.0)
00034   {
00035   }
00036 
00037   GetMapROIRequest_(const ContainerAllocator& _alloc)
00038   : x(0.0)
00039   , y(0.0)
00040   , l_x(0.0)
00041   , l_y(0.0)
00042   {
00043   }
00044 
00045   typedef double _x_type;
00046   double x;
00047 
00048   typedef double _y_type;
00049   double y;
00050 
00051   typedef double _l_x_type;
00052   double l_x;
00053 
00054   typedef double _l_y_type;
00055   double l_y;
00056 
00057 
00058   typedef boost::shared_ptr< ::map_msgs::GetMapROIRequest_<ContainerAllocator> > Ptr;
00059   typedef boost::shared_ptr< ::map_msgs::GetMapROIRequest_<ContainerAllocator>  const> ConstPtr;
00060   boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00061 }; // struct GetMapROIRequest
00062 typedef  ::map_msgs::GetMapROIRequest_<std::allocator<void> > GetMapROIRequest;
00063 
00064 typedef boost::shared_ptr< ::map_msgs::GetMapROIRequest> GetMapROIRequestPtr;
00065 typedef boost::shared_ptr< ::map_msgs::GetMapROIRequest const> GetMapROIRequestConstPtr;
00066 
00067 
00068 template <class ContainerAllocator>
00069 struct GetMapROIResponse_ {
00070   typedef GetMapROIResponse_<ContainerAllocator> Type;
00071 
00072   GetMapROIResponse_()
00073   : sub_map()
00074   {
00075   }
00076 
00077   GetMapROIResponse_(const ContainerAllocator& _alloc)
00078   : sub_map(_alloc)
00079   {
00080   }
00081 
00082   typedef  ::nav_msgs::OccupancyGrid_<ContainerAllocator>  _sub_map_type;
00083    ::nav_msgs::OccupancyGrid_<ContainerAllocator>  sub_map;
00084 
00085 
00086   typedef boost::shared_ptr< ::map_msgs::GetMapROIResponse_<ContainerAllocator> > Ptr;
00087   typedef boost::shared_ptr< ::map_msgs::GetMapROIResponse_<ContainerAllocator>  const> ConstPtr;
00088   boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00089 }; // struct GetMapROIResponse
00090 typedef  ::map_msgs::GetMapROIResponse_<std::allocator<void> > GetMapROIResponse;
00091 
00092 typedef boost::shared_ptr< ::map_msgs::GetMapROIResponse> GetMapROIResponsePtr;
00093 typedef boost::shared_ptr< ::map_msgs::GetMapROIResponse const> GetMapROIResponseConstPtr;
00094 
00095 struct GetMapROI
00096 {
00097 
00098 typedef GetMapROIRequest Request;
00099 typedef GetMapROIResponse Response;
00100 Request request;
00101 Response response;
00102 
00103 typedef Request RequestType;
00104 typedef Response ResponseType;
00105 }; // struct GetMapROI
00106 } // namespace map_msgs
00107 
00108 namespace ros
00109 {
00110 namespace message_traits
00111 {
00112 template<class ContainerAllocator> struct IsMessage< ::map_msgs::GetMapROIRequest_<ContainerAllocator> > : public TrueType {};
00113 template<class ContainerAllocator> struct IsMessage< ::map_msgs::GetMapROIRequest_<ContainerAllocator>  const> : public TrueType {};
00114 template<class ContainerAllocator>
00115 struct MD5Sum< ::map_msgs::GetMapROIRequest_<ContainerAllocator> > {
00116   static const char* value() 
00117   {
00118     return "43c2ff8f45af555c0eaf070c401e9a47";
00119   }
00120 
00121   static const char* value(const  ::map_msgs::GetMapROIRequest_<ContainerAllocator> &) { return value(); } 
00122   static const uint64_t static_value1 = 0x43c2ff8f45af555cULL;
00123   static const uint64_t static_value2 = 0x0eaf070c401e9a47ULL;
00124 };
00125 
00126 template<class ContainerAllocator>
00127 struct DataType< ::map_msgs::GetMapROIRequest_<ContainerAllocator> > {
00128   static const char* value() 
00129   {
00130     return "map_msgs/GetMapROIRequest";
00131   }
00132 
00133   static const char* value(const  ::map_msgs::GetMapROIRequest_<ContainerAllocator> &) { return value(); } 
00134 };
00135 
00136 template<class ContainerAllocator>
00137 struct Definition< ::map_msgs::GetMapROIRequest_<ContainerAllocator> > {
00138   static const char* value() 
00139   {
00140     return "float64 x\n\
00141 float64 y\n\
00142 float64 l_x\n\
00143 float64 l_y\n\
00144 \n\
00145 ";
00146   }
00147 
00148   static const char* value(const  ::map_msgs::GetMapROIRequest_<ContainerAllocator> &) { return value(); } 
00149 };
00150 
00151 template<class ContainerAllocator> struct IsFixedSize< ::map_msgs::GetMapROIRequest_<ContainerAllocator> > : public TrueType {};
00152 } // namespace message_traits
00153 } // namespace ros
00154 
00155 
00156 namespace ros
00157 {
00158 namespace message_traits
00159 {
00160 template<class ContainerAllocator> struct IsMessage< ::map_msgs::GetMapROIResponse_<ContainerAllocator> > : public TrueType {};
00161 template<class ContainerAllocator> struct IsMessage< ::map_msgs::GetMapROIResponse_<ContainerAllocator>  const> : public TrueType {};
00162 template<class ContainerAllocator>
00163 struct MD5Sum< ::map_msgs::GetMapROIResponse_<ContainerAllocator> > {
00164   static const char* value() 
00165   {
00166     return "4d1986519c00d81967d2891a606b234c";
00167   }
00168 
00169   static const char* value(const  ::map_msgs::GetMapROIResponse_<ContainerAllocator> &) { return value(); } 
00170   static const uint64_t static_value1 = 0x4d1986519c00d819ULL;
00171   static const uint64_t static_value2 = 0x67d2891a606b234cULL;
00172 };
00173 
00174 template<class ContainerAllocator>
00175 struct DataType< ::map_msgs::GetMapROIResponse_<ContainerAllocator> > {
00176   static const char* value() 
00177   {
00178     return "map_msgs/GetMapROIResponse";
00179   }
00180 
00181   static const char* value(const  ::map_msgs::GetMapROIResponse_<ContainerAllocator> &) { return value(); } 
00182 };
00183 
00184 template<class ContainerAllocator>
00185 struct Definition< ::map_msgs::GetMapROIResponse_<ContainerAllocator> > {
00186   static const char* value() 
00187   {
00188     return "nav_msgs/OccupancyGrid sub_map\n\
00189 \n\
00190 ================================================================================\n\
00191 MSG: nav_msgs/OccupancyGrid\n\
00192 # This represents a 2-D grid map, in which each cell represents the probability of\n\
00193 # occupancy.\n\
00194 \n\
00195 Header header \n\
00196 \n\
00197 #MetaData for the map\n\
00198 MapMetaData info\n\
00199 \n\
00200 # The map data, in row-major order, starting with (0,0).  Occupancy\n\
00201 # probabilities are in the range [0,100].  Unknown is -1.\n\
00202 int8[] data\n\
00203 \n\
00204 ================================================================================\n\
00205 MSG: std_msgs/Header\n\
00206 # Standard metadata for higher-level stamped data types.\n\
00207 # This is generally used to communicate timestamped data \n\
00208 # in a particular coordinate frame.\n\
00209 # \n\
00210 # sequence ID: consecutively increasing ID \n\
00211 uint32 seq\n\
00212 #Two-integer timestamp that is expressed as:\n\
00213 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00214 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00215 # time-handling sugar is provided by the client library\n\
00216 time stamp\n\
00217 #Frame this data is associated with\n\
00218 # 0: no frame\n\
00219 # 1: global frame\n\
00220 string frame_id\n\
00221 \n\
00222 ================================================================================\n\
00223 MSG: nav_msgs/MapMetaData\n\
00224 # This hold basic information about the characterists of the OccupancyGrid\n\
00225 \n\
00226 # The time at which the map was loaded\n\
00227 time map_load_time\n\
00228 # The map resolution [m/cell]\n\
00229 float32 resolution\n\
00230 # Map width [cells]\n\
00231 uint32 width\n\
00232 # Map height [cells]\n\
00233 uint32 height\n\
00234 # The origin of the map [m, m, rad].  This is the real-world pose of the\n\
00235 # cell (0,0) in the map.\n\
00236 geometry_msgs/Pose origin\n\
00237 ================================================================================\n\
00238 MSG: geometry_msgs/Pose\n\
00239 # A representation of pose in free space, composed of postion and orientation. \n\
00240 Point position\n\
00241 Quaternion orientation\n\
00242 \n\
00243 ================================================================================\n\
00244 MSG: geometry_msgs/Point\n\
00245 # This contains the position of a point in free space\n\
00246 float64 x\n\
00247 float64 y\n\
00248 float64 z\n\
00249 \n\
00250 ================================================================================\n\
00251 MSG: geometry_msgs/Quaternion\n\
00252 # This represents an orientation in free space in quaternion form.\n\
00253 \n\
00254 float64 x\n\
00255 float64 y\n\
00256 float64 z\n\
00257 float64 w\n\
00258 \n\
00259 ";
00260   }
00261 
00262   static const char* value(const  ::map_msgs::GetMapROIResponse_<ContainerAllocator> &) { return value(); } 
00263 };
00264 
00265 } // namespace message_traits
00266 } // namespace ros
00267 
00268 namespace ros
00269 {
00270 namespace serialization
00271 {
00272 
00273 template<class ContainerAllocator> struct Serializer< ::map_msgs::GetMapROIRequest_<ContainerAllocator> >
00274 {
00275   template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00276   {
00277     stream.next(m.x);
00278     stream.next(m.y);
00279     stream.next(m.l_x);
00280     stream.next(m.l_y);
00281   }
00282 
00283   ROS_DECLARE_ALLINONE_SERIALIZER;
00284 }; // struct GetMapROIRequest_
00285 } // namespace serialization
00286 } // namespace ros
00287 
00288 
00289 namespace ros
00290 {
00291 namespace serialization
00292 {
00293 
00294 template<class ContainerAllocator> struct Serializer< ::map_msgs::GetMapROIResponse_<ContainerAllocator> >
00295 {
00296   template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00297   {
00298     stream.next(m.sub_map);
00299   }
00300 
00301   ROS_DECLARE_ALLINONE_SERIALIZER;
00302 }; // struct GetMapROIResponse_
00303 } // namespace serialization
00304 } // namespace ros
00305 
00306 namespace ros
00307 {
00308 namespace service_traits
00309 {
00310 template<>
00311 struct MD5Sum<map_msgs::GetMapROI> {
00312   static const char* value() 
00313   {
00314     return "81aa75ecf00f4571a9be0d9dc6dea512";
00315   }
00316 
00317   static const char* value(const map_msgs::GetMapROI&) { return value(); } 
00318 };
00319 
00320 template<>
00321 struct DataType<map_msgs::GetMapROI> {
00322   static const char* value() 
00323   {
00324     return "map_msgs/GetMapROI";
00325   }
00326 
00327   static const char* value(const map_msgs::GetMapROI&) { return value(); } 
00328 };
00329 
00330 template<class ContainerAllocator>
00331 struct MD5Sum<map_msgs::GetMapROIRequest_<ContainerAllocator> > {
00332   static const char* value() 
00333   {
00334     return "81aa75ecf00f4571a9be0d9dc6dea512";
00335   }
00336 
00337   static const char* value(const map_msgs::GetMapROIRequest_<ContainerAllocator> &) { return value(); } 
00338 };
00339 
00340 template<class ContainerAllocator>
00341 struct DataType<map_msgs::GetMapROIRequest_<ContainerAllocator> > {
00342   static const char* value() 
00343   {
00344     return "map_msgs/GetMapROI";
00345   }
00346 
00347   static const char* value(const map_msgs::GetMapROIRequest_<ContainerAllocator> &) { return value(); } 
00348 };
00349 
00350 template<class ContainerAllocator>
00351 struct MD5Sum<map_msgs::GetMapROIResponse_<ContainerAllocator> > {
00352   static const char* value() 
00353   {
00354     return "81aa75ecf00f4571a9be0d9dc6dea512";
00355   }
00356 
00357   static const char* value(const map_msgs::GetMapROIResponse_<ContainerAllocator> &) { return value(); } 
00358 };
00359 
00360 template<class ContainerAllocator>
00361 struct DataType<map_msgs::GetMapROIResponse_<ContainerAllocator> > {
00362   static const char* value() 
00363   {
00364     return "map_msgs/GetMapROI";
00365   }
00366 
00367   static const char* value(const map_msgs::GetMapROIResponse_<ContainerAllocator> &) { return value(); } 
00368 };
00369 
00370 } // namespace service_traits
00371 } // namespace ros
00372 
00373 #endif // MAP_MSGS_SERVICE_GETMAPROI_H
00374 
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends


map_msgs
Author(s): Stéphane Magnenat
autogenerated on Fri May 31 2013 08:22:01