AP_NavEKF2: remove unused getAccelNED method

This commit is contained in:
Peter Barker 2020-12-17 15:30:37 +11:00 committed by Peter Barker
parent e32ca819fc
commit 6b60bae068
4 changed files with 0 additions and 20 deletions

View File

@ -970,14 +970,6 @@ float NavEKF2::getPosDownDerivative(int8_t instance) const
return 0.0f;
}
// This returns the specific forces in the NED frame
void NavEKF2::getAccelNED(Vector3f &accelNED) const
{
if (core) {
core[primary].getAccelNED(accelNED);
}
}
// return body axis gyro bias estimates in rad/sec
void NavEKF2::getGyroBias(int8_t instance, Vector3f &gyroBias) const
{

View File

@ -94,9 +94,6 @@ public:
// but will always be kinematically consistent with the z component of the EKF position state
float getPosDownDerivative(int8_t instance) const;
// This returns the specific forces in the NED frame
void getAccelNED(Vector3f &accelNED) const;
// return body axis gyro bias estimates in rad/sec for the specified instance
// An out of range instance (eg -1) returns data for the primary instance
void getGyroBias(int8_t instance, Vector3f &gyroBias) const;

View File

@ -197,12 +197,6 @@ float NavEKF2_core::getPosDownDerivative(void) const
return vertCompFiltState.vel + velOffsetNED.z;
}
// This returns the specific forces in the NED frame
void NavEKF2_core::getAccelNED(Vector3f &accelNED) const {
accelNED = velDotNED;
accelNED.z -= GRAVITY_MSS;
}
// return the Z-accel bias estimate in m/s^2
void NavEKF2_core::getAccelZBias(float &zbias) const {
if (dtEkfAvg > 0) {

View File

@ -111,9 +111,6 @@ public:
// but will always be kinematically consistent with the z component of the EKF position state
float getPosDownDerivative(void) const;
// This returns the specific forces in the NED frame
void getAccelNED(Vector3f &accelNED) const;
// return body axis gyro bias estimates in rad/sec
void getGyroBias(Vector3f &gyroBias) const;