mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
HAL_SITL: fixed GPS delay off by one
This commit is contained in:
parent
647cc84e00
commit
af27921225
@ -560,7 +560,7 @@ void SITL_State::_update_gps(double latitude, double longitude, float altitude,
|
||||
|
||||
// add in some GPS lag
|
||||
_gps_data[next_gps_index++] = d;
|
||||
if (next_gps_index >= gps_delay) {
|
||||
if (next_gps_index >= gps_delay+1) {
|
||||
next_gps_index = 0;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user