Skip to content

Commit 5cff6c0

Browse files
MichelleRospeterbarker
authored andcommitted
AP_HAL_ChibiOS: Fix regression in MCU max and min volt logging
1 parent 40ed9f6 commit 5cff6c0

File tree

1 file changed

+4
-0
lines changed

1 file changed

+4
-0
lines changed

libraries/AP_HAL_ChibiOS/AnalogIn.cpp

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -761,6 +761,10 @@ void AnalogIn::_timer_tick(void)
761761
// note min/max swap due to inversion
762762
_mcu_voltage_min = 3.3 * VREFINT_CAL / float(_mcu_vrefint_max+0.001);
763763
_mcu_voltage_max = 3.3 * VREFINT_CAL / float(_mcu_vrefint_min+0.001);
764+
765+
// reset min and max
766+
_mcu_vrefint_max = 0;
767+
_mcu_vrefint_min = 0;
764768
}
765769
#endif
766770
}

0 commit comments

Comments
 (0)