AP_NavEKF3: documentation update
This commit is contained in:
parent
a04aff7a7d
commit
4a898037e9
@ -350,7 +350,8 @@ void NavEKF3_core::readIMUData()
|
|||||||
/*
|
/*
|
||||||
* If the target EKF time step has been accumulated, and the frontend has allowed start of a new predict cycle,
|
* If the target EKF time step has been accumulated, and the frontend has allowed start of a new predict cycle,
|
||||||
* then store the accumulated IMU data to be used by the state prediction, ignoring the frontend permission if more
|
* then store the accumulated IMU data to be used by the state prediction, ignoring the frontend permission if more
|
||||||
* than twice the target time has lapsed.
|
* than twice the target time has lapsed. Adjust the target EKF step time threshold to allow for timing jitter in the
|
||||||
|
* IMU data.
|
||||||
*/
|
*/
|
||||||
if ((imuDataDownSampledNew.delAngDT >= (EKF_TARGET_DT-(dtIMUavg*0.5)) && startPredictEnabled) ||
|
if ((imuDataDownSampledNew.delAngDT >= (EKF_TARGET_DT-(dtIMUavg*0.5)) && startPredictEnabled) ||
|
||||||
(imuDataDownSampledNew.delAngDT >= 2.0f*EKF_TARGET_DT)) {
|
(imuDataDownSampledNew.delAngDT >= 2.0f*EKF_TARGET_DT)) {
|
||||||
|
Loading…
Reference in New Issue
Block a user