mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
AP_NavEKF: initialise quaternion from rotation matrix
This commit is contained in:
parent
2df314799e
commit
24e1070eb2
@ -327,7 +327,7 @@ void NavEKF::InitialiseFilterDynamic(void)
|
|||||||
|
|
||||||
// Calculate initial filter quaternion states from AHRS solution
|
// Calculate initial filter quaternion states from AHRS solution
|
||||||
Quaternion initQuat;
|
Quaternion initQuat;
|
||||||
initQuat.from_euler(_ahrs->roll, _ahrs->pitch, _ahrs->yaw);
|
initQuat.from_rotation_matrix(_ahrs->get_dcm_matrix());
|
||||||
|
|
||||||
// Calculate initial Tbn matrix and rotate Mag measurements into NED
|
// Calculate initial Tbn matrix and rotate Mag measurements into NED
|
||||||
// to set initial NED magnetic field states
|
// to set initial NED magnetic field states
|
||||||
|
Loading…
Reference in New Issue
Block a user