AP_InertialSensor: added error count increments in drivers

This commit is contained in:
Andrew Tridgell 2016-11-10 17:14:38 +11:00
parent bc614de4b3
commit 3289e90134
2 changed files with 18 additions and 0 deletions

View File

@ -232,6 +232,18 @@ void AP_InertialSensor_Backend::_set_gyro_error_count(uint8_t instance, uint32_t
_imu._gyro_error_count[instance] = error_count;
}
// increment accelerometer error_count
void AP_InertialSensor_Backend::_inc_accel_error_count(uint8_t instance)
{
_imu._accel_error_count[instance]++;
}
// increment gyro error_count
void AP_InertialSensor_Backend::_inc_gyro_error_count(uint8_t instance)
{
_imu._gyro_error_count[instance]++;
}
// return the requested sample rate in Hz
uint16_t AP_InertialSensor_Backend::get_sample_rate_hz(void) const
{

View File

@ -140,6 +140,12 @@ protected:
// set gyro error_count
void _set_gyro_error_count(uint8_t instance, uint32_t error_count);
// increment accelerometer error_count
void _inc_accel_error_count(uint8_t instance);
// increment gyro error_count
void _inc_gyro_error_count(uint8_t instance);
// backend unique identifier or -1 if backend doesn't identify itself
int16_t _id = -1;