Browse Source

AP_GPS: fixed fake ublox 3D lock PVT speed accuracy

allows EKF to startup fully with fake GPS lock
mission-4.1.18
Andrew Tridgell 7 years ago
parent
commit
dc2a776985
  1. 1
      libraries/AP_GPS/AP_GPS_UBLOX.cpp

1
libraries/AP_GPS/AP_GPS_UBLOX.cpp

@ -1013,6 +1013,7 @@ AP_GPS_UBLOX::_parse_gps(void) @@ -1013,6 +1013,7 @@ AP_GPS_UBLOX::_parse_gps(void)
state.time_week_ms = AP_HAL::millis() + 3*60*60*1000 + 37000;
state.last_gps_time_ms = AP_HAL::millis();
state.hdop = 130;
state.speed_accuracy = 0;
next_fix = state.status;
#endif
break;

Loading…
Cancel
Save