Browse Source

SITL: changes UBlox simulation to 5Hz

this matches the real UBlox driver
master
Andrew Tridgell 13 years ago
parent
commit
b811653800
  1. 4
      libraries/Desktop/support/sitl_gps.cpp

4
libraries/Desktop/support/sitl_gps.cpp

@ -115,8 +115,8 @@ void sitl_update_gps(double latitude, double longitude, float altitude, @@ -115,8 +115,8 @@ void sitl_update_gps(double latitude, double longitude, float altitude,
const uint8_t MSG_VELNED = 0x12;
double lon_scale;
// 4Hz
if (millis() - gps_state.last_update < 250) {
// 5Hz, to match the real UBlox config in APM
if (millis() - gps_state.last_update < 200) {
return;
}
gps_state.last_update = millis();

Loading…
Cancel
Save