Important changes to repositories hosted on mbed.com
Mbed hosted mercurial repositories are deprecated and are due to be permanently deleted in July 2026.
To keep a copy of this software download the repository Zip archive or clone locally using Mercurial.
It is also possible to export all your personal repositories from the account settings page.
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 typedef std_msgs::Header _header_type; 00018 _header_type header; 00019 typedef float _angle_min_type; 00020 _angle_min_type angle_min; 00021 typedef float _angle_max_type; 00022 _angle_max_type angle_max; 00023 typedef float _angle_increment_type; 00024 _angle_increment_type angle_increment; 00025 typedef float _time_increment_type; 00026 _time_increment_type time_increment; 00027 typedef float _scan_time_type; 00028 _scan_time_type scan_time; 00029 typedef float _range_min_type; 00030 _range_min_type range_min; 00031 typedef float _range_max_type; 00032 _range_max_type range_max; 00033 uint32_t ranges_length; 00034 typedef sensor_msgs::LaserEcho _ranges_type; 00035 _ranges_type st_ranges; 00036 _ranges_type * ranges; 00037 uint32_t intensities_length; 00038 typedef sensor_msgs::LaserEcho _intensities_type; 00039 _intensities_type st_intensities; 00040 _intensities_type * intensities; 00041 00042 MultiEchoLaserScan(): 00043 header(), 00044 angle_min(0), 00045 angle_max(0), 00046 angle_increment(0), 00047 time_increment(0), 00048 scan_time(0), 00049 range_min(0), 00050 range_max(0), 00051 ranges_length(0), ranges(NULL), 00052 intensities_length(0), intensities(NULL) 00053 { 00054 } 00055 00056 virtual int serialize(unsigned char *outbuffer) const 00057 { 00058 int offset = 0; 00059 offset += this->header.serialize(outbuffer + offset); 00060 union { 00061 float real; 00062 uint32_t base; 00063 } u_angle_min; 00064 u_angle_min.real = this->angle_min; 00065 *(outbuffer + offset + 0) = (u_angle_min.base >> (8 * 0)) & 0xFF; 00066 *(outbuffer + offset + 1) = (u_angle_min.base >> (8 * 1)) & 0xFF; 00067 *(outbuffer + offset + 2) = (u_angle_min.base >> (8 * 2)) & 0xFF; 00068 *(outbuffer + offset + 3) = (u_angle_min.base >> (8 * 3)) & 0xFF; 00069 offset += sizeof(this->angle_min); 00070 union { 00071 float real; 00072 uint32_t base; 00073 } u_angle_max; 00074 u_angle_max.real = this->angle_max; 00075 *(outbuffer + offset + 0) = (u_angle_max.base >> (8 * 0)) & 0xFF; 00076 *(outbuffer + offset + 1) = (u_angle_max.base >> (8 * 1)) & 0xFF; 00077 *(outbuffer + offset + 2) = (u_angle_max.base >> (8 * 2)) & 0xFF; 00078 *(outbuffer + offset + 3) = (u_angle_max.base >> (8 * 3)) & 0xFF; 00079 offset += sizeof(this->angle_max); 00080 union { 00081 float real; 00082 uint32_t base; 00083 } u_angle_increment; 00084 u_angle_increment.real = this->angle_increment; 00085 *(outbuffer + offset + 0) = (u_angle_increment.base >> (8 * 0)) & 0xFF; 00086 *(outbuffer + offset + 1) = (u_angle_increment.base >> (8 * 1)) & 0xFF; 00087 *(outbuffer + offset + 2) = (u_angle_increment.base >> (8 * 2)) & 0xFF; 00088 *(outbuffer + offset + 3) = (u_angle_increment.base >> (8 * 3)) & 0xFF; 00089 offset += sizeof(this->angle_increment); 00090 union { 00091 float real; 00092 uint32_t base; 00093 } u_time_increment; 00094 u_time_increment.real = this->time_increment; 00095 *(outbuffer + offset + 0) = (u_time_increment.base >> (8 * 0)) & 0xFF; 00096 *(outbuffer + offset + 1) = (u_time_increment.base >> (8 * 1)) & 0xFF; 00097 *(outbuffer + offset + 2) = (u_time_increment.base >> (8 * 2)) & 0xFF; 00098 *(outbuffer + offset + 3) = (u_time_increment.base >> (8 * 3)) & 0xFF; 00099 offset += sizeof(this->time_increment); 00100 union { 00101 float real; 00102 uint32_t base; 00103 } u_scan_time; 00104 u_scan_time.real = this->scan_time; 00105 *(outbuffer + offset + 0) = (u_scan_time.base >> (8 * 0)) & 0xFF; 00106 *(outbuffer + offset + 1) = (u_scan_time.base >> (8 * 1)) & 0xFF; 00107 *(outbuffer + offset + 2) = (u_scan_time.base >> (8 * 2)) & 0xFF; 00108 *(outbuffer + offset + 3) = (u_scan_time.base >> (8 * 3)) & 0xFF; 00109 offset += sizeof(this->scan_time); 00110 union { 00111 float real; 00112 uint32_t base; 00113 } u_range_min; 00114 u_range_min.real = this->range_min; 00115 *(outbuffer + offset + 0) = (u_range_min.base >> (8 * 0)) & 0xFF; 00116 *(outbuffer + offset + 1) = (u_range_min.base >> (8 * 1)) & 0xFF; 00117 *(outbuffer + offset + 2) = (u_range_min.base >> (8 * 2)) & 0xFF; 00118 *(outbuffer + offset + 3) = (u_range_min.base >> (8 * 3)) & 0xFF; 00119 offset += sizeof(this->range_min); 00120 union { 00121 float real; 00122 uint32_t base; 00123 } u_range_max; 00124 u_range_max.real = this->range_max; 00125 *(outbuffer + offset + 0) = (u_range_max.base >> (8 * 0)) & 0xFF; 00126 *(outbuffer + offset + 1) = (u_range_max.base >> (8 * 1)) & 0xFF; 00127 *(outbuffer + offset + 2) = (u_range_max.base >> (8 * 2)) & 0xFF; 00128 *(outbuffer + offset + 3) = (u_range_max.base >> (8 * 3)) & 0xFF; 00129 offset += sizeof(this->range_max); 00130 *(outbuffer + offset + 0) = (this->ranges_length >> (8 * 0)) & 0xFF; 00131 *(outbuffer + offset + 1) = (this->ranges_length >> (8 * 1)) & 0xFF; 00132 *(outbuffer + offset + 2) = (this->ranges_length >> (8 * 2)) & 0xFF; 00133 *(outbuffer + offset + 3) = (this->ranges_length >> (8 * 3)) & 0xFF; 00134 offset += sizeof(this->ranges_length); 00135 for( uint32_t i = 0; i < ranges_length; i++){ 00136 offset += this->ranges[i].serialize(outbuffer + offset); 00137 } 00138 *(outbuffer + offset + 0) = (this->intensities_length >> (8 * 0)) & 0xFF; 00139 *(outbuffer + offset + 1) = (this->intensities_length >> (8 * 1)) & 0xFF; 00140 *(outbuffer + offset + 2) = (this->intensities_length >> (8 * 2)) & 0xFF; 00141 *(outbuffer + offset + 3) = (this->intensities_length >> (8 * 3)) & 0xFF; 00142 offset += sizeof(this->intensities_length); 00143 for( uint32_t i = 0; i < intensities_length; i++){ 00144 offset += this->intensities[i].serialize(outbuffer + offset); 00145 } 00146 return offset; 00147 } 00148 00149 virtual int deserialize(unsigned char *inbuffer) 00150 { 00151 int offset = 0; 00152 offset += this->header.deserialize(inbuffer + offset); 00153 union { 00154 float real; 00155 uint32_t base; 00156 } u_angle_min; 00157 u_angle_min.base = 0; 00158 u_angle_min.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); 00159 u_angle_min.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00160 u_angle_min.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00161 u_angle_min.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00162 this->angle_min = u_angle_min.real; 00163 offset += sizeof(this->angle_min); 00164 union { 00165 float real; 00166 uint32_t base; 00167 } u_angle_max; 00168 u_angle_max.base = 0; 00169 u_angle_max.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); 00170 u_angle_max.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00171 u_angle_max.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00172 u_angle_max.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00173 this->angle_max = u_angle_max.real; 00174 offset += sizeof(this->angle_max); 00175 union { 00176 float real; 00177 uint32_t base; 00178 } u_angle_increment; 00179 u_angle_increment.base = 0; 00180 u_angle_increment.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); 00181 u_angle_increment.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00182 u_angle_increment.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00183 u_angle_increment.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00184 this->angle_increment = u_angle_increment.real; 00185 offset += sizeof(this->angle_increment); 00186 union { 00187 float real; 00188 uint32_t base; 00189 } u_time_increment; 00190 u_time_increment.base = 0; 00191 u_time_increment.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); 00192 u_time_increment.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00193 u_time_increment.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00194 u_time_increment.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00195 this->time_increment = u_time_increment.real; 00196 offset += sizeof(this->time_increment); 00197 union { 00198 float real; 00199 uint32_t base; 00200 } u_scan_time; 00201 u_scan_time.base = 0; 00202 u_scan_time.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); 00203 u_scan_time.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00204 u_scan_time.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00205 u_scan_time.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00206 this->scan_time = u_scan_time.real; 00207 offset += sizeof(this->scan_time); 00208 union { 00209 float real; 00210 uint32_t base; 00211 } u_range_min; 00212 u_range_min.base = 0; 00213 u_range_min.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); 00214 u_range_min.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00215 u_range_min.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00216 u_range_min.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00217 this->range_min = u_range_min.real; 00218 offset += sizeof(this->range_min); 00219 union { 00220 float real; 00221 uint32_t base; 00222 } u_range_max; 00223 u_range_max.base = 0; 00224 u_range_max.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); 00225 u_range_max.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00226 u_range_max.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00227 u_range_max.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00228 this->range_max = u_range_max.real; 00229 offset += sizeof(this->range_max); 00230 uint32_t ranges_lengthT = ((uint32_t) (*(inbuffer + offset))); 00231 ranges_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00232 ranges_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00233 ranges_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00234 offset += sizeof(this->ranges_length); 00235 if(ranges_lengthT > ranges_length) 00236 this->ranges = (sensor_msgs::LaserEcho*)realloc(this->ranges, ranges_lengthT * sizeof(sensor_msgs::LaserEcho)); 00237 ranges_length = ranges_lengthT; 00238 for( uint32_t i = 0; i < ranges_length; i++){ 00239 offset += this->st_ranges.deserialize(inbuffer + offset); 00240 memcpy( &(this->ranges[i]), &(this->st_ranges), sizeof(sensor_msgs::LaserEcho)); 00241 } 00242 uint32_t intensities_lengthT = ((uint32_t) (*(inbuffer + offset))); 00243 intensities_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00244 intensities_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00245 intensities_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00246 offset += sizeof(this->intensities_length); 00247 if(intensities_lengthT > intensities_length) 00248 this->intensities = (sensor_msgs::LaserEcho*)realloc(this->intensities, intensities_lengthT * sizeof(sensor_msgs::LaserEcho)); 00249 intensities_length = intensities_lengthT; 00250 for( uint32_t i = 0; i < intensities_length; i++){ 00251 offset += this->st_intensities.deserialize(inbuffer + offset); 00252 memcpy( &(this->intensities[i]), &(this->st_intensities), sizeof(sensor_msgs::LaserEcho)); 00253 } 00254 return offset; 00255 } 00256 00257 const char * getType(){ return "sensor_msgs/MultiEchoLaserScan"; }; 00258 const char * getMD5(){ return "6fefb0c6da89d7c8abe4b339f5c2f8fb"; }; 00259 00260 }; 00261 00262 } 00263 #endif
Generated on Wed Jul 13 2022 23:30:18 by
