mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_Empty: AnalogSource: return bool
This commit is contained in:
parent
f7cba024c1
commit
f479964c5a
|
@ -22,8 +22,9 @@ float AnalogSource::read_latest() {
|
||||||
return _v;
|
return _v;
|
||||||
}
|
}
|
||||||
|
|
||||||
void AnalogSource::set_pin(uint8_t p)
|
bool AnalogSource::set_pin(uint8_t p) {
|
||||||
{}
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
AnalogIn::AnalogIn()
|
AnalogIn::AnalogIn()
|
||||||
{}
|
{}
|
||||||
|
|
|
@ -7,7 +7,7 @@ public:
|
||||||
AnalogSource(float v);
|
AnalogSource(float v);
|
||||||
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(); }
|
||||||
|
|
Loading…
Reference in New Issue