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!
This commit is contained in:
Andrew Tridgell 2018-09-11 20:29:48 +10:00 committed by Randy Mackay
parent df360bb77a
commit 313baec2fd
1 changed files with 1 additions and 1 deletions

View File

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