mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-27 02:04:00 -04:00
AP_Arming: minor format fix
This commit is contained in:
parent
d8f6956366
commit
ba234330d9
@ -545,12 +545,12 @@ bool AP_Arming::gps_checks(bool report)
|
|||||||
if ((checks_to_perform & ARMING_CHECK_ALL) || (checks_to_perform & ARMING_CHECK_GPS)) {
|
if ((checks_to_perform & ARMING_CHECK_ALL) || (checks_to_perform & ARMING_CHECK_GPS)) {
|
||||||
|
|
||||||
// Any failure messages from GPS backends
|
// Any failure messages from GPS backends
|
||||||
char failure_msg[50] = {};
|
char failure_msg[50] = {};
|
||||||
if (!AP::gps().backends_healthy(failure_msg, ARRAY_SIZE(failure_msg))) {
|
if (!AP::gps().backends_healthy(failure_msg, ARRAY_SIZE(failure_msg))) {
|
||||||
if (failure_msg[0] != '\0') {
|
if (failure_msg[0] != '\0') {
|
||||||
check_failed(ARMING_CHECK_GPS, report, "%s", failure_msg);
|
check_failed(ARMING_CHECK_GPS, report, "%s", failure_msg);
|
||||||
}
|
}
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
for (uint8_t i = 0; i < gps.num_sensors(); i++) {
|
for (uint8_t i = 0; i < gps.num_sensors(); i++) {
|
||||||
|
Loading…
Reference in New Issue
Block a user