mirror of https://github.com/ArduPilot/ardupilot
SITL: correct buffer over-read in GPS lag simulation
This commit is contained in:
parent
6c16da21c5
commit
06c3290e15
|
@ -1108,7 +1108,7 @@ void GPS::update()
|
||||||
|
|
||||||
// add in some GPS lag
|
// add in some GPS lag
|
||||||
_gps_data[next_index++] = d;
|
_gps_data[next_index++] = d;
|
||||||
if (next_index >= delay+1) {
|
if (next_index >= delay) {
|
||||||
next_index = 0;
|
next_index = 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue