This program is porting rosserial_arduino for mbed http://www.ros.org/wiki/rosserial_arduino This program supported the revision of 169 of rosserial.

Dependencies:  

Dependents:   rosserial_mbed robot_S2

Committer:
nucho
Date:
Wed Feb 29 23:00:21 2012 +0000
Revision:
4:684f39d0c346
Parent:
3:1cf99502f396

        

Who changed what in which revision?

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