mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF: Publish small EKF quaternion and gyro bias outputs
This commit is contained in:
parent
17445d03f0
commit
5f24603ceb
|
@ -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
|
||||
|
|
|
@ -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:
|
||||
|
|
Loading…
Reference in New Issue