From aaa6b284bd8933502fd8f2ea36698334a8cc974a Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Sun, 11 Dec 2022 22:23:07 +0000 Subject: [PATCH] RC_Channel: add option to support ELRS at 420kbaud --- libraries/RC_Channel/RC_Channel.h | 5 +++++ libraries/RC_Channel/RC_Channels_VarInfo.h | 2 +- 2 files changed, 6 insertions(+), 1 deletion(-) diff --git a/libraries/RC_Channel/RC_Channel.h b/libraries/RC_Channel/RC_Channel.h index 8a8cb2e30f..9e39ea00c9 100644 --- a/libraries/RC_Channel/RC_Channel.h +++ b/libraries/RC_Channel/RC_Channel.h @@ -550,6 +550,10 @@ public: return get_singleton() != nullptr && (_options & uint32_t(Option::CRSF_FM_DISARM_STAR)) != 0; } + bool use_420kbaud_for_elrs(void) const { + return get_singleton() != nullptr && (_options & uint32_t(Option::ELRS_420KBAUD)) != 0; + } + // returns true if overrides should time out. If true is returned // then returned_timeout_ms will contain the timeout in // milliseconds, with 0 meaning overrides are disabled. @@ -626,6 +630,7 @@ protected: MULTI_RECEIVER_SUPPORT = (1U << 10), // allow multiple receivers USE_CRSF_LQ_AS_RSSI = (1U << 11), // returns CRSF link quality as RSSI value, instead of RSSI CRSF_FM_DISARM_STAR = (1U << 12), // when disarmed, add a star at the end of the flight mode in CRSF telemetry + ELRS_420KBAUD = (1U << 13), // use 420kbaud for ELRS protocol }; void new_override_received() { diff --git a/libraries/RC_Channel/RC_Channels_VarInfo.h b/libraries/RC_Channel/RC_Channels_VarInfo.h index 0e1193f362..41fee86789 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,10:Enable multiple receiver support, 11:CRSF RSSI shows Link Quality, 12:CRSF flight mode disarm star + // @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, 11:Use Link Quality for RSSI with CRSF, 12:Annotate CRSF flight mode with * on disarm, 13: Use 420kbaud for ELRS protocol AP_GROUPINFO("_OPTIONS", 33, RC_CHANNELS_SUBCLASS, _options, (uint32_t)RC_Channels::Option::ARMING_CHECK_THROTTLE), // @Param: _PROTOCOLS