Copter: use home_is_set function
This commit is contained in:
parent
e081b9d1c7
commit
d5fd6d2a99
@ -168,7 +168,7 @@ static void failsafe_gps_check()
|
||||
uint32_t last_gps_update_ms;
|
||||
|
||||
// return immediately if gps failsafe is disabled or we have never had GPS lock
|
||||
if (g.failsafe_gps_enabled == FS_GPS_DISABLED || !ap.home_is_set) {
|
||||
if (g.failsafe_gps_enabled == FS_GPS_DISABLED || !home_is_set()) {
|
||||
// if we have just disabled the gps failsafe, ensure the gps failsafe event is cleared
|
||||
if (failsafe.gps) {
|
||||
failsafe_gps_off_event();
|
||||
|
@ -334,7 +334,7 @@ static bool position_ok()
|
||||
}
|
||||
} else {
|
||||
// with interial nav use GPS based checks
|
||||
return (ap.home_is_set && gps.status() >= AP_GPS::GPS_OK_FIX_3D &&
|
||||
return (home_is_set() && gps.status() >= AP_GPS::GPS_OK_FIX_3D &&
|
||||
!gps_glitch.glitching() && !failsafe.gps &&
|
||||
!ekf_check_state.bad_compass && !failsafe.ekf);
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user