Browse Source

AP_BattMonitor: make C_TO_KELVIN a function macro; create KELVIN_TO_C

These are in celsius
gps-1.3.1
Peter Barker 3 years ago committed by Peter Barker
parent
commit
a894b93762
  1. 2
      libraries/AP_BattMonitor/AP_BattMonitor_SMBus.cpp
  2. 2
      libraries/AP_BattMonitor/AP_BattMonitor_SMBus_Rotoye.cpp
  3. 4
      libraries/AP_BattMonitor/AP_BattMonitor_UAVCAN.cpp

2
libraries/AP_BattMonitor/AP_BattMonitor_SMBus.cpp

@ -117,7 +117,7 @@ void AP_BattMonitor_SMBus::read_temp(void) @@ -117,7 +117,7 @@ void AP_BattMonitor_SMBus::read_temp(void)
_has_temperature = true;
_state.temperature_time = AP_HAL::millis();
_state.temperature = (data * 0.1f) - C_TO_KELVIN;
_state.temperature = KELVIN_TO_C(0.1f * data);
}
// reads the serial number if it's not already known

2
libraries/AP_BattMonitor/AP_BattMonitor_SMBus_Rotoye.cpp

@ -17,6 +17,6 @@ void AP_BattMonitor_SMBus_Rotoye::read_temp(void) { @@ -17,6 +17,6 @@ void AP_BattMonitor_SMBus_Rotoye::read_temp(void) {
uint16_t t;
_state.temperature_time = AP_HAL::millis();
t = ((t_ext > t_int) ? t_ext : t_int);
_state.temperature = 0.1f * (float)t - C_TO_KELVIN;
_state.temperature = KELVIN_TO_C(0.1f * (float)t);
}
}

4
libraries/AP_BattMonitor/AP_BattMonitor_UAVCAN.cpp

@ -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);

Loading…
Cancel
Save