AP_Arming: only compare AHRS vs GPS if GPS is enabled
This commit is contained in:
parent
ba234330d9
commit
cb39bd72d3
@ -598,6 +598,7 @@ bool AP_Arming::gps_checks(bool report)
|
|||||||
}
|
}
|
||||||
|
|
||||||
// check AHRS and GPS are within 10m of each other
|
// check AHRS and GPS are within 10m of each other
|
||||||
|
if (gps.num_sensors() > 0) {
|
||||||
const Location gps_loc = gps.location();
|
const Location gps_loc = gps.location();
|
||||||
Location ahrs_loc;
|
Location ahrs_loc;
|
||||||
if (AP::ahrs().get_location(ahrs_loc)) {
|
if (AP::ahrs().get_location(ahrs_loc)) {
|
||||||
@ -608,6 +609,7 @@ bool AP_Arming::gps_checks(bool report)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
}
|
||||||
|
|
||||||
if ((checks_to_perform & ARMING_CHECK_ALL) || (checks_to_perform & ARMING_CHECK_GPS_CONFIG)) {
|
if ((checks_to_perform & ARMING_CHECK_ALL) || (checks_to_perform & ARMING_CHECK_GPS_CONFIG)) {
|
||||||
uint8_t first_unconfigured;
|
uint8_t first_unconfigured;
|
||||||
|
Loading…
Reference in New Issue
Block a user