InertialNav: remove 3sec limit on position est after losing GPS

This commit is contained in:
Randy Mackay 2013-03-16 18:12:51 +09:00
parent 6a1aad30f1
commit c9571ad543
1 changed files with 1 additions and 1 deletions

View File

@ -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