mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
SRV_Channel: added k_GPIO and is_GPIO()
This commit is contained in:
parent
a6a18fe193
commit
874757a955
@ -50,6 +50,7 @@ public:
|
||||
|
||||
typedef enum
|
||||
{
|
||||
k_GPIO = -1, ///< used as GPIO pin (input or output)
|
||||
k_none = 0, ///< disabled
|
||||
k_manual = 1, ///< manual, just pass-thru the RC in signal
|
||||
k_flap = 2, ///< flap
|
||||
@ -531,6 +532,11 @@ public:
|
||||
// initialize before any call to push
|
||||
static void init();
|
||||
|
||||
// return true if a channel is set to type GPIO
|
||||
static bool is_GPIO(uint8_t channel) {
|
||||
return channel_function(channel) == SRV_Channel::k_GPIO;
|
||||
}
|
||||
|
||||
private:
|
||||
|
||||
static bool disabled_passthrough;
|
||||
|
Loading…
Reference in New Issue
Block a user