mirror of https://github.com/ArduPilot/ardupilot
Copter: AP_Arming calls parent's gps checks
Allows removing some duplicate code
This commit is contained in:
parent
e398bb5c68
commit
b30d743812
|
@ -464,20 +464,6 @@ bool AP_Arming_Copter::pre_arm_gps_checks(bool display_failure)
|
|||
return true;
|
||||
}
|
||||
|
||||
#if CONFIG_HAL_BOARD != HAL_BOARD_SITL
|
||||
// check GPS configuration has completed
|
||||
uint8_t first_unconfigured = copter.gps.first_unconfigured_gps();
|
||||
if (first_unconfigured != AP_GPS::GPS_ALL_CONFIGURED) {
|
||||
if (display_failure) {
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL,
|
||||
"PreArm: GPS %d failing configuration checks",
|
||||
first_unconfigured + 1);
|
||||
copter.gps.broadcast_first_configuration_failure_reason();
|
||||
}
|
||||
return false;
|
||||
}
|
||||
#endif
|
||||
|
||||
// warn about hdop separately - to prevent user confusion with no gps lock
|
||||
if (copter.gps.get_hdop() > copter.g.gps_hdop_good) {
|
||||
if (display_failure) {
|
||||
|
@ -487,6 +473,11 @@ bool AP_Arming_Copter::pre_arm_gps_checks(bool display_failure)
|
|||
return false;
|
||||
}
|
||||
|
||||
// call parent gps checks
|
||||
if (!AP_Arming::gps_checks(display_failure)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
// if we got here all must be ok
|
||||
AP_Notify::flags.pre_arm_gps_check = true;
|
||||
return true;
|
||||
|
|
|
@ -31,9 +31,9 @@ protected:
|
|||
// NOTE! the following check functions *DO* call into AP_Arming:
|
||||
bool ins_checks(bool display_failure) override;
|
||||
bool compass_checks(bool display_failure) override;
|
||||
bool gps_checks(bool display_failure) override;
|
||||
|
||||
// NOTE! the following check functions *DO NOT* call into AP_Arming!
|
||||
bool gps_checks(bool display_failure);
|
||||
bool fence_checks(bool display_failure);
|
||||
bool board_voltage_checks(bool display_failure);
|
||||
bool parameter_checks(bool display_failure);
|
||||
|
|
Loading…
Reference in New Issue