ROS Serial library for Mbed platforms for ROS Indigo Igloo. Check http://wiki.ros.org/rosserial_mbed/ for more information
Dependents: rosserial_mbed_hello_world_publisher rtos_base_control rosserial_mbed_F64MA ROS-RTOS ... more
LaserScan.h
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 LaserScan(): 00032 header(), 00033 angle_min(0), 00034 angle_max(0), 00035 angle_increment(0), 00036 time_increment(0), 00037 scan_time(0), 00038 range_min(0), 00039 range_max(0), 00040 ranges_length(0), ranges(NULL), 00041 intensities_length(0), intensities(NULL) 00042 { 00043 } 00044 00045 virtual int serialize(unsigned char *outbuffer) const 00046 { 00047 int offset = 0; 00048 offset += this->header.serialize(outbuffer + offset); 00049 union { 00050 float real; 00051 uint32_t base; 00052 } u_angle_min; 00053 u_angle_min.real = this->angle_min; 00054 *(outbuffer + offset + 0) = (u_angle_min.base >> (8 * 0)) & 0xFF; 00055 *(outbuffer + offset + 1) = (u_angle_min.base >> (8 * 1)) & 0xFF; 00056 *(outbuffer + offset + 2) = (u_angle_min.base >> (8 * 2)) & 0xFF; 00057 *(outbuffer + offset + 3) = (u_angle_min.base >> (8 * 3)) & 0xFF; 00058 offset += sizeof(this->angle_min); 00059 union { 00060 float real; 00061 uint32_t base; 00062 } u_angle_max; 00063 u_angle_max.real = this->angle_max; 00064 *(outbuffer + offset + 0) = (u_angle_max.base >> (8 * 0)) & 0xFF; 00065 *(outbuffer + offset + 1) = (u_angle_max.base >> (8 * 1)) & 0xFF; 00066 *(outbuffer + offset + 2) = (u_angle_max.base >> (8 * 2)) & 0xFF; 00067 *(outbuffer + offset + 3) = (u_angle_max.base >> (8 * 3)) & 0xFF; 00068 offset += sizeof(this->angle_max); 00069 union { 00070 float real; 00071 uint32_t base; 00072 } u_angle_increment; 00073 u_angle_increment.real = this->angle_increment; 00074 *(outbuffer + offset + 0) = (u_angle_increment.base >> (8 * 0)) & 0xFF; 00075 *(outbuffer + offset + 1) = (u_angle_increment.base >> (8 * 1)) & 0xFF; 00076 *(outbuffer + offset + 2) = (u_angle_increment.base >> (8 * 2)) & 0xFF; 00077 *(outbuffer + offset + 3) = (u_angle_increment.base >> (8 * 3)) & 0xFF; 00078 offset += sizeof(this->angle_increment); 00079 union { 00080 float real; 00081 uint32_t base; 00082 } u_time_increment; 00083 u_time_increment.real = this->time_increment; 00084 *(outbuffer + offset + 0) = (u_time_increment.base >> (8 * 0)) & 0xFF; 00085 *(outbuffer + offset + 1) = (u_time_increment.base >> (8 * 1)) & 0xFF; 00086 *(outbuffer + offset + 2) = (u_time_increment.base >> (8 * 2)) & 0xFF; 00087 *(outbuffer + offset + 3) = (u_time_increment.base >> (8 * 3)) & 0xFF; 00088 offset += sizeof(this->time_increment); 00089 union { 00090 float real; 00091 uint32_t base; 00092 } u_scan_time; 00093 u_scan_time.real = this->scan_time; 00094 *(outbuffer + offset + 0) = (u_scan_time.base >> (8 * 0)) & 0xFF; 00095 *(outbuffer + offset + 1) = (u_scan_time.base >> (8 * 1)) & 0xFF; 00096 *(outbuffer + offset + 2) = (u_scan_time.base >> (8 * 2)) & 0xFF; 00097 *(outbuffer + offset + 3) = (u_scan_time.base >> (8 * 3)) & 0xFF; 00098 offset += sizeof(this->scan_time); 00099 union { 00100 float real; 00101 uint32_t base; 00102 } u_range_min; 00103 u_range_min.real = this->range_min; 00104 *(outbuffer + offset + 0) = (u_range_min.base >> (8 * 0)) & 0xFF; 00105 *(outbuffer + offset + 1) = (u_range_min.base >> (8 * 1)) & 0xFF; 00106 *(outbuffer + offset + 2) = (u_range_min.base >> (8 * 2)) & 0xFF; 00107 *(outbuffer + offset + 3) = (u_range_min.base >> (8 * 3)) & 0xFF; 00108 offset += sizeof(this->range_min); 00109 union { 00110 float real; 00111 uint32_t base; 00112 } u_range_max; 00113 u_range_max.real = this->range_max; 00114 *(outbuffer + offset + 0) = (u_range_max.base >> (8 * 0)) & 0xFF; 00115 *(outbuffer + offset + 1) = (u_range_max.base >> (8 * 1)) & 0xFF; 00116 *(outbuffer + offset + 2) = (u_range_max.base >> (8 * 2)) & 0xFF; 00117 *(outbuffer + offset + 3) = (u_range_max.base >> (8 * 3)) & 0xFF; 00118 offset += sizeof(this->range_max); 00119 *(outbuffer + offset++) = ranges_length; 00120 *(outbuffer + offset++) = 0; 00121 *(outbuffer + offset++) = 0; 00122 *(outbuffer + offset++) = 0; 00123 for( uint8_t i = 0; i < ranges_length; i++){ 00124 union { 00125 float real; 00126 uint32_t base; 00127 } u_rangesi; 00128 u_rangesi.real = this->ranges[i]; 00129 *(outbuffer + offset + 0) = (u_rangesi.base >> (8 * 0)) & 0xFF; 00130 *(outbuffer + offset + 1) = (u_rangesi.base >> (8 * 1)) & 0xFF; 00131 *(outbuffer + offset + 2) = (u_rangesi.base >> (8 * 2)) & 0xFF; 00132 *(outbuffer + offset + 3) = (u_rangesi.base >> (8 * 3)) & 0xFF; 00133 offset += sizeof(this->ranges[i]); 00134 } 00135 *(outbuffer + offset++) = intensities_length; 00136 *(outbuffer + offset++) = 0; 00137 *(outbuffer + offset++) = 0; 00138 *(outbuffer + offset++) = 0; 00139 for( uint8_t i = 0; i < intensities_length; i++){ 00140 union { 00141 float real; 00142 uint32_t base; 00143 } u_intensitiesi; 00144 u_intensitiesi.real = this->intensities[i]; 00145 *(outbuffer + offset + 0) = (u_intensitiesi.base >> (8 * 0)) & 0xFF; 00146 *(outbuffer + offset + 1) = (u_intensitiesi.base >> (8 * 1)) & 0xFF; 00147 *(outbuffer + offset + 2) = (u_intensitiesi.base >> (8 * 2)) & 0xFF; 00148 *(outbuffer + offset + 3) = (u_intensitiesi.base >> (8 * 3)) & 0xFF; 00149 offset += sizeof(this->intensities[i]); 00150 } 00151 return offset; 00152 } 00153 00154 virtual int deserialize(unsigned char *inbuffer) 00155 { 00156 int offset = 0; 00157 offset += this->header.deserialize(inbuffer + offset); 00158 union { 00159 float real; 00160 uint32_t base; 00161 } u_angle_min; 00162 u_angle_min.base = 0; 00163 u_angle_min.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); 00164 u_angle_min.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00165 u_angle_min.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00166 u_angle_min.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00167 this->angle_min = u_angle_min.real; 00168 offset += sizeof(this->angle_min); 00169 union { 00170 float real; 00171 uint32_t base; 00172 } u_angle_max; 00173 u_angle_max.base = 0; 00174 u_angle_max.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); 00175 u_angle_max.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00176 u_angle_max.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00177 u_angle_max.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00178 this->angle_max = u_angle_max.real; 00179 offset += sizeof(this->angle_max); 00180 union { 00181 float real; 00182 uint32_t base; 00183 } u_angle_increment; 00184 u_angle_increment.base = 0; 00185 u_angle_increment.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); 00186 u_angle_increment.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00187 u_angle_increment.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00188 u_angle_increment.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00189 this->angle_increment = u_angle_increment.real; 00190 offset += sizeof(this->angle_increment); 00191 union { 00192 float real; 00193 uint32_t base; 00194 } u_time_increment; 00195 u_time_increment.base = 0; 00196 u_time_increment.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); 00197 u_time_increment.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00198 u_time_increment.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00199 u_time_increment.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00200 this->time_increment = u_time_increment.real; 00201 offset += sizeof(this->time_increment); 00202 union { 00203 float real; 00204 uint32_t base; 00205 } u_scan_time; 00206 u_scan_time.base = 0; 00207 u_scan_time.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); 00208 u_scan_time.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00209 u_scan_time.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00210 u_scan_time.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00211 this->scan_time = u_scan_time.real; 00212 offset += sizeof(this->scan_time); 00213 union { 00214 float real; 00215 uint32_t base; 00216 } u_range_min; 00217 u_range_min.base = 0; 00218 u_range_min.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); 00219 u_range_min.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00220 u_range_min.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00221 u_range_min.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00222 this->range_min = u_range_min.real; 00223 offset += sizeof(this->range_min); 00224 union { 00225 float real; 00226 uint32_t base; 00227 } u_range_max; 00228 u_range_max.base = 0; 00229 u_range_max.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); 00230 u_range_max.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00231 u_range_max.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00232 u_range_max.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00233 this->range_max = u_range_max.real; 00234 offset += sizeof(this->range_max); 00235 uint8_t ranges_lengthT = *(inbuffer + offset++); 00236 if(ranges_lengthT > ranges_length) 00237 this->ranges = (float*)realloc(this->ranges, ranges_lengthT * sizeof(float)); 00238 offset += 3; 00239 ranges_length = ranges_lengthT; 00240 for( uint8_t i = 0; i < ranges_length; i++){ 00241 union { 00242 float real; 00243 uint32_t base; 00244 } u_st_ranges; 00245 u_st_ranges.base = 0; 00246 u_st_ranges.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); 00247 u_st_ranges.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00248 u_st_ranges.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00249 u_st_ranges.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00250 this->st_ranges = u_st_ranges.real; 00251 offset += sizeof(this->st_ranges); 00252 memcpy( &(this->ranges[i]), &(this->st_ranges), sizeof(float)); 00253 } 00254 uint8_t intensities_lengthT = *(inbuffer + offset++); 00255 if(intensities_lengthT > intensities_length) 00256 this->intensities = (float*)realloc(this->intensities, intensities_lengthT * sizeof(float)); 00257 offset += 3; 00258 intensities_length = intensities_lengthT; 00259 for( uint8_t i = 0; i < intensities_length; i++){ 00260 union { 00261 float real; 00262 uint32_t base; 00263 } u_st_intensities; 00264 u_st_intensities.base = 0; 00265 u_st_intensities.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); 00266 u_st_intensities.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00267 u_st_intensities.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00268 u_st_intensities.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00269 this->st_intensities = u_st_intensities.real; 00270 offset += sizeof(this->st_intensities); 00271 memcpy( &(this->intensities[i]), &(this->st_intensities), sizeof(float)); 00272 } 00273 return offset; 00274 } 00275 00276 const char * getType(){ return "sensor_msgs/LaserScan"; }; 00277 const char * getMD5(){ return "90c7ef2dc6895d81024acba2ac42f369"; }; 00278 00279 }; 00280 00281 } 00282 #endif
Generated on Tue Jul 12 2022 18:39:39 by 1.7.2