It has only one change from original one. I added robotfeedback message on it.
Dependents: RobotFeedback mobileRobotITU
Fork of ros_lib_indigo by
sensor_msgs/PointCloud2.h@0:fd24f7ca9688, 2016-03-31 (annotated)
- Committer:
- garyservin
- Date:
- Thu Mar 31 14:22:59 2016 +0000
- Revision:
- 0:fd24f7ca9688
Initial commit, generated based on a clean indigo-desktop-full
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
garyservin | 0:fd24f7ca9688 | 1 | #ifndef _ROS_sensor_msgs_PointCloud2_h |
garyservin | 0:fd24f7ca9688 | 2 | #define _ROS_sensor_msgs_PointCloud2_h |
garyservin | 0:fd24f7ca9688 | 3 | |
garyservin | 0:fd24f7ca9688 | 4 | #include <stdint.h> |
garyservin | 0:fd24f7ca9688 | 5 | #include <string.h> |
garyservin | 0:fd24f7ca9688 | 6 | #include <stdlib.h> |
garyservin | 0:fd24f7ca9688 | 7 | #include "ros/msg.h" |
garyservin | 0:fd24f7ca9688 | 8 | #include "std_msgs/Header.h" |
garyservin | 0:fd24f7ca9688 | 9 | #include "sensor_msgs/PointField.h" |
garyservin | 0:fd24f7ca9688 | 10 | |
garyservin | 0:fd24f7ca9688 | 11 | namespace sensor_msgs |
garyservin | 0:fd24f7ca9688 | 12 | { |
garyservin | 0:fd24f7ca9688 | 13 | |
garyservin | 0:fd24f7ca9688 | 14 | class PointCloud2 : public ros::Msg |
garyservin | 0:fd24f7ca9688 | 15 | { |
garyservin | 0:fd24f7ca9688 | 16 | public: |
garyservin | 0:fd24f7ca9688 | 17 | std_msgs::Header header; |
garyservin | 0:fd24f7ca9688 | 18 | uint32_t height; |
garyservin | 0:fd24f7ca9688 | 19 | uint32_t width; |
garyservin | 0:fd24f7ca9688 | 20 | uint8_t fields_length; |
garyservin | 0:fd24f7ca9688 | 21 | sensor_msgs::PointField st_fields; |
garyservin | 0:fd24f7ca9688 | 22 | sensor_msgs::PointField * fields; |
garyservin | 0:fd24f7ca9688 | 23 | bool is_bigendian; |
garyservin | 0:fd24f7ca9688 | 24 | uint32_t point_step; |
garyservin | 0:fd24f7ca9688 | 25 | uint32_t row_step; |
garyservin | 0:fd24f7ca9688 | 26 | uint8_t data_length; |
garyservin | 0:fd24f7ca9688 | 27 | uint8_t st_data; |
garyservin | 0:fd24f7ca9688 | 28 | uint8_t * data; |
garyservin | 0:fd24f7ca9688 | 29 | bool is_dense; |
garyservin | 0:fd24f7ca9688 | 30 | |
garyservin | 0:fd24f7ca9688 | 31 | PointCloud2(): |
garyservin | 0:fd24f7ca9688 | 32 | header(), |
garyservin | 0:fd24f7ca9688 | 33 | height(0), |
garyservin | 0:fd24f7ca9688 | 34 | width(0), |
garyservin | 0:fd24f7ca9688 | 35 | fields_length(0), fields(NULL), |
garyservin | 0:fd24f7ca9688 | 36 | is_bigendian(0), |
garyservin | 0:fd24f7ca9688 | 37 | point_step(0), |
garyservin | 0:fd24f7ca9688 | 38 | row_step(0), |
garyservin | 0:fd24f7ca9688 | 39 | data_length(0), data(NULL), |
garyservin | 0:fd24f7ca9688 | 40 | is_dense(0) |
garyservin | 0:fd24f7ca9688 | 41 | { |
garyservin | 0:fd24f7ca9688 | 42 | } |
garyservin | 0:fd24f7ca9688 | 43 | |
garyservin | 0:fd24f7ca9688 | 44 | virtual int serialize(unsigned char *outbuffer) const |
garyservin | 0:fd24f7ca9688 | 45 | { |
garyservin | 0:fd24f7ca9688 | 46 | int offset = 0; |
garyservin | 0:fd24f7ca9688 | 47 | offset += this->header.serialize(outbuffer + offset); |
garyservin | 0:fd24f7ca9688 | 48 | *(outbuffer + offset + 0) = (this->height >> (8 * 0)) & 0xFF; |
garyservin | 0:fd24f7ca9688 | 49 | *(outbuffer + offset + 1) = (this->height >> (8 * 1)) & 0xFF; |
garyservin | 0:fd24f7ca9688 | 50 | *(outbuffer + offset + 2) = (this->height >> (8 * 2)) & 0xFF; |
garyservin | 0:fd24f7ca9688 | 51 | *(outbuffer + offset + 3) = (this->height >> (8 * 3)) & 0xFF; |
garyservin | 0:fd24f7ca9688 | 52 | offset += sizeof(this->height); |
garyservin | 0:fd24f7ca9688 | 53 | *(outbuffer + offset + 0) = (this->width >> (8 * 0)) & 0xFF; |
garyservin | 0:fd24f7ca9688 | 54 | *(outbuffer + offset + 1) = (this->width >> (8 * 1)) & 0xFF; |
garyservin | 0:fd24f7ca9688 | 55 | *(outbuffer + offset + 2) = (this->width >> (8 * 2)) & 0xFF; |
garyservin | 0:fd24f7ca9688 | 56 | *(outbuffer + offset + 3) = (this->width >> (8 * 3)) & 0xFF; |
garyservin | 0:fd24f7ca9688 | 57 | offset += sizeof(this->width); |
garyservin | 0:fd24f7ca9688 | 58 | *(outbuffer + offset++) = fields_length; |
garyservin | 0:fd24f7ca9688 | 59 | *(outbuffer + offset++) = 0; |
garyservin | 0:fd24f7ca9688 | 60 | *(outbuffer + offset++) = 0; |
garyservin | 0:fd24f7ca9688 | 61 | *(outbuffer + offset++) = 0; |
garyservin | 0:fd24f7ca9688 | 62 | for( uint8_t i = 0; i < fields_length; i++){ |
garyservin | 0:fd24f7ca9688 | 63 | offset += this->fields[i].serialize(outbuffer + offset); |
garyservin | 0:fd24f7ca9688 | 64 | } |
garyservin | 0:fd24f7ca9688 | 65 | union { |
garyservin | 0:fd24f7ca9688 | 66 | bool real; |
garyservin | 0:fd24f7ca9688 | 67 | uint8_t base; |
garyservin | 0:fd24f7ca9688 | 68 | } u_is_bigendian; |
garyservin | 0:fd24f7ca9688 | 69 | u_is_bigendian.real = this->is_bigendian; |
garyservin | 0:fd24f7ca9688 | 70 | *(outbuffer + offset + 0) = (u_is_bigendian.base >> (8 * 0)) & 0xFF; |
garyservin | 0:fd24f7ca9688 | 71 | offset += sizeof(this->is_bigendian); |
garyservin | 0:fd24f7ca9688 | 72 | *(outbuffer + offset + 0) = (this->point_step >> (8 * 0)) & 0xFF; |
garyservin | 0:fd24f7ca9688 | 73 | *(outbuffer + offset + 1) = (this->point_step >> (8 * 1)) & 0xFF; |
garyservin | 0:fd24f7ca9688 | 74 | *(outbuffer + offset + 2) = (this->point_step >> (8 * 2)) & 0xFF; |
garyservin | 0:fd24f7ca9688 | 75 | *(outbuffer + offset + 3) = (this->point_step >> (8 * 3)) & 0xFF; |
garyservin | 0:fd24f7ca9688 | 76 | offset += sizeof(this->point_step); |
garyservin | 0:fd24f7ca9688 | 77 | *(outbuffer + offset + 0) = (this->row_step >> (8 * 0)) & 0xFF; |
garyservin | 0:fd24f7ca9688 | 78 | *(outbuffer + offset + 1) = (this->row_step >> (8 * 1)) & 0xFF; |
garyservin | 0:fd24f7ca9688 | 79 | *(outbuffer + offset + 2) = (this->row_step >> (8 * 2)) & 0xFF; |
garyservin | 0:fd24f7ca9688 | 80 | *(outbuffer + offset + 3) = (this->row_step >> (8 * 3)) & 0xFF; |
garyservin | 0:fd24f7ca9688 | 81 | offset += sizeof(this->row_step); |
garyservin | 0:fd24f7ca9688 | 82 | *(outbuffer + offset++) = data_length; |
garyservin | 0:fd24f7ca9688 | 83 | *(outbuffer + offset++) = 0; |
garyservin | 0:fd24f7ca9688 | 84 | *(outbuffer + offset++) = 0; |
garyservin | 0:fd24f7ca9688 | 85 | *(outbuffer + offset++) = 0; |
garyservin | 0:fd24f7ca9688 | 86 | for( uint8_t i = 0; i < data_length; i++){ |
garyservin | 0:fd24f7ca9688 | 87 | *(outbuffer + offset + 0) = (this->data[i] >> (8 * 0)) & 0xFF; |
garyservin | 0:fd24f7ca9688 | 88 | offset += sizeof(this->data[i]); |
garyservin | 0:fd24f7ca9688 | 89 | } |
garyservin | 0:fd24f7ca9688 | 90 | union { |
garyservin | 0:fd24f7ca9688 | 91 | bool real; |
garyservin | 0:fd24f7ca9688 | 92 | uint8_t base; |
garyservin | 0:fd24f7ca9688 | 93 | } u_is_dense; |
garyservin | 0:fd24f7ca9688 | 94 | u_is_dense.real = this->is_dense; |
garyservin | 0:fd24f7ca9688 | 95 | *(outbuffer + offset + 0) = (u_is_dense.base >> (8 * 0)) & 0xFF; |
garyservin | 0:fd24f7ca9688 | 96 | offset += sizeof(this->is_dense); |
garyservin | 0:fd24f7ca9688 | 97 | return offset; |
garyservin | 0:fd24f7ca9688 | 98 | } |
garyservin | 0:fd24f7ca9688 | 99 | |
garyservin | 0:fd24f7ca9688 | 100 | virtual int deserialize(unsigned char *inbuffer) |
garyservin | 0:fd24f7ca9688 | 101 | { |
garyservin | 0:fd24f7ca9688 | 102 | int offset = 0; |
garyservin | 0:fd24f7ca9688 | 103 | offset += this->header.deserialize(inbuffer + offset); |
garyservin | 0:fd24f7ca9688 | 104 | this->height = ((uint32_t) (*(inbuffer + offset))); |
garyservin | 0:fd24f7ca9688 | 105 | this->height |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
garyservin | 0:fd24f7ca9688 | 106 | this->height |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
garyservin | 0:fd24f7ca9688 | 107 | this->height |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
garyservin | 0:fd24f7ca9688 | 108 | offset += sizeof(this->height); |
garyservin | 0:fd24f7ca9688 | 109 | this->width = ((uint32_t) (*(inbuffer + offset))); |
garyservin | 0:fd24f7ca9688 | 110 | this->width |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
garyservin | 0:fd24f7ca9688 | 111 | this->width |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
garyservin | 0:fd24f7ca9688 | 112 | this->width |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
garyservin | 0:fd24f7ca9688 | 113 | offset += sizeof(this->width); |
garyservin | 0:fd24f7ca9688 | 114 | uint8_t fields_lengthT = *(inbuffer + offset++); |
garyservin | 0:fd24f7ca9688 | 115 | if(fields_lengthT > fields_length) |
garyservin | 0:fd24f7ca9688 | 116 | this->fields = (sensor_msgs::PointField*)realloc(this->fields, fields_lengthT * sizeof(sensor_msgs::PointField)); |
garyservin | 0:fd24f7ca9688 | 117 | offset += 3; |
garyservin | 0:fd24f7ca9688 | 118 | fields_length = fields_lengthT; |
garyservin | 0:fd24f7ca9688 | 119 | for( uint8_t i = 0; i < fields_length; i++){ |
garyservin | 0:fd24f7ca9688 | 120 | offset += this->st_fields.deserialize(inbuffer + offset); |
garyservin | 0:fd24f7ca9688 | 121 | memcpy( &(this->fields[i]), &(this->st_fields), sizeof(sensor_msgs::PointField)); |
garyservin | 0:fd24f7ca9688 | 122 | } |
garyservin | 0:fd24f7ca9688 | 123 | union { |
garyservin | 0:fd24f7ca9688 | 124 | bool real; |
garyservin | 0:fd24f7ca9688 | 125 | uint8_t base; |
garyservin | 0:fd24f7ca9688 | 126 | } u_is_bigendian; |
garyservin | 0:fd24f7ca9688 | 127 | u_is_bigendian.base = 0; |
garyservin | 0:fd24f7ca9688 | 128 | u_is_bigendian.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); |
garyservin | 0:fd24f7ca9688 | 129 | this->is_bigendian = u_is_bigendian.real; |
garyservin | 0:fd24f7ca9688 | 130 | offset += sizeof(this->is_bigendian); |
garyservin | 0:fd24f7ca9688 | 131 | this->point_step = ((uint32_t) (*(inbuffer + offset))); |
garyservin | 0:fd24f7ca9688 | 132 | this->point_step |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
garyservin | 0:fd24f7ca9688 | 133 | this->point_step |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
garyservin | 0:fd24f7ca9688 | 134 | this->point_step |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
garyservin | 0:fd24f7ca9688 | 135 | offset += sizeof(this->point_step); |
garyservin | 0:fd24f7ca9688 | 136 | this->row_step = ((uint32_t) (*(inbuffer + offset))); |
garyservin | 0:fd24f7ca9688 | 137 | this->row_step |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
garyservin | 0:fd24f7ca9688 | 138 | this->row_step |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
garyservin | 0:fd24f7ca9688 | 139 | this->row_step |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
garyservin | 0:fd24f7ca9688 | 140 | offset += sizeof(this->row_step); |
garyservin | 0:fd24f7ca9688 | 141 | uint8_t data_lengthT = *(inbuffer + offset++); |
garyservin | 0:fd24f7ca9688 | 142 | if(data_lengthT > data_length) |
garyservin | 0:fd24f7ca9688 | 143 | this->data = (uint8_t*)realloc(this->data, data_lengthT * sizeof(uint8_t)); |
garyservin | 0:fd24f7ca9688 | 144 | offset += 3; |
garyservin | 0:fd24f7ca9688 | 145 | data_length = data_lengthT; |
garyservin | 0:fd24f7ca9688 | 146 | for( uint8_t i = 0; i < data_length; i++){ |
garyservin | 0:fd24f7ca9688 | 147 | this->st_data = ((uint8_t) (*(inbuffer + offset))); |
garyservin | 0:fd24f7ca9688 | 148 | offset += sizeof(this->st_data); |
garyservin | 0:fd24f7ca9688 | 149 | memcpy( &(this->data[i]), &(this->st_data), sizeof(uint8_t)); |
garyservin | 0:fd24f7ca9688 | 150 | } |
garyservin | 0:fd24f7ca9688 | 151 | union { |
garyservin | 0:fd24f7ca9688 | 152 | bool real; |
garyservin | 0:fd24f7ca9688 | 153 | uint8_t base; |
garyservin | 0:fd24f7ca9688 | 154 | } u_is_dense; |
garyservin | 0:fd24f7ca9688 | 155 | u_is_dense.base = 0; |
garyservin | 0:fd24f7ca9688 | 156 | u_is_dense.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); |
garyservin | 0:fd24f7ca9688 | 157 | this->is_dense = u_is_dense.real; |
garyservin | 0:fd24f7ca9688 | 158 | offset += sizeof(this->is_dense); |
garyservin | 0:fd24f7ca9688 | 159 | return offset; |
garyservin | 0:fd24f7ca9688 | 160 | } |
garyservin | 0:fd24f7ca9688 | 161 | |
garyservin | 0:fd24f7ca9688 | 162 | const char * getType(){ return "sensor_msgs/PointCloud2"; }; |
garyservin | 0:fd24f7ca9688 | 163 | const char * getMD5(){ return "1158d486dd51d683ce2f1be655c3c181"; }; |
garyservin | 0:fd24f7ca9688 | 164 | |
garyservin | 0:fd24f7ca9688 | 165 | }; |
garyservin | 0:fd24f7ca9688 | 166 | |
garyservin | 0:fd24f7ca9688 | 167 | } |
garyservin | 0:fd24f7ca9688 | 168 | #endif |