mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-20 15:48:29 -04:00
Copter: remove pointless pre_arm_gps_checks function
This commit is contained in:
parent
baaad8df94
commit
cbde87b390
@ -63,7 +63,7 @@ bool AP_Arming_Copter::pre_arm_checks(bool display_failure)
|
|||||||
if (copter.ap.pre_arm_check) {
|
if (copter.ap.pre_arm_check) {
|
||||||
// run gps checks because results may change and affect LED colour
|
// run gps checks because results may change and affect LED colour
|
||||||
// no need to display failures because arm_checks will do that if the pilot tries to arm
|
// no need to display failures because arm_checks will do that if the pilot tries to arm
|
||||||
pre_arm_gps_checks(false);
|
gps_checks(false);
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -138,15 +138,6 @@ bool AP_Arming_Copter::compass_checks(bool display_failure)
|
|||||||
return ret;
|
return ret;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool AP_Arming_Copter::gps_checks(bool display_failure)
|
|
||||||
{
|
|
||||||
// check GPS
|
|
||||||
if (!pre_arm_gps_checks(display_failure)) {
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
|
|
||||||
bool AP_Arming_Copter::fence_checks(bool display_failure)
|
bool AP_Arming_Copter::fence_checks(bool display_failure)
|
||||||
{
|
{
|
||||||
#if AC_FENCE == ENABLED
|
#if AC_FENCE == ENABLED
|
||||||
@ -380,7 +371,7 @@ void AP_Arming_Copter::pre_arm_rc_checks(const 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::pre_arm_gps_checks(bool display_failure)
|
bool AP_Arming_Copter::gps_checks(bool display_failure)
|
||||||
{
|
{
|
||||||
// always check if inertial nav has started and is ready
|
// always check if inertial nav has started and is ready
|
||||||
if (!ahrs.healthy()) {
|
if (!ahrs.healthy()) {
|
||||||
@ -631,7 +622,7 @@ bool AP_Arming_Copter::arm_checks(bool display_failure, bool arming_from_gcs)
|
|||||||
}
|
}
|
||||||
|
|
||||||
// always check gps
|
// always check gps
|
||||||
if (!pre_arm_gps_checks(display_failure)) {
|
if (!gps_checks(display_failure)) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -22,7 +22,6 @@ public:
|
|||||||
protected:
|
protected:
|
||||||
|
|
||||||
bool pre_arm_checks(bool display_failure) override;
|
bool pre_arm_checks(bool display_failure) override;
|
||||||
bool pre_arm_gps_checks(bool display_failure);
|
|
||||||
bool pre_arm_ekf_attitude_check();
|
bool pre_arm_ekf_attitude_check();
|
||||||
bool pre_arm_terrain_check(bool display_failure);
|
bool pre_arm_terrain_check(bool display_failure);
|
||||||
bool pre_arm_proximity_check(bool display_failure);
|
bool pre_arm_proximity_check(bool display_failure);
|
||||||
|
Loading…
Reference in New Issue
Block a user