mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF2: Remove unused function
This commit is contained in:
parent
02408861a1
commit
8afb26087d
|
@ -768,19 +768,6 @@ bool NavEKF2::getHeightControlLimit(float &height) const
|
|||
return core->getHeightControlLimit(height);
|
||||
}
|
||||
|
||||
// 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 NavEKF2::getDeltaQuaternion(void) const
|
||||
{
|
||||
if (!core) {
|
||||
return Quaternion();
|
||||
}
|
||||
return core->getDeltaQuaternion();
|
||||
}
|
||||
|
||||
// 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
|
||||
|
|
|
@ -216,10 +216,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
|
||||
|
|
|
@ -4807,14 +4807,6 @@ bool NavEKF2_core::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 NavEKF2_core::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 NavEKF2_core::getQuaternion(Quaternion& ret) const
|
||||
{
|
||||
|
|
|
@ -209,10 +209,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
|
||||
|
|
Loading…
Reference in New Issue