AP_HAL_Linux: AnalogSource: set_pin return true

This commit is contained in:
Iampete1 2021-09-22 20:48:45 +01:00 committed by Andrew Tridgell
parent f479964c5a
commit 62474e6dc8
6 changed files with 12 additions and 9 deletions

View File

@ -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()

View File

@ -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;

View File

@ -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()

View File

@ -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(); }

View File

@ -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()

View File

@ -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;