From 93031e297d803ec5866c980fb26f27ee14dc910f Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 7 Mar 2022 13:41:31 +1100 Subject: [PATCH] HAL_ChibiOS: fixed min/max inversion in MCU voltage logging --- libraries/AP_HAL_ChibiOS/AnalogIn.cpp | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/AnalogIn.cpp b/libraries/AP_HAL_ChibiOS/AnalogIn.cpp index 539acb7665..f206e984e1 100644 --- a/libraries/AP_HAL_ChibiOS/AnalogIn.cpp +++ b/libraries/AP_HAL_ChibiOS/AnalogIn.cpp @@ -513,8 +513,9 @@ void AnalogIn::_timer_tick(void) _mcu_temperature = ((110 - 30) / (TS_CAL2 - TS_CAL1)) * (float(buf_adc3[1]) - TS_CAL1) + 30; _mcu_voltage = 3.3 * VREFINT_CAL / float(buf_adc3[2]+0.001); - _mcu_voltage_min = 3.3 * VREFINT_CAL / float(min_adc3[2]+0.001); - _mcu_voltage_max = 3.3 * VREFINT_CAL / float(max_adc3[2]+0.001); + // note min/max swap due to inversion + _mcu_voltage_min = 3.3 * VREFINT_CAL / float(max_adc3[2]+0.001); + _mcu_voltage_max = 3.3 * VREFINT_CAL / float(min_adc3[2]+0.001); } #endif }