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.
BatteryState.h
00001 #ifndef _ROS_sensor_msgs_BatteryState_h 00002 #define _ROS_sensor_msgs_BatteryState_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 BatteryState : public ros::Msg 00014 { 00015 public: 00016 typedef std_msgs::Header _header_type; 00017 _header_type header; 00018 typedef float _voltage_type; 00019 _voltage_type voltage; 00020 typedef float _current_type; 00021 _current_type current; 00022 typedef float _charge_type; 00023 _charge_type charge; 00024 typedef float _capacity_type; 00025 _capacity_type capacity; 00026 typedef float _design_capacity_type; 00027 _design_capacity_type design_capacity; 00028 typedef float _percentage_type; 00029 _percentage_type percentage; 00030 typedef uint8_t _power_supply_status_type; 00031 _power_supply_status_type power_supply_status; 00032 typedef uint8_t _power_supply_health_type; 00033 _power_supply_health_type power_supply_health; 00034 typedef uint8_t _power_supply_technology_type; 00035 _power_supply_technology_type power_supply_technology; 00036 typedef bool _present_type; 00037 _present_type present; 00038 uint32_t cell_voltage_length; 00039 typedef float _cell_voltage_type; 00040 _cell_voltage_type st_cell_voltage; 00041 _cell_voltage_type * cell_voltage; 00042 typedef const char* _location_type; 00043 _location_type location; 00044 typedef const char* _serial_number_type; 00045 _serial_number_type serial_number; 00046 enum { POWER_SUPPLY_STATUS_UNKNOWN = 0 }; 00047 enum { POWER_SUPPLY_STATUS_CHARGING = 1 }; 00048 enum { POWER_SUPPLY_STATUS_DISCHARGING = 2 }; 00049 enum { POWER_SUPPLY_STATUS_NOT_CHARGING = 3 }; 00050 enum { POWER_SUPPLY_STATUS_FULL = 4 }; 00051 enum { POWER_SUPPLY_HEALTH_UNKNOWN = 0 }; 00052 enum { POWER_SUPPLY_HEALTH_GOOD = 1 }; 00053 enum { POWER_SUPPLY_HEALTH_OVERHEAT = 2 }; 00054 enum { POWER_SUPPLY_HEALTH_DEAD = 3 }; 00055 enum { POWER_SUPPLY_HEALTH_OVERVOLTAGE = 4 }; 00056 enum { POWER_SUPPLY_HEALTH_UNSPEC_FAILURE = 5 }; 00057 enum { POWER_SUPPLY_HEALTH_COLD = 6 }; 00058 enum { POWER_SUPPLY_HEALTH_WATCHDOG_TIMER_EXPIRE = 7 }; 00059 enum { POWER_SUPPLY_HEALTH_SAFETY_TIMER_EXPIRE = 8 }; 00060 enum { POWER_SUPPLY_TECHNOLOGY_UNKNOWN = 0 }; 00061 enum { POWER_SUPPLY_TECHNOLOGY_NIMH = 1 }; 00062 enum { POWER_SUPPLY_TECHNOLOGY_LION = 2 }; 00063 enum { POWER_SUPPLY_TECHNOLOGY_LIPO = 3 }; 00064 enum { POWER_SUPPLY_TECHNOLOGY_LIFE = 4 }; 00065 enum { POWER_SUPPLY_TECHNOLOGY_NICD = 5 }; 00066 enum { POWER_SUPPLY_TECHNOLOGY_LIMN = 6 }; 00067 00068 BatteryState(): 00069 header(), 00070 voltage(0), 00071 current(0), 00072 charge(0), 00073 capacity(0), 00074 design_capacity(0), 00075 percentage(0), 00076 power_supply_status(0), 00077 power_supply_health(0), 00078 power_supply_technology(0), 00079 present(0), 00080 cell_voltage_length(0), cell_voltage(NULL), 00081 location(""), 00082 serial_number("") 00083 { 00084 } 00085 00086 virtual int serialize(unsigned char *outbuffer) const 00087 { 00088 int offset = 0; 00089 offset += this->header.serialize(outbuffer + offset); 00090 union { 00091 float real; 00092 uint32_t base; 00093 } u_voltage; 00094 u_voltage.real = this->voltage; 00095 *(outbuffer + offset + 0) = (u_voltage.base >> (8 * 0)) & 0xFF; 00096 *(outbuffer + offset + 1) = (u_voltage.base >> (8 * 1)) & 0xFF; 00097 *(outbuffer + offset + 2) = (u_voltage.base >> (8 * 2)) & 0xFF; 00098 *(outbuffer + offset + 3) = (u_voltage.base >> (8 * 3)) & 0xFF; 00099 offset += sizeof(this->voltage); 00100 union { 00101 float real; 00102 uint32_t base; 00103 } u_current; 00104 u_current.real = this->current; 00105 *(outbuffer + offset + 0) = (u_current.base >> (8 * 0)) & 0xFF; 00106 *(outbuffer + offset + 1) = (u_current.base >> (8 * 1)) & 0xFF; 00107 *(outbuffer + offset + 2) = (u_current.base >> (8 * 2)) & 0xFF; 00108 *(outbuffer + offset + 3) = (u_current.base >> (8 * 3)) & 0xFF; 00109 offset += sizeof(this->current); 00110 union { 00111 float real; 00112 uint32_t base; 00113 } u_charge; 00114 u_charge.real = this->charge; 00115 *(outbuffer + offset + 0) = (u_charge.base >> (8 * 0)) & 0xFF; 00116 *(outbuffer + offset + 1) = (u_charge.base >> (8 * 1)) & 0xFF; 00117 *(outbuffer + offset + 2) = (u_charge.base >> (8 * 2)) & 0xFF; 00118 *(outbuffer + offset + 3) = (u_charge.base >> (8 * 3)) & 0xFF; 00119 offset += sizeof(this->charge); 00120 union { 00121 float real; 00122 uint32_t base; 00123 } u_capacity; 00124 u_capacity.real = this->capacity; 00125 *(outbuffer + offset + 0) = (u_capacity.base >> (8 * 0)) & 0xFF; 00126 *(outbuffer + offset + 1) = (u_capacity.base >> (8 * 1)) & 0xFF; 00127 *(outbuffer + offset + 2) = (u_capacity.base >> (8 * 2)) & 0xFF; 00128 *(outbuffer + offset + 3) = (u_capacity.base >> (8 * 3)) & 0xFF; 00129 offset += sizeof(this->capacity); 00130 union { 00131 float real; 00132 uint32_t base; 00133 } u_design_capacity; 00134 u_design_capacity.real = this->design_capacity; 00135 *(outbuffer + offset + 0) = (u_design_capacity.base >> (8 * 0)) & 0xFF; 00136 *(outbuffer + offset + 1) = (u_design_capacity.base >> (8 * 1)) & 0xFF; 00137 *(outbuffer + offset + 2) = (u_design_capacity.base >> (8 * 2)) & 0xFF; 00138 *(outbuffer + offset + 3) = (u_design_capacity.base >> (8 * 3)) & 0xFF; 00139 offset += sizeof(this->design_capacity); 00140 union { 00141 float real; 00142 uint32_t base; 00143 } u_percentage; 00144 u_percentage.real = this->percentage; 00145 *(outbuffer + offset + 0) = (u_percentage.base >> (8 * 0)) & 0xFF; 00146 *(outbuffer + offset + 1) = (u_percentage.base >> (8 * 1)) & 0xFF; 00147 *(outbuffer + offset + 2) = (u_percentage.base >> (8 * 2)) & 0xFF; 00148 *(outbuffer + offset + 3) = (u_percentage.base >> (8 * 3)) & 0xFF; 00149 offset += sizeof(this->percentage); 00150 *(outbuffer + offset + 0) = (this->power_supply_status >> (8 * 0)) & 0xFF; 00151 offset += sizeof(this->power_supply_status); 00152 *(outbuffer + offset + 0) = (this->power_supply_health >> (8 * 0)) & 0xFF; 00153 offset += sizeof(this->power_supply_health); 00154 *(outbuffer + offset + 0) = (this->power_supply_technology >> (8 * 0)) & 0xFF; 00155 offset += sizeof(this->power_supply_technology); 00156 union { 00157 bool real; 00158 uint8_t base; 00159 } u_present; 00160 u_present.real = this->present; 00161 *(outbuffer + offset + 0) = (u_present.base >> (8 * 0)) & 0xFF; 00162 offset += sizeof(this->present); 00163 *(outbuffer + offset + 0) = (this->cell_voltage_length >> (8 * 0)) & 0xFF; 00164 *(outbuffer + offset + 1) = (this->cell_voltage_length >> (8 * 1)) & 0xFF; 00165 *(outbuffer + offset + 2) = (this->cell_voltage_length >> (8 * 2)) & 0xFF; 00166 *(outbuffer + offset + 3) = (this->cell_voltage_length >> (8 * 3)) & 0xFF; 00167 offset += sizeof(this->cell_voltage_length); 00168 for( uint32_t i = 0; i < cell_voltage_length; i++){ 00169 union { 00170 float real; 00171 uint32_t base; 00172 } u_cell_voltagei; 00173 u_cell_voltagei.real = this->cell_voltage[i]; 00174 *(outbuffer + offset + 0) = (u_cell_voltagei.base >> (8 * 0)) & 0xFF; 00175 *(outbuffer + offset + 1) = (u_cell_voltagei.base >> (8 * 1)) & 0xFF; 00176 *(outbuffer + offset + 2) = (u_cell_voltagei.base >> (8 * 2)) & 0xFF; 00177 *(outbuffer + offset + 3) = (u_cell_voltagei.base >> (8 * 3)) & 0xFF; 00178 offset += sizeof(this->cell_voltage[i]); 00179 } 00180 uint32_t length_location = strlen(this->location); 00181 varToArr(outbuffer + offset, length_location); 00182 offset += 4; 00183 memcpy(outbuffer + offset, this->location, length_location); 00184 offset += length_location; 00185 uint32_t length_serial_number = strlen(this->serial_number); 00186 varToArr(outbuffer + offset, length_serial_number); 00187 offset += 4; 00188 memcpy(outbuffer + offset, this->serial_number, length_serial_number); 00189 offset += length_serial_number; 00190 return offset; 00191 } 00192 00193 virtual int deserialize(unsigned char *inbuffer) 00194 { 00195 int offset = 0; 00196 offset += this->header.deserialize(inbuffer + offset); 00197 union { 00198 float real; 00199 uint32_t base; 00200 } u_voltage; 00201 u_voltage.base = 0; 00202 u_voltage.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); 00203 u_voltage.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00204 u_voltage.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00205 u_voltage.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00206 this->voltage = u_voltage.real; 00207 offset += sizeof(this->voltage); 00208 union { 00209 float real; 00210 uint32_t base; 00211 } u_current; 00212 u_current.base = 0; 00213 u_current.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); 00214 u_current.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00215 u_current.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00216 u_current.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00217 this->current = u_current.real; 00218 offset += sizeof(this->current); 00219 union { 00220 float real; 00221 uint32_t base; 00222 } u_charge; 00223 u_charge.base = 0; 00224 u_charge.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); 00225 u_charge.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00226 u_charge.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00227 u_charge.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00228 this->charge = u_charge.real; 00229 offset += sizeof(this->charge); 00230 union { 00231 float real; 00232 uint32_t base; 00233 } u_capacity; 00234 u_capacity.base = 0; 00235 u_capacity.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); 00236 u_capacity.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00237 u_capacity.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00238 u_capacity.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00239 this->capacity = u_capacity.real; 00240 offset += sizeof(this->capacity); 00241 union { 00242 float real; 00243 uint32_t base; 00244 } u_design_capacity; 00245 u_design_capacity.base = 0; 00246 u_design_capacity.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); 00247 u_design_capacity.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00248 u_design_capacity.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00249 u_design_capacity.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00250 this->design_capacity = u_design_capacity.real; 00251 offset += sizeof(this->design_capacity); 00252 union { 00253 float real; 00254 uint32_t base; 00255 } u_percentage; 00256 u_percentage.base = 0; 00257 u_percentage.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); 00258 u_percentage.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00259 u_percentage.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00260 u_percentage.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00261 this->percentage = u_percentage.real; 00262 offset += sizeof(this->percentage); 00263 this->power_supply_status = ((uint8_t) (*(inbuffer + offset))); 00264 offset += sizeof(this->power_supply_status); 00265 this->power_supply_health = ((uint8_t) (*(inbuffer + offset))); 00266 offset += sizeof(this->power_supply_health); 00267 this->power_supply_technology = ((uint8_t) (*(inbuffer + offset))); 00268 offset += sizeof(this->power_supply_technology); 00269 union { 00270 bool real; 00271 uint8_t base; 00272 } u_present; 00273 u_present.base = 0; 00274 u_present.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); 00275 this->present = u_present.real; 00276 offset += sizeof(this->present); 00277 uint32_t cell_voltage_lengthT = ((uint32_t) (*(inbuffer + offset))); 00278 cell_voltage_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00279 cell_voltage_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00280 cell_voltage_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00281 offset += sizeof(this->cell_voltage_length); 00282 if(cell_voltage_lengthT > cell_voltage_length) 00283 this->cell_voltage = (float*)realloc(this->cell_voltage, cell_voltage_lengthT * sizeof(float)); 00284 cell_voltage_length = cell_voltage_lengthT; 00285 for( uint32_t i = 0; i < cell_voltage_length; i++){ 00286 union { 00287 float real; 00288 uint32_t base; 00289 } u_st_cell_voltage; 00290 u_st_cell_voltage.base = 0; 00291 u_st_cell_voltage.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); 00292 u_st_cell_voltage.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00293 u_st_cell_voltage.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00294 u_st_cell_voltage.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00295 this->st_cell_voltage = u_st_cell_voltage.real; 00296 offset += sizeof(this->st_cell_voltage); 00297 memcpy( &(this->cell_voltage[i]), &(this->st_cell_voltage), sizeof(float)); 00298 } 00299 uint32_t length_location; 00300 arrToVar(length_location, (inbuffer + offset)); 00301 offset += 4; 00302 for(unsigned int k= offset; k< offset+length_location; ++k){ 00303 inbuffer[k-1]=inbuffer[k]; 00304 } 00305 inbuffer[offset+length_location-1]=0; 00306 this->location = (char *)(inbuffer + offset-1); 00307 offset += length_location; 00308 uint32_t length_serial_number; 00309 arrToVar(length_serial_number, (inbuffer + offset)); 00310 offset += 4; 00311 for(unsigned int k= offset; k< offset+length_serial_number; ++k){ 00312 inbuffer[k-1]=inbuffer[k]; 00313 } 00314 inbuffer[offset+length_serial_number-1]=0; 00315 this->serial_number = (char *)(inbuffer + offset-1); 00316 offset += length_serial_number; 00317 return offset; 00318 } 00319 00320 const char * getType(){ return "sensor_msgs/BatteryState"; }; 00321 const char * getMD5(){ return "476f837fa6771f6e16e3bf4ef96f8770"; }; 00322 00323 }; 00324 00325 } 00326 #endif
Generated on Wed Jul 13 2022 23:30:17 by
