SITL: changes UBlox simulation to 5Hz

this matches the real UBlox driver
This commit is contained in:
Andrew Tridgell 2012-06-22 08:37:04 +10:00
parent 624fdda89c
commit 20c1baf585
1 changed files with 2 additions and 2 deletions

View File

@ -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();