mirror of https://github.com/ArduPilot/ardupilot
AP_HAL: added wait_pin() API
for waiting on data-ready lines
This commit is contained in:
parent
d8e208167d
commit
34df438560
|
@ -65,6 +65,12 @@ public:
|
|||
return attach_interrupt(pin, (AP_HAL::Proc)nullptr, AP_HAL::GPIO::INTERRUPT_NONE);
|
||||
}
|
||||
|
||||
/*
|
||||
block waiting for a pin to change. A timeout of 0 means wait
|
||||
forever. Return true on pin change, false on timeout
|
||||
*/
|
||||
virtual bool wait_pin(uint8_t pin, INTERRUPT_TRIGGER_TYPE mode, uint32_t timeout_us) { return false; }
|
||||
|
||||
/* return true if USB cable is connected */
|
||||
virtual bool usb_connected(void) = 0;
|
||||
};
|
||||
|
|
Loading…
Reference in New Issue