ROS Serial library for Mbed platforms for ROS Indigo Igloo. Check http://wiki.ros.org/rosserial_mbed/ for more information

Dependencies:   BufferedSerial

Dependents:   rosserial_mbed_hello_world_publisher rtos_base_control rosserial_mbed_F64MA ROS-RTOS ... more

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers MultiEchoLaserScan.h Source File

MultiEchoLaserScan.h

00001 #ifndef _ROS_sensor_msgs_MultiEchoLaserScan_h
00002 #define _ROS_sensor_msgs_MultiEchoLaserScan_h
00003 
00004 #include <stdint.h>
00005 #include <string.h>
00006 #include <stdlib.h>
00007 #include "ros/msg.h"
00008 #include "std_msgs/Header.h"
00009 #include "sensor_msgs/LaserEcho.h"
00010 
00011 namespace sensor_msgs
00012 {
00013 
00014   class MultiEchoLaserScan : public ros::Msg
00015   {
00016     public:
00017       std_msgs::Header header;
00018       float angle_min;
00019       float angle_max;
00020       float angle_increment;
00021       float time_increment;
00022       float scan_time;
00023       float range_min;
00024       float range_max;
00025       uint8_t ranges_length;
00026       sensor_msgs::LaserEcho st_ranges;
00027       sensor_msgs::LaserEcho * ranges;
00028       uint8_t intensities_length;
00029       sensor_msgs::LaserEcho st_intensities;
00030       sensor_msgs::LaserEcho * intensities;
00031 
00032     MultiEchoLaserScan():
00033       header(),
00034       angle_min(0),
00035       angle_max(0),
00036       angle_increment(0),
00037       time_increment(0),
00038       scan_time(0),
00039       range_min(0),
00040       range_max(0),
00041       ranges_length(0), ranges(NULL),
00042       intensities_length(0), intensities(NULL)
00043     {
00044     }
00045 
00046     virtual int serialize(unsigned char *outbuffer) const
00047     {
00048       int offset = 0;
00049       offset += this->header.serialize(outbuffer + offset);
00050       union {
00051         float real;
00052         uint32_t base;
00053       } u_angle_min;
00054       u_angle_min.real = this->angle_min;
00055       *(outbuffer + offset + 0) = (u_angle_min.base >> (8 * 0)) & 0xFF;
00056       *(outbuffer + offset + 1) = (u_angle_min.base >> (8 * 1)) & 0xFF;
00057       *(outbuffer + offset + 2) = (u_angle_min.base >> (8 * 2)) & 0xFF;
00058       *(outbuffer + offset + 3) = (u_angle_min.base >> (8 * 3)) & 0xFF;
00059       offset += sizeof(this->angle_min);
00060       union {
00061         float real;
00062         uint32_t base;
00063       } u_angle_max;
00064       u_angle_max.real = this->angle_max;
00065       *(outbuffer + offset + 0) = (u_angle_max.base >> (8 * 0)) & 0xFF;
00066       *(outbuffer + offset + 1) = (u_angle_max.base >> (8 * 1)) & 0xFF;
00067       *(outbuffer + offset + 2) = (u_angle_max.base >> (8 * 2)) & 0xFF;
00068       *(outbuffer + offset + 3) = (u_angle_max.base >> (8 * 3)) & 0xFF;
00069       offset += sizeof(this->angle_max);
00070       union {
00071         float real;
00072         uint32_t base;
00073       } u_angle_increment;
00074       u_angle_increment.real = this->angle_increment;
00075       *(outbuffer + offset + 0) = (u_angle_increment.base >> (8 * 0)) & 0xFF;
00076       *(outbuffer + offset + 1) = (u_angle_increment.base >> (8 * 1)) & 0xFF;
00077       *(outbuffer + offset + 2) = (u_angle_increment.base >> (8 * 2)) & 0xFF;
00078       *(outbuffer + offset + 3) = (u_angle_increment.base >> (8 * 3)) & 0xFF;
00079       offset += sizeof(this->angle_increment);
00080       union {
00081         float real;
00082         uint32_t base;
00083       } u_time_increment;
00084       u_time_increment.real = this->time_increment;
00085       *(outbuffer + offset + 0) = (u_time_increment.base >> (8 * 0)) & 0xFF;
00086       *(outbuffer + offset + 1) = (u_time_increment.base >> (8 * 1)) & 0xFF;
00087       *(outbuffer + offset + 2) = (u_time_increment.base >> (8 * 2)) & 0xFF;
00088       *(outbuffer + offset + 3) = (u_time_increment.base >> (8 * 3)) & 0xFF;
00089       offset += sizeof(this->time_increment);
00090       union {
00091         float real;
00092         uint32_t base;
00093       } u_scan_time;
00094       u_scan_time.real = this->scan_time;
00095       *(outbuffer + offset + 0) = (u_scan_time.base >> (8 * 0)) & 0xFF;
00096       *(outbuffer + offset + 1) = (u_scan_time.base >> (8 * 1)) & 0xFF;
00097       *(outbuffer + offset + 2) = (u_scan_time.base >> (8 * 2)) & 0xFF;
00098       *(outbuffer + offset + 3) = (u_scan_time.base >> (8 * 3)) & 0xFF;
00099       offset += sizeof(this->scan_time);
00100       union {
00101         float real;
00102         uint32_t base;
00103       } u_range_min;
00104       u_range_min.real = this->range_min;
00105       *(outbuffer + offset + 0) = (u_range_min.base >> (8 * 0)) & 0xFF;
00106       *(outbuffer + offset + 1) = (u_range_min.base >> (8 * 1)) & 0xFF;
00107       *(outbuffer + offset + 2) = (u_range_min.base >> (8 * 2)) & 0xFF;
00108       *(outbuffer + offset + 3) = (u_range_min.base >> (8 * 3)) & 0xFF;
00109       offset += sizeof(this->range_min);
00110       union {
00111         float real;
00112         uint32_t base;
00113       } u_range_max;
00114       u_range_max.real = this->range_max;
00115       *(outbuffer + offset + 0) = (u_range_max.base >> (8 * 0)) & 0xFF;
00116       *(outbuffer + offset + 1) = (u_range_max.base >> (8 * 1)) & 0xFF;
00117       *(outbuffer + offset + 2) = (u_range_max.base >> (8 * 2)) & 0xFF;
00118       *(outbuffer + offset + 3) = (u_range_max.base >> (8 * 3)) & 0xFF;
00119       offset += sizeof(this->range_max);
00120       *(outbuffer + offset++) = ranges_length;
00121       *(outbuffer + offset++) = 0;
00122       *(outbuffer + offset++) = 0;
00123       *(outbuffer + offset++) = 0;
00124       for( uint8_t i = 0; i < ranges_length; i++){
00125       offset += this->ranges[i].serialize(outbuffer + offset);
00126       }
00127       *(outbuffer + offset++) = intensities_length;
00128       *(outbuffer + offset++) = 0;
00129       *(outbuffer + offset++) = 0;
00130       *(outbuffer + offset++) = 0;
00131       for( uint8_t i = 0; i < intensities_length; i++){
00132       offset += this->intensities[i].serialize(outbuffer + offset);
00133       }
00134       return offset;
00135     }
00136 
00137     virtual int deserialize(unsigned char *inbuffer)
00138     {
00139       int offset = 0;
00140       offset += this->header.deserialize(inbuffer + offset);
00141       union {
00142         float real;
00143         uint32_t base;
00144       } u_angle_min;
00145       u_angle_min.base = 0;
00146       u_angle_min.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
00147       u_angle_min.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00148       u_angle_min.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00149       u_angle_min.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00150       this->angle_min = u_angle_min.real;
00151       offset += sizeof(this->angle_min);
00152       union {
00153         float real;
00154         uint32_t base;
00155       } u_angle_max;
00156       u_angle_max.base = 0;
00157       u_angle_max.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
00158       u_angle_max.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00159       u_angle_max.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00160       u_angle_max.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00161       this->angle_max = u_angle_max.real;
00162       offset += sizeof(this->angle_max);
00163       union {
00164         float real;
00165         uint32_t base;
00166       } u_angle_increment;
00167       u_angle_increment.base = 0;
00168       u_angle_increment.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
00169       u_angle_increment.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00170       u_angle_increment.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00171       u_angle_increment.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00172       this->angle_increment = u_angle_increment.real;
00173       offset += sizeof(this->angle_increment);
00174       union {
00175         float real;
00176         uint32_t base;
00177       } u_time_increment;
00178       u_time_increment.base = 0;
00179       u_time_increment.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
00180       u_time_increment.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00181       u_time_increment.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00182       u_time_increment.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00183       this->time_increment = u_time_increment.real;
00184       offset += sizeof(this->time_increment);
00185       union {
00186         float real;
00187         uint32_t base;
00188       } u_scan_time;
00189       u_scan_time.base = 0;
00190       u_scan_time.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
00191       u_scan_time.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00192       u_scan_time.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00193       u_scan_time.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00194       this->scan_time = u_scan_time.real;
00195       offset += sizeof(this->scan_time);
00196       union {
00197         float real;
00198         uint32_t base;
00199       } u_range_min;
00200       u_range_min.base = 0;
00201       u_range_min.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
00202       u_range_min.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00203       u_range_min.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00204       u_range_min.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00205       this->range_min = u_range_min.real;
00206       offset += sizeof(this->range_min);
00207       union {
00208         float real;
00209         uint32_t base;
00210       } u_range_max;
00211       u_range_max.base = 0;
00212       u_range_max.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
00213       u_range_max.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00214       u_range_max.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00215       u_range_max.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00216       this->range_max = u_range_max.real;
00217       offset += sizeof(this->range_max);
00218       uint8_t ranges_lengthT = *(inbuffer + offset++);
00219       if(ranges_lengthT > ranges_length)
00220         this->ranges = (sensor_msgs::LaserEcho*)realloc(this->ranges, ranges_lengthT * sizeof(sensor_msgs::LaserEcho));
00221       offset += 3;
00222       ranges_length = ranges_lengthT;
00223       for( uint8_t i = 0; i < ranges_length; i++){
00224       offset += this->st_ranges.deserialize(inbuffer + offset);
00225         memcpy( &(this->ranges[i]), &(this->st_ranges), sizeof(sensor_msgs::LaserEcho));
00226       }
00227       uint8_t intensities_lengthT = *(inbuffer + offset++);
00228       if(intensities_lengthT > intensities_length)
00229         this->intensities = (sensor_msgs::LaserEcho*)realloc(this->intensities, intensities_lengthT * sizeof(sensor_msgs::LaserEcho));
00230       offset += 3;
00231       intensities_length = intensities_lengthT;
00232       for( uint8_t i = 0; i < intensities_length; i++){
00233       offset += this->st_intensities.deserialize(inbuffer + offset);
00234         memcpy( &(this->intensities[i]), &(this->st_intensities), sizeof(sensor_msgs::LaserEcho));
00235       }
00236      return offset;
00237     }
00238 
00239     const char * getType(){ return "sensor_msgs/MultiEchoLaserScan"; };
00240     const char * getMD5(){ return "6fefb0c6da89d7c8abe4b339f5c2f8fb"; };
00241 
00242   };
00243 
00244 }
00245 #endif