AP_Mount: trim out dead getDebug method

This commit is contained in:
Peter Barker 2018-11-05 12:52:20 +11:00 committed by Peter Barker
parent 7d16888067
commit 126065e95c
2 changed files with 0 additions and 16 deletions

View File

@ -930,19 +930,6 @@ void SoloGimbalEKF::fixCovariance()
}
}
// return data for debugging EKF
void SoloGimbalEKF::getDebug(float &tilt, Vector3f &velocity, Vector3f &euler, Vector3f &gyroBias) const
{
tilt = TiltCorrection;
velocity = state.velocity;
state.quat.to_euler(euler.x, euler.y, euler.z);
if (dtIMU < 1.0e-6f) {
gyroBias.zero();
} else {
gyroBias = state.delAngBias / dtIMU;
}
}
// get gyro bias data
void SoloGimbalEKF::getGyroBias(Vector3f &gyroBias) const
{

View File

@ -82,9 +82,6 @@ public:
void reset();
// get some debug information
void getDebug(float &tilt, Vector3f &velocity, Vector3f &euler, Vector3f &gyroBias) const;
// get gyro bias data
void getGyroBias(Vector3f &gyroBias) const;