mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_SITL: AnalogSource: return bool for set_pin
This commit is contained in:
parent
62474e6dc8
commit
9f04cded3b
|
@ -58,8 +58,9 @@ float ADCSource::read_latest() {
|
|||
}
|
||||
}
|
||||
|
||||
void ADCSource::set_pin(uint8_t pin) {
|
||||
bool ADCSource::set_pin(uint8_t pin) {
|
||||
_pin = pin;
|
||||
return true;
|
||||
}
|
||||
|
||||
void AnalogIn::init() {
|
||||
|
|
|
@ -14,7 +14,7 @@ public:
|
|||
/* implement AnalogSource virtual api: */
|
||||
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 {
|
||||
|
|
Loading…
Reference in New Issue