mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
AP_Arming: minor format fix
This commit is contained in:
parent
4cf9c34187
commit
c8c49d060b
@ -545,12 +545,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
|
||||
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;
|
||||
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;
|
||||
}
|
||||
|
||||
for (uint8_t i = 0; i < gps.num_sensors(); i++) {
|
||||
|
Loading…
Reference in New Issue
Block a user