mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
AP_AHRS : add method to report if EKF is waiting to start
This commit is contained in:
parent
b06d3d3f52
commit
7cea7c6a18
@ -338,6 +338,9 @@ public:
|
||||
// is the AHRS subsystem healthy?
|
||||
virtual bool healthy(void) = 0;
|
||||
|
||||
// is the EKF waiting to start?
|
||||
virtual bool ekfNotStarted(void) = 0;
|
||||
|
||||
protected:
|
||||
AHRS_VehicleClass _vehicle_class;
|
||||
|
||||
|
@ -937,3 +937,8 @@ bool AP_AHRS_DCM::healthy(void)
|
||||
// consider ourselves healthy if there have been no failures for 5 seconds
|
||||
return (_last_failure_ms == 0 || hal.scheduler->millis() - _last_failure_ms > 5000);
|
||||
}
|
||||
|
||||
bool AP_AHRS_DCM::ekfNotStarted(void)
|
||||
{
|
||||
return false;
|
||||
}
|
||||
|
@ -106,6 +106,9 @@ public:
|
||||
// is the AHRS subsystem healthy?
|
||||
bool healthy(void);
|
||||
|
||||
// is the EKF waiting to start?
|
||||
bool ekfNotStarted(void);
|
||||
|
||||
private:
|
||||
float _ki;
|
||||
float _ki_yaw;
|
||||
|
@ -266,5 +266,10 @@ bool AP_AHRS_NavEKF::healthy(void)
|
||||
return AP_AHRS_DCM::healthy();
|
||||
}
|
||||
|
||||
bool AP_AHRS_NavEKF::ekfNotStarted(void)
|
||||
{
|
||||
return !ekf_started;
|
||||
}
|
||||
|
||||
#endif // AP_AHRS_NAVEKF_AVAILABLE
|
||||
|
||||
|
@ -95,6 +95,9 @@ public:
|
||||
// is the AHRS subsystem healthy?
|
||||
bool healthy(void);
|
||||
|
||||
// is the EKF waiting to start?
|
||||
bool ekfNotStarted(void);
|
||||
|
||||
private:
|
||||
bool using_EKF(void) const;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user