mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF: correct setting of _filled
Co-authored-by: luweiagi <luweiagi@163.com>
This commit is contained in:
parent
99f5e74a8e
commit
cd8f081611
|
@ -137,7 +137,7 @@ bool ekf_imu_buffer::init(uint32_t size)
|
|||
_size = size;
|
||||
_youngest = 0;
|
||||
_oldest = 0;
|
||||
_filled = 0;
|
||||
_filled = false;
|
||||
return true;
|
||||
}
|
||||
|
||||
|
@ -152,13 +152,14 @@ void ekf_imu_buffer::push_youngest_element(const void *element)
|
|||
return;
|
||||
}
|
||||
// push youngest to the buffer
|
||||
_youngest = (_youngest+1) % _size;
|
||||
_youngest++;
|
||||
if (_youngest == _size) {
|
||||
_youngest = 0;
|
||||
_filled = true;
|
||||
}
|
||||
memcpy(get_offset(_youngest), element, elsize);
|
||||
// set oldest data index
|
||||
_oldest = (_youngest+1) % _size;
|
||||
if (_oldest == 0) {
|
||||
_filled = true;
|
||||
}
|
||||
}
|
||||
|
||||
// retrieve the oldest data from the ring buffer tail
|
||||
|
|
Loading…
Reference in New Issue