Go to the documentation of this file.00001 #ifndef _ROS_nav_msgs_OccupancyGrid_h
00002 #define _ROS_nav_msgs_OccupancyGrid_h
00003
00004 #include <stdint.h>
00005 #include <string.h>
00006 #include <stdlib.h>
00007 #include "ros/msg.h"
00008 #include "std_msgs/Header.h"
00009 #include "nav_msgs/MapMetaData.h"
00010
00011 namespace nav_msgs
00012 {
00013
00014 class OccupancyGrid : public ros::Msg
00015 {
00016 public:
00017 std_msgs::Header header;
00018 nav_msgs::MapMetaData info;
00019 uint8_t data_length;
00020 int8_t st_data;
00021 int8_t * data;
00022
00023 virtual int serialize(unsigned char *outbuffer) const
00024 {
00025 int offset = 0;
00026 offset += this->header.serialize(outbuffer + offset);
00027 offset += this->info.serialize(outbuffer + offset);
00028 *(outbuffer + offset++) = data_length;
00029 *(outbuffer + offset++) = 0;
00030 *(outbuffer + offset++) = 0;
00031 *(outbuffer + offset++) = 0;
00032 for( uint8_t i = 0; i < data_length; i++){
00033 union {
00034 int8_t real;
00035 uint8_t base;
00036 } u_datai;
00037 u_datai.real = this->data[i];
00038 *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF;
00039 offset += sizeof(this->data[i]);
00040 }
00041 return offset;
00042 }
00043
00044 virtual int deserialize(unsigned char *inbuffer)
00045 {
00046 int offset = 0;
00047 offset += this->header.deserialize(inbuffer + offset);
00048 offset += this->info.deserialize(inbuffer + offset);
00049 uint8_t data_lengthT = *(inbuffer + offset++);
00050 if(data_lengthT > data_length)
00051 this->data = (int8_t*)realloc(this->data, data_lengthT * sizeof(int8_t));
00052 offset += 3;
00053 data_length = data_lengthT;
00054 for( uint8_t i = 0; i < data_length; i++){
00055 union {
00056 int8_t real;
00057 uint8_t base;
00058 } u_st_data;
00059 u_st_data.base = 0;
00060 u_st_data.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
00061 this->st_data = u_st_data.real;
00062 offset += sizeof(this->st_data);
00063 memcpy( &(this->data[i]), &(this->st_data), sizeof(int8_t));
00064 }
00065 return offset;
00066 }
00067
00068 const char * getType(){ return "nav_msgs/OccupancyGrid"; };
00069 const char * getMD5(){ return "3381f2d731d4076ec5c71b0759edbe4e"; };
00070
00071 };
00072
00073 }
00074 #endif