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.
Range.h
00001 #ifndef _ROS_sensor_msgs_Range_h 00002 #define _ROS_sensor_msgs_Range_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 Range : public ros::Msg 00014 { 00015 public: 00016 typedef std_msgs::Header _header_type; 00017 _header_type header; 00018 typedef uint8_t _radiation_type_type; 00019 _radiation_type_type radiation_type; 00020 typedef float _field_of_view_type; 00021 _field_of_view_type field_of_view; 00022 typedef float _min_range_type; 00023 _min_range_type min_range; 00024 typedef float _max_range_type; 00025 _max_range_type max_range; 00026 typedef float _range_type; 00027 _range_type range; 00028 enum { ULTRASOUND = 0 }; 00029 enum { INFRARED = 1 }; 00030 00031 Range(): 00032 header(), 00033 radiation_type(0), 00034 field_of_view(0), 00035 min_range(0), 00036 max_range(0), 00037 range(0) 00038 { 00039 } 00040 00041 virtual int serialize(unsigned char *outbuffer) const 00042 { 00043 int offset = 0; 00044 offset += this->header.serialize(outbuffer + offset); 00045 *(outbuffer + offset + 0) = (this->radiation_type >> (8 * 0)) & 0xFF; 00046 offset += sizeof(this->radiation_type); 00047 union { 00048 float real; 00049 uint32_t base; 00050 } u_field_of_view; 00051 u_field_of_view.real = this->field_of_view; 00052 *(outbuffer + offset + 0) = (u_field_of_view.base >> (8 * 0)) & 0xFF; 00053 *(outbuffer + offset + 1) = (u_field_of_view.base >> (8 * 1)) & 0xFF; 00054 *(outbuffer + offset + 2) = (u_field_of_view.base >> (8 * 2)) & 0xFF; 00055 *(outbuffer + offset + 3) = (u_field_of_view.base >> (8 * 3)) & 0xFF; 00056 offset += sizeof(this->field_of_view); 00057 union { 00058 float real; 00059 uint32_t base; 00060 } u_min_range; 00061 u_min_range.real = this->min_range; 00062 *(outbuffer + offset + 0) = (u_min_range.base >> (8 * 0)) & 0xFF; 00063 *(outbuffer + offset + 1) = (u_min_range.base >> (8 * 1)) & 0xFF; 00064 *(outbuffer + offset + 2) = (u_min_range.base >> (8 * 2)) & 0xFF; 00065 *(outbuffer + offset + 3) = (u_min_range.base >> (8 * 3)) & 0xFF; 00066 offset += sizeof(this->min_range); 00067 union { 00068 float real; 00069 uint32_t base; 00070 } u_max_range; 00071 u_max_range.real = this->max_range; 00072 *(outbuffer + offset + 0) = (u_max_range.base >> (8 * 0)) & 0xFF; 00073 *(outbuffer + offset + 1) = (u_max_range.base >> (8 * 1)) & 0xFF; 00074 *(outbuffer + offset + 2) = (u_max_range.base >> (8 * 2)) & 0xFF; 00075 *(outbuffer + offset + 3) = (u_max_range.base >> (8 * 3)) & 0xFF; 00076 offset += sizeof(this->max_range); 00077 union { 00078 float real; 00079 uint32_t base; 00080 } u_range; 00081 u_range.real = this->range; 00082 *(outbuffer + offset + 0) = (u_range.base >> (8 * 0)) & 0xFF; 00083 *(outbuffer + offset + 1) = (u_range.base >> (8 * 1)) & 0xFF; 00084 *(outbuffer + offset + 2) = (u_range.base >> (8 * 2)) & 0xFF; 00085 *(outbuffer + offset + 3) = (u_range.base >> (8 * 3)) & 0xFF; 00086 offset += sizeof(this->range); 00087 return offset; 00088 } 00089 00090 virtual int deserialize(unsigned char *inbuffer) 00091 { 00092 int offset = 0; 00093 offset += this->header.deserialize(inbuffer + offset); 00094 this->radiation_type = ((uint8_t) (*(inbuffer + offset))); 00095 offset += sizeof(this->radiation_type); 00096 union { 00097 float real; 00098 uint32_t base; 00099 } u_field_of_view; 00100 u_field_of_view.base = 0; 00101 u_field_of_view.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); 00102 u_field_of_view.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00103 u_field_of_view.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00104 u_field_of_view.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00105 this->field_of_view = u_field_of_view.real; 00106 offset += sizeof(this->field_of_view); 00107 union { 00108 float real; 00109 uint32_t base; 00110 } u_min_range; 00111 u_min_range.base = 0; 00112 u_min_range.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); 00113 u_min_range.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00114 u_min_range.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00115 u_min_range.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00116 this->min_range = u_min_range.real; 00117 offset += sizeof(this->min_range); 00118 union { 00119 float real; 00120 uint32_t base; 00121 } u_max_range; 00122 u_max_range.base = 0; 00123 u_max_range.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); 00124 u_max_range.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00125 u_max_range.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00126 u_max_range.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00127 this->max_range = u_max_range.real; 00128 offset += sizeof(this->max_range); 00129 union { 00130 float real; 00131 uint32_t base; 00132 } u_range; 00133 u_range.base = 0; 00134 u_range.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); 00135 u_range.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00136 u_range.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00137 u_range.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00138 this->range = u_range.real; 00139 offset += sizeof(this->range); 00140 return offset; 00141 } 00142 00143 const char * getType(){ return "sensor_msgs/Range"; }; 00144 const char * getMD5(){ return "c005c34273dc426c67a020a87bc24148"; }; 00145 00146 }; 00147 00148 } 00149 #endif
Generated on Wed Jul 13 2022 23:30:18 by
