mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_Mount: trim out dead getDebug method
This commit is contained in:
parent
7d16888067
commit
126065e95c
@ -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
|
// get gyro bias data
|
||||||
void SoloGimbalEKF::getGyroBias(Vector3f &gyroBias) const
|
void SoloGimbalEKF::getGyroBias(Vector3f &gyroBias) const
|
||||||
{
|
{
|
||||||
|
@ -82,9 +82,6 @@ public:
|
|||||||
|
|
||||||
void reset();
|
void reset();
|
||||||
|
|
||||||
// get some debug information
|
|
||||||
void getDebug(float &tilt, Vector3f &velocity, Vector3f &euler, Vector3f &gyroBias) const;
|
|
||||||
|
|
||||||
// get gyro bias data
|
// get gyro bias data
|
||||||
void getGyroBias(Vector3f &gyroBias) const;
|
void getGyroBias(Vector3f &gyroBias) const;
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user