mirror of https://github.com/ArduPilot/ardupilot
AP_AHRS: Allow checking all EKF cores for health
This commit is contained in:
parent
fe3b29a088
commit
334b1622e1
|
@ -497,6 +497,8 @@ public:
|
|||
// is the AHRS subsystem healthy?
|
||||
virtual bool healthy(void) const = 0;
|
||||
|
||||
virtual bool prearm_healthy(void) const { return healthy(); }
|
||||
|
||||
// true if the AHRS has completed initialisation
|
||||
virtual bool initialised(void) const {
|
||||
return true;
|
||||
|
|
|
@ -1114,6 +1114,33 @@ bool AP_AHRS_NavEKF::healthy(void) const
|
|||
return AP_AHRS_DCM::healthy();
|
||||
}
|
||||
|
||||
bool AP_AHRS_NavEKF::prearm_healthy(void) const
|
||||
{
|
||||
bool prearm_health = false;
|
||||
switch (ekf_type()) {
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
case EKF_TYPE_SITL:
|
||||
#endif
|
||||
case EKF_TYPE_NONE:
|
||||
prearm_health = true;
|
||||
break;
|
||||
|
||||
case EKF_TYPE2:
|
||||
default:
|
||||
if (_ekf2_started && EKF2.all_cores_healthy()) {
|
||||
prearm_health = true;
|
||||
}
|
||||
break;
|
||||
|
||||
case EKF_TYPE3:
|
||||
if (_ekf3_started && EKF3.all_cores_healthy()) {
|
||||
prearm_health = true;
|
||||
}
|
||||
break;
|
||||
}
|
||||
return prearm_health && healthy();
|
||||
}
|
||||
|
||||
void AP_AHRS_NavEKF::set_ekf_use(bool setting)
|
||||
{
|
||||
_ekf_type.set(setting?1:0);
|
||||
|
|
|
@ -175,6 +175,8 @@ public:
|
|||
// is the AHRS subsystem healthy?
|
||||
bool healthy() const override;
|
||||
|
||||
bool prearm_healthy() const override;
|
||||
|
||||
// true if the AHRS has completed initialisation
|
||||
bool initialised() const override;
|
||||
|
||||
|
|
Loading…
Reference in New Issue