AP_NavEKF: Added getAccelNED function
This commit is contained in:
parent
7be78621f4
commit
7692761f34
@ -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
|
||||||
{
|
{
|
||||||
|
@ -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;
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user