From 313baec2fd9f7d437a16e115b68fe5abe15c33d3 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 11 Sep 2018 20:29:48 +1000 Subject: [PATCH] HAL_ChibiOS: fixed ADC bug this caused bad analog readings when the number of channels being read was more than the number of hw channels thanks to @vierfuffzig for reporting! --- libraries/AP_HAL_ChibiOS/AnalogIn.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/AnalogIn.cpp b/libraries/AP_HAL_ChibiOS/AnalogIn.cpp index 8c07c1789c..aa8708f468 100644 --- a/libraries/AP_HAL_ChibiOS/AnalogIn.cpp +++ b/libraries/AP_HAL_ChibiOS/AnalogIn.cpp @@ -294,7 +294,7 @@ void AnalogIn::_timer_tick(void) Debug("chan %u value=%u\n", (unsigned)pin_config[i].channel, (unsigned)buf_adc[i]); - for (uint8_t j=0; j < ADC_GRP1_NUM_CHANNELS; j++) { + for (uint8_t j=0; j < ANALOG_MAX_CHANNELS; j++) { ChibiOS::AnalogSource *c = _channels[j]; if (c != nullptr && pin_config[i].channel == c->_pin) { // add a value