mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_AHRS: fixed earth frame accel for EKF3 with significant trim
This commit is contained in:
parent
b55826e75e
commit
e537eb925c
@ -591,7 +591,7 @@ void AP_AHRS::update_EKF3(void)
|
|||||||
// use the primary IMU for accel earth frame
|
// use the primary IMU for accel earth frame
|
||||||
Vector3f accel = _ins.get_accel(primary_accel);
|
Vector3f accel = _ins.get_accel(primary_accel);
|
||||||
accel -= abias;
|
accel -= abias;
|
||||||
_accel_ef = _dcm_matrix * accel;
|
_accel_ef = _dcm_matrix * get_rotation_autopilot_body_to_vehicle_body() * accel;
|
||||||
|
|
||||||
nav_filter_status filt_state;
|
nav_filter_status filt_state;
|
||||||
EKF3.getFilterStatus(filt_state);
|
EKF3.getFilterStatus(filt_state);
|
||||||
|
Loading…
Reference in New Issue
Block a user