AP_NavEKF: Make EKF2 PosDownDerivative interface follow coding conventions

Updates arising from peer review.
This commit is contained in:
Paul Riseborough 2015-10-15 16:32:47 +11:00 committed by Andrew Tridgell
parent 1323db10e8
commit 840f307d58
2 changed files with 3 additions and 3 deletions

View File

@ -3695,10 +3695,10 @@ void NavEKF::getVelNED(Vector3f &vel) const
}
// Return the rate of change of vertical position in the down diection (dPosD/dt) in m/s
void NavEKF::getPosDownDerivative(float &ret) const
float NavEKF::getPosDownDerivative(void) const
{
// return the value calculated from a complmentary filer applied to the EKF height and vertical acceleration
ret = posDownDerivative;
return posDownDerivative;
}
// Return the last calculated NED position relative to the reference point (m).

View File

@ -125,7 +125,7 @@ public:
// Return the rate of change of vertical position in the down diection (dPosD/dt) in m/s
// This can be different to the z component of the EKF velocity state because it will fluctuate with height errors and corrections in the EKF
// but will always be kinematically consistent with the z component of the EKF position state
void getPosDownDerivative(float &ret) const;
float getPosDownDerivative(void) const;
// This returns the specific forces in the NED frame
void getAccelNED(Vector3f &accelNED) const;