mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_HAL: added support for saving and restoring GPIO settings
this allows for using any pin (eg. UART TX, RX, RTS, CTS) as a GPIO, and restoring the old mode. Initial use is for spektrum bind on RX pin
This commit is contained in:
parent
25324ae0e2
commit
029743e27a
@ -55,6 +55,10 @@ public:
|
||||
virtual void toggle(uint8_t pin) = 0;
|
||||
virtual bool valid_pin(uint8_t pin) const { return true; }
|
||||
|
||||
// allow for save and restore of pin settings
|
||||
virtual bool get_mode(uint8_t pin, uint32_t &mode) { return false; }
|
||||
virtual void set_mode(uint8_t pin, uint32_t mode) {}
|
||||
|
||||
/* Alternative interface: */
|
||||
virtual AP_HAL::DigitalSource* channel(uint16_t n) = 0;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user