mirror of https://github.com/ArduPilot/ardupilot
RC_Channel: allow more libraries to compile with no HAL_GCS_ENABLED
This commit is contained in:
parent
ed5da4ead2
commit
d47a742272
|
@ -702,7 +702,7 @@ void RC_Channel::init_aux_function(const aux_func_t ch_option, const AuxSwitchPo
|
|||
run_aux_function(ch_option, ch_flag, AuxFuncTriggerSource::INIT);
|
||||
break;
|
||||
default:
|
||||
gcs().send_text(MAV_SEVERITY_WARNING, "Failed to init: RC%u_OPTION: %u\n",
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Failed to init: RC%u_OPTION: %u\n",
|
||||
(unsigned)(this->ch_in+1), (unsigned)ch_option);
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
AP_BoardConfig::config_error("Failed to init: RC%u_OPTION: %u",
|
||||
|
@ -830,7 +830,7 @@ bool RC_Channel::read_aux()
|
|||
// announce the change to the GCS:
|
||||
const char *aux_string = string_for_aux_function(_option);
|
||||
if (aux_string != nullptr) {
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "RC%i: %s %s", ch_in+1, aux_string, string_for_aux_pos(new_position));
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "RC%i: %s %s", ch_in+1, aux_string, string_for_aux_pos(new_position));
|
||||
}
|
||||
#endif
|
||||
|
||||
|
@ -870,19 +870,19 @@ void RC_Channel::do_aux_function_avoid_adsb(const AuxSwitchPos ch_flag)
|
|||
}
|
||||
// try to enable AP_Avoidance
|
||||
if (!adsb->enabled() || !adsb->healthy()) {
|
||||
gcs().send_text(MAV_SEVERITY_CRITICAL, "ADSB not available");
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "ADSB not available");
|
||||
return;
|
||||
}
|
||||
avoidance->enable();
|
||||
AP::logger().Write_Event(LogEvent::AVOIDANCE_ADSB_ENABLE);
|
||||
gcs().send_text(MAV_SEVERITY_CRITICAL, "ADSB Avoidance Enabled");
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "ADSB Avoidance Enabled");
|
||||
return;
|
||||
}
|
||||
|
||||
// disable AP_Avoidance
|
||||
avoidance->disable();
|
||||
AP::logger().Write_Event(LogEvent::AVOIDANCE_ADSB_DISABLE);
|
||||
gcs().send_text(MAV_SEVERITY_CRITICAL, "ADSB Avoidance Disabled");
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "ADSB Avoidance Disabled");
|
||||
#endif
|
||||
}
|
||||
|
||||
|
@ -1442,7 +1442,7 @@ bool RC_Channel::do_aux_function(const aux_func_t ch_option, const AuxSwitchPos
|
|||
case AUX_FUNC::OPTFLOW_CAL: {
|
||||
AP_OpticalFlow *optflow = AP::opticalflow();
|
||||
if (optflow == nullptr) {
|
||||
gcs().send_text(MAV_SEVERITY_CRITICAL, "OptFlow Cal: failed sensor not enabled");
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "OptFlow Cal: failed sensor not enabled");
|
||||
break;
|
||||
}
|
||||
if (ch_flag == AuxSwitchPos::HIGH) {
|
||||
|
@ -1574,7 +1574,7 @@ bool RC_Channel::do_aux_function(const aux_func_t ch_option, const AuxSwitchPos
|
|||
const bool autoreboot = false;
|
||||
compass.start_calibration_all(retry, autosave, delay, autoreboot);
|
||||
} else {
|
||||
gcs().send_text(MAV_SEVERITY_NOTICE, "Disarm to allow compass calibration");
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Disarm to allow compass calibration");
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
@ -1646,7 +1646,7 @@ bool RC_Channel::do_aux_function(const aux_func_t ch_option, const AuxSwitchPos
|
|||
break;
|
||||
|
||||
default:
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Invalid channel option (%u)", (unsigned int)ch_option);
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Invalid channel option (%u)", (unsigned int)ch_option);
|
||||
return false;
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue