Browse Source

HAL_SITL: fixed a warning

master
Andrew Tridgell 11 years ago
parent
commit
55ba536331
  1. 4
      libraries/AP_HAL_AVR_SITL/sitl_gps.cpp

4
libraries/AP_HAL_AVR_SITL/sitl_gps.cpp

@ -530,8 +530,8 @@ void SITL_State::_update_gps(double latitude, double longitude, float altitude,
char c; char c;
Vector3f glitch_offsets = _sitl->gps_glitch; Vector3f glitch_offsets = _sitl->gps_glitch;
// 5Hz, to match the real config in APM // run at configured GPS rate (default 5Hz)
if (hal.scheduler->millis() - gps_state.last_update < 1000/_sitl->gps_hertz) { if ((hal.scheduler->millis() - gps_state.last_update) < (uint32_t)(1000/_sitl->gps_hertz)) {
return; return;
} }

Loading…
Cancel
Save