AP_NavEKF: Added getAccelNED function

This commit is contained in:
Jonathan Challinger 2014-10-31 15:06:04 -07:00 committed by Randy Mackay
parent 7be78621f4
commit 7692761f34
2 changed files with 9 additions and 0 deletions

View File

@ -2795,6 +2795,12 @@ void NavEKF::getEulerAngles(Vector3f &euler) const
euler = euler - _ahrs->get_trim(); euler = euler - _ahrs->get_trim();
} }
// This returns the specific forces in the NED frame
void NavEKF::getAccelNED(Vector3f &accelNED) const {
accelNED = velDotNED;
accelNED.z -= GRAVITY_MSS;
}
// return NED velocity in m/s // return NED velocity in m/s
void NavEKF::getVelNED(Vector3f &vel) const void NavEKF::getVelNED(Vector3f &vel) const
{ {

View File

@ -102,6 +102,9 @@ public:
// return NED velocity in m/s // return NED velocity in m/s
void getVelNED(Vector3f &vel) const; void getVelNED(Vector3f &vel) const;
// This returns the specific forces in the NED frame
void getAccelNED(Vector3f &accelNED) const;
// return body axis gyro bias estimates in rad/sec // return body axis gyro bias estimates in rad/sec
void getGyroBias(Vector3f &gyroBias) const; void getGyroBias(Vector3f &gyroBias) const;