AP_NavEKF2: Make EKF2 PosDownDerivative interface follow coding conventions
Updates arising from peer review.
This commit is contained in:
parent
f63c32531c
commit
47ae0f35f6
@ -461,12 +461,13 @@ void NavEKF2::getVelNED(Vector3f &vel) const
|
||||
}
|
||||
|
||||
// Return the rate of change of vertical position in the down diection (dPosD/dt) in m/s
|
||||
void NavEKF2::getPosDownDerivative(float &ret) const
|
||||
float NavEKF2::getPosDownDerivative(void) const
|
||||
{
|
||||
// return the value calculated from a complmentary filer applied to the EKF height and vertical acceleration
|
||||
if (core) {
|
||||
core->getPosDownDerivative(ret);
|
||||
return core->getPosDownDerivative();
|
||||
}
|
||||
return 0.0f;
|
||||
}
|
||||
|
||||
// This returns the specific forces in the NED frame
|
||||
|
@ -68,7 +68,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;
|
||||
|
@ -150,10 +150,10 @@ void NavEKF2_core::getVelNED(Vector3f &vel) const
|
||||
}
|
||||
|
||||
// Return the rate of change of vertical position in the down diection (dPosD/dt) in m/s
|
||||
void NavEKF2_core::getPosDownDerivative(float &ret) const
|
||||
float NavEKF2_core::getPosDownDerivative(void) const
|
||||
{
|
||||
// return the value calculated from a complmentary filer applied to the EKF height and vertical acceleration
|
||||
ret = posDownDerivative;
|
||||
return posDownDerivative;
|
||||
}
|
||||
|
||||
// This returns the specific forces in the NED frame
|
||||
|
@ -71,7 +71,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;
|
||||
|
Loading…
Reference in New Issue
Block a user