mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
AP_NavEKF: fixed corrected del velocity to use both accels
This commit is contained in:
parent
db4ac68f5e
commit
c221959d5a
@ -733,7 +733,7 @@ void NavEKF::UpdateFilter()
|
||||
|
||||
// sum delta angles and time used by covariance prediction
|
||||
summedDelAng = summedDelAng + correctedDelAng;
|
||||
summedDelVel = summedDelVel + correctedDelVel1;
|
||||
summedDelVel = summedDelVel + correctedDelVel12;
|
||||
dt += dtIMUactual;
|
||||
|
||||
// perform a covariance prediction if the total delta angle has exceeded the limit
|
||||
|
Loading…
Reference in New Issue
Block a user