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