AP_NavEKF2: use exact matrix for trim rotation

This commit is contained in:
Jonathan Challinger 2016-08-09 11:33:51 -07:00 committed by Andrew Tridgell
parent 3eba985afd
commit dac59cb5da
1 changed files with 1 additions and 2 deletions

View File

@ -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