diff --git a/libraries/RC_Channel/RC_Channel.h b/libraries/RC_Channel/RC_Channel.h index 93bf28b892..fd91aa52d2 100644 --- a/libraries/RC_Channel/RC_Channel.h +++ b/libraries/RC_Channel/RC_Channel.h @@ -477,7 +477,9 @@ public: return get_singleton() != nullptr && (_options & uint32_t(Option::SUPPRESS_CRSF_MESSAGE)); } - + bool allow_rc_protocol_switching() const { + return _options & uint32_t(Option::ALLOW_RC_SWITCHING); + } // returns true if overrides should time out. If true is returned // then returned_timeout_ms will contain the timeout in @@ -537,6 +539,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 + ALLOW_RC_SWITCHING = (1U << 10), // allow switching RC protocols }; void new_override_received() { diff --git a/libraries/RC_Channel/RC_Channels_VarInfo.h b/libraries/RC_Channel/RC_Channels_VarInfo.h index 31b10193cf..09d516ec7a 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/Yay 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/Yay sticks, 7:Allow Switch reverse, 8:Use passthrough for CRSF telemetry, 9:Suppress CRSF mode/rate message for ELRS systems, 10:Enable RC Protocol re-detection AP_GROUPINFO("_OPTIONS", 33, RC_CHANNELS_SUBCLASS, _options, (uint32_t)RC_Channels::Option::ARMING_CHECK_THROTTLE), // @Param: _PROTOCOLS