mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 01:18:29 -04:00
Revert "AP_InertialSensor: disable temperature based fifo check on ICM20602"
This reverts commit 05f8e3c18d
.
this leads to bad IMU data on ICM20602
This commit is contained in:
parent
64774a2f92
commit
9fa3a433f5
@ -226,7 +226,6 @@ void AP_InertialSensor_Invensense::start()
|
|||||||
gdev = DEVTYPE_INS_ICM20602;
|
gdev = DEVTYPE_INS_ICM20602;
|
||||||
adev = DEVTYPE_INS_ICM20602;
|
adev = DEVTYPE_INS_ICM20602;
|
||||||
_enable_offset_checking = true;
|
_enable_offset_checking = true;
|
||||||
_disable_temp_fifo_check = true;
|
|
||||||
break;
|
break;
|
||||||
case Invensense_ICM20601:
|
case Invensense_ICM20601:
|
||||||
gdev = DEVTYPE_INS_ICM20601;
|
gdev = DEVTYPE_INS_ICM20601;
|
||||||
@ -547,7 +546,7 @@ bool AP_InertialSensor_Invensense::_accumulate(uint8_t *samples, uint8_t n_sampl
|
|||||||
accel *= _accel_scale;
|
accel *= _accel_scale;
|
||||||
|
|
||||||
int16_t t2 = int16_val(data, 3);
|
int16_t t2 = int16_val(data, 3);
|
||||||
if (!_disable_temp_fifo_check && !_check_raw_temp(t2)) {
|
if (!_check_raw_temp(t2)) {
|
||||||
if (!hal.scheduler->in_expected_delay()) {
|
if (!hal.scheduler->in_expected_delay()) {
|
||||||
debug("temp reset IMU[%u] %d %d", _accel_instance, _raw_temp, t2);
|
debug("temp reset IMU[%u] %d %d", _accel_instance, _raw_temp, t2);
|
||||||
}
|
}
|
||||||
@ -592,7 +591,7 @@ bool AP_InertialSensor_Invensense::_accumulate_sensor_rate_sampling(uint8_t *sam
|
|||||||
|
|
||||||
// use temperatue to detect FIFO corruption
|
// use temperatue to detect FIFO corruption
|
||||||
int16_t t2 = int16_val(data, 3);
|
int16_t t2 = int16_val(data, 3);
|
||||||
if (!_disable_temp_fifo_check && !_check_raw_temp(t2)) {
|
if (!_check_raw_temp(t2)) {
|
||||||
if (!hal.scheduler->in_expected_delay()) {
|
if (!hal.scheduler->in_expected_delay()) {
|
||||||
debug("temp reset IMU[%u] %d %d", _accel_instance, _raw_temp, t2);
|
debug("temp reset IMU[%u] %d %d", _accel_instance, _raw_temp, t2);
|
||||||
}
|
}
|
||||||
|
@ -169,9 +169,6 @@ private:
|
|||||||
// buffer for fifo read
|
// buffer for fifo read
|
||||||
uint8_t *_fifo_buffer;
|
uint8_t *_fifo_buffer;
|
||||||
|
|
||||||
// disable temperature based fifo check
|
|
||||||
bool _disable_temp_fifo_check;
|
|
||||||
|
|
||||||
/*
|
/*
|
||||||
accumulators for sensor_rate sampling
|
accumulators for sensor_rate sampling
|
||||||
See description in _accumulate_sensor_rate_sampling()
|
See description in _accumulate_sensor_rate_sampling()
|
||||||
|
Loading…
Reference in New Issue
Block a user