Working towards recieving twists

Dependencies:   BufferedSerial

Fork of ros_lib_kinetic by Gary Servin

Committer:
garyservin
Date:
Sat Dec 31 00:48:34 2016 +0000
Revision:
0:9e9b7db60fd5
Initial commit, generated based on a clean kinetic-desktop-full

Who changed what in which revision?

UserRevisionLine numberNew contents of line
garyservin 0:9e9b7db60fd5 1 #ifndef _ROS_sensor_msgs_PointCloud2_h
garyservin 0:9e9b7db60fd5 2 #define _ROS_sensor_msgs_PointCloud2_h
garyservin 0:9e9b7db60fd5 3
garyservin 0:9e9b7db60fd5 4 #include <stdint.h>
garyservin 0:9e9b7db60fd5 5 #include <string.h>
garyservin 0:9e9b7db60fd5 6 #include <stdlib.h>
garyservin 0:9e9b7db60fd5 7 #include "ros/msg.h"
garyservin 0:9e9b7db60fd5 8 #include "std_msgs/Header.h"
garyservin 0:9e9b7db60fd5 9 #include "sensor_msgs/PointField.h"
garyservin 0:9e9b7db60fd5 10
garyservin 0:9e9b7db60fd5 11 namespace sensor_msgs
garyservin 0:9e9b7db60fd5 12 {
garyservin 0:9e9b7db60fd5 13
garyservin 0:9e9b7db60fd5 14 class PointCloud2 : public ros::Msg
garyservin 0:9e9b7db60fd5 15 {
garyservin 0:9e9b7db60fd5 16 public:
garyservin 0:9e9b7db60fd5 17 typedef std_msgs::Header _header_type;
garyservin 0:9e9b7db60fd5 18 _header_type header;
garyservin 0:9e9b7db60fd5 19 typedef uint32_t _height_type;
garyservin 0:9e9b7db60fd5 20 _height_type height;
garyservin 0:9e9b7db60fd5 21 typedef uint32_t _width_type;
garyservin 0:9e9b7db60fd5 22 _width_type width;
garyservin 0:9e9b7db60fd5 23 uint32_t fields_length;
garyservin 0:9e9b7db60fd5 24 typedef sensor_msgs::PointField _fields_type;
garyservin 0:9e9b7db60fd5 25 _fields_type st_fields;
garyservin 0:9e9b7db60fd5 26 _fields_type * fields;
garyservin 0:9e9b7db60fd5 27 typedef bool _is_bigendian_type;
garyservin 0:9e9b7db60fd5 28 _is_bigendian_type is_bigendian;
garyservin 0:9e9b7db60fd5 29 typedef uint32_t _point_step_type;
garyservin 0:9e9b7db60fd5 30 _point_step_type point_step;
garyservin 0:9e9b7db60fd5 31 typedef uint32_t _row_step_type;
garyservin 0:9e9b7db60fd5 32 _row_step_type row_step;
garyservin 0:9e9b7db60fd5 33 uint32_t data_length;
garyservin 0:9e9b7db60fd5 34 typedef uint8_t _data_type;
garyservin 0:9e9b7db60fd5 35 _data_type st_data;
garyservin 0:9e9b7db60fd5 36 _data_type * data;
garyservin 0:9e9b7db60fd5 37 typedef bool _is_dense_type;
garyservin 0:9e9b7db60fd5 38 _is_dense_type is_dense;
garyservin 0:9e9b7db60fd5 39
garyservin 0:9e9b7db60fd5 40 PointCloud2():
garyservin 0:9e9b7db60fd5 41 header(),
garyservin 0:9e9b7db60fd5 42 height(0),
garyservin 0:9e9b7db60fd5 43 width(0),
garyservin 0:9e9b7db60fd5 44 fields_length(0), fields(NULL),
garyservin 0:9e9b7db60fd5 45 is_bigendian(0),
garyservin 0:9e9b7db60fd5 46 point_step(0),
garyservin 0:9e9b7db60fd5 47 row_step(0),
garyservin 0:9e9b7db60fd5 48 data_length(0), data(NULL),
garyservin 0:9e9b7db60fd5 49 is_dense(0)
garyservin 0:9e9b7db60fd5 50 {
garyservin 0:9e9b7db60fd5 51 }
garyservin 0:9e9b7db60fd5 52
garyservin 0:9e9b7db60fd5 53 virtual int serialize(unsigned char *outbuffer) const
garyservin 0:9e9b7db60fd5 54 {
garyservin 0:9e9b7db60fd5 55 int offset = 0;
garyservin 0:9e9b7db60fd5 56 offset += this->header.serialize(outbuffer + offset);
garyservin 0:9e9b7db60fd5 57 *(outbuffer + offset + 0) = (this->height >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 58 *(outbuffer + offset + 1) = (this->height >> (8 * 1)) & 0xFF;
garyservin 0:9e9b7db60fd5 59 *(outbuffer + offset + 2) = (this->height >> (8 * 2)) & 0xFF;
garyservin 0:9e9b7db60fd5 60 *(outbuffer + offset + 3) = (this->height >> (8 * 3)) & 0xFF;
garyservin 0:9e9b7db60fd5 61 offset += sizeof(this->height);
garyservin 0:9e9b7db60fd5 62 *(outbuffer + offset + 0) = (this->width >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 63 *(outbuffer + offset + 1) = (this->width >> (8 * 1)) & 0xFF;
garyservin 0:9e9b7db60fd5 64 *(outbuffer + offset + 2) = (this->width >> (8 * 2)) & 0xFF;
garyservin 0:9e9b7db60fd5 65 *(outbuffer + offset + 3) = (this->width >> (8 * 3)) & 0xFF;
garyservin 0:9e9b7db60fd5 66 offset += sizeof(this->width);
garyservin 0:9e9b7db60fd5 67 *(outbuffer + offset + 0) = (this->fields_length >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 68 *(outbuffer + offset + 1) = (this->fields_length >> (8 * 1)) & 0xFF;
garyservin 0:9e9b7db60fd5 69 *(outbuffer + offset + 2) = (this->fields_length >> (8 * 2)) & 0xFF;
garyservin 0:9e9b7db60fd5 70 *(outbuffer + offset + 3) = (this->fields_length >> (8 * 3)) & 0xFF;
garyservin 0:9e9b7db60fd5 71 offset += sizeof(this->fields_length);
garyservin 0:9e9b7db60fd5 72 for( uint32_t i = 0; i < fields_length; i++){
garyservin 0:9e9b7db60fd5 73 offset += this->fields[i].serialize(outbuffer + offset);
garyservin 0:9e9b7db60fd5 74 }
garyservin 0:9e9b7db60fd5 75 union {
garyservin 0:9e9b7db60fd5 76 bool real;
garyservin 0:9e9b7db60fd5 77 uint8_t base;
garyservin 0:9e9b7db60fd5 78 } u_is_bigendian;
garyservin 0:9e9b7db60fd5 79 u_is_bigendian.real = this->is_bigendian;
garyservin 0:9e9b7db60fd5 80 *(outbuffer + offset + 0) = (u_is_bigendian.base >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 81 offset += sizeof(this->is_bigendian);
garyservin 0:9e9b7db60fd5 82 *(outbuffer + offset + 0) = (this->point_step >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 83 *(outbuffer + offset + 1) = (this->point_step >> (8 * 1)) & 0xFF;
garyservin 0:9e9b7db60fd5 84 *(outbuffer + offset + 2) = (this->point_step >> (8 * 2)) & 0xFF;
garyservin 0:9e9b7db60fd5 85 *(outbuffer + offset + 3) = (this->point_step >> (8 * 3)) & 0xFF;
garyservin 0:9e9b7db60fd5 86 offset += sizeof(this->point_step);
garyservin 0:9e9b7db60fd5 87 *(outbuffer + offset + 0) = (this->row_step >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 88 *(outbuffer + offset + 1) = (this->row_step >> (8 * 1)) & 0xFF;
garyservin 0:9e9b7db60fd5 89 *(outbuffer + offset + 2) = (this->row_step >> (8 * 2)) & 0xFF;
garyservin 0:9e9b7db60fd5 90 *(outbuffer + offset + 3) = (this->row_step >> (8 * 3)) & 0xFF;
garyservin 0:9e9b7db60fd5 91 offset += sizeof(this->row_step);
garyservin 0:9e9b7db60fd5 92 *(outbuffer + offset + 0) = (this->data_length >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 93 *(outbuffer + offset + 1) = (this->data_length >> (8 * 1)) & 0xFF;
garyservin 0:9e9b7db60fd5 94 *(outbuffer + offset + 2) = (this->data_length >> (8 * 2)) & 0xFF;
garyservin 0:9e9b7db60fd5 95 *(outbuffer + offset + 3) = (this->data_length >> (8 * 3)) & 0xFF;
garyservin 0:9e9b7db60fd5 96 offset += sizeof(this->data_length);
garyservin 0:9e9b7db60fd5 97 for( uint32_t i = 0; i < data_length; i++){
garyservin 0:9e9b7db60fd5 98 *(outbuffer + offset + 0) = (this->data[i] >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 99 offset += sizeof(this->data[i]);
garyservin 0:9e9b7db60fd5 100 }
garyservin 0:9e9b7db60fd5 101 union {
garyservin 0:9e9b7db60fd5 102 bool real;
garyservin 0:9e9b7db60fd5 103 uint8_t base;
garyservin 0:9e9b7db60fd5 104 } u_is_dense;
garyservin 0:9e9b7db60fd5 105 u_is_dense.real = this->is_dense;
garyservin 0:9e9b7db60fd5 106 *(outbuffer + offset + 0) = (u_is_dense.base >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 107 offset += sizeof(this->is_dense);
garyservin 0:9e9b7db60fd5 108 return offset;
garyservin 0:9e9b7db60fd5 109 }
garyservin 0:9e9b7db60fd5 110
garyservin 0:9e9b7db60fd5 111 virtual int deserialize(unsigned char *inbuffer)
garyservin 0:9e9b7db60fd5 112 {
garyservin 0:9e9b7db60fd5 113 int offset = 0;
garyservin 0:9e9b7db60fd5 114 offset += this->header.deserialize(inbuffer + offset);
garyservin 0:9e9b7db60fd5 115 this->height = ((uint32_t) (*(inbuffer + offset)));
garyservin 0:9e9b7db60fd5 116 this->height |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:9e9b7db60fd5 117 this->height |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:9e9b7db60fd5 118 this->height |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:9e9b7db60fd5 119 offset += sizeof(this->height);
garyservin 0:9e9b7db60fd5 120 this->width = ((uint32_t) (*(inbuffer + offset)));
garyservin 0:9e9b7db60fd5 121 this->width |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:9e9b7db60fd5 122 this->width |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:9e9b7db60fd5 123 this->width |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:9e9b7db60fd5 124 offset += sizeof(this->width);
garyservin 0:9e9b7db60fd5 125 uint32_t fields_lengthT = ((uint32_t) (*(inbuffer + offset)));
garyservin 0:9e9b7db60fd5 126 fields_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:9e9b7db60fd5 127 fields_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:9e9b7db60fd5 128 fields_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:9e9b7db60fd5 129 offset += sizeof(this->fields_length);
garyservin 0:9e9b7db60fd5 130 if(fields_lengthT > fields_length)
garyservin 0:9e9b7db60fd5 131 this->fields = (sensor_msgs::PointField*)realloc(this->fields, fields_lengthT * sizeof(sensor_msgs::PointField));
garyservin 0:9e9b7db60fd5 132 fields_length = fields_lengthT;
garyservin 0:9e9b7db60fd5 133 for( uint32_t i = 0; i < fields_length; i++){
garyservin 0:9e9b7db60fd5 134 offset += this->st_fields.deserialize(inbuffer + offset);
garyservin 0:9e9b7db60fd5 135 memcpy( &(this->fields[i]), &(this->st_fields), sizeof(sensor_msgs::PointField));
garyservin 0:9e9b7db60fd5 136 }
garyservin 0:9e9b7db60fd5 137 union {
garyservin 0:9e9b7db60fd5 138 bool real;
garyservin 0:9e9b7db60fd5 139 uint8_t base;
garyservin 0:9e9b7db60fd5 140 } u_is_bigendian;
garyservin 0:9e9b7db60fd5 141 u_is_bigendian.base = 0;
garyservin 0:9e9b7db60fd5 142 u_is_bigendian.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:9e9b7db60fd5 143 this->is_bigendian = u_is_bigendian.real;
garyservin 0:9e9b7db60fd5 144 offset += sizeof(this->is_bigendian);
garyservin 0:9e9b7db60fd5 145 this->point_step = ((uint32_t) (*(inbuffer + offset)));
garyservin 0:9e9b7db60fd5 146 this->point_step |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:9e9b7db60fd5 147 this->point_step |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:9e9b7db60fd5 148 this->point_step |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:9e9b7db60fd5 149 offset += sizeof(this->point_step);
garyservin 0:9e9b7db60fd5 150 this->row_step = ((uint32_t) (*(inbuffer + offset)));
garyservin 0:9e9b7db60fd5 151 this->row_step |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:9e9b7db60fd5 152 this->row_step |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:9e9b7db60fd5 153 this->row_step |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:9e9b7db60fd5 154 offset += sizeof(this->row_step);
garyservin 0:9e9b7db60fd5 155 uint32_t data_lengthT = ((uint32_t) (*(inbuffer + offset)));
garyservin 0:9e9b7db60fd5 156 data_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:9e9b7db60fd5 157 data_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:9e9b7db60fd5 158 data_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:9e9b7db60fd5 159 offset += sizeof(this->data_length);
garyservin 0:9e9b7db60fd5 160 if(data_lengthT > data_length)
garyservin 0:9e9b7db60fd5 161 this->data = (uint8_t*)realloc(this->data, data_lengthT * sizeof(uint8_t));
garyservin 0:9e9b7db60fd5 162 data_length = data_lengthT;
garyservin 0:9e9b7db60fd5 163 for( uint32_t i = 0; i < data_length; i++){
garyservin 0:9e9b7db60fd5 164 this->st_data = ((uint8_t) (*(inbuffer + offset)));
garyservin 0:9e9b7db60fd5 165 offset += sizeof(this->st_data);
garyservin 0:9e9b7db60fd5 166 memcpy( &(this->data[i]), &(this->st_data), sizeof(uint8_t));
garyservin 0:9e9b7db60fd5 167 }
garyservin 0:9e9b7db60fd5 168 union {
garyservin 0:9e9b7db60fd5 169 bool real;
garyservin 0:9e9b7db60fd5 170 uint8_t base;
garyservin 0:9e9b7db60fd5 171 } u_is_dense;
garyservin 0:9e9b7db60fd5 172 u_is_dense.base = 0;
garyservin 0:9e9b7db60fd5 173 u_is_dense.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:9e9b7db60fd5 174 this->is_dense = u_is_dense.real;
garyservin 0:9e9b7db60fd5 175 offset += sizeof(this->is_dense);
garyservin 0:9e9b7db60fd5 176 return offset;
garyservin 0:9e9b7db60fd5 177 }
garyservin 0:9e9b7db60fd5 178
garyservin 0:9e9b7db60fd5 179 const char * getType(){ return "sensor_msgs/PointCloud2"; };
garyservin 0:9e9b7db60fd5 180 const char * getMD5(){ return "1158d486dd51d683ce2f1be655c3c181"; };
garyservin 0:9e9b7db60fd5 181
garyservin 0:9e9b7db60fd5 182 };
garyservin 0:9e9b7db60fd5 183
garyservin 0:9e9b7db60fd5 184 }
garyservin 0:9e9b7db60fd5 185 #endif