mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_AHRS: make the healthy() method const
This commit is contained in:
parent
850af14949
commit
68f64fa11c
@ -367,7 +367,7 @@ public:
|
||||
uint8_t get_active_accel_instance(void) const { return _active_accel_instance; }
|
||||
|
||||
// is the AHRS subsystem healthy?
|
||||
virtual bool healthy(void) = 0;
|
||||
virtual bool healthy(void) const = 0;
|
||||
|
||||
// true if the AHRS has completed initialisation
|
||||
virtual bool initialised(void) const { return true; };
|
||||
|
@ -960,7 +960,7 @@ void AP_AHRS_DCM::set_home(const Location &loc)
|
||||
/*
|
||||
check if the AHRS subsystem is healthy
|
||||
*/
|
||||
bool AP_AHRS_DCM::healthy(void)
|
||||
bool AP_AHRS_DCM::healthy(void) const
|
||||
{
|
||||
// consider ourselves healthy if there have been no failures for 5 seconds
|
||||
return (_last_failure_ms == 0 || hal.scheduler->millis() - _last_failure_ms > 5000);
|
||||
|
@ -111,7 +111,7 @@ public:
|
||||
void estimate_wind(void);
|
||||
|
||||
// is the AHRS subsystem healthy?
|
||||
bool healthy(void);
|
||||
bool healthy(void) const;
|
||||
|
||||
private:
|
||||
float _ki;
|
||||
|
@ -300,7 +300,7 @@ bool AP_AHRS_NavEKF::using_EKF(void) const
|
||||
/*
|
||||
check if the AHRS subsystem is healthy
|
||||
*/
|
||||
bool AP_AHRS_NavEKF::healthy(void)
|
||||
bool AP_AHRS_NavEKF::healthy(void) const
|
||||
{
|
||||
if (_ekf_use) {
|
||||
return ekf_started && EKF.healthy();
|
||||
|
@ -113,7 +113,7 @@ public:
|
||||
void set_ekf_use(bool setting) { _ekf_use.set(setting); }
|
||||
|
||||
// is the AHRS subsystem healthy?
|
||||
bool healthy(void);
|
||||
bool healthy(void) const;
|
||||
|
||||
// true if the AHRS has completed initialisation
|
||||
bool initialised(void) const;
|
||||
|
Loading…
Reference in New Issue
Block a user