AP_InertialSensor: use default value for temperature scale and offset

This commit is contained in:
Siddharth Purohit 2019-03-06 14:29:10 +05:30 committed by Andrew Tridgell
parent 6ff8f52957
commit 086b4c1cfd
2 changed files with 2 additions and 15 deletions

View File

@ -195,19 +195,6 @@ void AP_InertialSensor_Invensensev2::start()
break;
}
/*
setup temperature sensitivity and offset. This varies
considerably between parts
*/
switch (_inv2_type) {
case Invensensev2_ICM20948:
case Invensensev2_ICM20648:
case Invensensev2_ICM20649:
temp_zero = 21;
temp_sensitivity = 1.0f/333.87f;
break;
}
_gyro_instance = _imu.register_gyro(1125, _dev->get_bus_id_devtype(gdev));
_accel_instance = _imu.register_accel(1125, _dev->get_bus_id_devtype(adev));

View File

@ -104,8 +104,8 @@ private:
uint8_t _gyro_instance;
uint8_t _accel_instance;
float temp_sensitivity = 1.0/340; // degC/LSB
float temp_zero = 36.53; // degC
float temp_sensitivity = 1.0f/333.87f; // degC/LSB
float temp_zero = 21; // degC
float _temp_filtered;