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/LaserScan.h@4:80d9bee5079a, 2017-03-04 (annotated)
- Committer:
- randalthor
- Date:
- Sat Mar 04 14:07:56 2017 +0000
- Revision:
- 4:80d9bee5079a
- Parent:
- 0:fd24f7ca9688
fatih
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
garyservin | 0:fd24f7ca9688 | 1 | #ifndef _ROS_sensor_msgs_LaserScan_h |
garyservin | 0:fd24f7ca9688 | 2 | #define _ROS_sensor_msgs_LaserScan_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 | |
garyservin | 0:fd24f7ca9688 | 10 | namespace sensor_msgs |
garyservin | 0:fd24f7ca9688 | 11 | { |
garyservin | 0:fd24f7ca9688 | 12 | |
garyservin | 0:fd24f7ca9688 | 13 | class LaserScan : public ros::Msg |
garyservin | 0:fd24f7ca9688 | 14 | { |
garyservin | 0:fd24f7ca9688 | 15 | public: |
garyservin | 0:fd24f7ca9688 | 16 | std_msgs::Header header; |
garyservin | 0:fd24f7ca9688 | 17 | float angle_min; |
garyservin | 0:fd24f7ca9688 | 18 | float angle_max; |
garyservin | 0:fd24f7ca9688 | 19 | float angle_increment; |
garyservin | 0:fd24f7ca9688 | 20 | float time_increment; |
garyservin | 0:fd24f7ca9688 | 21 | float scan_time; |
garyservin | 0:fd24f7ca9688 | 22 | float range_min; |
garyservin | 0:fd24f7ca9688 | 23 | float range_max; |
garyservin | 0:fd24f7ca9688 | 24 | uint8_t ranges_length; |
garyservin | 0:fd24f7ca9688 | 25 | float st_ranges; |
garyservin | 0:fd24f7ca9688 | 26 | float * ranges; |
garyservin | 0:fd24f7ca9688 | 27 | uint8_t intensities_length; |
garyservin | 0:fd24f7ca9688 | 28 | float st_intensities; |
garyservin | 0:fd24f7ca9688 | 29 | float * intensities; |
garyservin | 0:fd24f7ca9688 | 30 | |
garyservin | 0:fd24f7ca9688 | 31 | LaserScan(): |
garyservin | 0:fd24f7ca9688 | 32 | header(), |
garyservin | 0:fd24f7ca9688 | 33 | angle_min(0), |
garyservin | 0:fd24f7ca9688 | 34 | angle_max(0), |
garyservin | 0:fd24f7ca9688 | 35 | angle_increment(0), |
garyservin | 0:fd24f7ca9688 | 36 | time_increment(0), |
garyservin | 0:fd24f7ca9688 | 37 | scan_time(0), |
garyservin | 0:fd24f7ca9688 | 38 | range_min(0), |
garyservin | 0:fd24f7ca9688 | 39 | range_max(0), |
garyservin | 0:fd24f7ca9688 | 40 | ranges_length(0), ranges(NULL), |
garyservin | 0:fd24f7ca9688 | 41 | intensities_length(0), intensities(NULL) |
garyservin | 0:fd24f7ca9688 | 42 | { |
garyservin | 0:fd24f7ca9688 | 43 | } |
garyservin | 0:fd24f7ca9688 | 44 | |
garyservin | 0:fd24f7ca9688 | 45 | virtual int serialize(unsigned char *outbuffer) const |
garyservin | 0:fd24f7ca9688 | 46 | { |
garyservin | 0:fd24f7ca9688 | 47 | int offset = 0; |
garyservin | 0:fd24f7ca9688 | 48 | offset += this->header.serialize(outbuffer + offset); |
garyservin | 0:fd24f7ca9688 | 49 | union { |
garyservin | 0:fd24f7ca9688 | 50 | float real; |
garyservin | 0:fd24f7ca9688 | 51 | uint32_t base; |
garyservin | 0:fd24f7ca9688 | 52 | } u_angle_min; |
garyservin | 0:fd24f7ca9688 | 53 | u_angle_min.real = this->angle_min; |
garyservin | 0:fd24f7ca9688 | 54 | *(outbuffer + offset + 0) = (u_angle_min.base >> (8 * 0)) & 0xFF; |
garyservin | 0:fd24f7ca9688 | 55 | *(outbuffer + offset + 1) = (u_angle_min.base >> (8 * 1)) & 0xFF; |
garyservin | 0:fd24f7ca9688 | 56 | *(outbuffer + offset + 2) = (u_angle_min.base >> (8 * 2)) & 0xFF; |
garyservin | 0:fd24f7ca9688 | 57 | *(outbuffer + offset + 3) = (u_angle_min.base >> (8 * 3)) & 0xFF; |
garyservin | 0:fd24f7ca9688 | 58 | offset += sizeof(this->angle_min); |
garyservin | 0:fd24f7ca9688 | 59 | union { |
garyservin | 0:fd24f7ca9688 | 60 | float real; |
garyservin | 0:fd24f7ca9688 | 61 | uint32_t base; |
garyservin | 0:fd24f7ca9688 | 62 | } u_angle_max; |
garyservin | 0:fd24f7ca9688 | 63 | u_angle_max.real = this->angle_max; |
garyservin | 0:fd24f7ca9688 | 64 | *(outbuffer + offset + 0) = (u_angle_max.base >> (8 * 0)) & 0xFF; |
garyservin | 0:fd24f7ca9688 | 65 | *(outbuffer + offset + 1) = (u_angle_max.base >> (8 * 1)) & 0xFF; |
garyservin | 0:fd24f7ca9688 | 66 | *(outbuffer + offset + 2) = (u_angle_max.base >> (8 * 2)) & 0xFF; |
garyservin | 0:fd24f7ca9688 | 67 | *(outbuffer + offset + 3) = (u_angle_max.base >> (8 * 3)) & 0xFF; |
garyservin | 0:fd24f7ca9688 | 68 | offset += sizeof(this->angle_max); |
garyservin | 0:fd24f7ca9688 | 69 | union { |
garyservin | 0:fd24f7ca9688 | 70 | float real; |
garyservin | 0:fd24f7ca9688 | 71 | uint32_t base; |
garyservin | 0:fd24f7ca9688 | 72 | } u_angle_increment; |
garyservin | 0:fd24f7ca9688 | 73 | u_angle_increment.real = this->angle_increment; |
garyservin | 0:fd24f7ca9688 | 74 | *(outbuffer + offset + 0) = (u_angle_increment.base >> (8 * 0)) & 0xFF; |
garyservin | 0:fd24f7ca9688 | 75 | *(outbuffer + offset + 1) = (u_angle_increment.base >> (8 * 1)) & 0xFF; |
garyservin | 0:fd24f7ca9688 | 76 | *(outbuffer + offset + 2) = (u_angle_increment.base >> (8 * 2)) & 0xFF; |
garyservin | 0:fd24f7ca9688 | 77 | *(outbuffer + offset + 3) = (u_angle_increment.base >> (8 * 3)) & 0xFF; |
garyservin | 0:fd24f7ca9688 | 78 | offset += sizeof(this->angle_increment); |
garyservin | 0:fd24f7ca9688 | 79 | union { |
garyservin | 0:fd24f7ca9688 | 80 | float real; |
garyservin | 0:fd24f7ca9688 | 81 | uint32_t base; |
garyservin | 0:fd24f7ca9688 | 82 | } u_time_increment; |
garyservin | 0:fd24f7ca9688 | 83 | u_time_increment.real = this->time_increment; |
garyservin | 0:fd24f7ca9688 | 84 | *(outbuffer + offset + 0) = (u_time_increment.base >> (8 * 0)) & 0xFF; |
garyservin | 0:fd24f7ca9688 | 85 | *(outbuffer + offset + 1) = (u_time_increment.base >> (8 * 1)) & 0xFF; |
garyservin | 0:fd24f7ca9688 | 86 | *(outbuffer + offset + 2) = (u_time_increment.base >> (8 * 2)) & 0xFF; |
garyservin | 0:fd24f7ca9688 | 87 | *(outbuffer + offset + 3) = (u_time_increment.base >> (8 * 3)) & 0xFF; |
garyservin | 0:fd24f7ca9688 | 88 | offset += sizeof(this->time_increment); |
garyservin | 0:fd24f7ca9688 | 89 | union { |
garyservin | 0:fd24f7ca9688 | 90 | float real; |
garyservin | 0:fd24f7ca9688 | 91 | uint32_t base; |
garyservin | 0:fd24f7ca9688 | 92 | } u_scan_time; |
garyservin | 0:fd24f7ca9688 | 93 | u_scan_time.real = this->scan_time; |
garyservin | 0:fd24f7ca9688 | 94 | *(outbuffer + offset + 0) = (u_scan_time.base >> (8 * 0)) & 0xFF; |
garyservin | 0:fd24f7ca9688 | 95 | *(outbuffer + offset + 1) = (u_scan_time.base >> (8 * 1)) & 0xFF; |
garyservin | 0:fd24f7ca9688 | 96 | *(outbuffer + offset + 2) = (u_scan_time.base >> (8 * 2)) & 0xFF; |
garyservin | 0:fd24f7ca9688 | 97 | *(outbuffer + offset + 3) = (u_scan_time.base >> (8 * 3)) & 0xFF; |
garyservin | 0:fd24f7ca9688 | 98 | offset += sizeof(this->scan_time); |
garyservin | 0:fd24f7ca9688 | 99 | union { |
garyservin | 0:fd24f7ca9688 | 100 | float real; |
garyservin | 0:fd24f7ca9688 | 101 | uint32_t base; |
garyservin | 0:fd24f7ca9688 | 102 | } u_range_min; |
garyservin | 0:fd24f7ca9688 | 103 | u_range_min.real = this->range_min; |
garyservin | 0:fd24f7ca9688 | 104 | *(outbuffer + offset + 0) = (u_range_min.base >> (8 * 0)) & 0xFF; |
garyservin | 0:fd24f7ca9688 | 105 | *(outbuffer + offset + 1) = (u_range_min.base >> (8 * 1)) & 0xFF; |
garyservin | 0:fd24f7ca9688 | 106 | *(outbuffer + offset + 2) = (u_range_min.base >> (8 * 2)) & 0xFF; |
garyservin | 0:fd24f7ca9688 | 107 | *(outbuffer + offset + 3) = (u_range_min.base >> (8 * 3)) & 0xFF; |
garyservin | 0:fd24f7ca9688 | 108 | offset += sizeof(this->range_min); |
garyservin | 0:fd24f7ca9688 | 109 | union { |
garyservin | 0:fd24f7ca9688 | 110 | float real; |
garyservin | 0:fd24f7ca9688 | 111 | uint32_t base; |
garyservin | 0:fd24f7ca9688 | 112 | } u_range_max; |
garyservin | 0:fd24f7ca9688 | 113 | u_range_max.real = this->range_max; |
garyservin | 0:fd24f7ca9688 | 114 | *(outbuffer + offset + 0) = (u_range_max.base >> (8 * 0)) & 0xFF; |
garyservin | 0:fd24f7ca9688 | 115 | *(outbuffer + offset + 1) = (u_range_max.base >> (8 * 1)) & 0xFF; |
garyservin | 0:fd24f7ca9688 | 116 | *(outbuffer + offset + 2) = (u_range_max.base >> (8 * 2)) & 0xFF; |
garyservin | 0:fd24f7ca9688 | 117 | *(outbuffer + offset + 3) = (u_range_max.base >> (8 * 3)) & 0xFF; |
garyservin | 0:fd24f7ca9688 | 118 | offset += sizeof(this->range_max); |
garyservin | 0:fd24f7ca9688 | 119 | *(outbuffer + offset++) = ranges_length; |
garyservin | 0:fd24f7ca9688 | 120 | *(outbuffer + offset++) = 0; |
garyservin | 0:fd24f7ca9688 | 121 | *(outbuffer + offset++) = 0; |
garyservin | 0:fd24f7ca9688 | 122 | *(outbuffer + offset++) = 0; |
garyservin | 0:fd24f7ca9688 | 123 | for( uint8_t i = 0; i < ranges_length; i++){ |
garyservin | 0:fd24f7ca9688 | 124 | union { |
garyservin | 0:fd24f7ca9688 | 125 | float real; |
garyservin | 0:fd24f7ca9688 | 126 | uint32_t base; |
garyservin | 0:fd24f7ca9688 | 127 | } u_rangesi; |
garyservin | 0:fd24f7ca9688 | 128 | u_rangesi.real = this->ranges[i]; |
garyservin | 0:fd24f7ca9688 | 129 | *(outbuffer + offset + 0) = (u_rangesi.base >> (8 * 0)) & 0xFF; |
garyservin | 0:fd24f7ca9688 | 130 | *(outbuffer + offset + 1) = (u_rangesi.base >> (8 * 1)) & 0xFF; |
garyservin | 0:fd24f7ca9688 | 131 | *(outbuffer + offset + 2) = (u_rangesi.base >> (8 * 2)) & 0xFF; |
garyservin | 0:fd24f7ca9688 | 132 | *(outbuffer + offset + 3) = (u_rangesi.base >> (8 * 3)) & 0xFF; |
garyservin | 0:fd24f7ca9688 | 133 | offset += sizeof(this->ranges[i]); |
garyservin | 0:fd24f7ca9688 | 134 | } |
garyservin | 0:fd24f7ca9688 | 135 | *(outbuffer + offset++) = intensities_length; |
garyservin | 0:fd24f7ca9688 | 136 | *(outbuffer + offset++) = 0; |
garyservin | 0:fd24f7ca9688 | 137 | *(outbuffer + offset++) = 0; |
garyservin | 0:fd24f7ca9688 | 138 | *(outbuffer + offset++) = 0; |
garyservin | 0:fd24f7ca9688 | 139 | for( uint8_t i = 0; i < intensities_length; i++){ |
garyservin | 0:fd24f7ca9688 | 140 | union { |
garyservin | 0:fd24f7ca9688 | 141 | float real; |
garyservin | 0:fd24f7ca9688 | 142 | uint32_t base; |
garyservin | 0:fd24f7ca9688 | 143 | } u_intensitiesi; |
garyservin | 0:fd24f7ca9688 | 144 | u_intensitiesi.real = this->intensities[i]; |
garyservin | 0:fd24f7ca9688 | 145 | *(outbuffer + offset + 0) = (u_intensitiesi.base >> (8 * 0)) & 0xFF; |
garyservin | 0:fd24f7ca9688 | 146 | *(outbuffer + offset + 1) = (u_intensitiesi.base >> (8 * 1)) & 0xFF; |
garyservin | 0:fd24f7ca9688 | 147 | *(outbuffer + offset + 2) = (u_intensitiesi.base >> (8 * 2)) & 0xFF; |
garyservin | 0:fd24f7ca9688 | 148 | *(outbuffer + offset + 3) = (u_intensitiesi.base >> (8 * 3)) & 0xFF; |
garyservin | 0:fd24f7ca9688 | 149 | offset += sizeof(this->intensities[i]); |
garyservin | 0:fd24f7ca9688 | 150 | } |
garyservin | 0:fd24f7ca9688 | 151 | return offset; |
garyservin | 0:fd24f7ca9688 | 152 | } |
garyservin | 0:fd24f7ca9688 | 153 | |
garyservin | 0:fd24f7ca9688 | 154 | virtual int deserialize(unsigned char *inbuffer) |
garyservin | 0:fd24f7ca9688 | 155 | { |
garyservin | 0:fd24f7ca9688 | 156 | int offset = 0; |
garyservin | 0:fd24f7ca9688 | 157 | offset += this->header.deserialize(inbuffer + offset); |
garyservin | 0:fd24f7ca9688 | 158 | union { |
garyservin | 0:fd24f7ca9688 | 159 | float real; |
garyservin | 0:fd24f7ca9688 | 160 | uint32_t base; |
garyservin | 0:fd24f7ca9688 | 161 | } u_angle_min; |
garyservin | 0:fd24f7ca9688 | 162 | u_angle_min.base = 0; |
garyservin | 0:fd24f7ca9688 | 163 | u_angle_min.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); |
garyservin | 0:fd24f7ca9688 | 164 | u_angle_min.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
garyservin | 0:fd24f7ca9688 | 165 | u_angle_min.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
garyservin | 0:fd24f7ca9688 | 166 | u_angle_min.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
garyservin | 0:fd24f7ca9688 | 167 | this->angle_min = u_angle_min.real; |
garyservin | 0:fd24f7ca9688 | 168 | offset += sizeof(this->angle_min); |
garyservin | 0:fd24f7ca9688 | 169 | union { |
garyservin | 0:fd24f7ca9688 | 170 | float real; |
garyservin | 0:fd24f7ca9688 | 171 | uint32_t base; |
garyservin | 0:fd24f7ca9688 | 172 | } u_angle_max; |
garyservin | 0:fd24f7ca9688 | 173 | u_angle_max.base = 0; |
garyservin | 0:fd24f7ca9688 | 174 | u_angle_max.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); |
garyservin | 0:fd24f7ca9688 | 175 | u_angle_max.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
garyservin | 0:fd24f7ca9688 | 176 | u_angle_max.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
garyservin | 0:fd24f7ca9688 | 177 | u_angle_max.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
garyservin | 0:fd24f7ca9688 | 178 | this->angle_max = u_angle_max.real; |
garyservin | 0:fd24f7ca9688 | 179 | offset += sizeof(this->angle_max); |
garyservin | 0:fd24f7ca9688 | 180 | union { |
garyservin | 0:fd24f7ca9688 | 181 | float real; |
garyservin | 0:fd24f7ca9688 | 182 | uint32_t base; |
garyservin | 0:fd24f7ca9688 | 183 | } u_angle_increment; |
garyservin | 0:fd24f7ca9688 | 184 | u_angle_increment.base = 0; |
garyservin | 0:fd24f7ca9688 | 185 | u_angle_increment.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); |
garyservin | 0:fd24f7ca9688 | 186 | u_angle_increment.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
garyservin | 0:fd24f7ca9688 | 187 | u_angle_increment.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
garyservin | 0:fd24f7ca9688 | 188 | u_angle_increment.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
garyservin | 0:fd24f7ca9688 | 189 | this->angle_increment = u_angle_increment.real; |
garyservin | 0:fd24f7ca9688 | 190 | offset += sizeof(this->angle_increment); |
garyservin | 0:fd24f7ca9688 | 191 | union { |
garyservin | 0:fd24f7ca9688 | 192 | float real; |
garyservin | 0:fd24f7ca9688 | 193 | uint32_t base; |
garyservin | 0:fd24f7ca9688 | 194 | } u_time_increment; |
garyservin | 0:fd24f7ca9688 | 195 | u_time_increment.base = 0; |
garyservin | 0:fd24f7ca9688 | 196 | u_time_increment.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); |
garyservin | 0:fd24f7ca9688 | 197 | u_time_increment.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
garyservin | 0:fd24f7ca9688 | 198 | u_time_increment.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
garyservin | 0:fd24f7ca9688 | 199 | u_time_increment.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
garyservin | 0:fd24f7ca9688 | 200 | this->time_increment = u_time_increment.real; |
garyservin | 0:fd24f7ca9688 | 201 | offset += sizeof(this->time_increment); |
garyservin | 0:fd24f7ca9688 | 202 | union { |
garyservin | 0:fd24f7ca9688 | 203 | float real; |
garyservin | 0:fd24f7ca9688 | 204 | uint32_t base; |
garyservin | 0:fd24f7ca9688 | 205 | } u_scan_time; |
garyservin | 0:fd24f7ca9688 | 206 | u_scan_time.base = 0; |
garyservin | 0:fd24f7ca9688 | 207 | u_scan_time.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); |
garyservin | 0:fd24f7ca9688 | 208 | u_scan_time.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
garyservin | 0:fd24f7ca9688 | 209 | u_scan_time.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
garyservin | 0:fd24f7ca9688 | 210 | u_scan_time.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
garyservin | 0:fd24f7ca9688 | 211 | this->scan_time = u_scan_time.real; |
garyservin | 0:fd24f7ca9688 | 212 | offset += sizeof(this->scan_time); |
garyservin | 0:fd24f7ca9688 | 213 | union { |
garyservin | 0:fd24f7ca9688 | 214 | float real; |
garyservin | 0:fd24f7ca9688 | 215 | uint32_t base; |
garyservin | 0:fd24f7ca9688 | 216 | } u_range_min; |
garyservin | 0:fd24f7ca9688 | 217 | u_range_min.base = 0; |
garyservin | 0:fd24f7ca9688 | 218 | u_range_min.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); |
garyservin | 0:fd24f7ca9688 | 219 | u_range_min.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
garyservin | 0:fd24f7ca9688 | 220 | u_range_min.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
garyservin | 0:fd24f7ca9688 | 221 | u_range_min.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
garyservin | 0:fd24f7ca9688 | 222 | this->range_min = u_range_min.real; |
garyservin | 0:fd24f7ca9688 | 223 | offset += sizeof(this->range_min); |
garyservin | 0:fd24f7ca9688 | 224 | union { |
garyservin | 0:fd24f7ca9688 | 225 | float real; |
garyservin | 0:fd24f7ca9688 | 226 | uint32_t base; |
garyservin | 0:fd24f7ca9688 | 227 | } u_range_max; |
garyservin | 0:fd24f7ca9688 | 228 | u_range_max.base = 0; |
garyservin | 0:fd24f7ca9688 | 229 | u_range_max.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); |
garyservin | 0:fd24f7ca9688 | 230 | u_range_max.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
garyservin | 0:fd24f7ca9688 | 231 | u_range_max.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
garyservin | 0:fd24f7ca9688 | 232 | u_range_max.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
garyservin | 0:fd24f7ca9688 | 233 | this->range_max = u_range_max.real; |
garyservin | 0:fd24f7ca9688 | 234 | offset += sizeof(this->range_max); |
garyservin | 0:fd24f7ca9688 | 235 | uint8_t ranges_lengthT = *(inbuffer + offset++); |
garyservin | 0:fd24f7ca9688 | 236 | if(ranges_lengthT > ranges_length) |
garyservin | 0:fd24f7ca9688 | 237 | this->ranges = (float*)realloc(this->ranges, ranges_lengthT * sizeof(float)); |
garyservin | 0:fd24f7ca9688 | 238 | offset += 3; |
garyservin | 0:fd24f7ca9688 | 239 | ranges_length = ranges_lengthT; |
garyservin | 0:fd24f7ca9688 | 240 | for( uint8_t i = 0; i < ranges_length; i++){ |
garyservin | 0:fd24f7ca9688 | 241 | union { |
garyservin | 0:fd24f7ca9688 | 242 | float real; |
garyservin | 0:fd24f7ca9688 | 243 | uint32_t base; |
garyservin | 0:fd24f7ca9688 | 244 | } u_st_ranges; |
garyservin | 0:fd24f7ca9688 | 245 | u_st_ranges.base = 0; |
garyservin | 0:fd24f7ca9688 | 246 | u_st_ranges.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); |
garyservin | 0:fd24f7ca9688 | 247 | u_st_ranges.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
garyservin | 0:fd24f7ca9688 | 248 | u_st_ranges.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
garyservin | 0:fd24f7ca9688 | 249 | u_st_ranges.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
garyservin | 0:fd24f7ca9688 | 250 | this->st_ranges = u_st_ranges.real; |
garyservin | 0:fd24f7ca9688 | 251 | offset += sizeof(this->st_ranges); |
garyservin | 0:fd24f7ca9688 | 252 | memcpy( &(this->ranges[i]), &(this->st_ranges), sizeof(float)); |
garyservin | 0:fd24f7ca9688 | 253 | } |
garyservin | 0:fd24f7ca9688 | 254 | uint8_t intensities_lengthT = *(inbuffer + offset++); |
garyservin | 0:fd24f7ca9688 | 255 | if(intensities_lengthT > intensities_length) |
garyservin | 0:fd24f7ca9688 | 256 | this->intensities = (float*)realloc(this->intensities, intensities_lengthT * sizeof(float)); |
garyservin | 0:fd24f7ca9688 | 257 | offset += 3; |
garyservin | 0:fd24f7ca9688 | 258 | intensities_length = intensities_lengthT; |
garyservin | 0:fd24f7ca9688 | 259 | for( uint8_t i = 0; i < intensities_length; i++){ |
garyservin | 0:fd24f7ca9688 | 260 | union { |
garyservin | 0:fd24f7ca9688 | 261 | float real; |
garyservin | 0:fd24f7ca9688 | 262 | uint32_t base; |
garyservin | 0:fd24f7ca9688 | 263 | } u_st_intensities; |
garyservin | 0:fd24f7ca9688 | 264 | u_st_intensities.base = 0; |
garyservin | 0:fd24f7ca9688 | 265 | u_st_intensities.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); |
garyservin | 0:fd24f7ca9688 | 266 | u_st_intensities.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
garyservin | 0:fd24f7ca9688 | 267 | u_st_intensities.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
garyservin | 0:fd24f7ca9688 | 268 | u_st_intensities.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
garyservin | 0:fd24f7ca9688 | 269 | this->st_intensities = u_st_intensities.real; |
garyservin | 0:fd24f7ca9688 | 270 | offset += sizeof(this->st_intensities); |
garyservin | 0:fd24f7ca9688 | 271 | memcpy( &(this->intensities[i]), &(this->st_intensities), sizeof(float)); |
garyservin | 0:fd24f7ca9688 | 272 | } |
garyservin | 0:fd24f7ca9688 | 273 | return offset; |
garyservin | 0:fd24f7ca9688 | 274 | } |
garyservin | 0:fd24f7ca9688 | 275 | |
garyservin | 0:fd24f7ca9688 | 276 | const char * getType(){ return "sensor_msgs/LaserScan"; }; |
garyservin | 0:fd24f7ca9688 | 277 | const char * getMD5(){ return "90c7ef2dc6895d81024acba2ac42f369"; }; |
garyservin | 0:fd24f7ca9688 | 278 | |
garyservin | 0:fd24f7ca9688 | 279 | }; |
garyservin | 0:fd24f7ca9688 | 280 | |
garyservin | 0:fd24f7ca9688 | 281 | } |
garyservin | 0:fd24f7ca9688 | 282 | #endif |