Direct Digital Synthesis

This program was an implementation of the SPI communication protocol using PIO on the Raspberry Pi Pico. RP2040 has two identical SPI controllers, both based on an ARM Primecell Synchronous Serial Port (SSP). I used an MCP4822 DAC to generate a sine wave of a given frequency. The Pico transmits data to the DAC using SPI. The resources for the project include the C SDK User Guide, the RP2040 Datasheet and Prof. Hunter's website.


The complete code

PIODDSDAC.c

#include <stdio.h> //The standard C library
#include "pico/stdlib.h" //Standard library for Pico
#include <math.h> //The standard math library
#include "hardware/gpio.h" //The hardware GPIO library
#include "hardware/adc.h" //The hardware ADC library
#include "pico/time.h" //The pico time library
#include "hardware/irq.h" //The hardware interrupt library
#include "hardware/pwm.h" //The hardware PWM library
#include "hardware/pio.h" //The hardware PIO library
#include "PIODDS.pio.h" //The pio header created after compilation

#define CS 18 //The chip-select pin
#define MOSI 19 //The MOSI pin
#define SCK 17 //The clock pin

#define SIZE 256 //The sine table size
#define Fs 44000 //The sampling frequency
#define two32divFs 97612.8930909 //(4294967296 / 44000)

#define DAC_config_chan_A 0b0011000000000000 //The DAC configuration bits

uint32_t phaseAccum = 0, phaseInc = 0; //The phase accumulator and the phase incrementer

uint16_t adcIn = 0, dacData; //The ADC input and data to be sent to DAC

int sinTable[SIZE]; //The sin table

PIO pio = pio0; //Identifier for the first (PIO 0) hardware PIO instance
uint sm = 0; //The state machine 

typedef struct pio_spi_inst{ //PIO SPI struct 
    PIO pio; //The PIO
    uint sm; //State machine
    uint cs_pin; //Chip select
} pio_spi_inst_t;

void pio_spi_write16_blocking(const pio_spi_inst_t *spi, const uint16_t *src, size_t len); //Function prototype to write 16 bits to the SPI channel

void __time_critical_func(pio_spi_write16_blocking)(const pio_spi_inst_t *spi, const uint16_t *src, size_t len){ //Decorates a function name, such that the function will execute from RAM
    size_t tx_remain = len; //The length of transmission
    io_rw_16 *txfifo = (io_rw_16 *) &spi->pio->txf[spi->sm]; //Address to the transmit buffer
    while (tx_remain) { //As long as there is data to transmit
        if (tx_remain && !pio_sm_is_tx_fifo_full(spi->pio, spi->sm)) { //If FIFO not full
            *txfifo = *src++; //Copy the number in the FIFO and increment the pointer
            --tx_remain; //Reduce the remaining transmit length
        }
    }
}

pio_spi_inst_t spi = { //The SPI instance
    .pio = pio0,
    .sm = 0,
    .cs_pin = CS
};

static bool repeating_timer_callback(struct repeating_timer *t) { //Callback for a repeating timer
    adcIn = adc_read(); //Read the ADC value
    phaseInc = adcIn * two32divFs; //Calculate the phase increment
    phaseAccum += phaseInc; //Add the incrementer to the accumulator
    dacData = sinTable[phaseAccum >> 24]; //We only care about the 8 most significant bits
    dacData = DAC_config_chan_A | (dacData & 0x0fff); //Configure DAC data using bitmasks on the data

    pio_spi_write16_blocking(&spi, &dacData, 1); //Send the data to the SPI channel
    return true;
}

int main() {//The program running on core 0
    stdio_init_all(); //Initialize all of the present standard stdio types that are linked into the binary
    struct repeating_timer timer; //The repeating timer object for interrupt
    int i; //The counter i
    for(i = 0; i < SIZE; i++){ //For the sine table size
        sinTable[i] = (int)(2047 * sin((float) i * 6.283 / (float) SIZE) + 2047); //Create the sine table
    }

    adc_init(); //Initialise the ADC hardware
    adc_gpio_init(26); //Initialise the gpio for use as an ADC pin
    adc_select_input(0); //Select an ADC input. 0...3 are GPIOs 26...29 respectively

    gpio_init(CS); //Initialize the CS pin as GPIO 
    gpio_set_dir(CS, GPIO_OUT); //Set the pin direction as output
    gpio_put(CS, 1); //Drive CS high

    uint offset = pio_add_program(spi.pio, &spi_cpha0_cs_program); //Attempt to load the program

    pio_spi_cs_init(spi.pio, spi.sm, offset, 16, 15.625f, false, false, SCK, MOSI); //Initialize the SPI program

    add_repeating_timer_us(-23, repeating_timer_callback, NULL, &timer); //Add a repeating timer that is called repeatedly at the specified interval in microseconds. Negative time means it is the time difference between the start times of 2 consecutive callbacks

    while(1){
    }
}


PIODDS.pio

assembly
.program spi_cpha0_cs ;Program name
.side_set 2 ;Set 2 pins for sideset

;Drive SPI
; Pin assignments:
; - SCK is side-set bit 0
; - CSn is side-set bit 1
; - MOSI is OUT bit 0 (host-to-device)
; - MISO is IN bit 0 (device-to-host)

.wrap_target ;Free 0 cycle unconditional jump
bitloop: ;Bitloop label
    out pins, 1        side 0x0 [1] ;Output the bit on pin, sideset the clock
    jmp x-- bitloop    side 0x1 [1] ;Jump to bitloop if bit counter still available

    out pins, 1        side 0x0 ;Output the bit on pin, sideset the clock
    mov x, y           side 0x0     ; Reload bit counter from Y
    jmp !osre bitloop  side 0x1 [1]     ; Fall-through if TXF empties

    nop                side 0x0 [1] ; CSn back porch
public entry_point:                 ; Must set X,Y to n-2 before starting!
    pull ifempty       side 0x2 [1] ; Block with CSn high (minimum 2 cycles)
.wrap                               ; Note ifempty to avoid time-of-check race

;Helper function

% c-sdk {
#include "hardware/gpio.h" //The hardware GPIO library
static inline void pio_spi_cs_init(PIO pio, uint sm, uint prog_offs, uint n_bits, float clkdiv, bool cpha, bool cpol, uint pin_sck, uint pin_mosi){ //The PIO SPI initialize functions
    pio_sm_config c = spi_cpha0_cs_program_get_default_config(prog_offs); //Get default configurations for the PIO state machine
    sm_config_set_out_pins(&c, pin_mosi, 1); //Set the 'out' pins in a state machine configuration
    sm_config_set_sideset_pins(&c, pin_sck); //Set the 'sideset' pins in a state machine configuration
    sm_config_set_out_shift(&c, false, true, n_bits); //Setup 'out' shifting parameters in a state machine configuration
    sm_config_set_clkdiv(&c, clkdiv); //Set the state machine clock divider

    pio_sm_set_pins_with_mask(pio, sm, (2u << pin_sck), (3u << pin_sck) | (1u << pin_mosi)); //Use a state machine to set a value on multiple pins for the PIO instance
    pio_sm_set_pindirs_with_mask(pio, sm, (3u << pin_sck) | (1u << pin_mosi), (3u << pin_sck) | (1u << pin_mosi)); //Use a state machine to set the pin directions for multiple pins for the PIO instance
    pio_gpio_init(pio, pin_mosi); //Setup the function select for a GPIO to use output from the given PIO instance
    pio_gpio_init(pio, pin_sck); //Setup the function select for a GPIO to use output from the given PIO instance
    pio_gpio_init(pio, pin_sck + 1); //Setup the function select for a GPIO to use output from the given PIO instance
    gpio_set_outover(pin_sck, cpol ? GPIO_OVERRIDE_INVERT : GPIO_OVERRIDE_NORMAL); //Set GPIO output override

    uint entry_point = prog_offs + spi_cpha0_cs_offset_entry_point; //The offset entry point
    pio_sm_init(pio, sm, entry_point, &c); //Resets the state machine to a consistent state, and configures it
    pio_sm_exec(pio, sm, pio_encode_set(pio_x, n_bits - 2)); //Put 14 in pio_x
    pio_sm_exec(pio, sm, pio_encode_set(pio_y, n_bits - 2)); //Put 14 in pio_y
    pio_sm_set_enabled(pio, sm, true); //Enable or disable a PIO state machine
}
%}


Direct Digital Synthesis

The observation upon which the direct digital synthesis algorithm is based is that a variable overflowing is isomorphic to one rotation of a phasor. A sine wave is generated by projecting a rotating phasor onto the imaginary axis, as shown below. We see the rotating phasor and it's associated angle in red, the projection onto the imaginary axis in green, and the generated sine wave streaming off in orange. Note that, after the phasor has rotated 360 degrees, we have completed one period of the sine wave and the whole thing repeats.

Now, suppose that we represented the angle of that phasor, from the positive x-axis, with a 32-bit number that we'll call the accumulator. A scaled version of the phase angle will be stored in the accumulator. An angle of 0 degrees from the positive x-axis will correspond to an accumulator value of 0 (a 0 in each of the 32 bits). An angle of 360 degrees from the positive x-axis will correspond to an accumulator value of $2^{32}−1$ (a 1 in each of the 32 bits). Then, overflowing the accumulator corresponds to completing a full rotation of the phasor.

We'll see why this is useful in the next section. For now, all that we've done is scaled the range of phasor angles from 0→2π radians to instead 0→$2^{32}−1$ units, and stored that rescaled value in a 32-bit variable that we are calling accumulator.

We need precise sample timing for your synthesized audio to sound right (our ears are quite sensitive to errors in sample rate). So, we will send new samples to the DAC at a rate, $F_s$ (Hz) and will use a timer interrupt to achieve that timing.

Each time the interrupt fires, it will rotate the phasor to a new orientation, lookup the value for the sine wave at that phasor angle (from a lookup table), and send that value to the DAC. Because of the isomorphism between the accumulator variable and the phasor angle, rotating the phasor is the same as adding an increment to the accumulator variable. The faster that you increment the accumulator variable, the faster the phasor moves around the circle and the higher-frequency the sine wave. The value of the increment and the frequency of the sine wave are, in fact, linearly related. It is not difficult to find that relationship.

What if we incremented the accumulator variable by 1 unit every audio sample?

Suppose that we are generating audio samples at $F_s$ Hz. And, furthermore, suppose that each time we generate a sample we increment the accumulator variable by 1. What will be the frequency of the resulting sine wave, $F_{out}$? Some quick dimensional analysis shows that:

\begin{align} F_{out} = \frac{1\text{ overflow (i.e. sine period)}}{2^{32}\text{ accumulator units}} \cdot \frac{1\text{ accumulator unit}}{1\text{ audio sample}} \cdot \frac{F_s\text{ audio samples}}{1\text{ sec}} = \frac{F_s}{2^{32}} Hz \end{align}

What if we incremented the accumulator variable by N units every audio sample?

As before, suppose that we are generating audio samples at $F_s$ Hz. Now, however, consider that we increment the accumulator variable by some arbitrary value $N$ each time we generate a sample. What will be the frequency of the resulting sine wave, $F_{out}$?

\begin{align} F_{out} = \frac{1\text{ overflow (i.e. sine period)}}{2^{32}\text{ accumulator units}} \cdot \frac{j\text{ accumulator units}}{1\text{ audio sample}} \cdot \frac{F_s\text{ audio samples}}{1\text{ sec}} = \left(\frac{F_s}{2^{32}} \cdot N\right) Hz \end{align}

For some desired output frequency, $F_{out}$, and a known sample frequency, $F_s$, what is the required increment, $N$?

Generally speaking, $F_s$ is a known parameter. It is known either because we decided upon it, or because the DAC that we're using specifies it. $F_out$, the output frequency, is the frequency of the sound that we want to generate. That value, therefore, is also known. The only unknown parameter in the above equation is $N$, the value of the increment. We can solve the above expression for $N$:

\begin{align} \boxed{N = \text{increment amount}= \frac{F_{out}}{F_s} \cdot 2^{32}} \end{align}

What is the precision of this synthesizer?

If the audio sample rate is 44kHz, then the resolution of the synthesizer is the sample rate divided by the range of the 32-bit accumulator. In other words, it's the frequency that is output when the accumulator is iterated by 1 every audio sample.

\begin{align} \text{resolution} &= \frac{F_s}{2^{32}}\\ &= \frac{44,000}{2^{32}}\\ &= 1.02 \times 10^{-5} Hz \end{align}

What if we used a short (16 bits) instead of an int (32 bits) for the accumulator. Then what would the resolution of the synthesizer be?

\begin{align} \text{resolution} &= \frac{F_s}{2^{16}}\\ &= \frac{44,000}{2^{16}}\\ &= 0.67 Hz \end{align}

And what if you used a char (8 bits)?

\begin{align} \text{resolution} &= \frac{F_s}{2^{8}}\\ &= \frac{44,000}{2^{8}}\\ &= 171.8 Hz \end{align}

So, an int accumulator is really accurate, a short is pretty accurate, and a char is terrible.


Stepping through the code

Includes

The first lines of code in the C source file include some header files. One of these is standard C headers (stdio.h) and the standard math header(math.h). The others are headers which come from the C SDK for the Raspberry Pi Pico. The first of these, pico/stdlib.h is what the SDK calls a "High-Level API." These high-level API's "provide higher level functionality that isn’t hardware related or provides a richer set of functionality above the basic hardware interfaces." The architecture of this SDK is described at length in the SDK manual. All libraries within the SDK are INTERFACE libraries.

The next includes pull in hardware APIs which are not already brought in by pico/stdlib.h. These include hardware/gpio.h, hardware/adc.h, hardware/irq.h, hardware/pwm.h, hardware/pio.h, pico/time.h and PIODDS.pio.h

Don't forget to link these in the CMakeLists.txt file!

#include <stdio.h>
#include <math.h>
#include "pico/stdlib.h"
#include "hardware/gpio.h"
#include "hardware/adc.h"
#include "pico/time.h"
#include "hardware/irq.h"
#include "hardware/pwm.h"
#include "hardware/pio.h"
#include "PIODDS.pio.h"


Global declarations and defines

The next section of the code is the #define's and the global variables which will be used throughout the code.

The following are the #define's to be used throughout the code:

The following are the variables to be used throughout the code:

#define CS 18
#define MOSI 19
#define SCK 17

#define SIZE 256
#define Fs 44000
#define two32divFs 97612.8930909

#define DAC_config_chan_A 0b0011000000000000

uint32_t phaseAccum = 0, phaseInc = 0;

uint16_t adcIn = 0, dacData;

int sinTable[SIZE];

PIO pio = pio0;
uint sm = 0; 

typedef struct pio_spi_inst{
    PIO pio;
    uint sm;
    uint cs_pin;
} pio_spi_inst_t;


Time critical writing to PIO

To transmit the data to the DAC using SPI, I used the __time_critical_func decorator to execute the pio_spi_write16_blocking() function from RAM.

void pio_spi_write16_blocking(const pio_spi_inst_t *spi, const uint16_t *src, size_t len);

void __time_critical_func(pio_spi_write16_blocking)(const pio_spi_inst_t *spi, const uint16_t *src, size_t len){
    size_t tx_remain = len;
    io_rw_16 *txfifo = (io_rw_16 *) &spi->pio->txf[spi->sm];
    while (tx_remain) {
        if (tx_remain && !pio_sm_is_tx_fifo_full(spi->pio, spi->sm)) {
            *txfifo = *src++;
            --tx_remain;
        }
    }
}


The interrupt handler

In order to get a constant sampling frequency of 44kHz, I used an interrupt which triggers every $23\mu s$ (1 / 44000). In order to handle the interrupt, I created an interrupt handler which does the following:

static bool repeating_timer_callback(struct repeating_timer *t) {
    adcIn = adc_read();
    phaseInc = adcIn * two32divFs;
    phaseAccum += phaseInc;
    dacData = sinTable[phaseAccum >> 24];
    dacData = DAC_config_chan_A | (dacData & 0x0fff);

    pio_spi_write16_blocking(&spi, &dacData, 1);
    return true;
}


The main function

Initializing communication

The first line in main() is a call to stdio_init_all(). This function initializes stdio to communicate through either UART or USB, depending on the configurations in the CMakeLists.txt file.

stdio_init_all();


Initializing the repeating timer

Initialize a repeating timer called timer to use it to trigger the interrupts.

struct repeating_timer timer;


Initializing the sine table

Initialize a 256 element wide sine table in order to contain the amplitudes for a single period of a sine wave.

int i;
for(i = 0; i < SIZE; i++){
    sinTable[i] = (int)(2047 * sin((float) i * 6.283 / (float) SIZE) + 2047);
}


Initializing the ADC

In order to use the ADC, I first initialised the ADC using the adc_init() function. I then initialized the GPIO 26 using the adc_gpio_init() function. From the datasheet, I know that the ADC inputs 0 to 3 are connected to GPIOs 26 to 29 respectively. In order to select the input, I used the adc_select_input() function.

adc_init();
adc_gpio_init(26);
adc_select_input(0);


Initializing the Chip Select

In order to initialise the chip select pin, I used the gpio_init(). Next, I used the gpio_set_dir() function to set the direction of the chip select pin as output. Lastly, I used the gpio_put() function to drive the chip select pin high.

gpio_init(CS);
gpio_set_dir(CS, GPIO_OUT);
gpio_put(CS, 1);


Initializing the timer interrupt

In order to initialize the interrupt on the timer, I used the add_repeating_timer_us() function. It takes the following parameters as arguments:

add_repeating_timer_us(-23, repeating_timer_callback, NULL, &timer);


The infinite while loop

For this code, the infinite while loop has no function except for to keep the program running.

while(1){
}


The output

In order to view the output of the DAC, I used an oscilloscope. As it is quite evident from the oscilloscope output, the output of the DAC is a sine wave of the desired frequency.

Output of the DAC

CMakeLists.txt

cmake_minimum_required(VERSION 3.13)

include(pico_sdk_import.cmake)

project(PIODDSDAC)

pico_sdk_init()

add_executable(PIODDSDAC PIODDSDAC.c)

pico_generate_pio_header(PIODDSDAC ${CMAKE_CURRENT_LIST_DIR}/PIODDS.pio)

pico_enable_stdio_usb(PIODDSDAC 1)
pico_enable_stdio_uart(PIODDSDAC 1)

pico_add_extra_outputs(PIODDSDAC)

target_link_libraries(PIODDSDAC pico_stdlib pico_time hardware_gpio hardware_irq hardware_pwm hardware_adc hardware_pio)