Add RC_OPTIONS feature gating of crsf flight mode star

This commit is contained in:
Mingchen Zhang 2022-11-21 00:27:06 -08:00 committed by Andrew Tridgell
parent ad6355c029
commit bb18372d95
3 changed files with 7 additions and 2 deletions

View File

@ -921,7 +921,7 @@ void AP_CRSF_Telem::calc_flight_mode()
sizeof(AP_CRSF_Telem::FlightModeFrame),
"%s%s",
notify->get_flight_mode_str(),
hal.util->get_soft_armed() ? "" : "*"
rc().crsf_fm_disarm_star() && !hal.util->get_soft_armed() ? "*" : ""
);
// Note: strlen(_telem.bcast.flightmode.flight_mode) is safe because called on a guaranteed null terminated string
_telem_size = strlen(_telem.bcast.flightmode.flight_mode) + 1; //send the terminator as well

View File

@ -545,6 +545,10 @@ public:
return get_singleton() != nullptr && (_options & uint32_t(Option::USE_CRSF_LQ_AS_RSSI)) != 0;
}
bool crsf_fm_disarm_star(void) const {
return get_singleton() != nullptr && (_options & uint32_t(Option::CRSF_FM_DISARM_STAR)) != 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.
@ -620,6 +624,7 @@ protected:
SUPPRESS_CRSF_MESSAGE = (1U << 9), // suppress CRSF mode/rate message for ELRS systems
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
};
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/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
// @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
AP_GROUPINFO("_OPTIONS", 33, RC_CHANNELS_SUBCLASS, _options, (uint32_t)RC_Channels::Option::ARMING_CHECK_THROTTLE),
// @Param: _PROTOCOLS