AP_AHRS: fixed earth frame accel for EKF3 with significant trim

This commit is contained in:
Andrew Tridgell 2023-02-26 10:55:46 +11:00
parent a24763a2ba
commit f7be18755e
1 changed files with 1 additions and 1 deletions

View File

@ -610,7 +610,7 @@ void AP_AHRS::update_EKF3(void)
// use the primary IMU for accel earth frame
Vector3f accel = _ins.get_accel(primary_accel);
accel -= abias;
_accel_ef = _dcm_matrix * accel;
_accel_ef = _dcm_matrix * get_rotation_autopilot_body_to_vehicle_body() * accel;
nav_filter_status filt_state;
EKF3.getFilterStatus(filt_state);