mirror of https://github.com/ArduPilot/ardupilot
IMU speedup by shorting the temp calculation. If someone bothers to temp calibrate their sensors, they'll need to edit this shortcut.
git-svn-id: https://arducopter.googlecode.com/svn/trunk@2677 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
569087199d
commit
ebfb132f34
|
@ -222,12 +222,12 @@ AP_IMU_Oilpan::_sensor_compensation(uint8_t channel, int temperature) const
|
|||
// do gyro temperature compensation
|
||||
if (channel < 3) {
|
||||
|
||||
//return 1658;
|
||||
//*
|
||||
return 1658;
|
||||
/*
|
||||
return _gyro_temp_curve[channel][0] +
|
||||
_gyro_temp_curve[channel][1] * temperature +
|
||||
_gyro_temp_curve[channel][2] * temperature * temperature;
|
||||
// */
|
||||
//*/
|
||||
}
|
||||
|
||||
// do fixed-offset accelerometer compensation
|
||||
|
|
|
@ -95,14 +95,14 @@ private:
|
|||
// Maximum possible value returned by an offset-corrected sensor channel
|
||||
//
|
||||
static const float _adc_constraint = 900;
|
||||
|
||||
|
||||
// Gyro and Accelerometer calibration criterial
|
||||
//
|
||||
static const float _gyro_total_cal_change = 4.0; // Experimentally derived - allows for some minor motion
|
||||
static const float _gyro_max_cal_offset = 320.0;
|
||||
static const float _gyro_max_cal_offset = 320.0;
|
||||
static const float _accel_total_cal_change = 4.0;
|
||||
static const float _accel_max_cal_offset = 250.0;
|
||||
|
||||
|
||||
};
|
||||
|
||||
#endif
|
||||
|
|
Loading…
Reference in New Issue