AP_SmallEKF: add function to report if the EKF is stable

This commit is contained in:
Arthur Benemann 2015-03-05 15:23:14 -08:00 committed by Randy Mackay
parent 7b28bf7d44
commit 1d9beed42f
2 changed files with 10 additions and 0 deletions

View File

@ -925,4 +925,11 @@ void SmallEKF::getQuat(Quaternion &quat) const
quat = state.quat;
}
// get filter status - true is aligned
bool SmallEKF::getStatus() const
{
float run_time = hal.scheduler->millis() - StartTime_ms;
return YawAligned && (run_time > 10000);
}
#endif // HAL_CPU_CLASS

View File

@ -92,6 +92,9 @@ public:
// get quaternion data
void getQuat(Quaternion &quat) const;
// get filter alignment status - true is aligned
bool getStatus(void) const;
static const struct AP_Param::GroupInfo var_info[];
private: