Go to the documentation of this file.00001 #ifndef _ROS_costmap_2d_VoxelGrid_h
00002 #define _ROS_costmap_2d_VoxelGrid_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 "geometry_msgs/Point32.h"
00010 #include "geometry_msgs/Vector3.h"
00011
00012 namespace costmap_2d
00013 {
00014
00015 class VoxelGrid : public ros::Msg
00016 {
00017 public:
00018 std_msgs::Header header;
00019 uint8_t data_length;
00020 uint32_t st_data;
00021 uint32_t * data;
00022 geometry_msgs::Point32 origin;
00023 geometry_msgs::Vector3 resolutions;
00024 uint32_t size_x;
00025 uint32_t size_y;
00026 uint32_t size_z;
00027
00028 virtual int serialize(unsigned char *outbuffer) const
00029 {
00030 int offset = 0;
00031 offset += this->header.serialize(outbuffer + offset);
00032 *(outbuffer + offset++) = data_length;
00033 *(outbuffer + offset++) = 0;
00034 *(outbuffer + offset++) = 0;
00035 *(outbuffer + offset++) = 0;
00036 for( uint8_t i = 0; i < data_length; i++){
00037 *(outbuffer + offset + 0) = (this->data[i] >> (8 * 0)) & 0xFF;
00038 *(outbuffer + offset + 1) = (this->data[i] >> (8 * 1)) & 0xFF;
00039 *(outbuffer + offset + 2) = (this->data[i] >> (8 * 2)) & 0xFF;
00040 *(outbuffer + offset + 3) = (this->data[i] >> (8 * 3)) & 0xFF;
00041 offset += sizeof(this->data[i]);
00042 }
00043 offset += this->origin.serialize(outbuffer + offset);
00044 offset += this->resolutions.serialize(outbuffer + offset);
00045 *(outbuffer + offset + 0) = (this->size_x >> (8 * 0)) & 0xFF;
00046 *(outbuffer + offset + 1) = (this->size_x >> (8 * 1)) & 0xFF;
00047 *(outbuffer + offset + 2) = (this->size_x >> (8 * 2)) & 0xFF;
00048 *(outbuffer + offset + 3) = (this->size_x >> (8 * 3)) & 0xFF;
00049 offset += sizeof(this->size_x);
00050 *(outbuffer + offset + 0) = (this->size_y >> (8 * 0)) & 0xFF;
00051 *(outbuffer + offset + 1) = (this->size_y >> (8 * 1)) & 0xFF;
00052 *(outbuffer + offset + 2) = (this->size_y >> (8 * 2)) & 0xFF;
00053 *(outbuffer + offset + 3) = (this->size_y >> (8 * 3)) & 0xFF;
00054 offset += sizeof(this->size_y);
00055 *(outbuffer + offset + 0) = (this->size_z >> (8 * 0)) & 0xFF;
00056 *(outbuffer + offset + 1) = (this->size_z >> (8 * 1)) & 0xFF;
00057 *(outbuffer + offset + 2) = (this->size_z >> (8 * 2)) & 0xFF;
00058 *(outbuffer + offset + 3) = (this->size_z >> (8 * 3)) & 0xFF;
00059 offset += sizeof(this->size_z);
00060 return offset;
00061 }
00062
00063 virtual int deserialize(unsigned char *inbuffer)
00064 {
00065 int offset = 0;
00066 offset += this->header.deserialize(inbuffer + offset);
00067 uint8_t data_lengthT = *(inbuffer + offset++);
00068 if(data_lengthT > data_length)
00069 this->data = (uint32_t*)realloc(this->data, data_lengthT * sizeof(uint32_t));
00070 offset += 3;
00071 data_length = data_lengthT;
00072 for( uint8_t i = 0; i < data_length; i++){
00073 this->st_data = ((uint32_t) (*(inbuffer + offset)));
00074 this->st_data |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00075 this->st_data |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00076 this->st_data |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00077 offset += sizeof(this->st_data);
00078 memcpy( &(this->data[i]), &(this->st_data), sizeof(uint32_t));
00079 }
00080 offset += this->origin.deserialize(inbuffer + offset);
00081 offset += this->resolutions.deserialize(inbuffer + offset);
00082 this->size_x = ((uint32_t) (*(inbuffer + offset)));
00083 this->size_x |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00084 this->size_x |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00085 this->size_x |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00086 offset += sizeof(this->size_x);
00087 this->size_y = ((uint32_t) (*(inbuffer + offset)));
00088 this->size_y |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00089 this->size_y |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00090 this->size_y |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00091 offset += sizeof(this->size_y);
00092 this->size_z = ((uint32_t) (*(inbuffer + offset)));
00093 this->size_z |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00094 this->size_z |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00095 this->size_z |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00096 offset += sizeof(this->size_z);
00097 return offset;
00098 }
00099
00100 const char * getType(){ return "costmap_2d/VoxelGrid"; };
00101 const char * getMD5(){ return "48a040827e1322073d78ece5a497029c"; };
00102
00103 };
00104
00105 }
00106 #endif