mirror of https://github.com/ArduPilot/ardupilot
Copter: remove bogus ARMING_CHECK_NONE 'bitmask value'
This commit is contained in:
parent
c26f98e817
commit
d42c66afcc
|
@ -35,7 +35,7 @@ bool AP_Arming_Copter::run_pre_arm_checks(bool display_failure)
|
|||
// at the same time. This cannot be allowed.
|
||||
if (rc().find_channel_for_option(RC_Channel::AUX_FUNC::MOTOR_INTERLOCK) &&
|
||||
rc().find_channel_for_option(RC_Channel::AUX_FUNC::MOTOR_ESTOP)){
|
||||
check_failed(ARMING_CHECK_NONE, display_failure, "Interlock/E-Stop Conflict");
|
||||
check_failed(display_failure, "Interlock/E-Stop Conflict");
|
||||
return false;
|
||||
}
|
||||
|
||||
|
@ -44,11 +44,11 @@ bool AP_Arming_Copter::run_pre_arm_checks(bool display_failure)
|
|||
// otherwise exit immediately. This check to be repeated,
|
||||
// as state can change at any time.
|
||||
if (copter.ap.using_interlock && copter.ap.motor_interlock_switch) {
|
||||
check_failed(ARMING_CHECK_NONE, display_failure, "Motor Interlock Enabled");
|
||||
check_failed(display_failure, "Motor Interlock Enabled");
|
||||
}
|
||||
|
||||
// succeed if pre arm checks are disabled
|
||||
if (checks_to_perform == ARMING_CHECK_NONE) {
|
||||
if (checks_to_perform == 0) {
|
||||
return true;
|
||||
}
|
||||
|
||||
|
@ -245,7 +245,7 @@ bool AP_Arming_Copter::motor_checks(bool display_failure)
|
|||
{
|
||||
// check motors initialised correctly
|
||||
if (!copter.motors->initialised_ok()) {
|
||||
check_failed(ARMING_CHECK_NONE, display_failure, "check firmware or FRAME_CLASS");
|
||||
check_failed(display_failure, "check firmware or FRAME_CLASS");
|
||||
return false;
|
||||
}
|
||||
|
||||
|
@ -260,11 +260,11 @@ bool AP_Arming_Copter::motor_checks(bool display_failure)
|
|||
}
|
||||
if (tcan_active) {
|
||||
if (copter.motors->get_pwm_output_min() != 1000) {
|
||||
check_failed(ARMING_CHECK_NONE, display_failure, "TCAN ESCs require MOT_PWM_MIN=1000");
|
||||
check_failed(display_failure, "TCAN ESCs require MOT_PWM_MIN=1000");
|
||||
return false;
|
||||
}
|
||||
if (copter.motors->get_pwm_output_max() != 2000) {
|
||||
check_failed(ARMING_CHECK_NONE, display_failure, "TCAN ESCs require MOT_PWM_MAX=2000");
|
||||
check_failed(display_failure, "TCAN ESCs require MOT_PWM_MAX=2000");
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
@ -301,9 +301,9 @@ bool AP_Arming_Copter::oa_checks(bool display_failure)
|
|||
}
|
||||
// display failure
|
||||
if (strlen(failure_msg) == 0) {
|
||||
check_failed(ARMING_CHECK_NONE, display_failure, "%s", "Check Object Avoidance");
|
||||
check_failed(display_failure, "%s", "Check Object Avoidance");
|
||||
} else {
|
||||
check_failed(ARMING_CHECK_NONE, display_failure, "%s", failure_msg);
|
||||
check_failed(display_failure, "%s", failure_msg);
|
||||
}
|
||||
return false;
|
||||
#else
|
||||
|
@ -339,7 +339,7 @@ bool AP_Arming_Copter::gps_checks(bool display_failure)
|
|||
if (reason == nullptr) {
|
||||
reason = "AHRS not healthy";
|
||||
}
|
||||
check_failed(ARMING_CHECK_NONE, display_failure, "%s", reason);
|
||||
check_failed(display_failure, "%s", reason);
|
||||
return false;
|
||||
}
|
||||
|
||||
|
@ -370,7 +370,7 @@ bool AP_Arming_Copter::gps_checks(bool display_failure)
|
|||
reason = "Need 3D Fix";
|
||||
}
|
||||
}
|
||||
check_failed(ARMING_CHECK_NONE, display_failure, "%s", reason);
|
||||
check_failed(display_failure, "%s", reason);
|
||||
return false;
|
||||
}
|
||||
|
||||
|
@ -378,7 +378,7 @@ bool AP_Arming_Copter::gps_checks(bool display_failure)
|
|||
nav_filter_status filt_status;
|
||||
if (ahrs.get_filter_status(filt_status)) {
|
||||
if (filt_status.flags.gps_glitching) {
|
||||
check_failed(ARMING_CHECK_NONE, display_failure, "GPS glitching");
|
||||
check_failed(display_failure, "GPS glitching");
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
@ -389,13 +389,13 @@ bool AP_Arming_Copter::gps_checks(bool display_failure)
|
|||
Vector2f offset;
|
||||
ahrs.get_variances(vel_variance, pos_variance, hgt_variance, mag_variance, tas_variance, offset);
|
||||
if (copter.g.fs_ekf_thresh > 0 && mag_variance.length() >= copter.g.fs_ekf_thresh) {
|
||||
check_failed(ARMING_CHECK_NONE, display_failure, "EKF compass variance");
|
||||
check_failed(display_failure, "EKF compass variance");
|
||||
return false;
|
||||
}
|
||||
|
||||
// check home and EKF origin are not too far
|
||||
if (copter.far_from_EKF_origin(ahrs.get_home())) {
|
||||
check_failed(ARMING_CHECK_NONE, display_failure, "EKF-home variance");
|
||||
check_failed(display_failure, "EKF-home variance");
|
||||
return false;
|
||||
}
|
||||
|
||||
|
@ -499,7 +499,7 @@ bool AP_Arming_Copter::arm_checks(AP_Arming::Method method)
|
|||
|
||||
// always check if inertial nav has started and is ready
|
||||
if (!ahrs.healthy()) {
|
||||
check_failed(ARMING_CHECK_NONE, true, "AHRS not healthy");
|
||||
check_failed(true, "AHRS not healthy");
|
||||
return false;
|
||||
}
|
||||
|
||||
|
@ -509,7 +509,7 @@ bool AP_Arming_Copter::arm_checks(AP_Arming::Method method)
|
|||
const Compass &_compass = AP::compass();
|
||||
// check compass health
|
||||
if (!_compass.healthy()) {
|
||||
check_failed(ARMING_CHECK_NONE, true, "Compass not healthy");
|
||||
check_failed(true, "Compass not healthy");
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
@ -519,7 +519,7 @@ bool AP_Arming_Copter::arm_checks(AP_Arming::Method method)
|
|||
|
||||
// always check if the current mode allows arming
|
||||
if (!copter.flightmode->allows_arming(method == AP_Arming::Method::MAVLINK)) {
|
||||
check_failed(ARMING_CHECK_NONE, true, "Mode not armable");
|
||||
check_failed(true, "Mode not armable");
|
||||
return false;
|
||||
}
|
||||
|
||||
|
@ -531,7 +531,7 @@ bool AP_Arming_Copter::arm_checks(AP_Arming::Method method)
|
|||
// if we are using motor interlock switch and it's enabled, fail to arm
|
||||
// skip check in Throw mode which takes control of the motor interlock
|
||||
if (copter.ap.using_interlock && copter.ap.motor_interlock_switch) {
|
||||
check_failed(ARMING_CHECK_NONE, true, "Motor Interlock Enabled");
|
||||
check_failed(true, "Motor Interlock Enabled");
|
||||
return false;
|
||||
}
|
||||
|
||||
|
@ -546,7 +546,7 @@ bool AP_Arming_Copter::arm_checks(AP_Arming::Method method)
|
|||
}
|
||||
|
||||
// succeed if arming checks are disabled
|
||||
if (checks_to_perform == ARMING_CHECK_NONE) {
|
||||
if (checks_to_perform == 0) {
|
||||
return true;
|
||||
}
|
||||
|
||||
|
@ -600,7 +600,7 @@ bool AP_Arming_Copter::arm_checks(AP_Arming::Method method)
|
|||
|
||||
// check if safety switch has been pushed
|
||||
if (hal.util->safety_switch_state() == AP_HAL::Util::SAFETY_DISARMED) {
|
||||
check_failed(ARMING_CHECK_NONE, true, "Safety Switch");
|
||||
check_failed(true, "Safety Switch");
|
||||
return false;
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue