|
|
|
@ -90,6 +90,7 @@ void AP_BattMonitor_UAVCAN::handle_battery_info(const BattInfoCb &cb)
@@ -90,6 +90,7 @@ void AP_BattMonitor_UAVCAN::handle_battery_info(const BattInfoCb &cb)
|
|
|
|
|
_interim_state.temperature = cb.msg->temperature; |
|
|
|
|
_interim_state.voltage = cb.msg->voltage; |
|
|
|
|
_interim_state.current_amps = cb.msg->current; |
|
|
|
|
_soc = cb.msg->state_of_charge_pct; |
|
|
|
|
|
|
|
|
|
uint32_t tnow = AP_HAL::micros(); |
|
|
|
|
uint32_t dt = tnow - _interim_state.last_time_micros; |
|
|
|
@ -137,4 +138,16 @@ void AP_BattMonitor_UAVCAN::read()
@@ -137,4 +138,16 @@ void AP_BattMonitor_UAVCAN::read()
|
|
|
|
|
_state.healthy = _interim_state.healthy; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/// capacity_remaining_pct - returns the % battery capacity remaining (0 ~ 100)
|
|
|
|
|
uint8_t AP_BattMonitor_UAVCAN::capacity_remaining_pct() const |
|
|
|
|
{ |
|
|
|
|
if ((uint32_t(_params._options.get()) & uint32_t(AP_BattMonitor_Params::Options::Ignore_UAVCAN_SoC)) || |
|
|
|
|
_soc > 100) { |
|
|
|
|
// a UAVCAN battery monitor may not be able to supply a state of charge. If it can't then
|
|
|
|
|
// the user can set the option to use current integration in the backend instead.
|
|
|
|
|
return AP_BattMonitor_Backend::capacity_remaining_pct(); |
|
|
|
|
} |
|
|
|
|
return _soc; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
#endif |
|
|
|
|