Maker.io main logo

Raspberry Pi Pico (RP2040) SPI Example with MicroPython and C/C++

7,667

2021-07-12 | By ShawnHymel

License: Attribution

Serial Peripheral Interface (SPI) is a simple communication protocol used to talk to various sensors, driver boards, microcontrollers, etc. It is a synchronous protocol, as it uses a separate clock line to tell the receiver when to sample data. Here is an article that offers a great explanation of SPI.

This tutorial walks you through the process of connecting an accelerometer to the Raspberry Pi Pico using SPI to reading data from it with MicroPython as well as C.

You can also view this tutorial in video form:

 

 

Required Hardware

You will need the following hardware:

Hardware Hookup

Connect the sensor to the Pico as follows:

Raspberry Pi Pico SPI connection to sensor

Here is how I connected the sensor to the Pico:

SPI connections with Raspberry Pi Pico

Bootloader Mode

Whenever this guide tells you to put your Pico into “bootloader mode,” you will need to unplug the USB cable. Press and hold the BOOTSEL button, and plug the USB cable back in. This will force the Pico to enumerate as a mass storage device on your computer, and you should see a drive appear on your computer with the name “RPI-RP2.”

Putting Pico into bootloader mode

MicroPython Example

Open Thonny. If you do not already have the MicroPython firmware running on the Pico, click on the bottom-right button and select the Raspberry Pi Pico as your board. Click again and select Configure Interpreter. In the pop-up window, select Install or update firmware

Upload MicroPython firmware to Pico

Click Install to install the latest MicroPython firmware. Close the pop-up windows when installation is done.

In a new new document, enter the following code:

Copy Code
import machine
import utime
import ustruct
import sys

###############################################################################
# Constants

# Registers
REG_DEVID = 0x00
REG_POWER_CTL = 0x2D
REG_DATAX0 = 0x32

# Other constants
DEVID = 0xE5
SENSITIVITY_2G = 1.0 / 256  # (g/LSB)
EARTH_GRAVITY = 9.80665     # Earth's gravity in [m/s^2]

###############################################################################
# Settings

# Assign chip select (CS) pin (and start it high)
cs = machine.Pin(17, machine.Pin.OUT)

# Initialize SPI
spi = machine.SPI(0,
                  baudrate=1000000,
                  polarity=1,
                  phase=1,
                  bits=8,
                  firstbit=machine.SPI.MSB,
                  sck=machine.Pin(18),
                  mosi=machine.Pin(19),
                  miso=machine.Pin(16))

###############################################################################
# Functions

def reg_write(spi, cs, reg, data):
    """
    Write 1 byte to the specified register.
    """
    
    # Construct message (set ~W bit low, MB bit low)
    msg = bytearray()
    msg.append(0x00 | reg)
    msg.append(data)
    
    # Send out SPI message
    cs.value(0)
    spi.write(msg)
    cs.value(1)
    
def reg_read(spi, cs, reg, nbytes=1):
    """
    Read byte(s) from specified register. If nbytes > 1, read from consecutive
    registers.
    """
    
    # Determine if multiple byte (MB) bit should be set
    if nbytes < 1:
        return bytearray()
    elif nbytes == 1:
        mb = 0
    else:
        mb = 1
    
    # Construct message (set ~W bit high)
    msg = bytearray()
    msg.append(0x80 | (mb << 6) | reg)
    
    # Send out SPI message and read
    cs.value(0)
    spi.write(msg)
    data = spi.read(nbytes)
    cs.value(1)
    
    return data

###############################################################################
# Main

# Start CS pin high
cs.value(1)

# Workaround: perform throw-away read to make SCK idle high
reg_read(spi, cs, REG_DEVID)

# Read device ID to make sure that we can communicate with the ADXL343
data = reg_read(spi, cs, REG_DEVID)
if (data != bytearray((DEVID,))):
    print("ERROR: Could not communicate with ADXL343")
    sys.exit()
    
# Read Power Control register
data = reg_read(spi, cs, REG_POWER_CTL)
print(data)

# Tell ADXL343 to start taking measurements by setting Measure bit to high
data = int.from_bytes(data, "big") | (1 << 3)
reg_write(spi, cs, REG_POWER_CTL, data)

# Test: read Power Control register back to make sure Measure bit was set
data = reg_read(spi, cs, REG_POWER_CTL)
print(data)

# Wait before taking measurements
utime.sleep(2.0)

# Run forever
while True:
    
    # Read X, Y, and Z values from registers (16 bits each)
    data = reg_read(spi, cs, REG_DATAX0, 6)

    # Convert 2 bytes (little-endian) into 16-bit integer (signed)
    acc_x = ustruct.unpack_from("<h", data, 0)[0]
    acc_y = ustruct.unpack_from("<h", data, 2)[0]
    acc_z = ustruct.unpack_from("<h", data, 4)[0]

    # Convert measurements to [m/s^2]
    acc_x = acc_x * SENSITIVITY_2G * EARTH_GRAVITY
    acc_y = acc_y * SENSITIVITY_2G * EARTH_GRAVITY
    acc_z = acc_z * SENSITIVITY_2G * EARTH_GRAVITY

    # Print results
    print("X:", "{:.2f}".format(acc_x), \
          "| Y:", "{:.2f}".format(acc_y), \
          "| Z:", "{:.2f}".format(acc_z))
    
    utime.sleep(0.1)

If you wish, save the program as a file on your computer for safekeeping (e.g. adxl343_spi.py).

Click the Run button. You should see the values of the POWER_CTL register printed out. 2 seconds later, the X, Y, and Z acceleration readings should start streaming across the console. Try moving the breadboard/accelerometer around to see how the values are affected.

Reading accelerometer values with MicroPython

C/C++ Example

If you have not done so already, follow this guide to set up the C/C++ SDK for Pico on your computer and create a Blink program. We will use that Blink program as a template for this project.

Open a file explorer. Create a copy of the blink directory you created in the C/C++ setup guide. Rename it to match your project (e.g. adxl343_spi). Delete the build directory inside the newly created project folder.

Open VS Code. Click File > Open Folder. Select your newly created project folder. Open CMakeLists.txt. Change the project name (e.g. blink to adxl343_spi) and add the hardware_spi library in the target_link_libraries() function. You may also want to set the USB or UART serial output, depending on if you are using a picoprobe for debugging (e.g. enable UART serial output for picoprobe, otherwise, use USB serial output).

Copy Code
# Set minimum required version of CMake
cmake_minimum_required(VERSION 3.12)

# Include build functions from Pico SDK
include($ENV{PICO_SDK_PATH}/external/pico_sdk_import.cmake)

# Set name of project (as PROJECT_NAME) and C/C++ standards
project(adxl343_spi C CXX ASM)
set(CMAKE_C_STANDARD 11)
set(CMAKE_CXX_STANDARD 17)

# Creates a pico-sdk subdirectory in our project for the libraries
pico_sdk_init()

# Tell CMake where to find the executable source file
add_executable(${PROJECT_NAME} 
    main.c
)

# Create map/bin/hex/uf2 files
pico_add_extra_outputs(${PROJECT_NAME})

# Link to pico_stdlib (gpio, time, etc. functions)
target_link_libraries(${PROJECT_NAME} 
    pico_stdlib
    hardware_spi
)

# Enable usb output, disable uart output
pico_enable_stdio_usb(${PROJECT_NAME} 1)
pico_enable_stdio_uart(${PROJECT_NAME} 0)

In main.c replace the code with the following:

Copy Code
#include <stdio.h>
#include "pico/stdlib.h"
#include "hardware/spi.h"

// Registers
static const uint8_t REG_DEVID = 0x00;
static const uint8_t REG_POWER_CTL = 0x2D;
static const uint8_t REG_DATAX0 = 0x32;

// Other constants
static const uint8_t DEVID = 0xE5;
static const float SENSITIVITY_2G = 1.0 / 256;  // (g/LSB)
static const float EARTH_GRAVITY = 9.80665;     // Earth's gravity in [m/s^2]

/*******************************************************************************
 * Function Declarations
 */
void reg_write( spi_inst_t *spi, 
                const uint cs, 
                const uint8_t reg, 
                const uint8_t data);

int reg_read(  spi_inst_t *spi,
                const uint cs,
                const uint8_t reg,
                uint8_t *buf,
                uint8_t nbytes);

/*******************************************************************************
 * Function Definitions
 */

// Write 1 byte to the specified register
void reg_write( spi_inst_t *spi, 
                const uint cs, 
                const uint8_t reg, 
                const uint8_t data) {

    uint8_t msg[2];
                
    // Construct message (set ~W bit low, MB bit low)
    msg[0] = 0x00 | reg;
    msg[1] = data;

    // Write to register
    gpio_put(cs, 0);
    spi_write_blocking(spi, msg, 2);
    gpio_put(cs, 1);
}

// Read byte(s) from specified register. If nbytes > 1, read from consecutive
// registers.
int reg_read(  spi_inst_t *spi,
                const uint cs,
                const uint8_t reg,
                uint8_t *buf,
                const uint8_t nbytes) {

    int num_bytes_read = 0;
    uint8_t mb = 0;

    // Determine if multiple byte (MB) bit should be set
    if (nbytes < 1) {
        return -1;
    } else if (nbytes == 1) {
        mb = 0;
    } else {
        mb = 1;
    }

    // Construct message (set ~W bit high)
    uint8_t msg = 0x80 | (mb << 6) | reg;

    // Read from register
    gpio_put(cs, 0);
    spi_write_blocking(spi, &msg, 1);
    num_bytes_read = spi_read_blocking(spi, 0, buf, nbytes);
    gpio_put(cs, 1);

    return num_bytes_read;
}

/*******************************************************************************
 * Main
 */
int main() {

    int16_t acc_x;
    int16_t acc_y;
    int16_t acc_z;
    float acc_x_f;
    float acc_y_f;
    float acc_z_f;

    // Pins
    const uint cs_pin = 17;
    const uint sck_pin = 18;
    const uint mosi_pin = 19;
    const uint miso_pin = 16;

    // Buffer to store raw reads
    uint8_t data[6];

    // Ports
    spi_inst_t *spi = spi0;

    // Initialize chosen serial port
    stdio_init_all();

    // Initialize CS pin high
    gpio_init(cs_pin);
    gpio_set_dir(cs_pin, GPIO_OUT);
    gpio_put(cs_pin, 1);

    // Initialize SPI port at 1 MHz
    spi_init(spi, 1000 * 1000);

    // Set SPI format
    spi_set_format( spi0,   // SPI instance
                    8,      // Number of bits per transfer
                    1,      // Polarity (CPOL)
                    1,      // Phase (CPHA)
                    SPI_MSB_FIRST);

    // Initialize SPI pins
    gpio_set_function(sck_pin, GPIO_FUNC_SPI);
    gpio_set_function(mosi_pin, GPIO_FUNC_SPI);
    gpio_set_function(miso_pin, GPIO_FUNC_SPI);

    // Workaround: perform throw-away read to make SCK idle high
    reg_read(spi, cs_pin, REG_DEVID, data, 1);

    // Read device ID to make sure that we can communicate with the ADXL343
    reg_read(spi, cs_pin, REG_DEVID, data, 1);
    if (data[0] != DEVID) {
        printf("ERROR: Could not communicate with ADXL343\r\n");
        while (true);
    }
    
    // Read Power Control register
    reg_read(spi, cs_pin, REG_POWER_CTL, data, 1);
    printf("0xX\r\n", data[0]);

    // Tell ADXL343 to start taking measurements by setting Measure bit to high
    data[0] |= (1 << 3);
    reg_write(spi, cs_pin, REG_POWER_CTL, data[0]);

    // Test: read Power Control register back to make sure Measure bit was set
    reg_read(spi, cs_pin, REG_POWER_CTL, data, 1);
    printf("0xX\r\n", data[0]);

    // Wait before taking measurements
    sleep_ms(2000);

    // Loop forever
    while (true) {

        // Read X, Y, and Z values from registers (16 bits each)
        reg_read(spi, cs_pin, REG_DATAX0, data, 6);

        // Convert 2 bytes (little-endian) into 16-bit integer (signed)
        acc_x = (int16_t)((data[1] << 8) | data[0]);
        acc_y = (int16_t)((data[3] << 8) | data[2]);
        acc_z = (int16_t)((data[5] << 8) | data[4]);

        // Convert measurements to [m/s^2]
        acc_x_f = acc_x * SENSITIVITY_2G * EARTH_GRAVITY;
        acc_y_f = acc_y * SENSITIVITY_2G * EARTH_GRAVITY;
        acc_z_f = acc_z * SENSITIVITY_2G * EARTH_GRAVITY;

        // Print results
        printf("X: %.2f | Y: %.2f | Z: %.2f\r\n", acc_x_f, acc_y_f, acc_z_f);

        sleep_ms(100);
    }
}

Run cmake and make (either from the command line or using the CMake extension in VS Code as outlined in this guide).

If you are using the picoprobe debugger, start debugging to upload the program and click the Run button to begin running it.

If you do not have picoprobe set up, put the Pico into bootloader mode and copy adxl343_spi.uf2 from the build directory to the RPI-RP2 drive that should have mounted on your computer.

Open your favorite serial terminal program and connect to the Pico with a baud rate of 115200. You might miss the printing of the POWER_CTL register, but you should see the values of the X, Y, and Z axes flying across the console.

Reading accelerometer values with C

Going Further

I recommend checking out the following documents if you wish to learn more about using SPI with the Raspberry Pi Pico and RP2040:

製造商零件編號 SC0915
RASPBERRY PI PICO RP2040
Raspberry Pi
製造商零件編號 4097
ADXL343 - TRIPLE-AXIS ACCELEROME
Adafruit Industries LLC
製造商零件編號 FIT0096
BREADBRD TERM STRIP 3.20X2.00"
DFRobot
製造商零件編號 1957
JUMPER WIRE M TO M 6" 28AWG
Adafruit Industries LLC
Add all DigiKey Parts to Cart
Have questions or comments? Continue the conversation on TechForum, DigiKey's online community and technical resource.