mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-03 22:48:28 -04:00
AP_HAL_Linux: Remove set_stop_pin from AnalogSource
This commit is contained in:
parent
69d3e97533
commit
979a431e4a
@ -12,8 +12,6 @@ public:
|
||||
float read_average() override;
|
||||
float read_latest() override;
|
||||
void set_pin(uint8_t p) override;
|
||||
void set_stop_pin(uint8_t p) override {}
|
||||
void set_settle_time(uint16_t settle_time_ms) override {}
|
||||
float voltage_average() override;
|
||||
float voltage_latest() override;
|
||||
float voltage_average_ratiometric() override;
|
||||
|
@ -114,12 +114,6 @@ void AnalogSource_IIO::set_pin(uint8_t pin)
|
||||
select_pin();
|
||||
}
|
||||
|
||||
void AnalogSource_IIO::set_stop_pin(uint8_t p)
|
||||
{}
|
||||
|
||||
void AnalogSource_IIO::set_settle_time(uint16_t settle_time_ms)
|
||||
{}
|
||||
|
||||
AnalogIn_IIO::AnalogIn_IIO()
|
||||
{}
|
||||
|
||||
|
@ -28,8 +28,6 @@ public:
|
||||
float read_average() override;
|
||||
float read_latest() override;
|
||||
void set_pin(uint8_t p) override;
|
||||
void set_stop_pin(uint8_t p) override;
|
||||
void set_settle_time(uint16_t settle_time_ms) override;
|
||||
float voltage_average() override;
|
||||
float voltage_latest() override;
|
||||
float voltage_average_ratiometric() override { return voltage_average(); }
|
||||
|
@ -13,8 +13,6 @@ public:
|
||||
float read_average() override;
|
||||
float read_latest() override;
|
||||
void set_pin(uint8_t p) override;
|
||||
void set_stop_pin(uint8_t p) override{}
|
||||
void set_settle_time(uint16_t settle_time_ms) override{}
|
||||
float voltage_average() override;
|
||||
float voltage_latest() override;
|
||||
float voltage_average_ratiometric() override;
|
||||
|
Loading…
Reference in New Issue
Block a user