mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-30 12:38:33 -04:00
AP_HAL: AnalogSource: set_pin returns bool
This commit is contained in:
parent
19f66803ff
commit
bb04406496
@ -9,7 +9,7 @@ class AP_HAL::AnalogSource {
|
||||
public:
|
||||
virtual float read_average() = 0;
|
||||
virtual float read_latest() = 0;
|
||||
virtual void set_pin(uint8_t p) = 0;
|
||||
virtual bool set_pin(uint8_t p) WARN_IF_UNUSED = 0;
|
||||
|
||||
// return a voltage from 0.0 to 5.0V, scaled
|
||||
// against a reference voltage
|
||||
|
@ -46,7 +46,7 @@ void loop(void) {
|
||||
//increment the pin number
|
||||
pin = (pin+1) % 16;
|
||||
//set pin corresponding to the new pin value
|
||||
chan->set_pin(pin);
|
||||
IGNORE_RETURN(chan->set_pin(pin));
|
||||
//give a delay of 100ms
|
||||
hal.scheduler->delay(100);
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user