modify for Hydro version

Dependencies:   MODSERIAL

Fork of rosserial_mbed_lib by nucho

Committer:
jjzak
Date:
Sat Oct 26 15:39:01 2013 +0000
Revision:
6:3c54bc7badd4
modify for Hydro version;

Who changed what in which revision?

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