|
|
|
@ -283,8 +283,10 @@ void AP_InertialSensor_BMI055::read_fifo_accel(void)
@@ -283,8 +283,10 @@ void AP_InertialSensor_BMI055::read_fifo_accel(void)
|
|
|
|
|
_publish_temperature(accel_instance, temp_degc); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if (!dev_accel->check_next_register()) { |
|
|
|
|
|
|
|
|
|
AP_HAL::Device::checkreg reg; |
|
|
|
|
if (!dev_accel->check_next_register(reg)) { |
|
|
|
|
log_register_change(dev_accel->get_bus_id(), reg); |
|
|
|
|
_inc_accel_error_count(accel_instance); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
@ -329,7 +331,9 @@ void AP_InertialSensor_BMI055::read_fifo_gyro(void)
@@ -329,7 +331,9 @@ void AP_InertialSensor_BMI055::read_fifo_gyro(void)
|
|
|
|
|
_notify_new_gyro_raw_sample(gyro_instance, gyro); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if (!dev_gyro->check_next_register()) { |
|
|
|
|
AP_HAL::Device::checkreg reg; |
|
|
|
|
if (!dev_gyro->check_next_register(reg)) { |
|
|
|
|
log_register_change(dev_gyro->get_bus_id(), reg); |
|
|
|
|
_inc_gyro_error_count(gyro_instance); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|