AP_NavEKF: Publish small EKF quaternion and gyro bias outputs

This commit is contained in:
Paul Riseborough 2015-01-31 19:26:35 +11:00 committed by Andrew Tridgell
parent 17445d03f0
commit 5f24603ceb
2 changed files with 17 additions and 0 deletions

View File

@ -894,5 +894,16 @@ void SmallEKF::getDebug(float &tilt, Vector3f &velocity, Vector3f &euler, Vector
gyroBias = state.delAngBias / dtIMU;
}
// get gyro bias data
void SmallEKF::getGyroBias(Vector3f &gyroBias) const
{
gyroBias = state.delAngBias / dtIMU;
}
// get quaternion data
void SmallEKF::getQuat(Quaternion &quat) const
{
quat = state.quat;
}
#endif // HAL_CPU_CLASS

View File

@ -86,6 +86,12 @@ public:
// get some debug information
void getDebug(float &tilt, Vector3f &velocity, Vector3f &euler, Vector3f &gyroBias) const;
// get gyro bias data
void getGyroBias(Vector3f &gyroBias) const;
// get quaternion data
void getQuat(Quaternion &quat) const;
static const struct AP_Param::GroupInfo var_info[];
private: