AP_NavEKF: Remove unused function

This commit is contained in:
Paul Riseborough 2015-09-23 17:56:32 +10:00 committed by Andrew Tridgell
parent c14dbcfc44
commit 02408861a1
2 changed files with 0 additions and 12 deletions

View File

@ -5379,14 +5379,6 @@ bool NavEKF::getHeightControlLimit(float &height) const
}
}
// provides the delta quaternion that was used by the INS calculation to rotate from the previous orientation to the orientation at the current time
// the delta quaternion returned will be a zero rotation if the INS calculation was not performed on that time step
Quaternion NavEKF::getDeltaQuaternion(void) const
{
// Note: correctedDelAngQuat is reset to a zero rotation at the start of every update cycle in UpdateFilter()
return correctedDelAngQuat;
}
// return the quaternions defining the rotation from NED to XYZ (body) axes
void NavEKF::getQuaternion(Quaternion& ret) const
{

View File

@ -258,10 +258,6 @@ public:
// this is needed to ensure the vehicle does not fly too high when using optical flow navigation
bool getHeightControlLimit(float &height) const;
// provides the quaternion that was used by the INS calculation to rotate from the previous orientation to the orientaion at the current time step
// returns a zero rotation quaternion if the INS calculation was not performed on that time step.
Quaternion getDeltaQuaternion(void) const;
// return the amount of yaw angle change due to the last yaw angle reset in radians
// returns true if a reset yaw angle has been updated and not queried
// this function should not have more than one client