Browse Source

AP_HAL_Linux: AnalogSource: set_pin return true

gps-1.3.1
Iampete1 3 years ago committed by Andrew Tridgell
parent
commit
62474e6dc8
  1. 5
      libraries/AP_HAL_Linux/AnalogIn_ADS1115.cpp
  2. 2
      libraries/AP_HAL_Linux/AnalogIn_ADS1115.h
  3. 5
      libraries/AP_HAL_Linux/AnalogIn_IIO.cpp
  4. 2
      libraries/AP_HAL_Linux/AnalogIn_IIO.h
  5. 5
      libraries/AP_HAL_Linux/AnalogIn_Navio2.cpp
  6. 2
      libraries/AP_HAL_Linux/AnalogIn_Navio2.h

5
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) { if (_pin == pin) {
return; return true;
} }
_pin = pin; _pin = pin;
return true;
} }
float AnalogSource_ADS1115::read_average() float AnalogSource_ADS1115::read_average()

2
libraries/AP_HAL_Linux/AnalogIn_ADS1115.h

@ -11,7 +11,7 @@ public:
AnalogSource_ADS1115(int16_t pin); AnalogSource_ADS1115(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;
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;

5
libraries/AP_HAL_Linux/AnalogIn_IIO.cpp

@ -98,10 +98,10 @@ float AnalogSource_IIO::voltage_latest()
return _latest; return _latest;
} }
void AnalogSource_IIO::set_pin(uint8_t pin) bool AnalogSource_IIO::set_pin(uint8_t pin)
{ {
if (_pin == pin) { if (_pin == pin) {
return; return true;
} }
WITH_SEMAPHORE(_semaphore); WITH_SEMAPHORE(_semaphore);
@ -112,6 +112,7 @@ void AnalogSource_IIO::set_pin(uint8_t pin)
_latest = 0; _latest = 0;
_value = 0; _value = 0;
select_pin(); select_pin();
return true;
} }
AnalogIn_IIO::AnalogIn_IIO() AnalogIn_IIO::AnalogIn_IIO()

2
libraries/AP_HAL_Linux/AnalogIn_IIO.h

@ -27,7 +27,7 @@ public:
AnalogSource_IIO(int16_t pin, float initial_value, float voltage_scaling); AnalogSource_IIO(int16_t pin, float initial_value, float voltage_scaling);
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;
float voltage_average() override; float voltage_average() override;
float voltage_latest() override; float voltage_latest() override;
float voltage_average_ratiometric() override { return voltage_average(); } float voltage_average_ratiometric() override { return voltage_average(); }

5
libraries/AP_HAL_Linux/AnalogIn_Navio2.cpp

@ -42,15 +42,16 @@ AnalogSource_Navio2::AnalogSource_Navio2(uint8_t pin)
set_channel(pin); set_channel(pin);
} }
void AnalogSource_Navio2::set_pin(uint8_t pin) bool AnalogSource_Navio2::set_pin(uint8_t pin)
{ {
if (_pin == pin) { if (_pin == pin) {
return; return true;
} }
set_channel(pin); set_channel(pin);
_pin = pin; _pin = pin;
return true;
} }
float AnalogSource_Navio2::read_average() float AnalogSource_Navio2::read_average()

2
libraries/AP_HAL_Linux/AnalogIn_Navio2.h

@ -12,7 +12,7 @@ public:
AnalogSource_Navio2(uint8_t pin); AnalogSource_Navio2(uint8_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;
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;

Loading…
Cancel
Save