PointCloud2.h
Go to the documentation of this file.
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       std_msgs::Header header;
00018       uint32_t height;
00019       uint32_t width;
00020       uint8_t fields_length;
00021       sensor_msgs::PointField st_fields;
00022       sensor_msgs::PointField * fields;
00023       bool is_bigendian;
00024       uint32_t point_step;
00025       uint32_t row_step;
00026       uint8_t data_length;
00027       uint8_t st_data;
00028       uint8_t * data;
00029       bool is_dense;
00030 
00031     virtual int serialize(unsigned char *outbuffer) const
00032     {
00033       int offset = 0;
00034       offset += this->header.serialize(outbuffer + offset);
00035       *(outbuffer + offset + 0) = (this->height >> (8 * 0)) & 0xFF;
00036       *(outbuffer + offset + 1) = (this->height >> (8 * 1)) & 0xFF;
00037       *(outbuffer + offset + 2) = (this->height >> (8 * 2)) & 0xFF;
00038       *(outbuffer + offset + 3) = (this->height >> (8 * 3)) & 0xFF;
00039       offset += sizeof(this->height);
00040       *(outbuffer + offset + 0) = (this->width >> (8 * 0)) & 0xFF;
00041       *(outbuffer + offset + 1) = (this->width >> (8 * 1)) & 0xFF;
00042       *(outbuffer + offset + 2) = (this->width >> (8 * 2)) & 0xFF;
00043       *(outbuffer + offset + 3) = (this->width >> (8 * 3)) & 0xFF;
00044       offset += sizeof(this->width);
00045       *(outbuffer + offset++) = fields_length;
00046       *(outbuffer + offset++) = 0;
00047       *(outbuffer + offset++) = 0;
00048       *(outbuffer + offset++) = 0;
00049       for( uint8_t i = 0; i < fields_length; i++){
00050       offset += this->fields[i].serialize(outbuffer + offset);
00051       }
00052       union {
00053         bool real;
00054         uint8_t base;
00055       } u_is_bigendian;
00056       u_is_bigendian.real = this->is_bigendian;
00057       *(outbuffer + offset + 0) = (u_is_bigendian.base >> (8 * 0)) & 0xFF;
00058       offset += sizeof(this->is_bigendian);
00059       *(outbuffer + offset + 0) = (this->point_step >> (8 * 0)) & 0xFF;
00060       *(outbuffer + offset + 1) = (this->point_step >> (8 * 1)) & 0xFF;
00061       *(outbuffer + offset + 2) = (this->point_step >> (8 * 2)) & 0xFF;
00062       *(outbuffer + offset + 3) = (this->point_step >> (8 * 3)) & 0xFF;
00063       offset += sizeof(this->point_step);
00064       *(outbuffer + offset + 0) = (this->row_step >> (8 * 0)) & 0xFF;
00065       *(outbuffer + offset + 1) = (this->row_step >> (8 * 1)) & 0xFF;
00066       *(outbuffer + offset + 2) = (this->row_step >> (8 * 2)) & 0xFF;
00067       *(outbuffer + offset + 3) = (this->row_step >> (8 * 3)) & 0xFF;
00068       offset += sizeof(this->row_step);
00069       *(outbuffer + offset++) = data_length;
00070       *(outbuffer + offset++) = 0;
00071       *(outbuffer + offset++) = 0;
00072       *(outbuffer + offset++) = 0;
00073       for( uint8_t i = 0; i < data_length; i++){
00074       *(outbuffer + offset + 0) = (this->data[i] >> (8 * 0)) & 0xFF;
00075       offset += sizeof(this->data[i]);
00076       }
00077       union {
00078         bool real;
00079         uint8_t base;
00080       } u_is_dense;
00081       u_is_dense.real = this->is_dense;
00082       *(outbuffer + offset + 0) = (u_is_dense.base >> (8 * 0)) & 0xFF;
00083       offset += sizeof(this->is_dense);
00084       return offset;
00085     }
00086 
00087     virtual int deserialize(unsigned char *inbuffer)
00088     {
00089       int offset = 0;
00090       offset += this->header.deserialize(inbuffer + offset);
00091       this->height =  ((uint32_t) (*(inbuffer + offset)));
00092       this->height |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00093       this->height |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00094       this->height |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00095       offset += sizeof(this->height);
00096       this->width =  ((uint32_t) (*(inbuffer + offset)));
00097       this->width |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00098       this->width |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00099       this->width |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00100       offset += sizeof(this->width);
00101       uint8_t fields_lengthT = *(inbuffer + offset++);
00102       if(fields_lengthT > fields_length)
00103         this->fields = (sensor_msgs::PointField*)realloc(this->fields, fields_lengthT * sizeof(sensor_msgs::PointField));
00104       offset += 3;
00105       fields_length = fields_lengthT;
00106       for( uint8_t i = 0; i < fields_length; i++){
00107       offset += this->st_fields.deserialize(inbuffer + offset);
00108         memcpy( &(this->fields[i]), &(this->st_fields), sizeof(sensor_msgs::PointField));
00109       }
00110       union {
00111         bool real;
00112         uint8_t base;
00113       } u_is_bigendian;
00114       u_is_bigendian.base = 0;
00115       u_is_bigendian.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
00116       this->is_bigendian = u_is_bigendian.real;
00117       offset += sizeof(this->is_bigendian);
00118       this->point_step =  ((uint32_t) (*(inbuffer + offset)));
00119       this->point_step |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00120       this->point_step |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00121       this->point_step |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00122       offset += sizeof(this->point_step);
00123       this->row_step =  ((uint32_t) (*(inbuffer + offset)));
00124       this->row_step |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00125       this->row_step |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00126       this->row_step |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00127       offset += sizeof(this->row_step);
00128       uint8_t data_lengthT = *(inbuffer + offset++);
00129       if(data_lengthT > data_length)
00130         this->data = (uint8_t*)realloc(this->data, data_lengthT * sizeof(uint8_t));
00131       offset += 3;
00132       data_length = data_lengthT;
00133       for( uint8_t i = 0; i < data_length; i++){
00134       this->st_data =  ((uint8_t) (*(inbuffer + offset)));
00135       offset += sizeof(this->st_data);
00136         memcpy( &(this->data[i]), &(this->st_data), sizeof(uint8_t));
00137       }
00138       union {
00139         bool real;
00140         uint8_t base;
00141       } u_is_dense;
00142       u_is_dense.base = 0;
00143       u_is_dense.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
00144       this->is_dense = u_is_dense.real;
00145       offset += sizeof(this->is_dense);
00146      return offset;
00147     }
00148 
00149     const char * getType(){ return "sensor_msgs/PointCloud2"; };
00150     const char * getMD5(){ return "1158d486dd51d683ce2f1be655c3c181"; };
00151 
00152   };
00153 
00154 }
00155 #endif


ric_mc
Author(s): RoboTiCan
autogenerated on Thu Aug 27 2015 14:39:50