mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_GPS: fixed fake ublox 3D lock PVT speed accuracy
allows EKF to startup fully with fake GPS lock
This commit is contained in:
parent
2493cdbcb6
commit
dc2a776985
@ -1013,6 +1013,7 @@ AP_GPS_UBLOX::_parse_gps(void)
|
|||||||
state.time_week_ms = AP_HAL::millis() + 3*60*60*1000 + 37000;
|
state.time_week_ms = AP_HAL::millis() + 3*60*60*1000 + 37000;
|
||||||
state.last_gps_time_ms = AP_HAL::millis();
|
state.last_gps_time_ms = AP_HAL::millis();
|
||||||
state.hdop = 130;
|
state.hdop = 130;
|
||||||
|
state.speed_accuracy = 0;
|
||||||
next_fix = state.status;
|
next_fix = state.status;
|
||||||
#endif
|
#endif
|
||||||
break;
|
break;
|
||||||
|
Loading…
Reference in New Issue
Block a user