mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_HAL_ChibiOS: fix set_pin and _pin_scalar methods for ADC2 and ADC3
This commit is contained in:
parent
dec618645d
commit
b17d864d1a
@ -148,6 +148,22 @@ float AnalogSource::_pin_scaler(void)
|
||||
break;
|
||||
}
|
||||
}
|
||||
#ifdef HAL_ANALOG2_PINS
|
||||
for (uint8_t i=0; i<ADC2_GRP1_NUM_CHANNELS; i++) {
|
||||
if (AnalogIn::pin_config[i].analog_pin == _pin && (_pin != ANALOG_INPUT_NONE)) {
|
||||
scaling = AnalogIn::pin_config[i].scaling;
|
||||
break;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
#ifdef HAL_ANALOG3_PINS
|
||||
for (uint8_t i=0; i<ADC3_GRP1_NUM_CHANNELS; i++) {
|
||||
if (AnalogIn::pin_config[i].analog_pin == _pin && (_pin != ANALOG_INPUT_NONE)) {
|
||||
scaling = AnalogIn::pin_config[i].scaling;
|
||||
break;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
return scaling;
|
||||
}
|
||||
|
||||
@ -195,6 +211,22 @@ bool AnalogSource::set_pin(uint8_t pin)
|
||||
break;
|
||||
}
|
||||
}
|
||||
#ifdef HAL_ANALOG2_PINS
|
||||
for (uint8_t i=0; i<ADC2_GRP1_NUM_CHANNELS; i++) {
|
||||
if (AnalogIn::pin_config_2[i].analog_pin == pin) {
|
||||
found_pin = true;
|
||||
break;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
#ifdef HAL_ANALOG3_PINS
|
||||
for (uint8_t i=0; i<ADC3_GRP1_NUM_CHANNELS; i++) {
|
||||
if (AnalogIn::pin_config_3[i].analog_pin == pin) {
|
||||
found_pin = true;
|
||||
break;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
}
|
||||
if (!found_pin) {
|
||||
return false;
|
||||
|
Loading…
Reference in New Issue
Block a user