AP_NavEKF3: remove unused quat2Tbn method

This commit is contained in:
Peter Barker 2020-10-16 14:20:27 +11:00 committed by Andrew Tridgell
parent 53305ba2a4
commit ef505df78a
2 changed files with 0 additions and 10 deletions

View File

@ -1544,13 +1544,6 @@ void NavEKF3_core::StoreQuatRotate(const Quaternion &deltaQuat)
outputDataDelayed.quat = outputDataDelayed.quat*deltaQuat;
}
// calculate nav to body quaternions from body to nav rotation matrix
void NavEKF3_core::quat2Tbn(Matrix3f &Tbn, const Quaternion &quat) const
{
// Calculate the body to nav cosine matrix
quat.rotation_matrix(Tbn);
}
// force symmetry on the covariance matrix to prevent ill-conditioning
void NavEKF3_core::ForceSymmetry()
{

View File

@ -715,9 +715,6 @@ private:
// Rotate the stored output quaternion history through a quaternion rotation
void StoreQuatRotate(const Quaternion &deltaQuat);
// calculate nav to body quaternions from body to nav rotation matrix
void quat2Tbn(Matrix3f &Tbn, const Quaternion &quat) const;
// calculate the NED earth spin vector in rad/sec
void calcEarthRateNED(Vector3f &omega, int32_t latitude) const;