Skip to content

Latest commit

 

History

History
185 lines (130 loc) · 16.5 KB

sensor_thermal_calibration.md

File metadata and controls

185 lines (130 loc) · 16.5 KB

Thermal Calibration and Compensation

PX4 contains functionality to calibrate and compensate accelerometer, gyro, magnetometer, and barometric pressure sensors for the effect of changing sensor temperature on sensor bias.

This topic details the test environment and calibration procedures. At the end there is a description of the implementation.

:::note After thermal calibration, the thermal calibration parameters (TC_*) are used for all calibration/compensation of the respective sensors. Any subsequent standard calibration will therefore update TC_* parameters and not the "normal" SYS_CAL_* calibration parameters (and in some cases these parameters may be reset). :::

:::note Releases up to PX4 v1.14, do not support thermal calibration of the magnetometer. :::

Test Setup/Best Practice

The calibration procedures described in the following sections are ideally run in an environmental chamber (a temperature and humidity controlled environment) as the board is heated from the lowest to the highest operating/calibration temperature. Before starting the calibration, the board is first cold soaked (cooled to the minimum temperature and allowed to reach equilibrium).

:::note Active electric heating elements will affect the magnetometer calibration values. Ensure that heating elements are either inactive or sufficiently far from the sensor to avoid injecting noise into the magnetometer calibration. :::

For the cold soak you can use a regular home freezer to achieve -20C, and commercial freezers can achieve of the order of -40C. The board should be placed in a ziplock/anti-static bag containing a silica packet, with a power lead coming out through a sealed hole. After the cold soak the bag can be moved to the test environment and the test continued in the same bag.

:::note The bag/silica is to prevent condensation from forming on the board. :::

It possible to perform the calibration without a commercial-grade environment chamber. A simple environment container can be created using a styrofoam box with a very small internal volume of air. This allows the autopilot to self-heat the air relatively quickly (be sure that the box has a small hole to equalize to ambient room pressure, but still be able to heat up inside).

Using this sort of setup it is possible to heat a board to ~70C. Anecdotal evidence suggests that many common boards can be heated to this temperature without adverse side effects. If in doubt, check the safe operating range with your manufacturer.

:::tip To check the status of the onboard thermal calibration use the MAVlink console (or NuttX console) to check the reported internal temp from the sensor. :::

Calibration Procedures

PX4 supports two calibration procedures:

  • onboard - calibration is run on the board itself. This method requires knowledge of the amount of temperature rise that is achievable with the test setup.
  • offboard - compensation parameters are calculated on a development computer based on log information collected during the calibration procedure. This method allows users to visually check the quality of the data and curve-fit.

The offboard approach is more complex and slower, but requires less knowledge of the test setup and is easier to validate.

Onboard Calibration Procedure

Onboard calibration is run entirely on the device. It require knowledge of the amount of temperature rise that is achievable with the test setup.

To perform and onboard calibration:

  1. Ensure the frame type is set before calibration, otherwise calibration parameters will be lost when the board is setup.
  2. Power the board and set the SYS_CAL_* parameters to 1 to enable calibration of the required sensors at the next startup. 1
  3. Set the SYS_CAL_TDEL parameter to the number of degrees of temperature rise required for the onboard calibrator to complete. If this parameter is too small, then the calibration will complete early and the temperature range for the calibration will not be sufficient to compensate when the board is fully warmed up. If this parameter is set too large, then the onboard calibrator will never complete. allowance should be made for the rise in temperature due to the boards self heating when setting this parameter. If the amount of temperature rise at the sensors is unknown, then the off-board method should be used.
  4. Set the SYS_CAL_TMIN parameter to the lowest temperature data that you want the calibrator to use. This enables a lower cold soak ambient temperature to be used to reduce the cold soak time whilst maintaining control over the calibration minimum temperature. The data for a sensor will not be used by the calibrator if it is below the value set by this parameter.
  5. Set the SYS_CAL_TMAX parameter to the highest starting sensor temperature that should be accepted by the calibrator. If the starting temperature is higher than the value set by this parameter, the calibration will exit with an error. Note that if the variation in measured temperature between different sensors exceeds the gap between SYS_CAL_TMAX and SYS_CAL_TMIN, then it will be impossible for the calibration to start.
  6. Remove power and cold soak the board to below the starting temperature specified by the SYS_CAL_TMIN parameter. Note that there is a 10 second delay on startup before calibration starts to allow any sensors to stabilise and the sensors will warm internally during this period.
  7. Keeping the board stationary2, apply power and warm to a temperature high enough to achieve the temperature rise specified by the SYS_CAL_TDEL parameter. The completion percentage is printed to the system console during calibration. 3
  8. When the calibration completes, remove power, allow the board to cool to a temperature that is within the calibration range before performing the next step.
  9. Perform a 6-point accel calibration via the system console using commander calibrate accel or via QGroundControl. If the board is being set-up for the first time, the gyro and magnetometer calibration will also need to be performed.
  10. The board should always be re-powered before flying after any sensor calibration, because sudden offset changes from calibration can upset the navigation estimator and some parameters are not loaded by the algorithms that use them until the next startup.

Offboard Calibration Procedure

Offboard calibration is run on a development computer using data collected during the calibration test. This method provides a way to visually check the quality of data and curve fit.

To perform an offboard calibration:

  1. Ensure the frame type is set before calibration, otherwise calibration parameters will be lost when the board is setup.
  2. Power up the board and set the TC_A_ENABLE, TC_B_ENABLE, TC_G_ENABLE, and TC_M_ENABLE parameters to 1.
  3. Set all CAL_ACC*, CAL_GYRO*, CAL_MAG*, and CAL_BARO* parameters to defaults.
  4. Set the SDLOG_MODE parameter to 2 to enable logging of data from boot.
  5. Set the SDLOG_PROFILE checkbox for thermal calibration (bit 2) to log the raw sensor data required for calibration.
  6. Cold soak the board to the minimum temperature it will be required to operate in.
  7. Apply power and keeping the board still 2, warm it slowly to the maximum required operating temperature. 3
  8. Remove power and extract the .ulog file.
  9. Open a terminal window in the Firmware/Tools directory and run the python calibration script:
    python process_sensor_caldata.py <full path name to .ulog file>
    This will generate a .pdf file showing the measured data and curve fits for each sensor, and a .params file containing the calibration parameters.
  10. Power the board, connect QGroundControl and load the parameter from the generated .params file onto the board using QGroundControl. Due to the number of parameters, loading them may take some time.
  11. After parameters have finished loading, set SDLOG_MODE to 1 to re-enable normal logging and remove power.
  12. Power the board and perform a normal accelerometer sensor calibration using QGroundControl. It is important that this step is performed when board is within the calibration temperature range. The board must be repowered after this step before flying as the sudden offset changes can upset the navigation estimator and some parameters are not loaded by the algorithms that use them until the next startup.

Implementation Detail

Calibration refers to the process of measuring the change in sensor value across a range of internal temperatures, and performing a polynomial fit on the data to calculate a set of coefficients (stored as parameters) that can be used to correct the sensor data. Compensation refers to the process of using the internal temperature to calculate an offset that is subtracted from the sensor reading to correct for changing offset with temperature

The accelerometer, gyro, and magnetometer sensor offsets are calculated using a 3rd order polynomial, whereas the barometric pressure sensor offset is calculated using a 5th order polynomial. Example fits are show below:

Thermal calibration accel

Thermal calibration gyro

Thermal calibration mag

Thermal calibration barometer

Calibration Parameter Storage

With the existing parameter system implementation we are limited to storing each value in the struct as a separate entry. To work around this limitation the following logical naming convention is used for the thermal compensation parameters:

TC_[type][instance]_[cal_name]_[axis]

Where:

  • type: is a single character indicating the type of sensor where A = accelerometer, G = rate gyroscope, M = magnetometer, and B = barometer.

  • instance: is an integer 0,1 or 2 allowing for calibration of up to three sensors of the same type.

  • cal_name: is a string identifying the calibration value. It has the following possible values:

    • Xn: Polynomial coefficient where n is the order of the coefficient, e.g. X3 * (temperature - reference temperature)**3.
    • SCL: scale factor.
    • TREF: reference temperature (deg C).
    • TMIN: minimum valid temperature (deg C).
    • TMAX: maximum valid temperature (deg C).
  • axis: is an integer 0,1 or 2 indicating that the calibration data is for X,Y or Z axis in the board frame of reference. For the barometric pressure sensor, the axis suffix is omitted.

Examples:

  • TC_A1_TREF is the reference temperature for the second accelerometer.
  • TC_G0_X3_0 is the ^3 coefficient for the first gyro x-axis.

Calibration Parameter Usage

The correction for thermal offsets (using the calibration parameters) is performed in the sensors module. The reference temperature is subtracted from the measured temperature to obtain a delta temperature where:

delta = measured_temperature - reference_temperature

The delta temperature is then used to calculate a offset, where:

offset = X0 + X1*delta + X2*delta**2 + ... + Xn*delta**n

The offset and temperature scale factor are then used to correct the sensor measurement where:

corrected_measurement = (raw_measurement - offset) * scale_factor

If the temperature is above the test range set by the *_TMIN and *_TMAX parameters, then the measured temperature will be clipped to remain within the limits.

Correction of the accelerometer, gyroscope, magnetometer, or barometer data is enabled by setting TC_A_ENABLE, TC_G_ENABLE, TC_M_ENABLE, or TC_B_ENABLE parameters to 1 respectively.

Compatibility with legacy CAL_* parameters and commander controlled calibration

The legacy temperature-agnostic PX4 rate gyro and accelerometer sensor calibration is performed by the commander module and involves adjusting offset, and in the case of accelerometer calibration, scale factor calibration parameters. The offset and scale factor parameters are applied within the driver for each sensor. These parameters are found in the CAL parameter group.

Onboard temperature calibration is controlled by the events module and the corrections are applied within the sensors module before the sensor combined uORB topic is published. This means that if thermal compensation is being used, all of the corresponding legacy offset and scale factor parameters must be set to defaults of zero and unity before a thermal calibration is performed. If an on-board temperature calibration is performed, this will be done automatically, however if an offboard calibration is being performed it is important that the legacy CAL*OFF and CAL*SCALE parameters be reset before calibration data is logged.

If accel thermal compensation has been enabled by setting the TC_A_ENABLE parameter to 1, then the commander controlled 6-point accel calibration can still be performed. However, instead of adjusting the *OFF and *SCALE parameters in the CAL parameter group, these parameters are set to defaults and the thermal compensation X0 and SCL parameters are adjusted instead.

If gyro thermal compensation has been enabled by setting the TC_G_ENABLE parameter to 1, then the commander controlled gyro calibration can still be performed, however it will be used to shift the compensation curve up or down by the amount required to zero the angular rate offset. It achieves this by adjusting the X0 coefficients.

If magnetometer thermal compensation has been enabled by setting the TC_M_ENABLE parameter to 1, then the commander controlled 6-point accel calibration can still be performed. However, instead of adjusting the *OFF and *SCALE parameters in the CAL parameter group, these parameters are set to defaults and the thermal compensation X0 and SCL parameters are adjusted instead.

Limitations

Scale factors are assumed to be temperature invariant due to the difficulty associated with measuring these at different temperatures. This limits the usefulness of the accelerometer calibration to those sensor models with stable scale factors. In theory with a thermal chamber or IMU heater capable of controlling IMU internal temperature to within a degree, it would be possible to perform a series of 6 sided accelerometer calibrations and correct the accelerometers for both offset and scale factor. Due to the complexity of integrating the required board movement with the calibration algorithm, this capability has not been included.


Footnotes

  1. The SYS_CAL_ACCEL, SYS_CAL_BARO and SYS_CAL_GYRO parameters are reset to 0 when the calibration is started.

  2. Calibration of the barometric pressure sensor offsets requires a stable air pressure environment. The air pressure will change slowly due to weather and inside buildings can change rapidly due to external wind fluctuations and HVAC system operation. 2

  3. Care must be taken when warming a cold soaked board to avoid formation of condensation on the board that can cause board damage under some circumstances. 2