mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-20 07:38:28 -04:00
AP_HAL_Empty: Remove set_stop_pin from AnalogSource
This commit is contained in:
parent
979a431e4a
commit
75b241622f
@ -25,12 +25,6 @@ float AnalogSource::read_latest() {
|
|||||||
void AnalogSource::set_pin(uint8_t p)
|
void AnalogSource::set_pin(uint8_t p)
|
||||||
{}
|
{}
|
||||||
|
|
||||||
void AnalogSource::set_stop_pin(uint8_t p)
|
|
||||||
{}
|
|
||||||
|
|
||||||
void AnalogSource::set_settle_time(uint16_t settle_time_ms)
|
|
||||||
{}
|
|
||||||
|
|
||||||
AnalogIn::AnalogIn()
|
AnalogIn::AnalogIn()
|
||||||
{}
|
{}
|
||||||
|
|
||||||
|
@ -8,8 +8,6 @@ public:
|
|||||||
float read_average() override;
|
float read_average() override;
|
||||||
float read_latest() override;
|
float read_latest() override;
|
||||||
void set_pin(uint8_t p) 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_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(); }
|
||||||
|
Loading…
Reference in New Issue
Block a user