RC_Channel: fix ELRS systems spamming CRSF mode/rate messages

This commit is contained in:
Hwurzburg 2021-07-12 13:24:51 -05:00 committed by Randy Mackay
parent f3e0a9e848
commit e1cf91af15
2 changed files with 7 additions and 1 deletions

View File

@ -473,6 +473,11 @@ public:
return _options & uint32_t(Option::ARMING_SKIP_CHECK_RPY);
}
bool suppress_crsf_message(void) const {
return get_singleton() != nullptr && (_options & uint32_t(Option::SUPPRESS_CRSF_MESSAGE));
}
// returns true if overrides should time out. If true is returned
// then returned_timeout_ms will contain the timeout in
@ -531,6 +536,7 @@ protected:
ARMING_SKIP_CHECK_RPY = (1U << 6), // skip the an arming checks for the roll/pitch/yaw channels
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
};
void new_override_received() {

View File

@ -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
// @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
AP_GROUPINFO("_OPTIONS", 33, RC_CHANNELS_SUBCLASS, _options, (uint32_t)RC_Channels::Option::ARMING_CHECK_THROTTLE),
// @Param: _PROTOCOLS