mirror of https://github.com/ArduPilot/ardupilot
InertialNav: remove 3sec limit on position est after losing GPS
This commit is contained in:
parent
6a1aad30f1
commit
c9571ad543
|
@ -117,7 +117,7 @@ void AP_InertialNav::set_time_constant_xy( float time_constant_in_seconds )
|
|||
// position_ok - return true if position has been initialised and have received gps data within 3 seconds
|
||||
bool AP_InertialNav::position_ok()
|
||||
{
|
||||
return _xy_enabled && (hal.scheduler->millis() - _gps_last_update < 3000);
|
||||
return _xy_enabled;
|
||||
}
|
||||
|
||||
// check_gps - check if new gps readings have arrived and use them to correct position estimates
|
||||
|
|
Loading…
Reference in New Issue