AP_AHRS: Remove unused uptime
This commit is contained in:
parent
94a1835a9b
commit
2ed1757353
@ -542,9 +542,6 @@ public:
|
||||
return false;
|
||||
}
|
||||
|
||||
// time that the AHRS has been up
|
||||
virtual uint32_t uptime_ms(void) const = 0;
|
||||
|
||||
// get the selected ekf type, for allocation decisions
|
||||
int8_t get_ekf_type(void) const {
|
||||
return _ekf_type;
|
||||
|
@ -1075,14 +1075,3 @@ bool AP_AHRS_DCM::healthy(void) const
|
||||
// consider ourselves healthy if there have been no failures for 5 seconds
|
||||
return (_last_failure_ms == 0 || AP_HAL::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 AP_HAL::millis() - _last_startup_ms;
|
||||
}
|
||||
|
@ -102,9 +102,6 @@ public:
|
||||
// is the AHRS subsystem healthy?
|
||||
bool healthy() const override;
|
||||
|
||||
// time that the AHRS has been up
|
||||
uint32_t uptime_ms() const override;
|
||||
|
||||
private:
|
||||
float _ki;
|
||||
float _ki_yaw;
|
||||
|
Loading…
Reference in New Issue
Block a user