AP_HAL_ChibiOS: AnalogSource: check for valid pin

This commit is contained in:
Iampete1 2021-09-22 20:47:38 +01:00 committed by Andrew Tridgell
parent bb04406496
commit f7cba024c1
2 changed files with 19 additions and 3 deletions

View File

@ -140,11 +140,26 @@ float AnalogSource::voltage_latest()
return _pin_scaler() * read_latest(); return _pin_scaler() * read_latest();
} }
void AnalogSource::set_pin(uint8_t pin) bool AnalogSource::set_pin(uint8_t pin)
{ {
if (_pin == pin) { if (_pin == pin) {
return; return true;
} }
bool found_pin = false;
if (_pin == ANALOG_SERVO_VRSSI_PIN) {
found_pin = true;
} else {
for (uint8_t i=0; i<ADC_GRP1_NUM_CHANNELS; i++) {
if (AnalogIn::pin_config[i].channel == pin) {
found_pin = true;
break;
}
}
}
if (!found_pin) {
return false;
}
WITH_SEMAPHORE(_semaphore); WITH_SEMAPHORE(_semaphore);
_pin = pin; _pin = pin;
_sum_value = 0; _sum_value = 0;
@ -153,6 +168,7 @@ void AnalogSource::set_pin(uint8_t pin)
_latest_value = 0; _latest_value = 0;
_value = 0; _value = 0;
_value_ratiometric = 0; _value_ratiometric = 0;
return true;
} }
/* /*

View File

@ -32,7 +32,7 @@ public:
AnalogSource(int16_t pin); AnalogSource(int16_t pin);
float read_average() override; float read_average() override;
float read_latest() override; float read_latest() override;
void set_pin(uint8_t p) override; bool set_pin(uint8_t p) override WARN_IF_UNUSED;
float voltage_average() override; float voltage_average() override;
float voltage_latest() override; float voltage_latest() override;
float voltage_average_ratiometric() override; float voltage_average_ratiometric() override;