mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF: correct initialisation of ekf_imu_buffer
this init() call can be called on an existing buffer, in which case we clear the object. Presumably since we've just zeroed all the elements its safe to say that we should mark the object as having never-been-filled
This commit is contained in:
parent
8452f5f0cd
commit
99f5e74a8e
|
@ -137,6 +137,7 @@ bool ekf_imu_buffer::init(uint32_t size)
|
|||
_size = size;
|
||||
_youngest = 0;
|
||||
_oldest = 0;
|
||||
_filled = 0;
|
||||
return true;
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue