Increased buffer size

Dependencies:   BufferedSerial

Fork of ros_lib_kinetic by Gary Servin

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers PointCloud2.h Source File

PointCloud2.h

00001 #ifndef _ROS_sensor_msgs_PointCloud2_h
00002 #define _ROS_sensor_msgs_PointCloud2_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 "sensor_msgs/PointField.h"
00010 
00011 namespace sensor_msgs
00012 {
00013 
00014   class PointCloud2 : public ros::Msg
00015   {
00016     public:
00017       typedef std_msgs::Header _header_type;
00018       _header_type header;
00019       typedef uint32_t _height_type;
00020       _height_type height;
00021       typedef uint32_t _width_type;
00022       _width_type width;
00023       uint32_t fields_length;
00024       typedef sensor_msgs::PointField _fields_type;
00025       _fields_type st_fields;
00026       _fields_type * fields;
00027       typedef bool _is_bigendian_type;
00028       _is_bigendian_type is_bigendian;
00029       typedef uint32_t _point_step_type;
00030       _point_step_type point_step;
00031       typedef uint32_t _row_step_type;
00032       _row_step_type row_step;
00033       uint32_t data_length;
00034       typedef uint8_t _data_type;
00035       _data_type st_data;
00036       _data_type * data;
00037       typedef bool _is_dense_type;
00038       _is_dense_type is_dense;
00039 
00040     PointCloud2():
00041       header(),
00042       height(0),
00043       width(0),
00044       fields_length(0), fields(NULL),
00045       is_bigendian(0),
00046       point_step(0),
00047       row_step(0),
00048       data_length(0), data(NULL),
00049       is_dense(0)
00050     {
00051     }
00052 
00053     virtual int serialize(unsigned char *outbuffer) const
00054     {
00055       int offset = 0;
00056       offset += this->header.serialize(outbuffer + offset);
00057       *(outbuffer + offset + 0) = (this->height >> (8 * 0)) & 0xFF;
00058       *(outbuffer + offset + 1) = (this->height >> (8 * 1)) & 0xFF;
00059       *(outbuffer + offset + 2) = (this->height >> (8 * 2)) & 0xFF;
00060       *(outbuffer + offset + 3) = (this->height >> (8 * 3)) & 0xFF;
00061       offset += sizeof(this->height);
00062       *(outbuffer + offset + 0) = (this->width >> (8 * 0)) & 0xFF;
00063       *(outbuffer + offset + 1) = (this->width >> (8 * 1)) & 0xFF;
00064       *(outbuffer + offset + 2) = (this->width >> (8 * 2)) & 0xFF;
00065       *(outbuffer + offset + 3) = (this->width >> (8 * 3)) & 0xFF;
00066       offset += sizeof(this->width);
00067       *(outbuffer + offset + 0) = (this->fields_length >> (8 * 0)) & 0xFF;
00068       *(outbuffer + offset + 1) = (this->fields_length >> (8 * 1)) & 0xFF;
00069       *(outbuffer + offset + 2) = (this->fields_length >> (8 * 2)) & 0xFF;
00070       *(outbuffer + offset + 3) = (this->fields_length >> (8 * 3)) & 0xFF;
00071       offset += sizeof(this->fields_length);
00072       for( uint32_t i = 0; i < fields_length; i++){
00073       offset += this->fields[i].serialize(outbuffer + offset);
00074       }
00075       union {
00076         bool real;
00077         uint8_t base;
00078       } u_is_bigendian;
00079       u_is_bigendian.real = this->is_bigendian;
00080       *(outbuffer + offset + 0) = (u_is_bigendian.base >> (8 * 0)) & 0xFF;
00081       offset += sizeof(this->is_bigendian);
00082       *(outbuffer + offset + 0) = (this->point_step >> (8 * 0)) & 0xFF;
00083       *(outbuffer + offset + 1) = (this->point_step >> (8 * 1)) & 0xFF;
00084       *(outbuffer + offset + 2) = (this->point_step >> (8 * 2)) & 0xFF;
00085       *(outbuffer + offset + 3) = (this->point_step >> (8 * 3)) & 0xFF;
00086       offset += sizeof(this->point_step);
00087       *(outbuffer + offset + 0) = (this->row_step >> (8 * 0)) & 0xFF;
00088       *(outbuffer + offset + 1) = (this->row_step >> (8 * 1)) & 0xFF;
00089       *(outbuffer + offset + 2) = (this->row_step >> (8 * 2)) & 0xFF;
00090       *(outbuffer + offset + 3) = (this->row_step >> (8 * 3)) & 0xFF;
00091       offset += sizeof(this->row_step);
00092       *(outbuffer + offset + 0) = (this->data_length >> (8 * 0)) & 0xFF;
00093       *(outbuffer + offset + 1) = (this->data_length >> (8 * 1)) & 0xFF;
00094       *(outbuffer + offset + 2) = (this->data_length >> (8 * 2)) & 0xFF;
00095       *(outbuffer + offset + 3) = (this->data_length >> (8 * 3)) & 0xFF;
00096       offset += sizeof(this->data_length);
00097       for( uint32_t i = 0; i < data_length; i++){
00098       *(outbuffer + offset + 0) = (this->data[i] >> (8 * 0)) & 0xFF;
00099       offset += sizeof(this->data[i]);
00100       }
00101       union {
00102         bool real;
00103         uint8_t base;
00104       } u_is_dense;
00105       u_is_dense.real = this->is_dense;
00106       *(outbuffer + offset + 0) = (u_is_dense.base >> (8 * 0)) & 0xFF;
00107       offset += sizeof(this->is_dense);
00108       return offset;
00109     }
00110 
00111     virtual int deserialize(unsigned char *inbuffer)
00112     {
00113       int offset = 0;
00114       offset += this->header.deserialize(inbuffer + offset);
00115       this->height =  ((uint32_t) (*(inbuffer + offset)));
00116       this->height |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00117       this->height |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00118       this->height |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00119       offset += sizeof(this->height);
00120       this->width =  ((uint32_t) (*(inbuffer + offset)));
00121       this->width |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00122       this->width |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00123       this->width |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00124       offset += sizeof(this->width);
00125       uint32_t fields_lengthT = ((uint32_t) (*(inbuffer + offset))); 
00126       fields_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
00127       fields_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
00128       fields_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
00129       offset += sizeof(this->fields_length);
00130       if(fields_lengthT > fields_length)
00131         this->fields = (sensor_msgs::PointField*)realloc(this->fields, fields_lengthT * sizeof(sensor_msgs::PointField));
00132       fields_length = fields_lengthT;
00133       for( uint32_t i = 0; i < fields_length; i++){
00134       offset += this->st_fields.deserialize(inbuffer + offset);
00135         memcpy( &(this->fields[i]), &(this->st_fields), sizeof(sensor_msgs::PointField));
00136       }
00137       union {
00138         bool real;
00139         uint8_t base;
00140       } u_is_bigendian;
00141       u_is_bigendian.base = 0;
00142       u_is_bigendian.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
00143       this->is_bigendian = u_is_bigendian.real;
00144       offset += sizeof(this->is_bigendian);
00145       this->point_step =  ((uint32_t) (*(inbuffer + offset)));
00146       this->point_step |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00147       this->point_step |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00148       this->point_step |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00149       offset += sizeof(this->point_step);
00150       this->row_step =  ((uint32_t) (*(inbuffer + offset)));
00151       this->row_step |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00152       this->row_step |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00153       this->row_step |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00154       offset += sizeof(this->row_step);
00155       uint32_t data_lengthT = ((uint32_t) (*(inbuffer + offset))); 
00156       data_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
00157       data_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
00158       data_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
00159       offset += sizeof(this->data_length);
00160       if(data_lengthT > data_length)
00161         this->data = (uint8_t*)realloc(this->data, data_lengthT * sizeof(uint8_t));
00162       data_length = data_lengthT;
00163       for( uint32_t i = 0; i < data_length; i++){
00164       this->st_data =  ((uint8_t) (*(inbuffer + offset)));
00165       offset += sizeof(this->st_data);
00166         memcpy( &(this->data[i]), &(this->st_data), sizeof(uint8_t));
00167       }
00168       union {
00169         bool real;
00170         uint8_t base;
00171       } u_is_dense;
00172       u_is_dense.base = 0;
00173       u_is_dense.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
00174       this->is_dense = u_is_dense.real;
00175       offset += sizeof(this->is_dense);
00176      return offset;
00177     }
00178 
00179     const char * getType(){ return "sensor_msgs/PointCloud2"; };
00180     const char * getMD5(){ return "1158d486dd51d683ce2f1be655c3c181"; };
00181 
00182   };
00183 
00184 }
00185 #endif