hairo

Dependencies:   mbed BufferedSerial

Committer:
tknara
Date:
Tue Dec 04 00:14:32 2018 +0000
Revision:
4:bcdd99711326
Parent:
0:9e9b7db60fd5
test

Who changed what in which revision?

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