mirror of https://github.com/ArduPilot/ardupilot
HAL_SITL: use SIM_GPS_LOCKTIME
This commit is contained in:
parent
a7967e00e4
commit
42181ee7c8
|
@ -1122,6 +1122,11 @@ void SITL_State::_update_gps(double latitude, double longitude, float altitude,
|
|||
struct gps_data d;
|
||||
char c;
|
||||
|
||||
// simulate delayed lock times
|
||||
if (AP_HAL::millis() < _sitl->gps_lock_time*1000UL) {
|
||||
have_lock = false;
|
||||
}
|
||||
|
||||
//Capture current position as basestation location for
|
||||
if (!_gps_has_basestation_position) {
|
||||
if (have_lock) {
|
||||
|
|
Loading…
Reference in New Issue