Browse Source

AP_InertialSensor: added error count increments in drivers

mission-4.1.18
Andrew Tridgell 8 years ago
parent
commit
3289e90134
  1. 12
      libraries/AP_InertialSensor/AP_InertialSensor_Backend.cpp
  2. 6
      libraries/AP_InertialSensor/AP_InertialSensor_Backend.h

12
libraries/AP_InertialSensor/AP_InertialSensor_Backend.cpp

@ -232,6 +232,18 @@ void AP_InertialSensor_Backend::_set_gyro_error_count(uint8_t instance, uint32_t @@ -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
{

6
libraries/AP_InertialSensor/AP_InertialSensor_Backend.h

@ -140,6 +140,12 @@ protected: @@ -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;

Loading…
Cancel
Save