Copter: factor pre-arm checks, continue testing after a failure

The functional change here is that we continue to run later checks
when a check fails.

The user-visible effect of that is that your GCS will tell you about
all pre-arm failures, not just the first.

This makes things work a little more like Plane, in preparation for
using AP_Arming.
This commit is contained in:
Peter Barker 2016-08-15 22:02:48 +10:00 committed by Lucas De Marchi
parent 08ef3271c1
commit f67d247a46
2 changed files with 62 additions and 0 deletions

View File

@ -635,6 +635,15 @@ private:
void set_land_complete_maybe(bool b);
void set_pre_arm_check(bool b);
void set_pre_arm_rc_check(bool b);
bool rc_calibration_checks(bool display_failure);
bool gps_checks(bool display_failure);
bool fence_checks(bool display_failure);
bool compass_checks(bool display_failure);
bool ins_checks(bool display_failure);
bool board_voltage_checks(bool display_failure);
bool parameter_checks(bool display_failure);
bool pilot_throttle_checks(bool display_failure);
bool barometer_checks(bool display_failure);
void update_using_interlock();
void set_motor_emergency_stop(bool b);
float get_smoothing_gain();

View File

@ -75,6 +75,22 @@ bool Copter::pre_arm_checks(bool display_failure)
return true;
}
bool ret = true;
ret &= barometer_checks(display_failure);
ret &= rc_calibration_checks(display_failure);
ret &= compass_checks(display_failure);
ret &= gps_checks(display_failure);
ret &= fence_checks(display_failure);
ret &= ins_checks(display_failure);
ret &= board_voltage_checks(display_failure);
ret &= parameter_checks(display_failure);
ret &= pilot_throttle_checks(display_failure);
return ret;
}
bool Copter::rc_calibration_checks(bool display_failure)
{
// pre-arm rc checks a prerequisite
pre_arm_rc_checks();
if (!ap.pre_arm_rc_check) {
@ -83,6 +99,11 @@ bool Copter::pre_arm_checks(bool display_failure)
}
return false;
}
return true;
}
bool Copter::barometer_checks(bool display_failure)
{
// check Baro
if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_BARO)) {
// barometer health check
@ -106,7 +127,11 @@ bool Copter::pre_arm_checks(bool display_failure)
}
}
}
return true;
}
bool Copter::compass_checks(bool display_failure)
{
// check Compass
if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_COMPASS)) {
//check if compass has calibrated and requires reboot
@ -161,11 +186,20 @@ bool Copter::pre_arm_checks(bool display_failure)
}
return true;
}
bool Copter::gps_checks(bool display_failure)
{
// check GPS
if (!pre_arm_gps_checks(display_failure)) {
return false;
}
return true;
}
bool Copter::fence_checks(bool display_failure)
{
#if AC_FENCE == ENABLED
// check fence is initialised
if (!fence.pre_arm_check()) {
@ -175,7 +209,11 @@ bool Copter::pre_arm_checks(bool display_failure)
return false;
}
#endif
return true;
}
bool Copter::ins_checks(bool display_failure)
{
// check INS
if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_INS)) {
// check accelerometers have been calibrated
@ -261,6 +299,11 @@ bool Copter::pre_arm_checks(bool display_failure)
return false;
}
}
return true;
}
bool Copter::board_voltage_checks(bool display_failure)
{
#if CONFIG_HAL_BOARD != HAL_BOARD_VRBRAIN
#ifndef CONFIG_ARCH_BOARD_PX4FMU_V1
// check board voltage
@ -285,6 +328,11 @@ bool Copter::pre_arm_checks(bool display_failure)
}
}
return true;
}
bool Copter::parameter_checks(bool display_failure)
{
// check various parameter values
if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_PARAMETERS)) {
@ -353,6 +401,11 @@ bool Copter::pre_arm_checks(bool display_failure)
}
}
return true;
}
bool Copter::pilot_throttle_checks(bool display_failure)
{
// check throttle is above failsafe throttle
// this is near the bottom to allow other failures to be displayed before checking pilot throttle
if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_RC)) {