Copter: skip pre-arm checks when already armed

This commit is contained in:
Randy Mackay 2014-12-26 21:52:04 +09:00
parent 4033f11a3c
commit 105e2e19ac
1 changed files with 6 additions and 0 deletions

View File

@ -215,7 +215,13 @@ static bool init_arm_motors()
// perform pre-arm checks and set ap.pre_arm_check flag
static void pre_arm_checks(bool display_failure)
{
// exit immediately if already armed
if (motors.armed()) {
return;
}
// exit immediately if we've already successfully performed the pre-arm check
// run gps checks because results may change and affect LED colour
if (ap.pre_arm_check) {
pre_arm_gps_checks(display_failure);
return;