Plane : EKF data logging fixes

This commit is contained in:
Paul Riseborough 2014-01-01 14:03:52 +11:00 committed by Andrew Tridgell
parent 6b9733c013
commit 2f95685bfc
2 changed files with 8 additions and 6 deletions

View File

@ -144,6 +144,8 @@ void NavEKF::UpdateFilter()
StoreStates();
// Check if on ground - status is used by covariance prediction
OnGroundCheck();
//debug code
onGround = false;
// sum delta angles and time used by covariance prediction
summedDelAng = summedDelAng + correctedDelAng;
summedDelVel = summedDelVel + correctedDelVel;

View File

@ -83,22 +83,22 @@ public:
// reference point (m). Return false if no position is available
bool getPosNED(Vector3f &pos);
// return the last calculated NED velocity (m/s)
// return NED velocity in m/s
void getVelNED(Vector3f &vel);
// return delta angle bias estimates
// return bodyaxis gyro bias estimates in deg/hr
void getGyroBias(Vector3f &gyroBias);
// return delta velocity bias estimates
// return body axis accelerometer bias estimates in m/s^2
void getAccelBias(Vector3f &accelBias);
// return the NE wind speed estimates
// return the NED wind speed estimates in m/s
void getWind(Vector3f &wind);
// return earth magnetic field estimates
// return earth magnetic field estimates in measurement units
void getMagNED(Vector3f &magNED);
// return body magnetic field estimates
// return body magnetic field estimates in measurement units
void getMagXYZ(Vector3f &magXYZ);
// return the last calculated latitude, longitude and height