AP_HAL_SITL: AnalogSource: return bool for set_pin

This commit is contained in:
Iampete1 2021-09-22 20:49:14 +01:00 committed by Andrew Tridgell
parent 62474e6dc8
commit 9f04cded3b
2 changed files with 3 additions and 2 deletions

View File

@ -58,8 +58,9 @@ float ADCSource::read_latest() {
}
}
void ADCSource::set_pin(uint8_t pin) {
bool ADCSource::set_pin(uint8_t pin) {
_pin = pin;
return true;
}
void AnalogIn::init() {

View File

@ -14,7 +14,7 @@ public:
/* implement AnalogSource virtual api: */
float read_average() override;
float read_latest() override;
void set_pin(uint8_t p) override;
bool set_pin(uint8_t p) override;
float voltage_average() override;
float voltage_latest() override;
float voltage_average_ratiometric() override {