mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
AP_InertialNav: remove virtual qualifier from error_count
This commit is contained in:
parent
0c0521a555
commit
e27ff75a71
@ -204,7 +204,7 @@ public:
|
|||||||
/**
|
/**
|
||||||
* error_count - returns number of missed updates from GPS
|
* error_count - returns number of missed updates from GPS
|
||||||
*/
|
*/
|
||||||
virtual uint8_t error_count() const { return _error_count; }
|
uint8_t error_count() const { return _error_count; }
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* ignore_next_error - the next error (if it occurs immediately) will not be added to the error count
|
* ignore_next_error - the next error (if it occurs immediately) will not be added to the error count
|
||||||
|
Loading…
Reference in New Issue
Block a user