1 #ifndef _ROS_SERVICE_SetMap_h
2 #define _ROS_SERVICE_SetMap_h
13 static const char SETMAP[] =
"nav_msgs/SetMap";
27 virtual int serialize(
unsigned char *outbuffer)
const
44 const char *
getMD5(){
return "91149a20d7be299b87c340df8cc94fd4"; };
58 virtual int serialize(
unsigned char *outbuffer)
const
66 *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF;
67 offset +=
sizeof(this->
success);
79 u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
81 offset +=
sizeof(this->
success);
86 const char *
getMD5(){
return "358e233cde0c8a8bcfea4ce193f8fc15"; };
Definition: OccupancyGrid.h:14
static const char SETMAP[]
Definition: SetMap.h:13
const char * getType()
Definition: SetMap.h:85
virtual int deserialize(unsigned char *inbuffer)
Definition: SetMap.h:71
const char * getMD5()
Definition: SetMap.h:44
geometry_msgs::PoseWithCovarianceStamped initial_pose
Definition: SetMap.h:19
virtual int deserialize(unsigned char *inbuffer)
Definition: OccupancyGrid.h:51
nav_msgs::OccupancyGrid map
Definition: SetMap.h:18
virtual int deserialize(unsigned char *inbuffer)
Definition: PoseWithCovarianceStamped.h:34
bool success
Definition: SetMap.h:51
virtual int serialize(unsigned char *outbuffer) const
Definition: OccupancyGrid.h:30
SetMapResponse()
Definition: SetMap.h:53
SetMapRequest()
Definition: SetMap.h:21
virtual int serialize(unsigned char *outbuffer) const
Definition: SetMap.h:58
const char * getType()
Definition: SetMap.h:43
virtual int deserialize(unsigned char *inbuffer)
Definition: SetMap.h:35
SetMapRequest Request
Definition: SetMap.h:92
virtual int serialize(unsigned char *outbuffer) const
Definition: PoseWithCovarianceStamped.h:26
SetMapResponse Response
Definition: SetMap.h:93
const char * getMD5()
Definition: SetMap.h:86
Definition: PoseWithCovarianceStamped.h:14
virtual int serialize(unsigned char *outbuffer) const
Definition: SetMap.h:27