mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-02 19:53:57 -04:00
AP_NavEKF2: use exact matrix for trim rotation
This commit is contained in:
parent
3eba985afd
commit
dac59cb5da
@ -136,9 +136,8 @@ void NavEKF2_core::getTiltError(float &ang) const
|
||||
// return the transformation matrix from XYZ (body) to NED axes
|
||||
void NavEKF2_core::getRotationBodyToNED(Matrix3f &mat) const
|
||||
{
|
||||
Vector3f trim = _ahrs->get_trim();
|
||||
outputDataNew.quat.rotation_matrix(mat);
|
||||
mat.rotateXYinv(trim);
|
||||
mat = mat * _ahrs->get_rotation_vehicle_body_to_autopilot_body();
|
||||
}
|
||||
|
||||
// return the quaternions defining the rotation from NED to XYZ (body) axes
|
||||
|
Loading…
Reference in New Issue
Block a user