mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-11 02:13:57 -04:00
AP_HAL: make new GPIO functions optional
not available on all boards
This commit is contained in:
parent
e0db1ad93e
commit
582318448f
@ -27,12 +27,15 @@ public:
|
|||||||
GPIO() {}
|
GPIO() {}
|
||||||
virtual void init() = 0;
|
virtual void init() = 0;
|
||||||
virtual void pinMode(uint8_t pin, uint8_t output) = 0;
|
virtual void pinMode(uint8_t pin, uint8_t output) = 0;
|
||||||
virtual void pinMode(uint8_t pin, uint8_t output, uint8_t alt) = 0;
|
|
||||||
|
// optional interface on some boards
|
||||||
|
virtual void pinMode(uint8_t pin, uint8_t output, uint8_t alt) {};
|
||||||
|
|
||||||
virtual uint8_t read(uint8_t pin) = 0;
|
virtual uint8_t read(uint8_t pin) = 0;
|
||||||
virtual void write(uint8_t pin, uint8_t value) = 0;
|
virtual void write(uint8_t pin, uint8_t value) = 0;
|
||||||
virtual void toggle(uint8_t pin) = 0;
|
virtual void toggle(uint8_t pin) = 0;
|
||||||
virtual void setPWMPeriod(uint8_t pin, uint32_t time_us) = 0;
|
virtual void setPWMPeriod(uint8_t pin, uint32_t time_us) {};
|
||||||
virtual void setPWMDuty(uint8_t pin, uint8_t percent) = 0;
|
virtual void setPWMDuty(uint8_t pin, uint8_t percent) {};
|
||||||
virtual int8_t analogPinToDigitalPin(uint8_t pin) = 0;
|
virtual int8_t analogPinToDigitalPin(uint8_t pin) = 0;
|
||||||
|
|
||||||
/* Alternative interface: */
|
/* Alternative interface: */
|
||||||
|
Loading…
Reference in New Issue
Block a user