|
|
|
@ -130,7 +130,7 @@ void AP_BattMonitor_UAVCAN::update_interim_state(const float voltage, const floa
@@ -130,7 +130,7 @@ void AP_BattMonitor_UAVCAN::update_interim_state(const float voltage, const floa
|
|
|
|
|
|
|
|
|
|
if (!isnanf(temperature_K) && temperature_K > 0) { |
|
|
|
|
// Temperature reported from battery in kelvin and stored internally in Celsius.
|
|
|
|
|
_interim_state.temperature = temperature_K - C_TO_KELVIN; |
|
|
|
|
_interim_state.temperature = KELVIN_TO_C(temperature_K); |
|
|
|
|
_interim_state.temperature_time = AP_HAL::millis(); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
@ -185,7 +185,7 @@ void AP_BattMonitor_UAVCAN::handle_mppt_stream(const MpptStreamCb &cb)
@@ -185,7 +185,7 @@ void AP_BattMonitor_UAVCAN::handle_mppt_stream(const MpptStreamCb &cb)
|
|
|
|
|
const uint8_t soc = 127; |
|
|
|
|
|
|
|
|
|
// convert C to Kelvin
|
|
|
|
|
const float temperature_K = isnanf(cb.msg->temperature) ? 0 : cb.msg->temperature + C_TO_KELVIN; |
|
|
|
|
const float temperature_K = isnanf(cb.msg->temperature) ? 0 : C_TO_KELVIN(cb.msg->temperature); |
|
|
|
|
|
|
|
|
|
update_interim_state(voltage, current, temperature_K, soc);
|
|
|
|
|
|
|
|
|
|