AP_RCTelemetry: remove intermediate option_is_enabled methods for RC_Channel

This commit is contained in:
Peter Barker 2023-06-11 15:13:42 +10:00 committed by Randy Mackay
parent f75c905d25
commit 8dad537b6f
1 changed files with 7 additions and 7 deletions

View File

@ -100,7 +100,7 @@ void AP_CRSF_Telem::setup_custom_telemetry()
return;
}
if (!rc().crsf_custom_telemetry()) {
if (!rc().option_is_enabled(RC_Channels::Option::CRSF_CUSTOM_TELEMETRY)) {
return;
}
@ -198,7 +198,7 @@ bool AP_CRSF_Telem::process_rf_mode_changes()
gcs().send_text(MAV_SEVERITY_WARNING, "%s: running on non-DMA serial port", get_protocol_string());
}
// note if option was set to show LQ in place of RSSI
bool current_lq_as_rssi_active = bool(rc().use_crsf_lq_as_rssi());
bool current_lq_as_rssi_active = rc().option_is_enabled(RC_Channels::Option::USE_CRSF_LQ_AS_RSSI);
if(_telem_bootstrap_msg_pending || _noted_lq_as_rssi_active != current_lq_as_rssi_active){
_noted_lq_as_rssi_active = current_lq_as_rssi_active;
gcs().send_text(MAV_SEVERITY_INFO, "%s: RSSI now displays %s", get_protocol_string(), current_lq_as_rssi_active ? " as LQ" : "normally");
@ -208,7 +208,7 @@ bool AP_CRSF_Telem::process_rf_mode_changes()
const bool is_high_speed = is_high_speed_telemetry(current_rf_mode);
if ((now - _telem_last_report_ms > 5000)) {
// report an RF mode change or a change in telemetry rate if we haven't done so in the last 5s
if (!rc().suppress_crsf_message() && (_telem_rf_mode != current_rf_mode || abs(int16_t(_telem_last_avg_rate) - int16_t(_scheduler.avg_packet_rate)) > 25)) {
if (!rc().option_is_enabled(RC_Channels::Option::SUPPRESS_CRSF_MESSAGE) && (_telem_rf_mode != current_rf_mode || abs(int16_t(_telem_last_avg_rate) - int16_t(_scheduler.avg_packet_rate)) > 25)) {
gcs().send_text(MAV_SEVERITY_INFO, "%s: Link rate %dHz, Telemetry rate %dHz",
get_protocol_string(), crsf->get_link_rate(_crsf_version.protocol), get_telemetry_rate());
}
@ -302,7 +302,7 @@ void AP_CRSF_Telem::queue_message(MAV_SEVERITY severity, const char *text)
{
// no need to queue status text messages when crossfire
// custom telemetry is not enabled
if (!rc().crsf_custom_telemetry()) {
if (!rc().option_is_enabled(RC_Channels::Option::CRSF_CUSTOM_TELEMETRY)) {
return;
}
AP_RCTelemetry::queue_message(severity, text);
@ -395,9 +395,9 @@ bool AP_CRSF_Telem::is_packet_ready(uint8_t idx, bool queue_empty)
return false;
#endif
case PASSTHROUGH:
return rc().crsf_custom_telemetry();
return rc().option_is_enabled(RC_Channels::Option::CRSF_CUSTOM_TELEMETRY);
case STATUS_TEXT:
return rc().crsf_custom_telemetry() && !queue_empty;
return rc().option_is_enabled(RC_Channels::Option::CRSF_CUSTOM_TELEMETRY) && !queue_empty;
case GENERAL_COMMAND:
return _baud_rate_request.pending;
case VERSION_PING:
@ -947,7 +947,7 @@ void AP_CRSF_Telem::calc_flight_mode()
sizeof(AP_CRSF_Telem::FlightModeFrame),
"%s%s",
notify->get_flight_mode_str(),
rc().crsf_fm_disarm_star() && !hal.util->get_soft_armed() ? "*" : ""
rc().option_is_enabled(RC_Channels::Option::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