MultiEchoLaserScan.h
Go to the documentation of this file.
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     virtual int serialize(unsigned char *outbuffer) const
00033     {
00034       int offset = 0;
00035       offset += this->header.serialize(outbuffer + offset);
00036       union {
00037         float real;
00038         uint32_t base;
00039       } u_angle_min;
00040       u_angle_min.real = this->angle_min;
00041       *(outbuffer + offset + 0) = (u_angle_min.base >> (8 * 0)) & 0xFF;
00042       *(outbuffer + offset + 1) = (u_angle_min.base >> (8 * 1)) & 0xFF;
00043       *(outbuffer + offset + 2) = (u_angle_min.base >> (8 * 2)) & 0xFF;
00044       *(outbuffer + offset + 3) = (u_angle_min.base >> (8 * 3)) & 0xFF;
00045       offset += sizeof(this->angle_min);
00046       union {
00047         float real;
00048         uint32_t base;
00049       } u_angle_max;
00050       u_angle_max.real = this->angle_max;
00051       *(outbuffer + offset + 0) = (u_angle_max.base >> (8 * 0)) & 0xFF;
00052       *(outbuffer + offset + 1) = (u_angle_max.base >> (8 * 1)) & 0xFF;
00053       *(outbuffer + offset + 2) = (u_angle_max.base >> (8 * 2)) & 0xFF;
00054       *(outbuffer + offset + 3) = (u_angle_max.base >> (8 * 3)) & 0xFF;
00055       offset += sizeof(this->angle_max);
00056       union {
00057         float real;
00058         uint32_t base;
00059       } u_angle_increment;
00060       u_angle_increment.real = this->angle_increment;
00061       *(outbuffer + offset + 0) = (u_angle_increment.base >> (8 * 0)) & 0xFF;
00062       *(outbuffer + offset + 1) = (u_angle_increment.base >> (8 * 1)) & 0xFF;
00063       *(outbuffer + offset + 2) = (u_angle_increment.base >> (8 * 2)) & 0xFF;
00064       *(outbuffer + offset + 3) = (u_angle_increment.base >> (8 * 3)) & 0xFF;
00065       offset += sizeof(this->angle_increment);
00066       union {
00067         float real;
00068         uint32_t base;
00069       } u_time_increment;
00070       u_time_increment.real = this->time_increment;
00071       *(outbuffer + offset + 0) = (u_time_increment.base >> (8 * 0)) & 0xFF;
00072       *(outbuffer + offset + 1) = (u_time_increment.base >> (8 * 1)) & 0xFF;
00073       *(outbuffer + offset + 2) = (u_time_increment.base >> (8 * 2)) & 0xFF;
00074       *(outbuffer + offset + 3) = (u_time_increment.base >> (8 * 3)) & 0xFF;
00075       offset += sizeof(this->time_increment);
00076       union {
00077         float real;
00078         uint32_t base;
00079       } u_scan_time;
00080       u_scan_time.real = this->scan_time;
00081       *(outbuffer + offset + 0) = (u_scan_time.base >> (8 * 0)) & 0xFF;
00082       *(outbuffer + offset + 1) = (u_scan_time.base >> (8 * 1)) & 0xFF;
00083       *(outbuffer + offset + 2) = (u_scan_time.base >> (8 * 2)) & 0xFF;
00084       *(outbuffer + offset + 3) = (u_scan_time.base >> (8 * 3)) & 0xFF;
00085       offset += sizeof(this->scan_time);
00086       union {
00087         float real;
00088         uint32_t base;
00089       } u_range_min;
00090       u_range_min.real = this->range_min;
00091       *(outbuffer + offset + 0) = (u_range_min.base >> (8 * 0)) & 0xFF;
00092       *(outbuffer + offset + 1) = (u_range_min.base >> (8 * 1)) & 0xFF;
00093       *(outbuffer + offset + 2) = (u_range_min.base >> (8 * 2)) & 0xFF;
00094       *(outbuffer + offset + 3) = (u_range_min.base >> (8 * 3)) & 0xFF;
00095       offset += sizeof(this->range_min);
00096       union {
00097         float real;
00098         uint32_t base;
00099       } u_range_max;
00100       u_range_max.real = this->range_max;
00101       *(outbuffer + offset + 0) = (u_range_max.base >> (8 * 0)) & 0xFF;
00102       *(outbuffer + offset + 1) = (u_range_max.base >> (8 * 1)) & 0xFF;
00103       *(outbuffer + offset + 2) = (u_range_max.base >> (8 * 2)) & 0xFF;
00104       *(outbuffer + offset + 3) = (u_range_max.base >> (8 * 3)) & 0xFF;
00105       offset += sizeof(this->range_max);
00106       *(outbuffer + offset++) = ranges_length;
00107       *(outbuffer + offset++) = 0;
00108       *(outbuffer + offset++) = 0;
00109       *(outbuffer + offset++) = 0;
00110       for( uint8_t i = 0; i < ranges_length; i++){
00111       offset += this->ranges[i].serialize(outbuffer + offset);
00112       }
00113       *(outbuffer + offset++) = intensities_length;
00114       *(outbuffer + offset++) = 0;
00115       *(outbuffer + offset++) = 0;
00116       *(outbuffer + offset++) = 0;
00117       for( uint8_t i = 0; i < intensities_length; i++){
00118       offset += this->intensities[i].serialize(outbuffer + offset);
00119       }
00120       return offset;
00121     }
00122 
00123     virtual int deserialize(unsigned char *inbuffer)
00124     {
00125       int offset = 0;
00126       offset += this->header.deserialize(inbuffer + offset);
00127       union {
00128         float real;
00129         uint32_t base;
00130       } u_angle_min;
00131       u_angle_min.base = 0;
00132       u_angle_min.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
00133       u_angle_min.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00134       u_angle_min.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00135       u_angle_min.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00136       this->angle_min = u_angle_min.real;
00137       offset += sizeof(this->angle_min);
00138       union {
00139         float real;
00140         uint32_t base;
00141       } u_angle_max;
00142       u_angle_max.base = 0;
00143       u_angle_max.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
00144       u_angle_max.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00145       u_angle_max.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00146       u_angle_max.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00147       this->angle_max = u_angle_max.real;
00148       offset += sizeof(this->angle_max);
00149       union {
00150         float real;
00151         uint32_t base;
00152       } u_angle_increment;
00153       u_angle_increment.base = 0;
00154       u_angle_increment.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
00155       u_angle_increment.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00156       u_angle_increment.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00157       u_angle_increment.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00158       this->angle_increment = u_angle_increment.real;
00159       offset += sizeof(this->angle_increment);
00160       union {
00161         float real;
00162         uint32_t base;
00163       } u_time_increment;
00164       u_time_increment.base = 0;
00165       u_time_increment.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
00166       u_time_increment.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00167       u_time_increment.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00168       u_time_increment.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00169       this->time_increment = u_time_increment.real;
00170       offset += sizeof(this->time_increment);
00171       union {
00172         float real;
00173         uint32_t base;
00174       } u_scan_time;
00175       u_scan_time.base = 0;
00176       u_scan_time.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
00177       u_scan_time.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00178       u_scan_time.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00179       u_scan_time.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00180       this->scan_time = u_scan_time.real;
00181       offset += sizeof(this->scan_time);
00182       union {
00183         float real;
00184         uint32_t base;
00185       } u_range_min;
00186       u_range_min.base = 0;
00187       u_range_min.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
00188       u_range_min.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00189       u_range_min.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00190       u_range_min.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00191       this->range_min = u_range_min.real;
00192       offset += sizeof(this->range_min);
00193       union {
00194         float real;
00195         uint32_t base;
00196       } u_range_max;
00197       u_range_max.base = 0;
00198       u_range_max.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
00199       u_range_max.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00200       u_range_max.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00201       u_range_max.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00202       this->range_max = u_range_max.real;
00203       offset += sizeof(this->range_max);
00204       uint8_t ranges_lengthT = *(inbuffer + offset++);
00205       if(ranges_lengthT > ranges_length)
00206         this->ranges = (sensor_msgs::LaserEcho*)realloc(this->ranges, ranges_lengthT * sizeof(sensor_msgs::LaserEcho));
00207       offset += 3;
00208       ranges_length = ranges_lengthT;
00209       for( uint8_t i = 0; i < ranges_length; i++){
00210       offset += this->st_ranges.deserialize(inbuffer + offset);
00211         memcpy( &(this->ranges[i]), &(this->st_ranges), sizeof(sensor_msgs::LaserEcho));
00212       }
00213       uint8_t intensities_lengthT = *(inbuffer + offset++);
00214       if(intensities_lengthT > intensities_length)
00215         this->intensities = (sensor_msgs::LaserEcho*)realloc(this->intensities, intensities_lengthT * sizeof(sensor_msgs::LaserEcho));
00216       offset += 3;
00217       intensities_length = intensities_lengthT;
00218       for( uint8_t i = 0; i < intensities_length; i++){
00219       offset += this->st_intensities.deserialize(inbuffer + offset);
00220         memcpy( &(this->intensities[i]), &(this->st_intensities), sizeof(sensor_msgs::LaserEcho));
00221       }
00222      return offset;
00223     }
00224 
00225     const char * getType(){ return "sensor_msgs/MultiEchoLaserScan"; };
00226     const char * getMD5(){ return "6fefb0c6da89d7c8abe4b339f5c2f8fb"; };
00227 
00228   };
00229 
00230 }
00231 #endif


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