INS: add get_accel_health_all and get_gyro_health_all

Returns true only if all available accels or gyros are healthy
This commit is contained in:
Randy Mackay 2014-09-01 20:20:27 +09:00
parent 50ae5b2519
commit 74553e523d
2 changed files with 26 additions and 0 deletions

View File

@ -294,6 +294,30 @@ AP_InertialSensor::init_gyro()
_save_parameters();
}
// get_gyro_health_all - return true if all gyros are healthy
bool AP_InertialSensor::get_gyro_health_all(void) const
{
for (uint8_t i=0; i<get_gyro_count(); i++) {
if (!get_gyro_health(i)) {
return false;
}
}
// return true if we have at least one gyro
return (get_gyro_count() > 0);
}
// get_accel_health_all - return true if all accels are healthy
bool AP_InertialSensor::get_accel_health_all(void) const
{
for (uint8_t i=0; i<get_accel_count(); i++) {
if (!get_accel_health(i)) {
return false;
}
}
// return true if we have at least one accel
return (get_accel_count() > 0);
}
void
AP_InertialSensor::_init_accel()
{

View File

@ -118,10 +118,12 @@ public:
// multi-device interface
virtual bool get_gyro_health(uint8_t instance) const { return true; }
bool get_gyro_health(void) const { return get_gyro_health(_get_primary_gyro()); }
bool get_gyro_health_all(void) const;
virtual uint8_t get_gyro_count(void) const { return 1; };
virtual bool get_accel_health(uint8_t instance) const { return true; }
bool get_accel_health(void) const { return get_accel_health(get_primary_accel()); }
bool get_accel_health_all(void) const;
virtual uint8_t get_accel_count(void) const { return 1; };
// get accel offsets in m/s/s