mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
AHRS: rename ekfNotStarted method to initialised
Also created default implementation in AP_AHRS class so AP_AHRS_DCM does not need to implement it.
This commit is contained in:
parent
b51d01f979
commit
29c704fecc
@ -338,8 +338,8 @@ public:
|
|||||||
// is the AHRS subsystem healthy?
|
// is the AHRS subsystem healthy?
|
||||||
virtual bool healthy(void) = 0;
|
virtual bool healthy(void) = 0;
|
||||||
|
|
||||||
// is the EKF waiting to start?
|
// true if the AHRS has completed initialisation
|
||||||
virtual bool ekfNotStarted(void) = 0;
|
virtual bool initialised(void) const { return true; };
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
AHRS_VehicleClass _vehicle_class;
|
AHRS_VehicleClass _vehicle_class;
|
||||||
|
@ -937,8 +937,3 @@ bool AP_AHRS_DCM::healthy(void)
|
|||||||
// consider ourselves healthy if there have been no failures for 5 seconds
|
// consider ourselves healthy if there have been no failures for 5 seconds
|
||||||
return (_last_failure_ms == 0 || hal.scheduler->millis() - _last_failure_ms > 5000);
|
return (_last_failure_ms == 0 || hal.scheduler->millis() - _last_failure_ms > 5000);
|
||||||
}
|
}
|
||||||
|
|
||||||
bool AP_AHRS_DCM::ekfNotStarted(void)
|
|
||||||
{
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
|
@ -106,9 +106,6 @@ public:
|
|||||||
// is the AHRS subsystem healthy?
|
// is the AHRS subsystem healthy?
|
||||||
bool healthy(void);
|
bool healthy(void);
|
||||||
|
|
||||||
// is the EKF waiting to start?
|
|
||||||
bool ekfNotStarted(void);
|
|
||||||
|
|
||||||
private:
|
private:
|
||||||
float _ki;
|
float _ki;
|
||||||
float _ki_yaw;
|
float _ki_yaw;
|
||||||
|
@ -266,10 +266,12 @@ bool AP_AHRS_NavEKF::healthy(void)
|
|||||||
return AP_AHRS_DCM::healthy();
|
return AP_AHRS_DCM::healthy();
|
||||||
}
|
}
|
||||||
|
|
||||||
bool AP_AHRS_NavEKF::ekfNotStarted(void)
|
// true if the AHRS has completed initialisation
|
||||||
|
bool AP_AHRS_NavEKF::initialised(void) const
|
||||||
{
|
{
|
||||||
return !ekf_started;
|
// initialisation complete 10sec after ekf has started
|
||||||
}
|
return (ekf_started && (hal.scheduler->millis() - start_time_ms > AP_AHRS_NAVEKF_SETTLE_TIME_MS));
|
||||||
|
};
|
||||||
|
|
||||||
#endif // AP_AHRS_NAVEKF_AVAILABLE
|
#endif // AP_AHRS_NAVEKF_AVAILABLE
|
||||||
|
|
||||||
|
@ -28,6 +28,7 @@
|
|||||||
#include <AP_NavEKF.h>
|
#include <AP_NavEKF.h>
|
||||||
|
|
||||||
#define AP_AHRS_NAVEKF_AVAILABLE 1
|
#define AP_AHRS_NAVEKF_AVAILABLE 1
|
||||||
|
#define AP_AHRS_NAVEKF_SETTLE_TIME_MS 20000 // time in milliseconds the ekf needs to settle after being started
|
||||||
|
|
||||||
class AP_AHRS_NavEKF : public AP_AHRS_DCM
|
class AP_AHRS_NavEKF : public AP_AHRS_DCM
|
||||||
{
|
{
|
||||||
@ -95,8 +96,8 @@ public:
|
|||||||
// is the AHRS subsystem healthy?
|
// is the AHRS subsystem healthy?
|
||||||
bool healthy(void);
|
bool healthy(void);
|
||||||
|
|
||||||
// is the EKF waiting to start?
|
// true if the AHRS has completed initialisation
|
||||||
bool ekfNotStarted(void);
|
bool initialised(void) const;
|
||||||
|
|
||||||
private:
|
private:
|
||||||
bool using_EKF(void) const;
|
bool using_EKF(void) const;
|
||||||
|
Loading…
Reference in New Issue
Block a user