diff --git a/libraries/AP_HAL_Linux/AnalogIn_ADS1115.cpp b/libraries/AP_HAL_Linux/AnalogIn_ADS1115.cpp index 8a40166a42..24adaab39a 100644 --- a/libraries/AP_HAL_Linux/AnalogIn_ADS1115.cpp +++ b/libraries/AP_HAL_Linux/AnalogIn_ADS1115.cpp @@ -6,12 +6,13 @@ AnalogSource_ADS1115::AnalogSource_ADS1115(int16_t pin): { } -void AnalogSource_ADS1115::set_pin(uint8_t pin) +bool AnalogSource_ADS1115::set_pin(uint8_t pin) { if (_pin == pin) { - return; + return true; } _pin = pin; + return true; } float AnalogSource_ADS1115::read_average() diff --git a/libraries/AP_HAL_Linux/AnalogIn_ADS1115.h b/libraries/AP_HAL_Linux/AnalogIn_ADS1115.h index f899418489..6d6e7724c3 100644 --- a/libraries/AP_HAL_Linux/AnalogIn_ADS1115.h +++ b/libraries/AP_HAL_Linux/AnalogIn_ADS1115.h @@ -11,7 +11,7 @@ public: AnalogSource_ADS1115(int16_t pin); 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; diff --git a/libraries/AP_HAL_Linux/AnalogIn_IIO.cpp b/libraries/AP_HAL_Linux/AnalogIn_IIO.cpp index c566cea8df..fff9815f43 100644 --- a/libraries/AP_HAL_Linux/AnalogIn_IIO.cpp +++ b/libraries/AP_HAL_Linux/AnalogIn_IIO.cpp @@ -98,10 +98,10 @@ float AnalogSource_IIO::voltage_latest() return _latest; } -void AnalogSource_IIO::set_pin(uint8_t pin) +bool AnalogSource_IIO::set_pin(uint8_t pin) { if (_pin == pin) { - return; + return true; } WITH_SEMAPHORE(_semaphore); @@ -112,6 +112,7 @@ void AnalogSource_IIO::set_pin(uint8_t pin) _latest = 0; _value = 0; select_pin(); + return true; } AnalogIn_IIO::AnalogIn_IIO() diff --git a/libraries/AP_HAL_Linux/AnalogIn_IIO.h b/libraries/AP_HAL_Linux/AnalogIn_IIO.h index 962b05c5ad..635957aad7 100644 --- a/libraries/AP_HAL_Linux/AnalogIn_IIO.h +++ b/libraries/AP_HAL_Linux/AnalogIn_IIO.h @@ -27,7 +27,7 @@ public: AnalogSource_IIO(int16_t pin, float initial_value, float voltage_scaling); 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 { return voltage_average(); } diff --git a/libraries/AP_HAL_Linux/AnalogIn_Navio2.cpp b/libraries/AP_HAL_Linux/AnalogIn_Navio2.cpp index f21d756aa9..0d05ad641e 100644 --- a/libraries/AP_HAL_Linux/AnalogIn_Navio2.cpp +++ b/libraries/AP_HAL_Linux/AnalogIn_Navio2.cpp @@ -42,15 +42,16 @@ AnalogSource_Navio2::AnalogSource_Navio2(uint8_t pin) set_channel(pin); } -void AnalogSource_Navio2::set_pin(uint8_t pin) +bool AnalogSource_Navio2::set_pin(uint8_t pin) { if (_pin == pin) { - return; + return true; } set_channel(pin); _pin = pin; + return true; } float AnalogSource_Navio2::read_average() diff --git a/libraries/AP_HAL_Linux/AnalogIn_Navio2.h b/libraries/AP_HAL_Linux/AnalogIn_Navio2.h index a03cfafec0..816c7cb4f5 100644 --- a/libraries/AP_HAL_Linux/AnalogIn_Navio2.h +++ b/libraries/AP_HAL_Linux/AnalogIn_Navio2.h @@ -12,7 +12,7 @@ public: AnalogSource_Navio2(uint8_t pin); 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;