mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
AP_AHRS: added uptime_ms() interface
This commit is contained in:
parent
23787cf695
commit
7a76f72bf5
@ -354,6 +354,9 @@ public:
|
||||
// true if the AHRS has completed initialisation
|
||||
virtual bool initialised(void) const { return true; };
|
||||
|
||||
// time that the AHRS has been up
|
||||
virtual uint32_t uptime_ms(void) const = 0;
|
||||
|
||||
protected:
|
||||
AHRS_VehicleClass _vehicle_class;
|
||||
|
||||
|
@ -967,3 +967,14 @@ 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);
|
||||
}
|
||||
|
||||
/*
|
||||
return amount of time that AHRS has been up
|
||||
*/
|
||||
uint32_t AP_AHRS_DCM::uptime_ms(void) const
|
||||
{
|
||||
if (_last_startup_ms == 0) {
|
||||
return 0;
|
||||
}
|
||||
return hal.scheduler->millis() - _last_startup_ms;
|
||||
}
|
||||
|
@ -110,6 +110,9 @@ public:
|
||||
// is the AHRS subsystem healthy?
|
||||
bool healthy(void) const;
|
||||
|
||||
// time that the AHRS has been up
|
||||
uint32_t uptime_ms(void) const;
|
||||
|
||||
private:
|
||||
float _ki;
|
||||
float _ki_yaw;
|
||||
|
Loading…
Reference in New Issue
Block a user