mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
AP_NavEKF2: remove unused getAccelNED method
This commit is contained in:
parent
e32ca819fc
commit
6b60bae068
@ -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
|
||||
{
|
||||
|
@ -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;
|
||||
|
@ -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) {
|
||||
|
@ -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;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user