From 6c2689fef2f5d6d460ebdb4d2158237399f3f1f3 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 11 Oct 2021 09:32:03 +1100 Subject: [PATCH] RC_Channel: added RC_OPTION bit for allowing RC protocol switching this is meant to prevent accidential switching to a disconnected pin --- libraries/RC_Channel/RC_Channel.h | 5 ++++- libraries/RC_Channel/RC_Channels_VarInfo.h | 2 +- 2 files changed, 5 insertions(+), 2 deletions(-) diff --git a/libraries/RC_Channel/RC_Channel.h b/libraries/RC_Channel/RC_Channel.h index 9fdc7721ea..66ca9e6f0f 100644 --- a/libraries/RC_Channel/RC_Channel.h +++ b/libraries/RC_Channel/RC_Channel.h @@ -496,7 +496,9 @@ public: return get_singleton() != nullptr && (_options & uint32_t(Option::SUPPRESS_CRSF_MESSAGE)); } - + bool multiple_receiver_support() const { + return _options & uint32_t(Option::MULTI_RECEIVER_SUPPORT); + } // returns true if overrides should time out. If true is returned // then returned_timeout_ms will contain the timeout in @@ -556,6 +558,7 @@ protected: ALLOW_SWITCH_REV = (1U << 7), // honor the reversed flag on switches CRSF_CUSTOM_TELEMETRY = (1U << 8), // use passthrough data for crsf telemetry SUPPRESS_CRSF_MESSAGE = (1U << 9), // suppress CRSF mode/rate message for ELRS systems + MULTI_RECEIVER_SUPPORT = (1U << 10), // allow multiple receivers }; void new_override_received() { diff --git a/libraries/RC_Channel/RC_Channels_VarInfo.h b/libraries/RC_Channel/RC_Channels_VarInfo.h index fedf8c6a6a..e9baf64ae9 100644 --- a/libraries/RC_Channel/RC_Channels_VarInfo.h +++ b/libraries/RC_Channel/RC_Channels_VarInfo.h @@ -89,7 +89,7 @@ const AP_Param::GroupInfo RC_Channels::var_info[] = { // @DisplayName: RC options // @Description: RC input options // @User: Advanced - // @Bitmask: 0:Ignore RC Receiver, 1:Ignore MAVLink Overrides, 2:Ignore Receiver Failsafe bit but allow other RC failsafes if setup, 3:FPort Pad, 4:Log RC input bytes, 5:Arming check throttle for 0 input, 6:Skip the arming check for neutral Roll/Pitch/Yaw sticks, 7:Allow Switch reverse, 8:Use passthrough for CRSF telemetry, 9:Suppress CRSF mode/rate message for ELRS systems + // @Bitmask: 0:Ignore RC Receiver, 1:Ignore MAVLink Overrides, 2:Ignore Receiver Failsafe bit but allow other RC failsafes if setup, 3:FPort Pad, 4:Log RC input bytes, 5:Arming check throttle for 0 input, 6:Skip the arming check for neutral Roll/Pitch/Yaw sticks, 7:Allow Switch reverse, 8:Use passthrough for CRSF telemetry, 9:Suppress CRSF mode/rate message for ELRS systems,10:Enable multiple receiver support AP_GROUPINFO("_OPTIONS", 33, RC_CHANNELS_SUBCLASS, _options, (uint32_t)RC_Channels::Option::ARMING_CHECK_THROTTLE), // @Param: _PROTOCOLS