mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
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:
parent
1e0ca409d1
commit
490d6eea20
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user