1 #ifndef _ROS_nav_msgs_OccupancyGrid_h
2 #define _ROS_nav_msgs_OccupancyGrid_h
30 virtual int serialize(
unsigned char *outbuffer)
const
36 *(outbuffer + offset++) = 0;
37 *(outbuffer + offset++) = 0;
38 *(outbuffer + offset++) = 0;
44 u_datai.real = this->
data[i];
45 *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF;
46 offset +=
sizeof(this->
data[i]);
56 uint8_t data_lengthT = *(inbuffer + offset++);
58 this->
data = (int8_t*)realloc(this->
data, data_lengthT *
sizeof(int8_t));
67 u_st_data.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
69 offset +=
sizeof(this->
st_data);
70 memcpy( &(this->
data[i]), &(this->
st_data),
sizeof(int8_t));
75 const char *
getType(){
return "nav_msgs/OccupancyGrid"; };
76 const char *
getMD5(){
return "3381f2d731d4076ec5c71b0759edbe4e"; };
Definition: OccupancyGrid.h:14
const char * getType()
Definition: OccupancyGrid.h:75
int8_t st_data
Definition: OccupancyGrid.h:20
virtual int deserialize(unsigned char *inbuffer)
Definition: OccupancyGrid.h:51
const char * getMD5()
Definition: OccupancyGrid.h:76
virtual int serialize(unsigned char *outbuffer) const
Definition: OccupancyGrid.h:30
int8_t * data
Definition: OccupancyGrid.h:21
nav_msgs::MapMetaData info
Definition: OccupancyGrid.h:18
uint8_t data_length
Definition: OccupancyGrid.h:19
std_msgs::Header header
Definition: OccupancyGrid.h:17
OccupancyGrid()
Definition: OccupancyGrid.h:23