Skip to content

Commit

Permalink
AP_NavEKF3: use filtered gyro in INS position correction
Browse files Browse the repository at this point in the history
this reduces the impact of IMU noise on the output velocity from the
EKF
  • Loading branch information
tridge committed Apr 17, 2024
1 parent eed50a0 commit dce2492
Showing 1 changed file with 1 addition and 1 deletion.
2 changes: 1 addition & 1 deletion libraries/AP_NavEKF3/AP_NavEKF3_core.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down

0 comments on commit dce2492

Please sign in to comment.