Browse Source

AP_Arming: don't show the GPS arming error in SITL

it just makes users think something is wrong
mission-4.1.18
Andrew Tridgell 9 years ago
parent
commit
9df58e1e0a
  1. 4
      libraries/AP_Arming/AP_Arming.cpp

4
libraries/AP_Arming/AP_Arming.cpp

@ -339,6 +339,7 @@ bool AP_Arming::gps_checks(bool report) @@ -339,6 +339,7 @@ bool AP_Arming::gps_checks(bool report)
}
}
#if CONFIG_HAL_BOARD != HAL_BOARD_SITL
if ((checks_to_perform & ARMING_CHECK_ALL) || (checks_to_perform & ARMING_CHECK_GPS_CONFIG)) {
uint8_t first_unconfigured = gps.first_unconfigured_gps();
if (first_unconfigured != AP_GPS::GPS_ALL_CONFIGURED) {
@ -348,11 +349,10 @@ bool AP_Arming::gps_checks(bool report) @@ -348,11 +349,10 @@ bool AP_Arming::gps_checks(bool report)
first_unconfigured + 1);
gps.broadcast_first_configuration_failure_reason();
}
#if CONFIG_HAL_BOARD != HAL_BOARD_SITL
return false;
#endif
}
}
#endif
return true;
}

Loading…
Cancel
Save