Copter: always check GPS before arming in Loiter

This commit is contained in:
Randy Mackay 2015-08-26 12:54:14 +09:00
parent 749c0c190f
commit 920d5cefbb
1 changed files with 11 additions and 11 deletions

View File

@ -627,12 +627,6 @@ bool Copter::pre_arm_gps_checks(bool display_failure)
return false;
}
// return true immediately if gps check is disabled
if (!(g.arming_check == ARMING_CHECK_ALL || g.arming_check & ARMING_CHECK_GPS)) {
AP_Notify::flags.pre_arm_gps_check = true;
return true;
}
// check if flight mode requires GPS
bool gps_required = mode_requires_GPS(control_mode);
@ -667,6 +661,12 @@ bool Copter::pre_arm_gps_checks(bool display_failure)
return false;
}
// return true immediately if gps check is disabled
if (!(g.arming_check == ARMING_CHECK_ALL || g.arming_check & ARMING_CHECK_GPS)) {
AP_Notify::flags.pre_arm_gps_check = true;
return true;
}
// warn about hdop separately - to prevent user confusion with no gps lock
if (gps.get_hdop() > g.gps_hdop_good) {
if (display_failure) {
@ -723,6 +723,11 @@ bool Copter::arm_checks(bool display_failure, bool arming_from_gcs)
return false;
}
// always check gps
if (!pre_arm_gps_checks(display_failure)) {
return false;
}
// always check if rotor is spinning on heli
#if FRAME_CONFIG == HELI_FRAME
// heli specific arming check
@ -761,11 +766,6 @@ bool Copter::arm_checks(bool display_failure, bool arming_from_gcs)
}
}
// check gps
if (!pre_arm_gps_checks(display_failure)) {
return false;
}
#if AC_FENCE == ENABLED
// check vehicle is within fence
if(!fence.pre_arm_check()) {