Skip to content
5 changes: 3 additions & 2 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@ project(pico_serprog)
pico_sdk_init()

add_executable(pico_serprog)
target_sources(pico_serprog PRIVATE main.c usb_descriptors.c)
target_link_libraries(pico_serprog PRIVATE pico_stdlib hardware_spi tinyusb_device)
pico_generate_pio_header(pico_serprog ${CMAKE_CURRENT_LIST_DIR}/spi.pio)
target_sources(pico_serprog PRIVATE main.c usb_descriptors.c pio_spi.c)
target_link_libraries(pico_serprog PRIVATE pico_stdlib hardware_spi hardware_pio tinyusb_device)
pico_add_extra_outputs(pico_serprog)
71 changes: 51 additions & 20 deletions main.c
Original file line number Diff line number Diff line change
Expand Up @@ -8,12 +8,17 @@
* https://github.com/dword1511/stm32-vserprog
*
*/

#include <stdlib.h>
#include <stdio.h>
#include <string.h>
#include "pico/stdlib.h"
#include "pico/time.h"
#include "hardware/spi.h"
#include "tusb.h"
#include "serprog.h"
#include "pio_spi.h"



#define CDC_ITF 0 // USB CDC interface no

Expand All @@ -23,14 +28,43 @@
#define SPI_MISO 4
#define SPI_MOSI 3
#define SPI_SCK 2
#define MAX_BUFFER_SIZE 1024
#define MAX_OPBUF_SIZE 1024
#define SERIAL_BUFFER_SIZE 1024
#define MAX_BUFFER_SIZE 512
#define MAX_OPBUF_SIZE 512
#define SERIAL_BUFFER_SIZE 512

// Define a global operation buffer and a pointer to track the current position
uint8_t opbuf[MAX_OPBUF_SIZE];
uint32_t opbuf_pos = 0;


void sendbytes_usb(const uint8_t *buf, size_t len) {
// Check if USB is ready for data transfer
if (tud_cdc_connected()) {
// Write data to the USB CDC interface
tud_cdc_write(buf, len);
tud_cdc_write_flush();
}
}


void read_spi_and_send_via_usb(const pio_spi_inst_t *spi, const uint32_t rlen) {
static uint8_t rxbuf[MAX_BUFFER_SIZE];
memset(rxbuf, 0, MAX_BUFFER_SIZE); // Clear the rx buffer

// Ensure we send rlen bytes
uint32_t remaining = rlen;
while (remaining) {
// Perform a dummy write and then read
uint32_t chunk_size = (remaining < MAX_BUFFER_SIZE) ? remaining : MAX_BUFFER_SIZE;
pio_spi_read8_blocking(spi, rxbuf, chunk_size);
remaining -= chunk_size;

// Transfer data via USB
sendbytes_usb(rxbuf, chunk_size);
}
}


static void enable_spi(uint baud)
{
// Setup chip select GPIO
Expand Down Expand Up @@ -100,6 +134,7 @@ static inline uint8_t readbyte_blocking(void)
return b;
}


static void wait_for_write(void)
{
do {
Expand All @@ -123,6 +158,7 @@ static inline void sendbyte_blocking(uint8_t b)
tud_cdc_n_write(CDC_ITF, &b, 1);
}


static void command_loop(void)
{
uint baud = spi_get_baudrate(SPI_IF);
Expand Down Expand Up @@ -224,24 +260,16 @@ static void command_loop(void)
break;
}

// Send ACK after handling slen (before reading)
sendbyte_blocking(S_ACK);

// Handle receive operation in chunks for large rlen
uint32_t chunk;
char buf[128];

for(uint32_t i = 0; i < rlen; i += chunk) {
chunk = MIN(rlen - i, sizeof(buf));
spi_read_blocking(SPI_IF, 0, buf, chunk);
// Send ACK followed by received data
sendbyte_blocking(S_ACK);
sendbytes_blocking(buf, rlen);
}
cs_deselect(SPI_CS);
// Now call the modified function to read from SPI and send via USB
// Assuming rlen is the length of data to read and send
pio_spi_inst_t spi = {
.pio = pio0,
.sm = 0
};
read_spi_and_send_via_usb(&spi, rlen);
break;
}
case S_CMD_S_SPI_FREQ:
case S_CMD_S_SPI_FREQ:
{
uint32_t want_baud;
readbytes_blocking(&want_baud, 4);
Expand Down Expand Up @@ -342,7 +370,10 @@ static void command_loop(void)
int main()
{
// Setup USB
stdio_init_all();

tusb_init();

// Setup PL022 SPI
enable_spi(SPI_BAUD);

Expand Down
68 changes: 68 additions & 0 deletions pio_spi.c
Original file line number Diff line number Diff line change
@@ -0,0 +1,68 @@
/**
* Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
*
* SPDX-License-Identifier: BSD-3-Clause
*/

#include "pio_spi.h"

// Just 8 bit functions provided here. The PIO program supports any frame size
// 1...32, but the software to do the necessary FIFO shuffling is left as an
// exercise for the reader :)
//
// Likewise we only provide MSB-first here. To do LSB-first, you need to
// - Do shifts when reading from the FIFO, for general case n != 8, 16, 32
// - Do a narrow read at a one halfword or 3 byte offset for n == 16, 8
// in order to get the read data correctly justified.

void __time_critical_func(pio_spi_write8_blocking)(const pio_spi_inst_t *spi, const uint8_t *src, size_t len) {
size_t tx_remain = len, rx_remain = len;
// Do 8 bit accesses on FIFO, so that write data is byte-replicated. This
// gets us the left-justification for free (for MSB-first shift-out)
io_rw_8 *txfifo = (io_rw_8 *) &spi->pio->txf[spi->sm];
io_rw_8 *rxfifo = (io_rw_8 *) &spi->pio->rxf[spi->sm];
while (tx_remain || rx_remain) {
if (tx_remain && !pio_sm_is_tx_fifo_full(spi->pio, spi->sm)) {
*txfifo = *src++;
--tx_remain;
}
if (rx_remain && !pio_sm_is_rx_fifo_empty(spi->pio, spi->sm)) {
(void) *rxfifo;
--rx_remain;
}
}
}

void __time_critical_func(pio_spi_read8_blocking)(const pio_spi_inst_t *spi, uint8_t *dst, size_t len) {
size_t tx_remain = len, rx_remain = len;
io_rw_8 *txfifo = (io_rw_8 *) &spi->pio->txf[spi->sm];
io_rw_8 *rxfifo = (io_rw_8 *) &spi->pio->rxf[spi->sm];
while (tx_remain || rx_remain) {
if (tx_remain && !pio_sm_is_tx_fifo_full(spi->pio, spi->sm)) {
*txfifo = 0;
--tx_remain;
}
if (rx_remain && !pio_sm_is_rx_fifo_empty(spi->pio, spi->sm)) {
*dst++ = *rxfifo;
--rx_remain;
}
}
}

void __time_critical_func(pio_spi_write8_read8_blocking)(const pio_spi_inst_t *spi, uint8_t *src, uint8_t *dst,
size_t len) {
size_t tx_remain = len, rx_remain = len;
io_rw_8 *txfifo = (io_rw_8 *) &spi->pio->txf[spi->sm];
io_rw_8 *rxfifo = (io_rw_8 *) &spi->pio->rxf[spi->sm];
while (tx_remain || rx_remain) {
if (tx_remain && !pio_sm_is_tx_fifo_full(spi->pio, spi->sm)) {
*txfifo = *src++;
--tx_remain;
}
if (rx_remain && !pio_sm_is_rx_fifo_empty(spi->pio, spi->sm)) {
*dst++ = *rxfifo;
--rx_remain;
}
}
}

24 changes: 24 additions & 0 deletions pio_spi.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,24 @@
/**
* Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#ifndef _PIO_SPI_H
#define _PIO_SPI_H

#include "hardware/pio.h"
#include "spi.pio.h"

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

void pio_spi_write8_blocking(const pio_spi_inst_t *spi, const uint8_t *src, size_t len);

void pio_spi_read8_blocking(const pio_spi_inst_t *spi, uint8_t *dst, size_t len);

void pio_spi_write8_read8_blocking(const pio_spi_inst_t *spi, uint8_t *src, uint8_t *dst, size_t len);

#endif
168 changes: 168 additions & 0 deletions spi.pio
Original file line number Diff line number Diff line change
@@ -0,0 +1,168 @@
;
; Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
;
; SPDX-License-Identifier: BSD-3-Clause
;

; These programs implement full-duplex SPI, with a SCK period of 4 clock
; cycles. A different program is provided for each value of CPHA, and CPOL is
; achieved using the hardware GPIO inversion available in the IO controls.
;
; Transmit-only SPI can go twice as fast -- see the ST7789 example!


.program spi_cpha0
.side_set 1

; Pin assignments:
; - SCK is side-set pin 0
; - MOSI is OUT pin 0
; - MISO is IN pin 0
;
; Autopush and autopull must be enabled, and the serial frame size is set by
; configuring the push/pull threshold. Shift left/right is fine, but you must
; justify the data yourself. This is done most conveniently for frame sizes of
; 8 or 16 bits by using the narrow store replication and narrow load byte
; picking behaviour of RP2040's IO fabric.

; Clock phase = 0: data is captured on the leading edge of each SCK pulse, and
; transitions on the trailing edge, or some time before the first leading edge.

out pins, 1 side 0 [1] ; Stall here on empty (sideset proceeds even if
in pins, 1 side 1 [1] ; instruction stalls, so we stall with SCK low)

.program spi_cpha1
.side_set 1

; Clock phase = 1: data transitions on the leading edge of each SCK pulse, and
; is captured on the trailing edge.

out x, 1 side 0 ; Stall here on empty (keep SCK deasserted)
mov pins, x side 1 [1] ; Output data, assert SCK (mov pins uses OUT mapping)
in pins, 1 side 0 ; Input data, deassert SCK

% c-sdk {
#include "hardware/gpio.h"
static inline void pio_spi_init(PIO pio, uint sm, uint prog_offs, uint n_bits,
float clkdiv, bool cpha, bool cpol, uint pin_sck, uint pin_mosi, uint pin_miso) {
pio_sm_config c = cpha ? spi_cpha1_program_get_default_config(prog_offs) : spi_cpha0_program_get_default_config(prog_offs);
sm_config_set_out_pins(&c, pin_mosi, 1);
sm_config_set_in_pins(&c, pin_miso);
sm_config_set_sideset_pins(&c, pin_sck);
// Only support MSB-first in this example code (shift to left, auto push/pull, threshold=nbits)
sm_config_set_out_shift(&c, false, true, n_bits);
sm_config_set_in_shift(&c, false, true, n_bits);
sm_config_set_clkdiv(&c, clkdiv);

// MOSI, SCK output are low, MISO is input
pio_sm_set_pins_with_mask(pio, sm, 0, (1u << pin_sck) | (1u << pin_mosi));
pio_sm_set_pindirs_with_mask(pio, sm, (1u << pin_sck) | (1u << pin_mosi), (1u << pin_sck) | (1u << pin_mosi) | (1u << pin_miso));
pio_gpio_init(pio, pin_mosi);
pio_gpio_init(pio, pin_miso);
pio_gpio_init(pio, pin_sck);

// The pin muxes can be configured to invert the output (among other things
// and this is a cheesy way to get CPOL=1
gpio_set_outover(pin_sck, cpol ? GPIO_OVERRIDE_INVERT : GPIO_OVERRIDE_NORMAL);
// SPI is synchronous, so bypass input synchroniser to reduce input delay.
hw_set_bits(&pio->input_sync_bypass, 1u << pin_miso);

pio_sm_init(pio, sm, prog_offs, &c);
pio_sm_set_enabled(pio, sm, true);
}
%}

; SPI with Chip Select
; -----------------------------------------------------------------------------
;
; For your amusement, here are some SPI programs with an automatic chip select
; (asserted once data appears in TX FIFO, deasserts when FIFO bottoms out, has
; a nice front/back porch).
;
; The number of bits per FIFO entry is configured via the Y register
; and the autopush/pull threshold. From 2 to 32 bits.
;
; 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)
;
; This program only supports one chip select -- use GPIO if more are needed
;
; Provide a variation for each possibility of CPHA; for CPOL we can just
; invert SCK in the IO muxing controls (downstream from PIO)


; CPHA=0: data is captured on the leading edge of each SCK pulse (including
; the first pulse), and transitions on the trailing edge

.program spi_cpha0_cs
.side_set 2

.wrap_target
bitloop:
out pins, 1 side 0x0 [1]
in pins, 1 side 0x1
jmp x-- bitloop side 0x1

out pins, 1 side 0x0
mov x, y side 0x0 ; Reload bit counter from Y
in pins, 1 side 0x1
jmp !osre bitloop side 0x1 ; 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

; CPHA=1: data transitions on the leading edge of each SCK pulse, and is
; captured on the trailing edge

.program spi_cpha1_cs
.side_set 2

.wrap_target
bitloop:
out pins, 1 side 0x1 [1]
in pins, 1 side 0x0
jmp x-- bitloop side 0x0

out pins, 1 side 0x1
mov x, y side 0x1
in pins, 1 side 0x0
jmp !osre bitloop side 0x0

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

% c-sdk {
#include "hardware/gpio.h"
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, uint pin_miso) {
pio_sm_config c = cpha ? spi_cpha1_cs_program_get_default_config(prog_offs) : spi_cpha0_cs_program_get_default_config(prog_offs);
sm_config_set_out_pins(&c, pin_mosi, 1);
sm_config_set_in_pins(&c, pin_miso);
sm_config_set_sideset_pins(&c, pin_sck);
sm_config_set_out_shift(&c, false, true, n_bits);
sm_config_set_in_shift(&c, false, true, n_bits);
sm_config_set_clkdiv(&c, clkdiv);

pio_sm_set_pins_with_mask(pio, sm, (2u << pin_sck), (3u << pin_sck) | (1u << pin_mosi));
pio_sm_set_pindirs_with_mask(pio, sm, (3u << pin_sck) | (1u << pin_mosi), (3u << pin_sck) | (1u << pin_mosi) | (1u << pin_miso));
pio_gpio_init(pio, pin_mosi);
pio_gpio_init(pio, pin_miso);
pio_gpio_init(pio, pin_sck);
pio_gpio_init(pio, pin_sck + 1);
gpio_set_outover(pin_sck, cpol ? GPIO_OVERRIDE_INVERT : GPIO_OVERRIDE_NORMAL);
hw_set_bits(&pio->input_sync_bypass, 1u << pin_miso);

uint entry_point = prog_offs + (cpha ? spi_cpha1_cs_offset_entry_point : spi_cpha0_cs_offset_entry_point);
pio_sm_init(pio, sm, entry_point, &c);
pio_sm_exec(pio, sm, pio_encode_set(pio_x, n_bits - 2));
pio_sm_exec(pio, sm, pio_encode_set(pio_y, n_bits - 2));
pio_sm_set_enabled(pio, sm, true);
}
%}
Loading