diff --git a/libraries/AP_NavEKF3/AP_NavEKF3.cpp b/libraries/AP_NavEKF3/AP_NavEKF3.cpp index ef4aaffd81..41f248c928 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3.cpp @@ -1067,6 +1067,17 @@ void NavEKF3::getRotationBodyToNED(Matrix3f &mat) const } // return the quaternions defining the rotation from NED to XYZ (body) axes +void NavEKF3::getQuaternionBodyToNED(int8_t instance, Quaternion &quat) const +{ + if (instance < 0 || instance >= num_cores) instance = primary; + if (core) { + Matrix3f mat; + core[instance].getRotationBodyToNED(mat); + quat.from_rotation_matrix(mat); + } +} + +// return the quaternions defining the rotation from NED to XYZ (autopilot) axes void NavEKF3::getQuaternion(int8_t instance, Quaternion &quat) const { if (instance < 0 || instance >= num_cores) instance = primary; diff --git a/libraries/AP_NavEKF3/AP_NavEKF3.h b/libraries/AP_NavEKF3/AP_NavEKF3.h index 0461173f58..923d7bc0e9 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3.h +++ b/libraries/AP_NavEKF3/AP_NavEKF3.h @@ -179,6 +179,9 @@ public: void getRotationBodyToNED(Matrix3f &mat) const; // return the quaternions defining the rotation from NED to XYZ (body) axes + void getQuaternionBodyToNED(int8_t instance, Quaternion &quat) const; + + // return the quaternions defining the rotation from NED to XYZ (autopilot) axes void getQuaternion(int8_t instance, Quaternion &quat) const; // return the innovations for the specified instance