AP_AHRS: fill in _dcm_matrix whenever EKF started
this ensures get_dcm_matrix() always returns valid data
This commit is contained in:
parent
4c42f53636
commit
df271fbd59
@ -64,8 +64,8 @@ void AP_AHRS_NavEKF::update(void)
|
||||
}
|
||||
if (ekf_started) {
|
||||
EKF.UpdateFilter();
|
||||
EKF.getRotationBodyToNED(_dcm_matrix);
|
||||
if (using_EKF()) {
|
||||
EKF.getRotationBodyToNED(_dcm_matrix);
|
||||
Vector3f eulers;
|
||||
EKF.getEulerAngles(eulers);
|
||||
roll = eulers.x;
|
||||
|
Loading…
Reference in New Issue
Block a user