Go to the documentation of this file.00001 #ifndef ros_SERVICE_GetMap_h
00002 #define ros_SERVICE_GetMap_h
00003 #include <stdint.h>
00004 #include <string.h>
00005 #include <stdlib.h>
00006 #include "../ros/msg.h"
00007 #include "nav_msgs/OccupancyGrid.h"
00008
00009 namespace nav_msgs
00010 {
00011
00012 static const char GETMAP[] = "nav_msgs/GetMap";
00013
00014 class GetMapRequest : public ros::Msg
00015 {
00016 public:
00017
00018 virtual int serialize(unsigned char *outbuffer)
00019 {
00020 int offset = 0;
00021 return offset;
00022 }
00023
00024 virtual int deserialize(unsigned char *inbuffer)
00025 {
00026 int offset = 0;
00027 return offset;
00028 }
00029
00030 const char * getType(){ return GETMAP; };
00031
00032 };
00033
00034 class GetMapResponse : public ros::Msg
00035 {
00036 public:
00037 nav_msgs::OccupancyGrid map;
00038
00039 virtual int serialize(unsigned char *outbuffer)
00040 {
00041 int offset = 0;
00042 offset += this->map.serialize(outbuffer + offset);
00043 return offset;
00044 }
00045
00046 virtual int deserialize(unsigned char *inbuffer)
00047 {
00048 int offset = 0;
00049 offset += this->map.deserialize(inbuffer + offset);
00050 return offset;
00051 }
00052
00053 const char * getType(){ return GETMAP; };
00054
00055 };
00056
00057 }
00058 #endif