From 959e3da406a2297cad6175261921277e3ffceb5c Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 13 Aug 2020 12:28:28 +1000 Subject: [PATCH] RC_Channel: added RC_PROTOCOLS mask allows selection of supported protocols --- libraries/RC_Channel/RC_Channel.h | 4 ++++ libraries/RC_Channel/RC_Channels.cpp | 9 +++++++++ libraries/RC_Channel/RC_Channels_VarInfo.h | 7 +++++++ 3 files changed, 20 insertions(+) diff --git a/libraries/RC_Channel/RC_Channel.h b/libraries/RC_Channel/RC_Channel.h index f2ebeb4485..851c2bbaf5 100644 --- a/libraries/RC_Channel/RC_Channel.h +++ b/libraries/RC_Channel/RC_Channel.h @@ -419,6 +419,9 @@ public: return _override_timeout.get() * 1e3f; } + // get mask of enabled protocols + uint32_t enabled_protocols() const; + // returns true if we have had a direct detach RC reciever, does not include overrides bool has_had_rc_receiver() const { return _has_had_rc_receiver; } @@ -459,6 +462,7 @@ private: AP_Float _override_timeout; AP_Int32 _options; + AP_Int32 _protocols; // flight_mode_channel_number must be overridden in vehicle specific code virtual int8_t flight_mode_channel_number() const = 0; diff --git a/libraries/RC_Channel/RC_Channels.cpp b/libraries/RC_Channel/RC_Channels.cpp index b70eccdf42..b53f7cb2ce 100644 --- a/libraries/RC_Channel/RC_Channels.cpp +++ b/libraries/RC_Channel/RC_Channels.cpp @@ -224,6 +224,15 @@ bool RC_Channels::get_pwm(uint8_t c, uint16_t &pwm) const return true; } +// return mask of enabled protocols. +uint32_t RC_Channels::enabled_protocols() const +{ + if (_singleton == nullptr) { + // for example firmware + return 1U; + } + return uint32_t(_protocols.get()); +} // singleton instance RC_Channels *RC_Channels::_singleton; diff --git a/libraries/RC_Channel/RC_Channels_VarInfo.h b/libraries/RC_Channel/RC_Channels_VarInfo.h index 1bfc1b9910..4d3a143cbd 100644 --- a/libraries/RC_Channel/RC_Channels_VarInfo.h +++ b/libraries/RC_Channel/RC_Channels_VarInfo.h @@ -92,5 +92,12 @@ const AP_Param::GroupInfo RC_Channels::var_info[] = { // @Bitmask: 0:Ignore RC Receiver, 1:Ignore MAVLink Overrides, 2:Ignore Receiver Failsafe, 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 AP_GROUPINFO("_OPTIONS", 33, RC_CHANNELS_SUBCLASS, _options, (uint32_t)RC_Channels::Option::ARMING_CHECK_THROTTLE), + // @Param: _PROTOCOLS + // @DisplayName: RC protocols enabled + // @Description: Bitmask of enabled RC protocols. Allows narrowing the protocol detection to only specific types of RC receivers which can avoid issues with incorrect detection. Set to 1 to enable all protocols. + // @User: Advanced + // @Bitmask: 0:All,1:PPM,2:IBUS,3:SBUS,4:SBUS_NI,5:DSM,6:SUMD,7:SRXL,8:SRXL2,9:CRSF,10:ST24,11:FPORT + AP_GROUPINFO("_PROTOCOLS", 34, RC_CHANNELS_SUBCLASS, _protocols, 1), + AP_GROUPEND };