kitt_platform
 All Classes Namespaces Files Functions Variables Typedefs Enumerator Macros
OccupancyGrid.h
Go to the documentation of this file.
1 #ifndef _ROS_nav_msgs_OccupancyGrid_h
2 #define _ROS_nav_msgs_OccupancyGrid_h
3 
4 #include <stdint.h>
5 #include <string.h>
6 #include <stdlib.h>
7 #include "ros/msg.h"
8 #include "std_msgs/Header.h"
9 #include "nav_msgs/MapMetaData.h"
10 
11 namespace nav_msgs
12 {
13 
14  class OccupancyGrid : public ros::Msg
15  {
16  public:
19  uint8_t data_length;
20  int8_t st_data;
21  int8_t * data;
22 
24  header(),
25  info(),
26  data_length(0), data(NULL)
27  {
28  }
29 
30  virtual int serialize(unsigned char *outbuffer) const
31  {
32  int offset = 0;
33  offset += this->header.serialize(outbuffer + offset);
34  offset += this->info.serialize(outbuffer + offset);
35  *(outbuffer + offset++) = data_length;
36  *(outbuffer + offset++) = 0;
37  *(outbuffer + offset++) = 0;
38  *(outbuffer + offset++) = 0;
39  for( uint8_t i = 0; i < data_length; i++){
40  union {
41  int8_t real;
42  uint8_t base;
43  } u_datai;
44  u_datai.real = this->data[i];
45  *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF;
46  offset += sizeof(this->data[i]);
47  }
48  return offset;
49  }
50 
51  virtual int deserialize(unsigned char *inbuffer)
52  {
53  int offset = 0;
54  offset += this->header.deserialize(inbuffer + offset);
55  offset += this->info.deserialize(inbuffer + offset);
56  uint8_t data_lengthT = *(inbuffer + offset++);
57  if(data_lengthT > data_length)
58  this->data = (int8_t*)realloc(this->data, data_lengthT * sizeof(int8_t));
59  offset += 3;
60  data_length = data_lengthT;
61  for( uint8_t i = 0; i < data_length; i++){
62  union {
63  int8_t real;
64  uint8_t base;
65  } u_st_data;
66  u_st_data.base = 0;
67  u_st_data.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
68  this->st_data = u_st_data.real;
69  offset += sizeof(this->st_data);
70  memcpy( &(this->data[i]), &(this->st_data), sizeof(int8_t));
71  }
72  return offset;
73  }
74 
75  const char * getType(){ return "nav_msgs/OccupancyGrid"; };
76  const char * getMD5(){ return "3381f2d731d4076ec5c71b0759edbe4e"; };
77 
78  };
79 
80 }
81 #endif
Definition: OccupancyGrid.h:14
const char * getType()
Definition: OccupancyGrid.h:75
virtual int deserialize(unsigned char *inbuffer)
Definition: Header.h:53
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: Header.h:27
virtual int deserialize(unsigned char *inbuffer)
Definition: MapMetaData.h:69
virtual int serialize(unsigned char *outbuffer) const
Definition: OccupancyGrid.h:30
Definition: Header.h:13
Definition: MapMetaData.h:14
int8_t * data
Definition: OccupancyGrid.h:21
nav_msgs::MapMetaData info
Definition: OccupancyGrid.h:18
virtual int serialize(unsigned char *outbuffer) const
Definition: MapMetaData.h:32
uint8_t data_length
Definition: OccupancyGrid.h:19
std_msgs::Header header
Definition: OccupancyGrid.h:17
Definition: msg.h:43
OccupancyGrid()
Definition: OccupancyGrid.h:23