mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 01:18:29 -04:00
AP_NavEKF2: Fix bug in vertical position derivative calculation
This commit is contained in:
parent
f6ad79688e
commit
2b13020c19
@ -628,10 +628,8 @@ void NavEKF2_core::calcOutputStatesFast() {
|
||||
// update vertical velocity and position states used to provide a vertical position derivative output
|
||||
// using a simple complementary filter
|
||||
float lastPosDownDerivative = posDownDerivative;
|
||||
posDownDerivative += delVelNav.z;
|
||||
float posDownDerivativeCorrection = 0.2f * (outputDataNew.position.z - posDown);
|
||||
posDown += (posDownDerivative + lastPosDownDerivative) * (imuDataNew.delVelDT*0.5f) + posDownDerivativeCorrection * imuDataNew.delVelDT;
|
||||
|
||||
posDownDerivative = 2.0f * (outputDataNew.position.z - posDown);
|
||||
posDown += (posDownDerivative + lastPosDownDerivative + 2.0f*delVelNav.z) * (imuDataNew.delVelDT*0.5f);
|
||||
}
|
||||
|
||||
/*
|
||||
|
Loading…
Reference in New Issue
Block a user