diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_LSM9DS0.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_LSM9DS0.cpp index f201017270..5a17fb4d61 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_LSM9DS0.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_LSM9DS0.cpp @@ -476,8 +476,8 @@ bool AP_InertialSensor_LSM9DS0::_hardware_init() } // setup for register checking - _dev_gyro->setup_checked_registers(5); - _dev_accel->setup_checked_registers(4); + _dev_gyro->setup_checked_registers(5, 20); + _dev_accel->setup_checked_registers(4, 20); for (tries = 0; tries < 5; tries++) { _dev_gyro->set_speed(AP_HAL::Device::SPEED_LOW); @@ -694,15 +694,12 @@ bool AP_InertialSensor_LSM9DS0::_poll_data() _read_data_transaction_a(); } - if (_reg_check_counter++ == 10) { - _reg_check_counter = 0; - // check next register value for correctness - if (!_dev_gyro->check_next_register()) { - _inc_gyro_error_count(_gyro_instance); - } - if (!_dev_accel->check_next_register()) { - _inc_accel_error_count(_accel_instance); - } + // check next register value for correctness + if (!_dev_gyro->check_next_register()) { + _inc_gyro_error_count(_gyro_instance); + } + if (!_dev_accel->check_next_register()) { + _inc_accel_error_count(_accel_instance); } return true; diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_LSM9DS0.h b/libraries/AP_InertialSensor/AP_InertialSensor_LSM9DS0.h index 038abc39d5..49373e1d93 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_LSM9DS0.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor_LSM9DS0.h @@ -103,6 +103,4 @@ private: */ enum Rotation _rotation_a; enum Rotation _rotation_g; - - uint8_t _reg_check_counter; }; diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp index 2827134cbc..aae7ffb31c 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp @@ -669,14 +669,13 @@ void AP_InertialSensor_MPU6000::_read_fifo() } check_registers: - if (_reg_check_counter++ == 10) { - _reg_check_counter = 0; - // check next register value for correctness - if (!_dev->check_next_register()) { - _inc_gyro_error_count(_gyro_instance); - _inc_accel_error_count(_accel_instance); - } + // check next register value for correctness + _dev->set_speed(AP_HAL::Device::SPEED_LOW); + if (!_dev->check_next_register()) { + _inc_gyro_error_count(_gyro_instance); + _inc_accel_error_count(_accel_instance); } + _dev->set_speed(AP_HAL::Device::SPEED_HIGH); } bool AP_InertialSensor_MPU6000::_block_read(uint8_t reg, uint8_t *buf, @@ -766,7 +765,7 @@ bool AP_InertialSensor_MPU6000::_hardware_init(void) } // setup for register checking - _dev->setup_checked_registers(7); + _dev->setup_checked_registers(7, 20); // initially run the bus at low speed _dev->set_speed(AP_HAL::Device::SPEED_LOW); diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.h b/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.h index 65bcc5d260..07a4d55cfa 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.h @@ -109,8 +109,6 @@ private: // buffer for fifo read uint8_t *_fifo_buffer; - uint8_t _reg_check_counter; - /* accumulators for fast sampling See description in _accumulate_fast_sampling() diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_MPU9250.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_MPU9250.cpp index b02c2d39f9..c6385176e4 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_MPU9250.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_MPU9250.cpp @@ -605,15 +605,13 @@ bool AP_InertialSensor_MPU9250::_read_sample() } check_registers: - if (_reg_check_counter++ == 10) { - _reg_check_counter = 0; - // check next register value for correctness - if (!_dev->check_next_register()) { - _inc_gyro_error_count(_gyro_instance); - _inc_accel_error_count(_accel_instance); - } + // check next register value for correctness + _dev->set_speed(AP_HAL::Device::SPEED_LOW); + if (!_dev->check_next_register()) { + _inc_gyro_error_count(_gyro_instance); + _inc_accel_error_count(_accel_instance); } - + _dev->set_speed(AP_HAL::Device::SPEED_HIGH); return true; } @@ -642,7 +640,7 @@ bool AP_InertialSensor_MPU9250::_hardware_init(void) } // setup for register checking - _dev->setup_checked_registers(6); + _dev->setup_checked_registers(6, 20); // initially run the bus at low speed _dev->set_speed(AP_HAL::Device::SPEED_LOW); diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_MPU9250.h b/libraries/AP_InertialSensor/AP_InertialSensor_MPU9250.h index 7e79d754c9..4dc1d2e9fc 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_MPU9250.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor_MPU9250.h @@ -97,8 +97,6 @@ private: // buffer for fifo read uint8_t *_fifo_buffer; - uint8_t _reg_check_counter; - /* accumulators for fast sampling See description in _accumulate_fast_sampling()