MPU6050 with Raspberry Pi Pico (Accelerometer, Gyroscope, and Temperature)

In this tutorial, we will learn to use the MPU6050 MEMS module with Raspberry Pi Pico to measure accelerometer, gyroscope, and temperature values using MicroPython firmware. Firstly, we will see an introduction of MPU6050 such as pinout diagram, pin configuration. Secondly, we will see how to upload the MPU6050 MicroPython library to Raspberry Pi Pico using Thonny IDE. In the end, we will see how to get an accelerometer, gyroscope, and temperature readings from the MPU6050 module with Raspberry Pi Pico.

MicroPython MPU6050 with Raspberry Pi Pico (Accelerometer, Gyroscope, and Temperature)

Prerequisites

Before we start this lesson, make sure you are familiar with and have the latest version of Python3 installed in your system and set up MicroPython in your Raspberry Pi Pico. Additionally, you should have a running Integrated Development Environment(IDE) to do the programming. We will be using the same Thonny IDE as we have done previously when we learned how to blink and chase LEDs in MicroPython here:

If you are using uPyCraft IDE, you can check this getting started guide:

MPU6050 Sensor Module Introduction 

The MPU6050 sensor module is a MEMS( Micro-Electro-Mechanical System) module that contains an integrated circuit MPU6050 IC. This chip contains a three-axis gyroscope, three-axis accelerometer, and digital motion control processor within a single IC package. On top of that, it also contains an integrated temperature sensor. All these sensors are manufactured on the same die of MPU6050. We can use this module for velocity, acceleration, orientation, displacement, and other motion related parameters measurement. Nowadays all modern smartphones come with a built-in inertial motion sensor. MPU6050 also belongs to one of these categories of sensors. This sensor provides a complete solution for any six-axis motion tracking system. 

MPU6050 sensor Module Accelerometer Gyroscope Temperature Sensor

One of the most important features of MPU6050 MEMS sensors is that it contains a powerful and high processing power digital motion processor (DMP). DMP performs all complex calculations internally before letting the users read data from the sensor on the I2C port. That means we do not have to perform high power calculations on the microcontroller after reading data from the MPU6050 chip. 

I2C Output Interface

As discussed earlier, MPU6050 provides output data on an I2C bus. Therefore, we can use an I2C bus interface of MPU6050 to transfer a 3-axis accelerometer and 3-axis gyroscope values to Raspberry Pi Pico. In other words, we can use any microcontroller which has an I2C port to read sensors’ output data. There is a specific dedicated address assigned to each parameter value in the MPU6050 I2C interface. We can use these addresses to get specific values from a sensor such as acceleration, gyro, and temperature. 

One of the advantages of using the I2C interface of this sensor is that we can interface multiple MPU5060 modules with a single microcontroller. 

MPU6050 Pinout 

The MPU6050 chip consists of 24 pins. But only 8 pins are exposed on the pinout of the module. This MEMS sensor module consists of 8 pins and these pins are used for different configurations and used to read data from the sensor. 

The following picture shows the pinout diagram of MPU6050 MEMS module: 

MPU6050 Pinout diagram

Pins Description

  • First one is a VCC pin that is used to power the sensor and 3 to 5 volts dc voltages are applied to power on this sensor. But usually, a 5V power source is provided directly from a microcontroller. 
  • The second [pin is a GND pin which is connected to the source ground and ground pin of a microcontroller.
  • Pin number three is  a SCL (serial clock) pin which is connected to a microcontroller SCL pin to which we want to interface MPU6050 sensor. SCL is a clock pulse pin used in I2C communication. The clock source is provided by the master device which is a microcontroller in our case. 
  • Fourth pin is a SDA (serial data) pin which is used to transfer data to a microcontroller. We connect SDA pin of MPU6050 with a SDA pin of a microcontroller
  • Fifth one is a XDA (Auxiliary Serial Data) pin which is used to connect external I2C modules with MPU6050 such as magnetometer. But the use of this pin is completely optional. 
  • Sixth one is a XCL (Auxiliary clock) pin which is also connected to another 12C interface sensor to enable its pin from this sensor module. 
  • AD0 (Pin7) : AD0 (Address select pin) which is a 12C slave address select pin.For example, if we use more than one MPU6050 modules with a single microcontroller, this pin is used to vary the slave address for each MEMS sensor. By doing so, each MEMS sensor can be easily distinguished on an I2C bus with its unique address. 
  • INT(Pin8) : The INT (interrupt) pin which is an interrupt digital output pin and used to give indication to a microcontroller that the data is available to read from a MPU6050 sensor module. 

Interface MPU6050 with Raspberry Pi Pico

As you see, the MPU6050 has 8 terminals but in order to connect with Raspberry Pi Pico, we will only require the first four pins. These are VCC, GND, SCL, and SDA.

Raspberry Pi Pico I2C Pins

Raspberry Pi Pico has two I2C controllers. Both I2C controllers are accessible through GPIO pins of Raspberry Pi Pico. The following table shows the connection of GPIO pins with both I2C controllers. Each connection of the controller can be configured through multiple GPIO pins as shown in the figure. But before using an I2C controller, you should configure in software which GPIO pins you want to use with a specific I2C controller. 

I2C ControllerGPIO Pins
I2C0 – SDAGP0/GP4/GP8/GP12/GP16/GP20
I2C0 – SCLGP1/GP5/GP9/GP13/GP17/GP21
I2C1 – SDAGP2/GP6/GP10/GP14/GP18/GP26
I2C1 – SCLGP3/GP7/GP11/GP15/GP19/GP27

The connections between the two devices which we are using can be seen below.

MPU6050Raspberry Pi Pico
VCC3.3V
SDAGP0 (I2C0 SDA)
SCLGP1 (I2C0 SCL)
GNDGND

The VCC pin is connected with the 3.3V from the Raspberry Pi Pico to power up. Both the grounds of the two devices are connected in common. The SCL pin of MPU6050 is connected with I2C0 SCL pin of Pi Pico. Likewise, the SDA pin is connected with the I2C0 SDA pin of Pi Pico.

We have used the same connections as specified in the table above. However you can use other combinations of SDA/SCL pins as well.

Raspberry Pi Pico with MPU6050 connection diagram
Raspberry Pi Pico with MPU6050 connection diagram
Raspberry Pi Pico with MPU6050

MPU6050 MicroPython Libraries

For this project we will require two libraries: imu.py and vector3d.py. Copy both of these libraries and save them in your Raspberry Pi Pico with the respective file names. Open a new file in Thonny. Copy the libraries given below. Save them to Raspberry Pi Pico with names imu.py and vector32.py under the lib folder.

imu.py

# imu.py MicroPython driver for the InvenSense inertial measurement units
# This is the base class
# Adapted from Sebastian Plamauer's MPU9150 driver:
# https://github.com/micropython-IMU/micropython-mpu9150.git
# Authors Peter Hinch, Sebastian Plamauer
# V0.2 17th May 2017 Platform independent: utime and machine replace pyb

'''
mpu9250 is a micropython module for the InvenSense MPU9250 sensor.
It measures acceleration, turn rate and the magnetic field in three axis.
mpu9150 driver modified for the MPU9250 by Peter Hinch

The MIT License (MIT)
Copyright (c) 2014 Sebastian Plamauer, oeplse@gmail.com, Peter Hinch
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
copies of the Software, and to permit persons to whom the Software is
furnished to do so, subject to the following conditions:
The above copyright notice and this permission notice shall be included in
all copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
THE SOFTWARE.
'''

# User access is now by properties e.g.
# myimu = MPU9250('X')
# magx = myimu.mag.x
# accelxyz = myimu.accel.xyz
# Error handling: on code used for initialisation, abort with message
# At runtime try to continue returning last good data value. We don't want aircraft
# crashing. However if the I2C has crashed we're probably stuffed.

from utime import sleep_ms
from machine import I2C
from vector3d import Vector3d


class MPUException(OSError):
    '''
    Exception for MPU devices
    '''
    pass


def bytes_toint(msb, lsb):
    '''
    Convert two bytes to signed integer (big endian)
    for little endian reverse msb, lsb arguments
    Can be used in an interrupt handler
    '''
    if not msb & 0x80:
        return msb << 8 | lsb  # +ve
    return - (((msb ^ 255) << 8) | (lsb ^ 255) + 1)


class MPU6050(object):
    '''
    Module for InvenSense IMUs. Base class implements MPU6050 6DOF sensor, with
    features common to MPU9150 and MPU9250 9DOF sensors.
    '''

    _I2Cerror = "I2C failure when communicating with IMU"
    _mpu_addr = (104, 105)  # addresses of MPU9150/MPU6050. There can be two devices
    _chip_id = 104

    def __init__(self, side_str, device_addr=None, transposition=(0, 1, 2), scaling=(1, 1, 1)):

        self._accel = Vector3d(transposition, scaling, self._accel_callback)
        self._gyro = Vector3d(transposition, scaling, self._gyro_callback)
        self.buf1 = bytearray(1)                # Pre-allocated buffers for reads: allows reads to
        self.buf2 = bytearray(2)                # be done in interrupt handlers
        self.buf3 = bytearray(3)
        self.buf6 = bytearray(6)

        sleep_ms(200)                           # Ensure PSU and device have settled
        if isinstance(side_str, str):           # Non-pyb targets may use other than X or Y
            self._mpu_i2c = I2C(side_str)
        elif hasattr(side_str, 'readfrom'):     # Soft or hard I2C instance. See issue #3097
            self._mpu_i2c = side_str
        else:
            raise ValueError("Invalid I2C instance")

        if device_addr is None:
            devices = set(self._mpu_i2c.scan())
            mpus = devices.intersection(set(self._mpu_addr))
            number_of_mpus = len(mpus)
            if number_of_mpus == 0:
                raise MPUException("No MPU's detected")
            elif number_of_mpus == 1:
                self.mpu_addr = mpus.pop()
            else:
                raise ValueError("Two MPU's detected: must specify a device address")
        else:
            if device_addr not in (0, 1):
                raise ValueError('Device address must be 0 or 1')
            self.mpu_addr = self._mpu_addr[device_addr]

        self.chip_id                     # Test communication by reading chip_id: throws exception on error
        # Can communicate with chip. Set it up.
        self.wake()                             # wake it up
        self.passthrough = True                 # Enable mag access from main I2C bus
        self.accel_range = 0                    # default to highest sensitivity
        self.gyro_range = 0                     # Likewise for gyro

    # read from device
    def _read(self, buf, memaddr, addr):        # addr = I2C device address, memaddr = memory location within the I2C device
        '''
        Read bytes to pre-allocated buffer Caller traps OSError.
        '''
        self._mpu_i2c.readfrom_mem_into(addr, memaddr, buf)

    # write to device
    def _write(self, data, memaddr, addr):
        '''
        Perform a memory write. Caller should trap OSError.
        '''
        self.buf1[0] = data
        self._mpu_i2c.writeto_mem(addr, memaddr, self.buf1)

    # wake
    def wake(self):
        '''
        Wakes the device.
        '''
        try:
            self._write(0x01, 0x6B, self.mpu_addr)  # Use best clock source
        except OSError:
            raise MPUException(self._I2Cerror)
        return 'awake'

    # mode
    def sleep(self):
        '''
        Sets the device to sleep mode.
        '''
        try:
            self._write(0x40, 0x6B, self.mpu_addr)
        except OSError:
            raise MPUException(self._I2Cerror)
        return 'asleep'

    # chip_id
    @property
    def chip_id(self):
        '''
        Returns Chip ID
        '''
        try:
            self._read(self.buf1, 0x75, self.mpu_addr)
        except OSError:
            raise MPUException(self._I2Cerror)
        chip_id = int(self.buf1[0])
        if chip_id != self._chip_id:
            raise ValueError('Bad chip ID retrieved: MPU communication failure')
        return chip_id

    @property
    def sensors(self):
        '''
        returns sensor objects accel, gyro
        '''
        return self._accel, self._gyro

    # get temperature
    @property
    def temperature(self):
        '''
        Returns the temperature in degree C.
        '''
        try:
            self._read(self.buf2, 0x41, self.mpu_addr)
        except OSError:
            raise MPUException(self._I2Cerror)
        return bytes_toint(self.buf2[0], self.buf2[1])/340 + 35  # I think

    # passthrough
    @property
    def passthrough(self):
        '''
        Returns passthrough mode True or False
        '''
        try:
            self._read(self.buf1, 0x37, self.mpu_addr)
            return self.buf1[0] & 0x02 > 0
        except OSError:
            raise MPUException(self._I2Cerror)

    @passthrough.setter
    def passthrough(self, mode):
        '''
        Sets passthrough mode True or False
        '''
        if type(mode) is bool:
            val = 2 if mode else 0
            try:
                self._write(val, 0x37, self.mpu_addr)  # I think this is right.
                self._write(0x00, 0x6A, self.mpu_addr)
            except OSError:
                raise MPUException(self._I2Cerror)
        else:
            raise ValueError('pass either True or False')

    # sample rate. Not sure why you'd ever want to reduce this from the default.
    @property
    def sample_rate(self):
        '''
        Get sample rate as per Register Map document section 4.4
        SAMPLE_RATE= Internal_Sample_Rate / (1 + rate)
        default rate is zero i.e. sample at internal rate.
        '''
        try:
            self._read(self.buf1, 0x19, self.mpu_addr)
            return self.buf1[0]
        except OSError:
            raise MPUException(self._I2Cerror)

    @sample_rate.setter
    def sample_rate(self, rate):
        '''
        Set sample rate as per Register Map document section 4.4
        '''
        if rate < 0 or rate > 255:
            raise ValueError("Rate must be in range 0-255")
        try:
            self._write(rate, 0x19, self.mpu_addr)
        except OSError:
            raise MPUException(self._I2Cerror)

    # Low pass filters. Using the filter_range property of the MPU9250 is
    # harmless but gyro_filter_range is preferred and offers an extra setting.
    @property
    def filter_range(self):
        '''
        Returns the gyro and temperature sensor low pass filter cutoff frequency
        Pass:               0   1   2   3   4   5   6
        Cutoff (Hz):        250 184 92  41  20  10  5
        Sample rate (KHz):  8   1   1   1   1   1   1
        '''
        try:
            self._read(self.buf1, 0x1A, self.mpu_addr)
            res = self.buf1[0] & 7
        except OSError:
            raise MPUException(self._I2Cerror)
        return res

    @filter_range.setter
    def filter_range(self, filt):
        '''
        Sets the gyro and temperature sensor low pass filter cutoff frequency
        Pass:               0   1   2   3   4   5   6
        Cutoff (Hz):        250 184 92  41  20  10  5
        Sample rate (KHz):  8   1   1   1   1   1   1
        '''
        # set range
        if filt in range(7):
            try:
                self._write(filt, 0x1A, self.mpu_addr)
            except OSError:
                raise MPUException(self._I2Cerror)
        else:
            raise ValueError('Filter coefficient must be between 0 and 6')

    # accelerometer range
    @property
    def accel_range(self):
        '''
        Accelerometer range
        Value:              0   1   2   3
        for range +/-:      2   4   8   16  g
        '''
        try:
            self._read(self.buf1, 0x1C, self.mpu_addr)
            ari = self.buf1[0]//8
        except OSError:
            raise MPUException(self._I2Cerror)
        return ari

    @accel_range.setter
    def accel_range(self, accel_range):
        '''
        Set accelerometer range
        Pass:               0   1   2   3
        for range +/-:      2   4   8   16  g
        '''
        ar_bytes = (0x00, 0x08, 0x10, 0x18)
        if accel_range in range(len(ar_bytes)):
            try:
                self._write(ar_bytes[accel_range], 0x1C, self.mpu_addr)
            except OSError:
                raise MPUException(self._I2Cerror)
        else:
            raise ValueError('accel_range can only be 0, 1, 2 or 3')

    # gyroscope range
    @property
    def gyro_range(self):
        '''
        Gyroscope range
        Value:              0   1   2    3
        for range +/-:      250 500 1000 2000  degrees/second
        '''
        # set range
        try:
            self._read(self.buf1, 0x1B, self.mpu_addr)
            gri = self.buf1[0]//8
        except OSError:
            raise MPUException(self._I2Cerror)
        return gri

    @gyro_range.setter
    def gyro_range(self, gyro_range):
        '''
        Set gyroscope range
        Pass:               0   1   2    3
        for range +/-:      250 500 1000 2000  degrees/second
        '''
        gr_bytes = (0x00, 0x08, 0x10, 0x18)
        if gyro_range in range(len(gr_bytes)):
            try:
                self._write(gr_bytes[gyro_range], 0x1B, self.mpu_addr)  # Sets fchoice = b11 which enables filter
            except OSError:
                raise MPUException(self._I2Cerror)
        else:
            raise ValueError('gyro_range can only be 0, 1, 2 or 3')

    # Accelerometer
    @property
    def accel(self):
        '''
        Acceleremoter object
        '''
        return self._accel

    def _accel_callback(self):
        '''
        Update accelerometer Vector3d object
        '''
        try:
            self._read(self.buf6, 0x3B, self.mpu_addr)
        except OSError:
            raise MPUException(self._I2Cerror)
        self._accel._ivector[0] = bytes_toint(self.buf6[0], self.buf6[1])
        self._accel._ivector[1] = bytes_toint(self.buf6[2], self.buf6[3])
        self._accel._ivector[2] = bytes_toint(self.buf6[4], self.buf6[5])
        scale = (16384, 8192, 4096, 2048)
        self._accel._vector[0] = self._accel._ivector[0]/scale[self.accel_range]
        self._accel._vector[1] = self._accel._ivector[1]/scale[self.accel_range]
        self._accel._vector[2] = self._accel._ivector[2]/scale[self.accel_range]

    def get_accel_irq(self):
        '''
        For use in interrupt handlers. Sets self._accel._ivector[] to signed
        unscaled integer accelerometer values
        '''
        self._read(self.buf6, 0x3B, self.mpu_addr)
        self._accel._ivector[0] = bytes_toint(self.buf6[0], self.buf6[1])
        self._accel._ivector[1] = bytes_toint(self.buf6[2], self.buf6[3])
        self._accel._ivector[2] = bytes_toint(self.buf6[4], self.buf6[5])

    # Gyro
    @property
    def gyro(self):
        '''
        Gyroscope object
        '''
        return self._gyro

    def _gyro_callback(self):
        '''
        Update gyroscope Vector3d object
        '''
        try:
            self._read(self.buf6, 0x43, self.mpu_addr)
        except OSError:
            raise MPUException(self._I2Cerror)
        self._gyro._ivector[0] = bytes_toint(self.buf6[0], self.buf6[1])
        self._gyro._ivector[1] = bytes_toint(self.buf6[2], self.buf6[3])
        self._gyro._ivector[2] = bytes_toint(self.buf6[4], self.buf6[5])
        scale = (131, 65.5, 32.8, 16.4)
        self._gyro._vector[0] = self._gyro._ivector[0]/scale[self.gyro_range]
        self._gyro._vector[1] = self._gyro._ivector[1]/scale[self.gyro_range]
        self._gyro._vector[2] = self._gyro._ivector[2]/scale[self.gyro_range]

    def get_gyro_irq(self):
        '''
        For use in interrupt handlers. Sets self._gyro._ivector[] to signed
        unscaled integer gyro values. Error trapping disallowed.
        '''
        self._read(self.buf6, 0x43, self.mpu_addr)
        self._gyro._ivector[0] = bytes_toint(self.buf6[0], self.buf6[1])
        self._gyro._ivector[1] = bytes_toint(self.buf6[2], self.buf6[3])
        self._gyro._ivector[2] = bytes_toint(self.buf6[4], self.buf6[5])

vector3d.py

# vector3d.py 3D vector class for use in inertial measurement unit drivers
# Authors Peter Hinch, Sebastian Plamauer

# V0.7 17th May 2017 pyb replaced with utime
# V0.6 18th June 2015

'''
The MIT License (MIT)
Copyright (c) 2014 Sebastian Plamauer, oeplse@gmail.com, Peter Hinch
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
copies of the Software, and to permit persons to whom the Software is
furnished to do so, subject to the following conditions:
The above copyright notice and this permission notice shall be included in
all copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
THE SOFTWARE.
'''

from utime import sleep_ms
from math import sqrt, degrees, acos, atan2


def default_wait():
    '''
    delay of 50 ms
    '''
    sleep_ms(50)


class Vector3d(object):
    '''
    Represents a vector in a 3D space using Cartesian coordinates.
    Internally uses sensor relative coordinates.
    Returns vehicle-relative x, y and z values.
    '''
    def __init__(self, transposition, scaling, update_function):
        self._vector = [0, 0, 0]
        self._ivector = [0, 0, 0]
        self.cal = (0, 0, 0)
        self.argcheck(transposition, "Transposition")
        self.argcheck(scaling, "Scaling")
        if set(transposition) != {0, 1, 2}:
            raise ValueError('Transpose indices must be unique and in range 0-2')
        self._scale = scaling
        self._transpose = transposition
        self.update = update_function

    def argcheck(self, arg, name):
        '''
        checks if arguments are of correct length
        '''
        if len(arg) != 3 or not (type(arg) is list or type(arg) is tuple):
            raise ValueError(name + ' must be a 3 element list or tuple')

    def calibrate(self, stopfunc, waitfunc=default_wait):
        '''
        calibration routine, sets cal
        '''
        self.update()
        maxvec = self._vector[:]                # Initialise max and min lists with current values
        minvec = self._vector[:]
        while not stopfunc():
            waitfunc()
            self.update()
            maxvec = list(map(max, maxvec, self._vector))
            minvec = list(map(min, minvec, self._vector))
        self.cal = tuple(map(lambda a, b: (a + b)/2, maxvec, minvec))

    @property
    def _calvector(self):
        '''
        Vector adjusted for calibration offsets
        '''
        return list(map(lambda val, offset: val - offset, self._vector, self.cal))

    @property
    def x(self):                                # Corrected, vehicle relative floating point values
        self.update()
        return self._calvector[self._transpose[0]] * self._scale[0]

    @property
    def y(self):
        self.update()
        return self._calvector[self._transpose[1]] * self._scale[1]

    @property
    def z(self):
        self.update()
        return self._calvector[self._transpose[2]] * self._scale[2]

    @property
    def xyz(self):
        self.update()
        return (self._calvector[self._transpose[0]] * self._scale[0],
                self._calvector[self._transpose[1]] * self._scale[1],
                self._calvector[self._transpose[2]] * self._scale[2])

    @property
    def magnitude(self):
        x, y, z = self.xyz  # All measurements must correspond to the same instant
        return sqrt(x**2 + y**2 + z**2)

    @property
    def inclination(self):
        x, y, z = self.xyz
        return degrees(acos(z / sqrt(x**2 + y**2 + z**2)))

    @property
    def elevation(self):
        return 90 - self.inclination

    @property
    def azimuth(self):
        x, y, z = self.xyz
        return degrees(atan2(y, x))

    # Raw uncorrected integer values from sensor
    @property
    def ix(self):
        return self._ivector[0]

    @property
    def iy(self):
        return self._ivector[1]

    @property
    def iz(self):
        return self._ivector[2]

    @property
    def ixyz(self):
        return self._ivector

    @property
    def transpose(self):
        return tuple(self._transpose)

    @property
    def scale(self):
        return tuple(self._scale)

MicroPython MPU6050: Getting Accelerometer, Gyroscope, and Temperature values

After uploading the two libraries mentioned above to our Raspberry Pi Pico, let us program our board with MPU6050.

Let’s now look at an example to show the working of the sensor. We will connect our MPU6050 sensor with the Raspberry Pi Pico via the I2C protocol as shown above in the connection diagram. We will see a MicroPython script code and after uploading it to our board, we will see readings of Accelerometer, Gyroscope, and Temperature printed on the MicroPython shell terminal.

MPU6050 MicroPython Code

Now let’s look at the MicroPython script for MPU6050 to get sensor readings. Copy the following code to the main.py file and upload the main.py file to Raspberry Pi Pico.

This MicroPython script reads Accelerometer, Gyroscope, and Temperature values from MPU-6050 over I2C lines and prints them on the MicroPython shell console.

from imu import MPU6050
from time import sleep
from machine import Pin, I2C

i2c = I2C(0, sda=Pin(0), scl=Pin(1), freq=400000)
imu = MPU6050(i2c)

while True:
    ax=round(imu.accel.x,2)
    ay=round(imu.accel.y,2)
    az=round(imu.accel.z,2)
    gx=round(imu.gyro.x)
    gy=round(imu.gyro.y)
    gz=round(imu.gyro.z)
    tem=round(imu.temperature,2)
    print("ax",ax,"\t","ay",ay,"\t","az",az,"\t","gx",gx,"\t","gy",gy,"\t","gz",gz,"\t","Temperature",tem,"        ",end="\r")
    sleep(0.2)

How the Code Works?

Importing Libraries

Firstly, we will be importing the Pin class and I2C class from the machine module. This is because we have to specify the pin for I2C communication. We also import the sleep module so that we will be able to add a delay in between our readings. Also, import MPU6050 from the imu library that we just uploaded to our board.

from imu import MPU6050
from time import sleep
from machine import Pin, I2C

Defining Raspberry Pi I2C Pins for MPU-6050

Next, we will initialize the I2C GPIO pins for SCL and SDA respectively. We have used the I2C0 SCL and I2C0 SDA pins.

We have created an I2C() method which takes in four parameters. The first parameter is the I2C channel that we are using. The second parameter specifies the I2C GPIO pin of the board which is connected to the SDA line. The third parameter specifies the I2C GPIO pin of the board which is connected to the SCL line. The last parameter is the frequency connection.

We are setting the SCL on pin 1 and the SDA on pin 0.

We create an object of MPU6050 named imu and access the sensor’s readings through it.

i2c = I2C(0, sda=Pin(0), scl=Pin(1), freq=400000)
imu = MPU6050(i2c)

Next, we run an infinite loop inside which we access the sensor’s readings. We will print the values in the terminal by giving the print command. We also add a delay after each set of readings are updated to new ones.

The readings include acceleration (x, y and z), gyroscope (x, y and z) and temperature.

while True:
    ax=round(imu.accel.x,2)
    ay=round(imu.accel.y,2)
    az=round(imu.accel.z,2)
    gx=round(imu.gyro.x)
    gy=round(imu.gyro.y)
    gz=round(imu.gyro.z)
    tem=round(imu.temperature,2)
    print("ax",ax,"\t","ay",ay,"\t","az",az,"\t","gx",gx,"\t","gy",gy,"\t","gz",gz,"\t","Temperature",tem,"        ",end="\r")
    sleep(0.2)

Demo

To test the MicroPython script for MPU-6050 with Raspberry Pi Pico, upload the main.py file to your board.

You will see the Accelerometer, Gyroscope, and Temperature values on the shell console constantly changing as you move the sensor in different orientations.

Raspberry Pi Pico MPU60 readings

Other sensors interfacing with Raspberry Pi Pico:

You may like to read related MPU6050 tutorials:

11 thoughts on “MPU6050 with Raspberry Pi Pico (Accelerometer, Gyroscope, and Temperature)”

  1. >>> %Run -c $EDITOR_CONTENT
    Traceback (most recent call last):
    File “”, line 6, in
    File “imu.py”, line 105, in __init__
    File “imu.py”, line 158, in chip_id
    MPUException: I2C failure when communicating with IMU

    no idea how to get past this point.

    Reply
      • Yes. I am new (a noob). I am trying to use 2 MPU6050 on I2C0, and I hooked up the MPU6050 to multiple GPIO pins instead of just 2. So I got it working, sort of. Now I2C.scan can detect both Hex address (0x68 and 0x69). But now my issue is, I cannot read output data of either MPU6050. Error is:
        Traceback (most recent call last):
        File “”, line 11, in
        File “imu.py”, line 98, in __init__
        ValueError: Two MPU’s detected: must specify a device address

        Now I cannot figure out how to specify device address to read both MPU6050 connected. Unplugging 1 MPU6050 it displays output (no matter Hex address), but having both connected, I get nothing.

        Reply
  2. How to convince the “Thonny” program to see additional libraries:

    MicroPython v1.18 on 2022-01-17; Raspberry Pi Pico with RP2040
    Type “help ()” for more information.
    >>>% Run -c $ EDITOR_CONTENT
    Traceback (most recent call last):
    File “”, line 26, in
    ImportError: no module named ‘imu’.

    I use Google translator

    I checked the paths:
    >>> import sys
    sys.path
    [”, ‘.frozen’, ‘/ lib’]
    files are located in the RPI Pico root directory and in ‘/lib’

    I don’t know what to do next.

    Reply
  3. Soy nuevo en esto y preguntaba cómo podría hacerle si requiero guardar esos datos en algún documento, o tabla para después procesar esos datos

    Reply
  4. imu.py and vector3d.py saved to Pico, no issue.
    Run pico6050 script , the gx, gy, and gz values apparently show valid values instantaneously, but rezero once position stops changing.
    for example if the sensor is turned while flat on its back, the gz value changes if turned 90 degrees, then next scan or so it shows zero again.
    When using MPU6050 with Arduino, the displayed values are absolute values of position references from where it booted up and initialized.
    Does this Pico version provide the gyro sensor ? what could the issue for maintained values of pitch, roll, and yaw ? Thanks for any insights

    Reply
  5. Hey there thanks for helping
    in my pico w pin 1 and 2 is not working so i connect with pin 4 and 5
    and also make change in code by changing the pin no. but still getting this error don’t know why so please help me

    Traceback (most recent call last):
    File “”, line 6, in
    File “imu.py”, line 95, in __init__
    MPUException: No MPU’s detected

    i’m getting this error please help me

    Reply

Leave a Comment