mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_InertialSensor: remove unused ins error count logging
This commit is contained in:
parent
81044760c7
commit
be634a893f
@ -197,7 +197,6 @@ public:
|
||||
// return the main loop delta_t in seconds
|
||||
float get_loop_delta_t(void) const { return _loop_delta_t; }
|
||||
|
||||
uint16_t error_count(void) const { return 0; }
|
||||
bool healthy(void) const { return get_gyro_health() && get_accel_health(); }
|
||||
|
||||
uint8_t get_primary_accel(void) const { return _primary_accel; }
|
||||
|
Loading…
Reference in New Issue
Block a user