Gary Servin / ros_lib_indigo

Dependencies:   BufferedSerial

Dependents:   rosserial_mbed_hello_world_publisher rtos_base_control rosserial_mbed_F64MA ROS-RTOS ... more

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