Important changes to repositories hosted on mbed.com
Mbed hosted mercurial repositories are deprecated and are due to be permanently deleted in July 2026.
To keep a copy of this software download the repository Zip archive or clone locally using Mercurial.
It is also possible to export all your personal repositories from the account settings page.
Fork of rosserial_mbed_lib by
Diff: sensor_msgs/PointCloud2.h
- Revision:
- 6:3c54bc7badd4
diff -r 8cd48977ec68 -r 3c54bc7badd4 sensor_msgs/PointCloud2.h
--- /dev/null Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_msgs/PointCloud2.h Sat Oct 26 15:39:01 2013 +0000
@@ -0,0 +1,155 @@
+#ifndef _ROS_sensor_msgs_PointCloud2_h
+#define _ROS_sensor_msgs_PointCloud2_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "sensor_msgs/PointField.h"
+
+namespace sensor_msgs
+{
+
+ class PointCloud2 : public ros::Msg
+ {
+ public:
+ std_msgs::Header header;
+ uint32_t height;
+ uint32_t width;
+ uint8_t fields_length;
+ sensor_msgs::PointField st_fields;
+ sensor_msgs::PointField * fields;
+ bool is_bigendian;
+ uint32_t point_step;
+ uint32_t row_step;
+ uint8_t data_length;
+ uint8_t st_data;
+ uint8_t * data;
+ bool is_dense;
+
+ virtual int serialize(unsigned char *outbuffer) const
+ {
+ int offset = 0;
+ offset += this->header.serialize(outbuffer + offset);
+ *(outbuffer + offset + 0) = (this->height >> (8 * 0)) & 0xFF;
+ *(outbuffer + offset + 1) = (this->height >> (8 * 1)) & 0xFF;
+ *(outbuffer + offset + 2) = (this->height >> (8 * 2)) & 0xFF;
+ *(outbuffer + offset + 3) = (this->height >> (8 * 3)) & 0xFF;
+ offset += sizeof(this->height);
+ *(outbuffer + offset + 0) = (this->width >> (8 * 0)) & 0xFF;
+ *(outbuffer + offset + 1) = (this->width >> (8 * 1)) & 0xFF;
+ *(outbuffer + offset + 2) = (this->width >> (8 * 2)) & 0xFF;
+ *(outbuffer + offset + 3) = (this->width >> (8 * 3)) & 0xFF;
+ offset += sizeof(this->width);
+ *(outbuffer + offset++) = fields_length;
+ *(outbuffer + offset++) = 0;
+ *(outbuffer + offset++) = 0;
+ *(outbuffer + offset++) = 0;
+ for( uint8_t i = 0; i < fields_length; i++){
+ offset += this->fields[i].serialize(outbuffer + offset);
+ }
+ union {
+ bool real;
+ uint8_t base;
+ } u_is_bigendian;
+ u_is_bigendian.real = this->is_bigendian;
+ *(outbuffer + offset + 0) = (u_is_bigendian.base >> (8 * 0)) & 0xFF;
+ offset += sizeof(this->is_bigendian);
+ *(outbuffer + offset + 0) = (this->point_step >> (8 * 0)) & 0xFF;
+ *(outbuffer + offset + 1) = (this->point_step >> (8 * 1)) & 0xFF;
+ *(outbuffer + offset + 2) = (this->point_step >> (8 * 2)) & 0xFF;
+ *(outbuffer + offset + 3) = (this->point_step >> (8 * 3)) & 0xFF;
+ offset += sizeof(this->point_step);
+ *(outbuffer + offset + 0) = (this->row_step >> (8 * 0)) & 0xFF;
+ *(outbuffer + offset + 1) = (this->row_step >> (8 * 1)) & 0xFF;
+ *(outbuffer + offset + 2) = (this->row_step >> (8 * 2)) & 0xFF;
+ *(outbuffer + offset + 3) = (this->row_step >> (8 * 3)) & 0xFF;
+ offset += sizeof(this->row_step);
+ *(outbuffer + offset++) = data_length;
+ *(outbuffer + offset++) = 0;
+ *(outbuffer + offset++) = 0;
+ *(outbuffer + offset++) = 0;
+ for( uint8_t i = 0; i < data_length; i++){
+ *(outbuffer + offset + 0) = (this->data[i] >> (8 * 0)) & 0xFF;
+ offset += sizeof(this->data[i]);
+ }
+ union {
+ bool real;
+ uint8_t base;
+ } u_is_dense;
+ u_is_dense.real = this->is_dense;
+ *(outbuffer + offset + 0) = (u_is_dense.base >> (8 * 0)) & 0xFF;
+ offset += sizeof(this->is_dense);
+ return offset;
+ }
+
+ virtual int deserialize(unsigned char *inbuffer)
+ {
+ int offset = 0;
+ offset += this->header.deserialize(inbuffer + offset);
+ this->height = ((uint32_t) (*(inbuffer + offset)));
+ this->height |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+ this->height |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+ this->height |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+ offset += sizeof(this->height);
+ this->width = ((uint32_t) (*(inbuffer + offset)));
+ this->width |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+ this->width |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+ this->width |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+ offset += sizeof(this->width);
+ uint8_t fields_lengthT = *(inbuffer + offset++);
+ if(fields_lengthT > fields_length)
+ this->fields = (sensor_msgs::PointField*)realloc(this->fields, fields_lengthT * sizeof(sensor_msgs::PointField));
+ offset += 3;
+ fields_length = fields_lengthT;
+ for( uint8_t i = 0; i < fields_length; i++){
+ offset += this->st_fields.deserialize(inbuffer + offset);
+ memcpy( &(this->fields[i]), &(this->st_fields), sizeof(sensor_msgs::PointField));
+ }
+ union {
+ bool real;
+ uint8_t base;
+ } u_is_bigendian;
+ u_is_bigendian.base = 0;
+ u_is_bigendian.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+ this->is_bigendian = u_is_bigendian.real;
+ offset += sizeof(this->is_bigendian);
+ this->point_step = ((uint32_t) (*(inbuffer + offset)));
+ this->point_step |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+ this->point_step |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+ this->point_step |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+ offset += sizeof(this->point_step);
+ this->row_step = ((uint32_t) (*(inbuffer + offset)));
+ this->row_step |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+ this->row_step |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+ this->row_step |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+ offset += sizeof(this->row_step);
+ uint8_t data_lengthT = *(inbuffer + offset++);
+ if(data_lengthT > data_length)
+ this->data = (uint8_t*)realloc(this->data, data_lengthT * sizeof(uint8_t));
+ offset += 3;
+ data_length = data_lengthT;
+ for( uint8_t i = 0; i < data_length; i++){
+ this->st_data = ((uint8_t) (*(inbuffer + offset)));
+ offset += sizeof(this->st_data);
+ memcpy( &(this->data[i]), &(this->st_data), sizeof(uint8_t));
+ }
+ union {
+ bool real;
+ uint8_t base;
+ } u_is_dense;
+ u_is_dense.base = 0;
+ u_is_dense.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+ this->is_dense = u_is_dense.real;
+ offset += sizeof(this->is_dense);
+ return offset;
+ }
+
+ const char * getType(){ return "sensor_msgs/PointCloud2"; };
+ const char * getMD5(){ return "1158d486dd51d683ce2f1be655c3c181"; };
+
+ };
+
+}
+#endif
