mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_Arming: remove redundant checks_to_perform check
This is identical to the check just above it
This commit is contained in:
parent
066ad0f8da
commit
5613610641
@ -480,15 +480,12 @@ bool AP_Arming::gps_checks(bool report)
|
||||
if ((checks_to_perform & ARMING_CHECK_ALL) || (checks_to_perform & ARMING_CHECK_GPS)) {
|
||||
|
||||
// Any failure messages from GPS backends
|
||||
if ((checks_to_perform & ARMING_CHECK_ALL) ||
|
||||
(checks_to_perform & ARMING_CHECK_GPS)) {
|
||||
char failure_msg[50] = {};
|
||||
if (!AP::gps().backends_healthy(failure_msg, ARRAY_SIZE(failure_msg))) {
|
||||
if (failure_msg[0] != '\0') {
|
||||
check_failed(ARMING_CHECK_GPS, report, "%s", failure_msg);
|
||||
}
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
//GPS OK?
|
||||
|
Loading…
Reference in New Issue
Block a user