Gyroscope and Accelerometer Calibration with Raspberry Pi

mpu9250_measure.jpg
“As an Amazon Associates Program member, clicking on links may result in Maker Portal receiving a small commission that helps support future projects.”

This is the second entry into the series entitled "Calibration of an Inertial Measurement Unit (IMU) with Raspberry Pi" (Link to Part I) where the gyroscope and accelerometer are calibrated using our Calibration Block. Python is used as the coding language on the Raspberry Pi to find the calibration coefficients for the two sensors. Validation methods are also used to integrate the IMU variables to test the calibration of each sensor. The gyroscope shows a fairly accurate response when calibrated and integrated, and found to be within a degree of the actual rotation test. The accelerometer was slightly less accurate, likely due to the double integration required to approximate displacement and the unbalanced table upon which the IMU was calibrated. Filtering methods are also introduced to smooth the accelerometer data for integration. The final sensor, the magnetometer (AK8963), will be calibrated in the next iteration of this series.


The MPU9250 is a 9 degree-of-freedom (9-DoF) inertial measurement unit (IMU) that houses an accelerometer/gyroscope combination sensor (MPU6050) and a magnetometer sensor (AK8963). The data read by the accel/gyro (MPU6050) and mag (AK8963) can be best understood by first investigating the configuration of each sensor’s coordinate system. Below is the coordinate composition for both sensors:

mpu6050_ak8963_drawing_coordinates.png

The accelerometer coordinate system uses a somewhat traditional cartesian coordinate system. Similarly, the gyroscope uses a counter-clockwise rotation as the positive rotation direction. The magnetometer switches the x- and y-directions, while reversing the direction of the z-direction amplitude. These conventions will come into play during calibration and will be clarified and discussed for each of the three sensors.

The coordinate references will be essential for understanding the data being read by the MPU9250 and developing methods for calibrating the IMU.

Range of each Sensor:

  • Accelerometer - will be calibrated under the range of 0g-2g

  • Gyroscope - will be calibrated under the range of 0dps - 250dps

  • Magnetometer - will be calibrated under the range of 0μT - 4800μT

 

-note on sample rate-

The sample rate being used is 8kHz, which is the fastest update rate for the gyroscope. The accelerometer rate is nearer to 1kHz, and the magnetometer maxes out at 100Hz. The effective sample rate is ≈ 400Hz, which results in repeated values for the AK8963 sensor.
 

The MPU9250 will be attached to our Calibration Block which will allow for rotation along each axis and ensure that the sensors are calibrated for best alignment with gravity (accelerometer) and rotation about each axis (magnetometer).

IMU_cal_block.gif

IMU Calibration Block Kit with MPU9250


The simplest calibration of an IMU consists of calculating the offset for each axis of the gyroscope. The gyroscope is the easiest calibration due to the expected readings outputted under steady conditions. Each of the three axes of the gyro should read 0 degrees-per-second (dps, °/s) when the IMU is not moving. The offsets can be measured by first taking some readings while the IMU is not moving, then using those values as ‘offsets’ when reading the gyro values in the future. This is merely the simplest calibration method for the IMU and suffices for most casual uses of the gyroscope and IMU. There are a range of higher-order gyroscope calibration routines, which can be found at the following links (with application descriptions):

The MPU6050’s gyroscope offsets can be found by recording a sample chunk of data from each axis and using the average of each sample. The gyro calibration routine (and all other codes used in this tutorial) can be found at this project’s GitHub page:

The gyroscope offset calculation sample code is also given below:

######################################################
# Copyright (c) 2021 Maker Portal LLC
# Author: Joshua Hrisko
######################################################
#
# This code reads data from the MPU9250/MPU9265 board
# (MPU6050 - accel/gyro, AK8963 - mag)
# and solves for calibration coefficients for the
# gyroscope
#
#
######################################################
#
# wait 5-sec for IMU to connect
import time
t0 = time.time()
start_bool = False # if IMU start fails - stop calibration
while time.time()-t0<5:
    try: 
        from mpu9250_i2c import *
        start_bool = True
        break
    except:
        continue
import numpy as np
import csv,datetime
import matplotlib.pyplot as plt

time.sleep(2) # wait for MPU to load and settle
# 
#####################################
# Gyro calibration (Steady)
#####################################
#
def get_gyro():
    _,_,_,wx,wy,wz = mpu6050_conv() # read and convert gyro data
    return wx,wy,wz

def gyro_cal():
    print("-"*50)
    print('Gyro Calibrating - Keep the IMU Steady')
    [get_gyro() for ii in range(0,cal_size)] # clear buffer before calibration
    mpu_array = []
    gyro_offsets = [0.0,0.0,0.0]
    while True:
        try:
            wx,wy,wz = get_gyro() # get gyro vals
        except:
            continue

        mpu_array.append([wx,wy,wz])

        if np.shape(mpu_array)[0]==cal_size:
            for qq in range(0,3):
                gyro_offsets[qq] = np.mean(np.array(mpu_array)[:,qq]) # average
            break
    print('Gyro Calibration Complete')
    return gyro_offsets

if __name__ == '__main__':
    if not start_bool:
        print("IMU not Started - Check Wiring and I2C")
    else:
        #
        ###################################
        # Gyroscope Offset Calculation
        ###################################
        #
        gyro_labels = ['w_x','w_y','w_z'] # gyro labels for plots
        cal_size = 500 # points to use for calibration
        gyro_offsets = gyro_cal() # calculate gyro offsets
        #
        ###################################
        # Record new data 
        ###################################
        #
        data = np.array([get_gyro() for ii in range(0,cal_size)]) # new values
        #
        ###################################
        # Plot with and without offsets
        ###################################
        #
        plt.style.use('ggplot')
        fig,axs = plt.subplots(2,1,figsize=(12,9))
        for ii in range(0,3):
            axs[0].plot(data[:,ii],
                        label='${}$, Uncalibrated'.format(gyro_labels[ii]))
            axs[1].plot(data[:,ii]-gyro_offsets[ii],
                        label='${}$, Calibrated'.format(gyro_labels[ii]))
        axs[0].legend(fontsize=14);axs[1].legend(fontsize=14)
        axs[0].set_ylabel('$w_{x,y,z}$ [$^{\circ}/s$]',fontsize=18)
        axs[1].set_ylabel('$w_{x,y,z}$ [$^{\circ}/s$]',fontsize=18)
        axs[1].set_xlabel('Sample',fontsize=18)
        axs[0].set_ylim([-2,2]);axs[1].set_ylim([-2,2])
        axs[0].set_title('Gyroscope Calibration Offset Correction',fontsize=22)
        fig.savefig('gyro_calibration_output.png',dpi=300,
                    bbox_inches='tight',facecolor='#FCFCFC')
        fig.show()

The output from the code above plots the triple-axis gyroscope for both uncalibrated and calibrated values for a number of samples prescribed in the variable “cal_size” (chosen as 500 samples in our case). The example output for our gyroscope is shown below:

gyro_calibration_output.jpg

It is easy to see that the offsets are essential for minimizing the expected minimal values under steady IMU conditions.


We can further test the calibration of the gyroscope by integrating an array of angular velocity values over time under a known rotation. For example, we can rotate the IMU Calibration Block by 180° and integrate the gyro over time to verify that the gyroscope is functioning properly.

By integrating the gyroscope’s angular velocity, approximations of angular displacement can be made:

angular_velocity_integration.png

For discrete points, a numerical integration technique is required, for which we use trapezoidal numerical integration:

The ‘scipy’ package in Python has a great implementation of the trapezoidal numerical integration, which makes it easy to approximate rotation of the IMU by integration of the gyroscope. An example implementation of the gyroscope integration is given below in the plot:

The gyroscope approximates the 180° rotation to be roughly 179.8°, which is quite accurate. It also tells us that the directionality of the IMU is accurate, as in the case above the rotation was carried out in the counter-clockwise direction. Thus, we have a reasonably accurate calibration of the gyroscope on the MPU9250 (MPU6050). Of course, the validation above is for a very steady and idealized rotation. Nonetheless, the gyro can be considered as zeroth-order calibrated. In the next section, the accelerometer will be calibrated similarly, but with a first-order approximation, which is slightly more involved and requires three calibration steps for each axis. The accelerometer will also be validated by numerical integration in a similar manner as the gyroscope.


Calibration of the accelerometer requires taking advantage of the acceleration due to gravity, which we can use in the positive and negative orientation of the IMU. Additionally, we can also position the IMU perpendicular to gravity in order to acquire a third calibration point. This results in three unique values that can be combined to formulate a linear fit between the three values and the values outputted by each axis of the accelerometer.

The calibration procedure for the accelerometer is as follows (for each axis):

1. Point the IMU Upward Against Gravity (1g)

2. Point the IMU Downward Toward Gravity (-1g)

3. Point the IMU Perpendicular to Gravity (0g)

These three calibrations should be done for each of the 3-axes. The three points will allow for least-squares fitting of a first-order model to the scale factor and offset (slope and intercept) of each axis of the accelerometer.

The Python code used to calibrate the accelerometer is given below:

######################################################
# Copyright (c) 2021 Maker Portal LLC
# Author: Joshua Hrisko
######################################################
#
# This code reads data from the MPU9250/MPU9265 board
# (MPU6050 - accel/gyro, AK8963 - mag)
# and solves for calibration coefficients for the
# accelerometer
#
#
######################################################
#
# wait 5-sec for IMU to connect
import time,sys
sys.path.append('../')
t0 = time.time()
start_bool = False # if IMU start fails - stop calibration
while time.time()-t0<5:
    try: 
        from mpu9250_i2c import *
        start_bool = True
        break
    except:
        continue
import numpy as np
import csv,datetime
import matplotlib.pyplot as plt
from scipy.optimize import curve_fit 

time.sleep(2) # wait for MPU to load and settle
# 
#####################################
# Accel Calibration (gravity)
#####################################
#
def accel_fit(x_input,m_x,b):
    return (m_x*x_input)+b # fit equation for accel calibration
#
def get_accel():
    ax,ay,az,_,_,_ = mpu6050_conv() # read and convert accel data
    return ax,ay,az
    
def accel_cal():
    print("-"*50)
    print("Accelerometer Calibration")
    mpu_offsets = [[],[],[]] # offset array to be printed
    axis_vec = ['z','y','x'] # axis labels
    cal_directions = ["upward","downward","perpendicular to gravity"] # direction for IMU cal
    cal_indices = [2,1,0] # axis indices
    for qq,ax_qq in enumerate(axis_vec):
        ax_offsets = [[],[],[]]
        print("-"*50)
        for direc_ii,direc in enumerate(cal_directions):
            input("-"*8+" Press Enter and Keep IMU Steady to Calibrate the Accelerometer with the -"+\
              ax_qq+"-axis pointed "+direc)
            [mpu6050_conv() for ii in range(0,cal_size)] # clear buffer between readings
            mpu_array = []
            while len(mpu_array)<cal_size:
                try:
                    ax,ay,az = get_accel()
                    mpu_array.append([ax,ay,az]) # append to array
                except:
                    continue
            ax_offsets[direc_ii] = np.array(mpu_array)[:,cal_indices[qq]] # offsets for direction

        # Use three calibrations (+1g, -1g, 0g) for linear fit
        popts,_ = curve_fit(accel_fit,np.append(np.append(ax_offsets[0],
                                 ax_offsets[1]),ax_offsets[2]),
                   np.append(np.append(1.0*np.ones(np.shape(ax_offsets[0])),
                    -1.0*np.ones(np.shape(ax_offsets[1]))),
                        0.0*np.ones(np.shape(ax_offsets[2]))),
                            maxfev=10000)
        mpu_offsets[cal_indices[qq]] = popts # place slope and intercept in offset array
    print('Accelerometer Calibrations Complete')
    return mpu_offsets

if __name__ == '__main__':
    if not start_bool:
        print("IMU not Started - Check Wiring and I2C")
    else:
        #
        ###################################
        # Accelerometer Gravity Calibration
        ###################################
        #
        accel_labels = ['a_x','a_y','a_z'] # gyro labels for plots
        cal_size = 1000 # number of points to use for calibration 
        accel_coeffs = accel_cal() # grab accel coefficients
#
        ###################################
        # Record new data 
        ###################################
        #
        data = np.array([get_accel() for ii in range(0,cal_size)]) # new values
        #
        ###################################
        # Plot with and without offsets
        ###################################
        #
        plt.style.use('ggplot')
        fig,axs = plt.subplots(2,1,figsize=(12,9))
        for ii in range(0,3):
            axs[0].plot(data[:,ii],
                        label='${}$, Uncalibrated'.format(accel_labels[ii]))
            axs[1].plot(accel_fit(data[:,ii],*accel_coeffs[ii]),
                        label='${}$, Calibrated'.format(accel_labels[ii]))
        axs[0].legend(fontsize=14);axs[1].legend(fontsize=14)
        axs[0].set_ylabel('$a_{x,y,z}$ [g]',fontsize=18)
        axs[1].set_ylabel('$a_{x,y,z}$ [g]',fontsize=18)
        axs[1].set_xlabel('Sample',fontsize=18)
        axs[0].set_ylim([-2,2]);axs[1].set_ylim([-2,2])
        axs[0].set_title('Accelerometer Calibration Calibration Correction',fontsize=18)
        fig.savefig('accel_calibration_output.png',dpi=300,
                    bbox_inches='tight',facecolor='#FCFCFC')
        fig.show()

The code above takes the user through the calibration steps for each of the three axes and outputs a plot similar to the following:

accel_calibration_output.jpg

The above calibration represents the IMU attached to the Calibration Block with the z-direction pointed upward. This is why we see an acceleration of 1g in the z-direction, and near zero values in the other two directions.

We can again see the benefit of the calibration for each axis in terms of the linear fit below:

Linear Fit for All Accelerometer Axes under -1g, 0g, +1g

Next, validation of the accelerometer will be carried out by moving the IMU Calibration Block a known distance in a chosen direction. The corresponding acceleration measured by the accelerometer will be integrated twice to approximate displacement.


The accelerometer calibration can be validated in a similar manner as the gyroscope - by numerical integration. The difference between the gyroscope integration and the accelerometer integration is that the acceleration values will be integrated twice to output an approximate displacement of the IMU, according to the following integration:

Again, the above relationship needs to be discretized in order to make it suitable for real-world movements, which first requires integration of acceleration to first approximate velocity:

Next, the velocity array must be integrated to then approximate displacement:

veloc_to_displacement_trapz.png

In Python, we first use ‘intergrate.cumtrapz’ which implements trapezoidal numerical integration in step-by-step increments. The first integration gives a velocity vector, while the second integration results in a displacement array.

The double integration of the acceleration test makes several assumptions:

  1. The object (IMU Calibration Block) is at rest

  2. The time between samples is known (likely not uniform for the IMU)

  3. The IMU is sliding in one direction

  4. The acceleration axis is perpendicular to gravity (0g influence of gravity)

Under these assumptions, the accelerometer values can be easily integrated in one direction. Below is a demonstration of the IMU Calibration Block being slid across a tap measure in one direction. The measured displacement will be compared with the twice-integrated accelerometer data for validation of the accelerometer calibration.

imu_calibration.gif

MPU9250 Accelerometer Displacement Testing

The code given below either calibrates the accelerometer or takes calibration coefficients as input (from a previous calibration). It then employs a 4th-Order Butterworth digital filter to smooth the signal, and ultimately outputs acceleration, velocity, and displacement to depict the integration results:

######################################################
# Copyright (c) 2021 Maker Portal LLC
# Author: Joshua Hrisko
######################################################
#
# This code reads data from the MPU9250/MPU9265 board
# (MPU6050 - accel/gyro, AK8963 - mag)
# and solves for calibration coefficients for the
# accelerometer, and option of integration for testing
#
#
######################################################
#
# wait 5-sec for IMU to connect
import time,sys
sys.path.append('../')
t0 = time.time()
start_bool = False # if IMU start fails - stop calibration
while time.time()-t0<5:
    try: 
        from mpu9250_i2c import *
        start_bool = True
        break
    except:
        continue
import numpy as np
import csv,datetime
import matplotlib.pyplot as plt
from scipy.optimize import curve_fit
from scipy.integrate import cumtrapz
from scipy import signal

time.sleep(2) # wait for MPU to load and settle
# 
#####################################
# Accel Calibration (gravity)
#####################################
#
def accel_fit(x_input,m_x,b):
    return (m_x*x_input)+b # fit equation for accel calibration
#
def get_accel():
    ax,ay,az,_,_,_ = mpu6050_conv() # read and convert accel data
    return ax,ay,az
    
def accel_cal():
    print("-"*50)
    print("Accelerometer Calibration")
    mpu_offsets = [[],[],[]] # offset array to be printed
    axis_vec = ['z','y','x'] # axis labels
    cal_directions = ["upward","downward","perpendicular to gravity"] # direction for IMU cal
    cal_indices = [2,1,0] # axis indices
    for qq,ax_qq in enumerate(axis_vec):
        ax_offsets = [[],[],[]]
        print("-"*50)
        for direc_ii,direc in enumerate(cal_directions):
            input("-"*8+" Press Enter and Keep IMU Steady to Calibrate the Accelerometer with the -"+\
              ax_qq+"-axis pointed "+direc)
            [mpu6050_conv() for ii in range(0,cal_size)] # clear buffer between readings
            mpu_array = []
            while len(mpu_array)<cal_size:
                try:
                    ax,ay,az = get_accel()
                    mpu_array.append([ax,ay,az]) # append to array
                except:
                    continue
            ax_offsets[direc_ii] = np.array(mpu_array)[:,cal_indices[qq]] # offsets for direction

        # Use three calibrations (+1g, -1g, 0g) for linear fit
        popts,_ = curve_fit(accel_fit,np.append(np.append(ax_offsets[0],
                                 ax_offsets[1]),ax_offsets[2]),
                   np.append(np.append(1.0*np.ones(np.shape(ax_offsets[0])),
                    -1.0*np.ones(np.shape(ax_offsets[1]))),
                        0.0*np.ones(np.shape(ax_offsets[2]))),
                            maxfev=10000)
        mpu_offsets[cal_indices[qq]] = popts # place slope and intercept in offset array
    print('Accelerometer Calibrations Complete')
    return mpu_offsets

def imu_integrator():
    #############################
    # Main Loop to Integrate IMU
    #############################
    #
    data_indx = 1 # index of variable to integrate
    dt_stop = 5 # seconds to record and integrate

    plt.style.use('ggplot')
    plt.ion()
    fig,axs = plt.subplots(3,1,figsize=(12,9))
    break_bool = False
    while True:
        #
        ##################################
        # Reading and Printing IMU values 
        ##################################
        #
        accel_array,t_array = [],[]
        print("Starting Data Acquisition")
        [axs[ii].clear() for ii in range(0,3)]
        t0 = time.time()
        loop_bool = False
        while True:
            try:
                ax,ay,az,wx,wy,wz = mpu6050_conv() # read and convert mpu6050 data
                mx,my,mz = AK8963_conv() # read and convert AK8963 magnetometer data
                t_array.append(time.time()-t0)
                data_array = [ax,ay,az,wx,wy,wz,mx,my,mz]
                accel_array.append(accel_fit(data_array[data_indx],
                                             *accel_coeffs[data_indx]))
                if not loop_bool:
                    loop_bool = True
                    print("Start Moving IMU...")
            except:
                continue
            if time.time()-t0>dt_stop:
                print("Data Acquisition Stopped")
                break
            
        if break_bool:
            break
        #
        ##################################
        # Signal Filtering
        ##################################
        #
        Fs_approx = len(accel_array)/dt_stop
        b_filt,a_filt = signal.butter(4,5,'low',fs=Fs_approx)
        accel_array = signal.filtfilt(b_filt,a_filt,accel_array)
        accel_array = np.multiply(accel_array,9.80665)
        #
        ##################################
        # Print Sample Rate and Accel
        # Integration Value
        ##################################
        #
        print("Sample Rate: {0:2.0f}Hz".format(len(accel_array)/dt_stop))
        veloc_array = np.append(0.0,cumtrapz(accel_array,x=t_array))
        dist_approx = np.trapz(veloc_array,x=t_array)
        dist_array = np.append(0.0,cumtrapz(veloc_array,x=t_array))
        print("Displace in y-dir: {0:2.2f}m".format(dist_approx))
        axs[0].plot(t_array,accel_array,label="$"+mpu_labels[data_indx]+"$",
                    color=plt.cm.Set1(0),linewidth=2.5)
        axs[1].plot(t_array,veloc_array,
                    label="$v_"+mpu_labels[data_indx].split("_")[1]+"$",
                    color=plt.cm.Set1(1),linewidth=2.5)
        axs[2].plot(t_array,dist_array,
                    label="$d_"+mpu_labels[data_indx].split("_")[1]+"$",
                    color=plt.cm.Set1(2),linewidth=2.5)
        [axs[ii].legend() for ii in range(0,len(axs))]
        axs[0].set_ylabel('Acceleration [m$\cdot$s$^{-2}$]',fontsize=16)
        axs[1].set_ylabel('Velocity [m$\cdot$s$^{-1}$]',fontsize=16)
        axs[2].set_ylabel('Displacement [m]',fontsize=16)
        axs[2].set_xlabel('Time [s]',fontsize=18)
        axs[0].set_title("MPU9250 Accelerometer Integration",fontsize=18)
        plt.pause(0.01)
        plt.savefig("accel_veloc_displace_integration.png",dpi=300,
                    bbox_inches='tight',facecolor="#FCFCFC")

if __name__ == '__main__':
    if not start_bool:
        print("IMU not Started - Check Wiring and I2C")
    else:
        #
        ###################################
        # Accelerometer Gravity Calibration
        ###################################
        #
        mpu_labels = ['a_x','a_y','a_z'] # gyro labels for plots
        cal_size = 1000 # number of points to use for calibration 
        old_vals_bool = True # True uses values from another calibration
        if not old_vals_bool:
            accel_coeffs = accel_cal() # grab accel coefficients
        else:
            accel_coeffs = [np.array([ 0.9978107 , -0.19471673]),
                            np.array([ 0.99740193, -0.56129248]),
                            np.array([0.9893495 , 0.20589886])]
#
        ###################################
        # Record new data 
        ###################################
        #
        data = np.array([get_accel() for ii in range(0,cal_size)]) # new values
        #
        ###################################
        # integration over time
        ###################################
        #
        imu_integrator()

An example output is also given below, for a test case of the IMU sliding in the +y-direction for 0.5m:

Several observations can be made for the plot above:

  • The acceleration is not zero, even after calibration (likely due to an unbalanced table)

  • The acceleration starts positive (acceleration), crosses zero, then goes negative (deceleration)

  • The velocity is positive throughout (forward movement)

  • The displacement is positive (forward movement)

  • The velocity and displacement are constantly changing due to the imbalanced acceleration (unbalanced table)

The approximation of displacement was found to be roughly 0.4m for the 0.5m test. This inaccuracy is due to the double integration and uncertainty associated with the sensors, along with the imperfect calibration. This can be remedied by ensuring the IMU is perpendicular to gravity during calibration (with a level) and also ensuring the test is being done on a level surface.


In this tutorial, calibration of the gyroscope and accelerometer on the MPU9250 (MPU6050) was explored through various methods. The gyroscope was calibrated under steady conditions by calculating the mean offset from a measurement sample array. The accuracy of the gyroscope was explored by first integrating the angular velocity over time and looking at the result after a known rotation. The accuracy after 180 degrees of rotation was found to be less than 1-degree, which is quite accurate. This is, of course, under very idealized conditions: smooth and small angle rotation. Similarly, the accelerometer was tested for a range of three calibration points: +1g, -1g, and 0g. These three points were fitted to line using least-squares methods. The accelerometer was also integrated, this time twice, to approximate the movement of the IMU over a known displacement. The accuracy of this method was found to be quite error prone, likely due to the following factors: the IMU was placed on a table not perfectly perpendicular to gravity, the double integration results in greater errors. The accelerometer was also filtered to smooth the signal (which was quite noisy, particularly when sliding on a table). The filtering can also be done on the gyroscope. In Part III, the next and final entry of this series, the magnetometer will be calibrated. The magnetometer is much more involved than both the gyro and accelerometer calibration due to the requirement of two axis components for calibrating under Earth’s magnetic field. An ensemble calibration will also be introduced with a routine to save all calibration coefficients for all three sensors (for all 9-DoF). This will allow for users to calibrate once and employ the calibration coefficients into their application.

 
Citation for This Page:
 

See More in Raspberry Pi and Engineering: