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


lizi_arduino
Author(s): RoboTiCan
autogenerated on Wed Aug 26 2015 12:24:22