mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 01:18:29 -04:00
Copter: do common gps arming checks first before moving on
This commit is contained in:
parent
5074b6d336
commit
da7d34224d
@ -417,15 +417,6 @@ bool AP_Arming_Copter::rc_calibration_checks(bool display_failure)
|
|||||||
// performs pre_arm gps related checks and returns true if passed
|
// performs pre_arm gps related checks and returns true if passed
|
||||||
bool AP_Arming_Copter::gps_checks(bool display_failure)
|
bool AP_Arming_Copter::gps_checks(bool display_failure)
|
||||||
{
|
{
|
||||||
// run mandatory gps checks first
|
|
||||||
if (!mandatory_gps_checks(display_failure)) {
|
|
||||||
AP_Notify::flags.pre_arm_gps_check = false;
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
|
|
||||||
// check if flight mode requires GPS
|
|
||||||
bool mode_requires_gps = copter.flightmode->requires_GPS();
|
|
||||||
|
|
||||||
// check if fence requires GPS
|
// check if fence requires GPS
|
||||||
bool fence_requires_gps = false;
|
bool fence_requires_gps = false;
|
||||||
#if AC_FENCE == ENABLED
|
#if AC_FENCE == ENABLED
|
||||||
@ -433,6 +424,23 @@ bool AP_Arming_Copter::gps_checks(bool display_failure)
|
|||||||
fence_requires_gps = (copter.fence.get_enabled_fences() & (AC_FENCE_TYPE_CIRCLE | AC_FENCE_TYPE_POLYGON)) > 0;
|
fence_requires_gps = (copter.fence.get_enabled_fences() & (AC_FENCE_TYPE_CIRCLE | AC_FENCE_TYPE_POLYGON)) > 0;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// check if flight mode requires GPS
|
||||||
|
bool mode_requires_gps = copter.flightmode->requires_GPS();
|
||||||
|
|
||||||
|
// call parent gps checks
|
||||||
|
if (mode_requires_gps || fence_requires_gps) {
|
||||||
|
if (!AP_Arming::gps_checks(display_failure)) {
|
||||||
|
AP_Notify::flags.pre_arm_gps_check = false;
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// run mandatory gps checks first
|
||||||
|
if (!mandatory_gps_checks(display_failure)) {
|
||||||
|
AP_Notify::flags.pre_arm_gps_check = false;
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
// return true if GPS is not required
|
// return true if GPS is not required
|
||||||
if (!mode_requires_gps && !fence_requires_gps) {
|
if (!mode_requires_gps && !fence_requires_gps) {
|
||||||
AP_Notify::flags.pre_arm_gps_check = true;
|
AP_Notify::flags.pre_arm_gps_check = true;
|
||||||
@ -452,12 +460,6 @@ bool AP_Arming_Copter::gps_checks(bool display_failure)
|
|||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
// call parent gps checks
|
|
||||||
if (!AP_Arming::gps_checks(display_failure)) {
|
|
||||||
AP_Notify::flags.pre_arm_gps_check = false;
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
|
|
||||||
// if we got here all must be ok
|
// if we got here all must be ok
|
||||||
AP_Notify::flags.pre_arm_gps_check = true;
|
AP_Notify::flags.pre_arm_gps_check = true;
|
||||||
return true;
|
return true;
|
||||||
|
Loading…
Reference in New Issue
Block a user