mirror of https://github.com/ArduPilot/ardupilot
AP_InertialSensor: fixed typo
This commit is contained in:
parent
081df44d92
commit
cb858d2c99
|
@ -130,7 +130,7 @@ public:
|
||||||
bool get_accel_health(uint8_t instance) const { return (instance<_accel_count) ? _accel_healthy[instance] : false; }
|
bool get_accel_health(uint8_t instance) const { return (instance<_accel_count) ? _accel_healthy[instance] : false; }
|
||||||
bool get_accel_health(void) const { return get_accel_health(_primary_accel); }
|
bool get_accel_health(void) const { return get_accel_health(_primary_accel); }
|
||||||
bool get_accel_health_all(void) const;
|
bool get_accel_health_all(void) const;
|
||||||
uint8_t get_accel_count(void) const { return _accel_count; };
|
uint8_t get_accel_count(void) const { return _accel_count; }
|
||||||
bool accel_calibrated_ok_all() const;
|
bool accel_calibrated_ok_all() const;
|
||||||
bool use_accel(uint8_t instance) const;
|
bool use_accel(uint8_t instance) const;
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue