Copter: use new motors arming check

This commit is contained in:
Iampete1 2022-09-04 02:57:03 +01:00 committed by Andrew Tridgell
parent ff94ef1c60
commit b59c179079
2 changed files with 3 additions and 22 deletions

View File

@ -44,7 +44,9 @@ bool AP_Arming_Copter::run_pre_arm_checks(bool display_failure)
}
// always check motors
if (!motor_checks(display_failure)) {
char failure_msg[50] {};
if (!copter.motors->arming_checks(ARRAY_SIZE(failure_msg), failure_msg)) {
check_failed(display_failure, "Motors: %s", failure_msg);
return false;
}
@ -304,26 +306,6 @@ bool AP_Arming_Copter::parameter_checks(bool display_failure)
return true;
}
// check motor setup was successful
bool AP_Arming_Copter::motor_checks(bool display_failure)
{
// check motors initialised correctly
if (!copter.motors->initialised_ok()) {
check_failed(display_failure, "Check firmware or FRAME_CLASS");
return false;
}
// servo_test check
#if FRAME_CONFIG == HELI_FRAME
if (copter.motors->servo_test_running()) {
check_failed(display_failure, "Servo Test is still running");
return false;
}
#endif
return true;
}
bool AP_Arming_Copter::oa_checks(bool display_failure)
{
#if AC_OAPATHPLANNER_ENABLED == ENABLED

View File

@ -42,7 +42,6 @@ protected:
// NOTE! the following check functions *DO NOT* call into AP_Arming!
bool parameter_checks(bool display_failure);
bool motor_checks(bool display_failure);
bool oa_checks(bool display_failure);
bool mandatory_gps_checks(bool display_failure);
bool gcs_failsafe_check(bool display_failure);