mirror of https://github.com/ArduPilot/ardupilot
HAL_SITL: fixed a warning
This commit is contained in:
parent
84336bc74e
commit
55ba536331
|
@ -530,8 +530,8 @@ void SITL_State::_update_gps(double latitude, double longitude, float altitude,
|
|||
char c;
|
||||
Vector3f glitch_offsets = _sitl->gps_glitch;
|
||||
|
||||
// 5Hz, to match the real config in APM
|
||||
if (hal.scheduler->millis() - gps_state.last_update < 1000/_sitl->gps_hertz) {
|
||||
// run at configured GPS rate (default 5Hz)
|
||||
if ((hal.scheduler->millis() - gps_state.last_update) < (uint32_t)(1000/_sitl->gps_hertz)) {
|
||||
return;
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue