#include "Copter.h"
#pragma GCC diagnostic push
#if defined(__clang_major__) && __clang_major__ >= 14
#pragma GCC diagnostic ignored "-Wbitwise-instead-of-logical"
#endif
bool AP_Arming_Copter::pre_arm_checks(bool display_failure)
{
const bool passed = run_pre_arm_checks(display_failure);
set_pre_arm_check(passed);
return passed;
}
bool AP_Arming_Copter::run_pre_arm_checks(bool display_failure)
{
if (copter.motors->armed()) {
return true;
}
if (!hal.scheduler->is_system_initialized()) {
check_failed(display_failure, "System not initialised");
return false;
}
bool passed = true;
if (rc().find_channel_for_option(RC_Channel::AUX_FUNC::MOTOR_INTERLOCK) &&
(rc().find_channel_for_option(RC_Channel::AUX_FUNC::MOTOR_ESTOP) ||
rc().find_channel_for_option(RC_Channel::AUX_FUNC::ARM_EMERGENCY_STOP))){
check_failed(display_failure, "Interlock/E-Stop Conflict");
passed = false;
}
if (copter.ap.using_interlock && copter.ap.motor_interlock_switch) {
check_failed(display_failure, "Motor Interlock Enabled");
passed = false;
}
if (!disarm_switch_checks(display_failure)) {
passed = false;
}
char failure_msg[100] {};
if (!copter.motors->arming_checks(ARRAY_SIZE(failure_msg), failure_msg)) {
check_failed(display_failure, "Motors: %s", failure_msg);
passed = false;
}
#if FRAME_CONFIG == HELI_FRAME && MODE_AUTOROTATE_ENABLED
if (!copter.g2.arot.arming_checks(ARRAY_SIZE(failure_msg), failure_msg)) {
check_failed(display_failure, "AROT: %s", failure_msg);
passed = false;
}
#endif
if (!passed) {
return false;
}
if (checks_to_perform == 0) {
return mandatory_checks(display_failure);
}
return parameter_checks(display_failure)
& oa_checks(display_failure)
& gcs_failsafe_check(display_failure)
& winch_checks(display_failure)
& rc_throttle_failsafe_checks(display_failure)
& alt_checks(display_failure)
#if AP_AIRSPEED_ENABLED
& AP_Arming::airspeed_checks(display_failure)
#endif
& AP_Arming::pre_arm_checks(display_failure);
}
bool AP_Arming_Copter::rc_throttle_failsafe_checks(bool display_failure) const
{
if (!check_enabled(Check::RC)) {
return true;
}
if (copter.g.failsafe_throttle == FS_THR_DISABLED) {
return true;
}
#if FRAME_CONFIG == HELI_FRAME
const char *rc_item = "Collective";
#else
const char *rc_item = "Throttle";
#endif
if (!rc().has_had_rc_receiver() && !rc().has_had_rc_override()) {
check_failed(Check::RC, display_failure, "RC not found");
return false;
}
if (copter.channel_throttle->get_radio_in() < copter.g.failsafe_throttle_value) {
check_failed(Check::RC, display_failure, "%s below failsafe", rc_item);
return false;
}
return true;
}
bool AP_Arming_Copter::barometer_checks(bool display_failure)
{
if (!AP_Arming::barometer_checks(display_failure)) {
return false;
}
bool ret = true;
if (check_enabled(Check::BARO)) {
const auto &ahrs = AP::ahrs();
const bool using_baro_ref = !ahrs.has_status(AP_AHRS::Status::PRED_HORIZ_POS_REL) && ahrs.has_status(AP_AHRS::Status::PRED_HORIZ_POS_ABS);
float pos_d_m = 0;
UNUSED_RESULT(AP::ahrs().get_relative_position_D_origin_float(pos_d_m));
if (using_baro_ref) {
if (fabsf(-pos_d_m - copter.baro_alt_m) > PREARM_MAX_ALT_DISPARITY_M) {
check_failed(Check::BARO, display_failure, "Altitude disparity");
ret = false;
}
}
}
return ret;
}
bool AP_Arming_Copter::ins_checks(bool display_failure)
{
bool ret = AP_Arming::ins_checks(display_failure);
if (check_enabled(Check::INS)) {
if (!pre_arm_ekf_attitude_check()) {
check_failed(Check::INS, display_failure, "EKF attitude is bad");
ret = false;
}
}
return ret;
}
bool AP_Arming_Copter::board_voltage_checks(bool display_failure)
{
if (!AP_Arming::board_voltage_checks(display_failure)) {
return false;
}
if (check_enabled(Check::VOLTAGE)) {
if (copter.battery.has_failsafed()) {
check_failed(Check::VOLTAGE, display_failure, "Battery failsafe");
return false;
}
}
return true;
}
bool AP_Arming_Copter::terrain_database_required() const
{
if (copter.wp_nav->get_terrain_source() == AC_WPNav::TerrainSource::TERRAIN_FROM_RANGEFINDER) {
return false;
}
if (copter.wp_nav->get_terrain_source() == AC_WPNav::TerrainSource::TERRAIN_FROM_TERRAINDATABASE &&
copter.mode_rtl.get_alt_type() == ModeRTL::RTLAltType::TERRAIN) {
return true;
}
return AP_Arming::terrain_database_required();
}
bool AP_Arming_Copter::parameter_checks(bool display_failure)
{
if (check_enabled(Check::PARAMETERS)) {
if (copter.g.failsafe_throttle) {
if (copter.channel_throttle->get_radio_min() <= copter.g.failsafe_throttle_value+10 || copter.g.failsafe_throttle_value < 910) {
check_failed(Check::PARAMETERS, display_failure, "Check FS_THR_VALUE");
return false;
}
}
if (copter.g.failsafe_gcs == FS_GCS_ENABLED_CONTINUE_MISSION) {
check_failed(Check::PARAMETERS, display_failure, "FS_GCS_ENABLE=2 removed, see FS_OPTIONS");
}
if (copter.aparm.angle_max < 1000 || copter.aparm.angle_max > 8000) {
check_failed(Check::PARAMETERS, display_failure, "Check ANGLE_MAX");
return false;
}
#if MODE_ACRO_ENABLED || MODE_SPORT_ENABLED
if ((copter.g.acro_balance_roll > copter.attitude_control->get_angle_roll_p().kP()) || (copter.g.acro_balance_pitch > copter.attitude_control->get_angle_pitch_p().kP())) {
check_failed(Check::PARAMETERS, display_failure, "Check ACRO_BAL_ROLL/PITCH");
return false;
}
#endif
if (copter.g.pilot_speed_up_cms <= 0) {
check_failed(Check::PARAMETERS, display_failure, "Check PILOT_SPEED_UP");
return false;
}
#if FRAME_CONFIG == HELI_FRAME
char fail_msg[100]{};
if (!copter.input_manager.parameter_check(fail_msg, ARRAY_SIZE(fail_msg))) {
check_failed(Check::PARAMETERS, display_failure, "%s", fail_msg);
return false;
}
if (rc().find_channel_for_option(RC_Channel::AUX_FUNC::MOTOR_INTERLOCK) == nullptr) {
check_failed(Check::PARAMETERS, display_failure, "Motor Interlock not configured");
return false;
}
#else
switch (copter.g2.frame_class.get()) {
case AP_Motors::MOTOR_FRAME_HELI_QUAD:
case AP_Motors::MOTOR_FRAME_HELI_DUAL:
case AP_Motors::MOTOR_FRAME_HELI:
check_failed(Check::PARAMETERS, display_failure, "Invalid MultiCopter FRAME_CLASS");
return false;
default:
break;
}
#endif
#if MODE_RTL_ENABLED
if (copter.mode_rtl.get_alt_type() == ModeRTL::RTLAltType::TERRAIN) {
const char *failure_template = "RTL_ALT_TYPE is above-terrain but %s";
switch (copter.wp_nav->get_terrain_source()) {
case AC_WPNav::TerrainSource::TERRAIN_UNAVAILABLE:
check_failed(Check::PARAMETERS, display_failure, failure_template, "no terrain data");
return false;
break;
case AC_WPNav::TerrainSource::TERRAIN_FROM_RANGEFINDER:
#if AP_RANGEFINDER_ENABLED
if (!copter.rangefinder_state.enabled || !copter.rangefinder.has_orientation(ROTATION_PITCH_270)) {
check_failed(Check::PARAMETERS, display_failure, failure_template, "no rangefinder");
return false;
}
if (copter.g.rtl_altitude_cm > copter.rangefinder.max_distance_orient(ROTATION_PITCH_270) * 100) {
check_failed(Check::PARAMETERS, display_failure, failure_template, "RTL_ALT (in cm) above RNGFND_MAX (in metres)");
return false;
}
#else
check_failed(Check::PARAMETERS, display_failure, failure_template, "rangefinder not in firmware");
#endif
break;
case AC_WPNav::TerrainSource::TERRAIN_FROM_TERRAINDATABASE:
break;
}
}
#endif
#if HAL_ADSB_ENABLED
if (copter.failsafe.adsb) {
check_failed(Check::PARAMETERS, display_failure, "ADSB threat detected");
return false;
}
#endif
char failure_msg[100] = {};
if (!copter.pos_control->pre_arm_checks("PSC", failure_msg, ARRAY_SIZE(failure_msg))) {
check_failed(Check::PARAMETERS, display_failure, "Bad parameter: %s", failure_msg);
return false;
}
if (!copter.attitude_control->pre_arm_checks("ATC", failure_msg, ARRAY_SIZE(failure_msg))) {
check_failed(Check::PARAMETERS, display_failure, "Bad parameter: %s", failure_msg);
return false;
}
}
return true;
}
bool AP_Arming_Copter::oa_checks(bool display_failure)
{
#if AP_OAPATHPLANNER_ENABLED
char failure_msg[100] = {};
if (copter.g2.oa.pre_arm_check(failure_msg, ARRAY_SIZE(failure_msg))) {
return true;
}
if (strlen(failure_msg) == 0) {
check_failed(display_failure, "%s", "Check Object Avoidance");
} else {
check_failed(display_failure, "%s", failure_msg);
}
return false;
#else
return true;
#endif
}
bool AP_Arming_Copter::rc_calibration_checks(bool display_failure)
{
const RC_Channel *channels[] = {
copter.channel_roll,
copter.channel_pitch,
copter.channel_throttle,
copter.channel_yaw
};
copter.ap.pre_arm_rc_check = rc_checks_copter_sub(display_failure, channels)
& AP_Arming::rc_calibration_checks(display_failure);
return copter.ap.pre_arm_rc_check;
}
bool AP_Arming_Copter::gps_checks(bool display_failure)
{
bool fence_requires_gps = false;
#if AP_FENCE_ENABLED
fence_requires_gps = (copter.fence.get_enabled_fences() & (AC_FENCE_TYPE_CIRCLE | AC_FENCE_TYPE_POLYGON)) > 0;
#endif
bool mode_requires_gps = copter.flightmode->requires_GPS() || fence_requires_gps || (copter.simple_mode == Copter::SimpleMode::SUPERSIMPLE);
if (mode_requires_gps) {
if (!AP_Arming::gps_checks(display_failure)) {
AP_Notify::flags.pre_arm_gps_check = false;
return false;
}
}
if (!mandatory_gps_checks(display_failure)) {
AP_Notify::flags.pre_arm_gps_check = false;
return false;
}
if (!mode_requires_gps) {
AP_Notify::flags.pre_arm_gps_check = true;
return true;
}
if (!check_enabled(Check::GPS)) {
AP_Notify::flags.pre_arm_gps_check = true;
return true;
}
if ((copter.gps.num_sensors() > 0) && (copter.gps.get_hdop() > copter.g.gps_hdop_good)) {
check_failed(Check::GPS, display_failure, "High GPS HDOP");
AP_Notify::flags.pre_arm_gps_check = false;
return false;
}
AP_Notify::flags.pre_arm_gps_check = true;
return true;
}
bool AP_Arming_Copter::pre_arm_ekf_attitude_check()
{
return AP::ahrs().has_status(AP_AHRS::Status::ATTITUDE_VALID);
}
#if HAL_PROXIMITY_ENABLED
bool AP_Arming_Copter::proximity_checks(bool display_failure) const
{
if (!AP_Arming::proximity_checks(display_failure)) {
return false;
}
if (!check_enabled(Check::PARAMETERS)) {
return true;
}
#if AP_AVOIDANCE_ENABLED
float angle_deg, distance;
if (copter.avoid.proximity_avoidance_enabled() && copter.g2.proximity.get_closest_object(angle_deg, distance)) {
const float tolerance = 0.6f;
if (distance <= tolerance) {
check_failed(Check::PARAMETERS, display_failure, "Proximity %d deg, %4.2fm (want > %0.1fm)", (int)angle_deg, (double)distance, (double)tolerance);
return false;
}
}
#endif
return true;
}
#endif
bool AP_Arming_Copter::mandatory_gps_checks(bool display_failure)
{
bool mode_requires_gps = copter.flightmode->requires_GPS();
const auto &ahrs = AP::ahrs();
char failure_msg[100] = {};
if (!ahrs.pre_arm_check(mode_requires_gps, failure_msg, sizeof(failure_msg))) {
check_failed(display_failure, "AHRS: %s", failure_msg);
return false;
}
bool fence_requires_gps = false;
#if AP_FENCE_ENABLED
fence_requires_gps = (copter.fence.get_enabled_fences() & (AC_FENCE_TYPE_CIRCLE | AC_FENCE_TYPE_POLYGON)) > 0;
#endif
if (mode_requires_gps || require_location == RequireLocation::YES) {
if (!copter.position_ok()) {
check_failed(display_failure, "Need Position Estimate");
return false;
}
} else if (fence_requires_gps) {
if (!copter.position_ok()) {
check_failed(display_failure, "Fence enabled, need position estimate");
return false;
}
} else {
return true;
}
nav_filter_status filt_status;
if (ahrs.get_filter_status(filt_status)) {
if (filt_status.flags.gps_glitching) {
check_failed(display_failure, "GPS glitching");
return false;
}
}
if (copter.g.fs_ekf_thresh > 0.0f) {
float vel_variance, pos_variance, hgt_variance, tas_variance;
Vector3f mag_variance;
ahrs.get_variances(vel_variance, pos_variance, hgt_variance, mag_variance, tas_variance);
const struct {
const char *name;
float value;
} variances[] {
{ "compass", mag_variance.length() },
{ "position", pos_variance },
{ "velocity", vel_variance },
{ "height", hgt_variance },
};
for (auto &variance : variances) {
if (variance.value < copter.g.fs_ekf_thresh) {
continue;
}
check_failed(display_failure, "EKF %s variance", variance.name);
return false;
}
}
return true;
}
bool AP_Arming_Copter::gcs_failsafe_check(bool display_failure)
{
if (copter.failsafe.gcs) {
check_failed(display_failure, "GCS failsafe on");
return false;
}
return true;
}
bool AP_Arming_Copter::winch_checks(bool display_failure) const
{
#if AP_WINCH_ENABLED
if (!check_enabled(Check::PARAMETERS)) {
return true;
}
const AP_Winch *winch = AP::winch();
if (winch == nullptr) {
return true;
}
char failure_msg[100] = {};
if (!winch->pre_arm_check(failure_msg, sizeof(failure_msg))) {
check_failed(display_failure, "%s", failure_msg);
return false;
}
#endif
return true;
}
bool AP_Arming_Copter::alt_checks(bool display_failure)
{
if (!copter.flightmode->has_manual_throttle() && !copter.ekf_alt_ok()) {
check_failed(display_failure, "Need Alt Estimate");
return false;
}
return true;
}
bool AP_Arming_Copter::arm_checks(AP_Arming::Method method)
{
const auto &ahrs = AP::ahrs();
if (!ahrs.healthy()) {
check_failed(true, "AHRS not healthy");
return false;
}
#ifndef ALLOW_ARM_NO_COMPASS
if (!ahrs.using_noncompass_for_yaw()) {
const Compass &_compass = AP::compass();
if (!_compass.healthy()) {
check_failed(true, "Compass not healthy");
return false;
}
}
#endif
if (!copter.flightmode->allows_arming(method)) {
check_failed(true, "%s mode not armable", copter.flightmode->name());
return false;
}
if (checks_to_perform == 0) {
return true;
}
if (check_enabled(Check::INS)) {
if (degrees(acosf(ahrs.cos_roll()*ahrs.cos_pitch()))*100.0f > copter.aparm.angle_max) {
check_failed(Check::INS, true, "Leaning");
return false;
}
}
#if HAL_ADSB_ENABLED
if (check_enabled(Check::PARAMETERS)) {
if (copter.failsafe.adsb) {
check_failed(Check::PARAMETERS, true, "ADSB threat detected");
return false;
}
}
#endif
if (check_enabled(Check::RC)) {
#if FRAME_CONFIG == HELI_FRAME
const char *rc_item = "Collective";
#else
const char *rc_item = "Throttle";
#endif
if (!((AP_Arming::method_is_GCS(method) || method == AP_Arming::Method::SCRIPTING) && copter.flightmode->allows_GCS_or_SCR_arming_with_throttle_high())) {
if (copter.get_pilot_desired_climb_rate_ms() > 0.0f) {
check_failed(Check::RC, true, "%s too high", rc_item);
return false;
}
#if FRAME_CONFIG != HELI_FRAME
if ((copter.flightmode->has_manual_throttle() || copter.flightmode->mode_number() == Mode::Number::DRIFT) && copter.channel_throttle->get_control_in() > 0) {
check_failed(Check::RC, true, "%s too high", rc_item);
return false;
}
#endif
}
}
if (hal.util->safety_switch_state() == AP_HAL::Util::SAFETY_DISARMED) {
check_failed(true, "Safety Switch");
return false;
}
return AP_Arming::arm_checks(method);
}
bool AP_Arming_Copter::mandatory_checks(bool display_failure)
{
bool result = mandatory_gps_checks(display_failure);
AP_Notify::flags.pre_arm_gps_check = result;
if (!alt_checks(display_failure)) {
result = false;
}
return result & AP_Arming::mandatory_checks(display_failure);
}
void AP_Arming_Copter::set_pre_arm_check(bool b)
{
copter.ap.pre_arm_check = b;
AP_Notify::flags.pre_arm_check = b;
}
bool AP_Arming_Copter::arm(const AP_Arming::Method method, const bool do_arming_checks)
{
static bool in_arm_motors = false;
if (in_arm_motors) {
return false;
}
in_arm_motors = true;
if (copter.motors->armed()) {
in_arm_motors = false;
return true;
}
if (!AP_Arming::arm(method, do_arming_checks)) {
AP_Notify::events.arming_failed = true;
in_arm_motors = false;
return false;
}
#if HAL_LOGGING_ENABLED
AP::logger().set_vehicle_armed(true);
#endif
copter.failsafe_disable();
AP_Notify::flags.armed = true;
for (uint8_t i=0; i<=10; i++) {
AP::notify().update();
}
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
send_arm_disarm_statustext("Arming motors");
#endif
copter.init_simple_bearing();
auto &ahrs = AP::ahrs();
copter.initial_armed_bearing_rad = ahrs.get_yaw_rad();
if (!ahrs.home_is_set()) {
ahrs.resetHeightDatum();
LOGGER_WRITE_EVENT(LogEvent::EKF_ALT_RESET);
copter.arming_altitude_m = 0;
} else if (!ahrs.home_is_locked()) {
if (!copter.set_home_to_current_location(false)) {
}
float pos_d_m = 0;
UNUSED_RESULT(AP::ahrs().get_relative_position_D_origin_float(pos_d_m));
copter.arming_altitude_m = -pos_d_m;
}
copter.update_super_simple_bearing(false);
#if MODE_SMARTRTL_ENABLED
copter.g2.smart_rtl.set_home(copter.position_ok());
#endif
hal.util->set_soft_armed(true);
#if HAL_SPRAYER_ENABLED
copter.sprayer.test_pump(false);
#endif
copter.motors->output_min();
copter.motors->armed(true);
#if HAL_LOGGING_ENABLED
AP::logger().Write_Mode((uint8_t)copter.flightmode->mode_number(), copter.control_mode_reason);
#endif
copter.failsafe_enable();
AP::scheduler().perf_info.ignore_this_loop();
in_arm_motors = false;
copter.arm_time_ms = millis();
copter.ap.in_arming_delay = true;
copter.ap.armed_with_airmode_switch = false;
return true;
}
bool AP_Arming_Copter::disarm(const AP_Arming::Method method, bool do_disarm_checks)
{
if (!copter.motors->armed()) {
return true;
}
if (do_disarm_checks &&
AP_Arming::method_is_GCS(method) &&
!copter.ap.land_complete) {
return false;
}
if (method == AP_Arming::Method::RUDDER) {
if (!copter.flightmode->has_manual_throttle() && !copter.ap.land_complete) {
return false;
}
}
if (!AP_Arming::disarm(method, do_disarm_checks)) {
return false;
}
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
send_arm_disarm_statustext("Disarming motors");
#endif
auto &ahrs = AP::ahrs();
Compass &compass = AP::compass();
if (ahrs.use_compass() && compass.get_learn_type() == Compass::LearnType::COPY_FROM_EKF) {
for(uint8_t i=0; i<COMPASS_MAX_INSTANCES; i++) {
Vector3f magOffsets;
if (ahrs.getMagOffsets(i, magOffsets)) {
compass.set_and_save_offsets(i, magOffsets);
}
}
}
copter.set_land_complete(true);
copter.set_land_complete_maybe(true);
copter.motors->armed(false);
#if MODE_AUTO_ENABLED
copter.mode_auto.mission.reset();
#endif
#if HAL_LOGGING_ENABLED
AP::logger().set_vehicle_armed(false);
#endif
hal.util->set_soft_armed(false);
copter.ap.in_arming_delay = false;
#if AUTOTUNE_ENABLED
copter.mode_autotune.autotune.disarmed(copter.flightmode == &copter.mode_autotune);
#endif
return true;
}
#pragma GCC diagnostic pop