AP_InertialSensor: widen allowable temp gap on invensense IMUs

some sensors have more temperature noise
This commit is contained in:
Andrew Tridgell 2019-02-17 14:30:07 +11:00
parent 5f88340919
commit 2b285089e9
1 changed files with 1 additions and 1 deletions

View File

@ -625,7 +625,7 @@ bool AP_InertialSensor_Invensense::_check_raw_temp(int16_t t2)
if (_block_read(MPUREG_TEMP_OUT_H, trx, 2)) {
_raw_temp = int16_val(trx, 0);
}
return (abs(t2 - _raw_temp) < 400);
return (abs(t2 - _raw_temp) < 800);
}
bool AP_InertialSensor_Invensense::_block_read(uint8_t reg, uint8_t *buf,