AP_NavEKF3: use filtered gyro in INS position correction

this reduces the impact of IMU noise on the output velocity from the
EKF
This commit is contained in:
Andrew Tridgell 2024-04-16 08:31:22 +10:00
parent eed50a0872
commit dce2492321
1 changed files with 1 additions and 1 deletions

View File

@ -863,7 +863,7 @@ void NavEKF3_core::calcOutputStates()
if (!accelPosOffset.is_zero()) {
// calculate the average angular rate across the last IMU update
// note delAngDT is prevented from being zero in readIMUData()
Vector3F angRate = imuDataNew.delAng * (1.0f/imuDataNew.delAngDT);
Vector3F angRate = dal.ins().get_gyro(gyro_index_active).toftype();
// Calculate the velocity of the body frame origin relative to the IMU in body frame
// and rotate into earth frame. Note % operator has been overloaded to perform a cross product