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 unsigned long height;
00019 unsigned long width;
00020 unsigned char fields_length;
00021 sensor_msgs::PointField st_fields;
00022 sensor_msgs::PointField * fields;
00023 bool is_bigendian;
00024 unsigned long point_step;
00025 unsigned long row_step;
00026 unsigned char data_length;
00027 unsigned char st_data;
00028 unsigned char * data;
00029 bool is_dense;
00030
00031 virtual int serialize(unsigned char *outbuffer)
00032 {
00033 int offset = 0;
00034 offset += this->header.serialize(outbuffer + offset);
00035 union {
00036 unsigned long real;
00037 unsigned long base;
00038 } u_height;
00039 u_height.real = this->height;
00040 *(outbuffer + offset + 0) = (u_height.base >> (8 * 0)) & 0xFF;
00041 *(outbuffer + offset + 1) = (u_height.base >> (8 * 1)) & 0xFF;
00042 *(outbuffer + offset + 2) = (u_height.base >> (8 * 2)) & 0xFF;
00043 *(outbuffer + offset + 3) = (u_height.base >> (8 * 3)) & 0xFF;
00044 offset += sizeof(this->height);
00045 union {
00046 unsigned long real;
00047 unsigned long base;
00048 } u_width;
00049 u_width.real = this->width;
00050 *(outbuffer + offset + 0) = (u_width.base >> (8 * 0)) & 0xFF;
00051 *(outbuffer + offset + 1) = (u_width.base >> (8 * 1)) & 0xFF;
00052 *(outbuffer + offset + 2) = (u_width.base >> (8 * 2)) & 0xFF;
00053 *(outbuffer + offset + 3) = (u_width.base >> (8 * 3)) & 0xFF;
00054 offset += sizeof(this->width);
00055 *(outbuffer + offset++) = fields_length;
00056 *(outbuffer + offset++) = 0;
00057 *(outbuffer + offset++) = 0;
00058 *(outbuffer + offset++) = 0;
00059 for( unsigned char i = 0; i < fields_length; i++){
00060 offset += this->fields[i].serialize(outbuffer + offset);
00061 }
00062 union {
00063 bool real;
00064 unsigned char base;
00065 } u_is_bigendian;
00066 u_is_bigendian.real = this->is_bigendian;
00067 *(outbuffer + offset + 0) = (u_is_bigendian.base >> (8 * 0)) & 0xFF;
00068 offset += sizeof(this->is_bigendian);
00069 union {
00070 unsigned long real;
00071 unsigned long base;
00072 } u_point_step;
00073 u_point_step.real = this->point_step;
00074 *(outbuffer + offset + 0) = (u_point_step.base >> (8 * 0)) & 0xFF;
00075 *(outbuffer + offset + 1) = (u_point_step.base >> (8 * 1)) & 0xFF;
00076 *(outbuffer + offset + 2) = (u_point_step.base >> (8 * 2)) & 0xFF;
00077 *(outbuffer + offset + 3) = (u_point_step.base >> (8 * 3)) & 0xFF;
00078 offset += sizeof(this->point_step);
00079 union {
00080 unsigned long real;
00081 unsigned long base;
00082 } u_row_step;
00083 u_row_step.real = this->row_step;
00084 *(outbuffer + offset + 0) = (u_row_step.base >> (8 * 0)) & 0xFF;
00085 *(outbuffer + offset + 1) = (u_row_step.base >> (8 * 1)) & 0xFF;
00086 *(outbuffer + offset + 2) = (u_row_step.base >> (8 * 2)) & 0xFF;
00087 *(outbuffer + offset + 3) = (u_row_step.base >> (8 * 3)) & 0xFF;
00088 offset += sizeof(this->row_step);
00089 *(outbuffer + offset++) = data_length;
00090 *(outbuffer + offset++) = 0;
00091 *(outbuffer + offset++) = 0;
00092 *(outbuffer + offset++) = 0;
00093 for( unsigned char i = 0; i < data_length; i++){
00094 union {
00095 unsigned char real;
00096 unsigned char base;
00097 } u_datai;
00098 u_datai.real = this->data[i];
00099 *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF;
00100 offset += sizeof(this->data[i]);
00101 }
00102 union {
00103 bool real;
00104 unsigned char base;
00105 } u_is_dense;
00106 u_is_dense.real = this->is_dense;
00107 *(outbuffer + offset + 0) = (u_is_dense.base >> (8 * 0)) & 0xFF;
00108 offset += sizeof(this->is_dense);
00109 return offset;
00110 }
00111
00112 virtual int deserialize(unsigned char *inbuffer)
00113 {
00114 int offset = 0;
00115 offset += this->header.deserialize(inbuffer + offset);
00116 union {
00117 unsigned long real;
00118 unsigned long base;
00119 } u_height;
00120 u_height.base = 0;
00121 u_height.base |= ((typeof(u_height.base)) (*(inbuffer + offset + 0))) << (8 * 0);
00122 u_height.base |= ((typeof(u_height.base)) (*(inbuffer + offset + 1))) << (8 * 1);
00123 u_height.base |= ((typeof(u_height.base)) (*(inbuffer + offset + 2))) << (8 * 2);
00124 u_height.base |= ((typeof(u_height.base)) (*(inbuffer + offset + 3))) << (8 * 3);
00125 this->height = u_height.real;
00126 offset += sizeof(this->height);
00127 union {
00128 unsigned long real;
00129 unsigned long base;
00130 } u_width;
00131 u_width.base = 0;
00132 u_width.base |= ((typeof(u_width.base)) (*(inbuffer + offset + 0))) << (8 * 0);
00133 u_width.base |= ((typeof(u_width.base)) (*(inbuffer + offset + 1))) << (8 * 1);
00134 u_width.base |= ((typeof(u_width.base)) (*(inbuffer + offset + 2))) << (8 * 2);
00135 u_width.base |= ((typeof(u_width.base)) (*(inbuffer + offset + 3))) << (8 * 3);
00136 this->width = u_width.real;
00137 offset += sizeof(this->width);
00138 unsigned char fields_lengthT = *(inbuffer + offset++);
00139 if(fields_lengthT > fields_length)
00140 this->fields = (sensor_msgs::PointField*)realloc(this->fields, fields_lengthT * sizeof(sensor_msgs::PointField));
00141 offset += 3;
00142 fields_length = fields_lengthT;
00143 for( unsigned char i = 0; i < fields_length; i++){
00144 offset += this->st_fields.deserialize(inbuffer + offset);
00145 memcpy( &(this->fields[i]), &(this->st_fields), sizeof(sensor_msgs::PointField));
00146 }
00147 union {
00148 bool real;
00149 unsigned char base;
00150 } u_is_bigendian;
00151 u_is_bigendian.base = 0;
00152 u_is_bigendian.base |= ((typeof(u_is_bigendian.base)) (*(inbuffer + offset + 0))) << (8 * 0);
00153 this->is_bigendian = u_is_bigendian.real;
00154 offset += sizeof(this->is_bigendian);
00155 union {
00156 unsigned long real;
00157 unsigned long base;
00158 } u_point_step;
00159 u_point_step.base = 0;
00160 u_point_step.base |= ((typeof(u_point_step.base)) (*(inbuffer + offset + 0))) << (8 * 0);
00161 u_point_step.base |= ((typeof(u_point_step.base)) (*(inbuffer + offset + 1))) << (8 * 1);
00162 u_point_step.base |= ((typeof(u_point_step.base)) (*(inbuffer + offset + 2))) << (8 * 2);
00163 u_point_step.base |= ((typeof(u_point_step.base)) (*(inbuffer + offset + 3))) << (8 * 3);
00164 this->point_step = u_point_step.real;
00165 offset += sizeof(this->point_step);
00166 union {
00167 unsigned long real;
00168 unsigned long base;
00169 } u_row_step;
00170 u_row_step.base = 0;
00171 u_row_step.base |= ((typeof(u_row_step.base)) (*(inbuffer + offset + 0))) << (8 * 0);
00172 u_row_step.base |= ((typeof(u_row_step.base)) (*(inbuffer + offset + 1))) << (8 * 1);
00173 u_row_step.base |= ((typeof(u_row_step.base)) (*(inbuffer + offset + 2))) << (8 * 2);
00174 u_row_step.base |= ((typeof(u_row_step.base)) (*(inbuffer + offset + 3))) << (8 * 3);
00175 this->row_step = u_row_step.real;
00176 offset += sizeof(this->row_step);
00177 unsigned char data_lengthT = *(inbuffer + offset++);
00178 if(data_lengthT > data_length)
00179 this->data = (unsigned char*)realloc(this->data, data_lengthT * sizeof(unsigned char));
00180 offset += 3;
00181 data_length = data_lengthT;
00182 for( unsigned char i = 0; i < data_length; i++){
00183 union {
00184 unsigned char real;
00185 unsigned char base;
00186 } u_st_data;
00187 u_st_data.base = 0;
00188 u_st_data.base |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 0))) << (8 * 0);
00189 this->st_data = u_st_data.real;
00190 offset += sizeof(this->st_data);
00191 memcpy( &(this->data[i]), &(this->st_data), sizeof(unsigned char));
00192 }
00193 union {
00194 bool real;
00195 unsigned char base;
00196 } u_is_dense;
00197 u_is_dense.base = 0;
00198 u_is_dense.base |= ((typeof(u_is_dense.base)) (*(inbuffer + offset + 0))) << (8 * 0);
00199 this->is_dense = u_is_dense.real;
00200 offset += sizeof(this->is_dense);
00201 return offset;
00202 }
00203
00204 const char * getType(){ return "sensor_msgs/PointCloud2"; };
00205
00206 };
00207
00208 }
00209 #endif