Skip to content

Commit

Permalink
Implement SPI for Rp2040 (#2466)
Browse files Browse the repository at this point in the history
* Avoid explicity CPU frequencies where slow/normal/fast is sufficient

* Update pico SDK to latest develop (1.3.1)

Considered 1.3.0 but there are bugfixes

* Implement Rp2040 SPIClass

Supports minimum 4 bit transfers so update tests accordingly.

* Get samples building for RP2040

Use spiffs-2m or less if possible
Fix library samples to build for rp2040, add to CI

NB. Basic_WebSkeletonApp needs wifi_set_sleep_type.
Basic_Tasks needs AnalogRead

* Request 24MHz for ILI9341

Will get 20MHz on ESP and 24MHz on RP2040

* Update Rp2040 README

* Implement Host SPI using RP2040 code
  • Loading branch information
mikee47 authored Jan 12, 2022
1 parent ae7240e commit 3b10eeb
Show file tree
Hide file tree
Showing 73 changed files with 816 additions and 469 deletions.
2 changes: 1 addition & 1 deletion Sming/Arch/Rp2040/Components/rp2040/pico-sdk
Submodule pico-sdk updated 161 files
4 changes: 2 additions & 2 deletions Sming/Arch/Rp2040/Components/rp2040/pico-sdk.patch
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
diff --git a/src/rp2_common/pico_platform/include/pico/platform.h b/src/rp2_common/pico_platform/include/pico/platform.h
index c008b95..bf5a690 100644
index 596b0db..0fb309f 100644
--- a/src/rp2_common/pico_platform/include/pico/platform.h
+++ b/src/rp2_common/pico_platform/include/pico/platform.h
@@ -146,7 +146,7 @@ static inline void tight_loop_contents(void) {}
@@ -357,7 +357,7 @@ static __force_inline void tight_loop_contents(void) {}
* \return a * b
*/
__force_inline static int32_t __mul_instruction(int32_t a, int32_t b) {
Expand Down
5 changes: 3 additions & 2 deletions Sming/Arch/Rp2040/README.rst
Original file line number Diff line number Diff line change
Expand Up @@ -35,15 +35,16 @@ Tested and working:
Exception information not yet implemented.
- System functions :cpp:func:`system_get_chip_id`, :cpp:func:`system_get_sdk_version`.
- Partitions and file systems (except SD cards and FAT)
- SPIClass tested with Radio_nRF24L01 sample only

The following items are yet to be implemented:

USB
Best to write a separate ``Sming-USB`` library (based on TinyUSB) to support the RP2040, ESP32-S2 & ESP32-S3 variants.
Needs some thought about good integration into the framework.
Arduino-Pico overrides ``HardwareSerial`` to support serial devices, we can do something similar.
SPI
Nice for messing around with displays.
HardwareSPI
To support DMA, etc.
Analogue I/O
Has 4 channels + temperature.
PWM
Expand Down
2 changes: 2 additions & 0 deletions Sming/Arch/Rp2040/Tools/ci/build.run.sh
Original file line number Diff line number Diff line change
Expand Up @@ -3,3 +3,5 @@
# Rp2040 build.run.sh

$MAKE_PARALLEL samples DEBUG_VERBOSE_LEVEL=3 STRICT=1

$MAKE_PARALLEL component-samples STRICT=1
5 changes: 3 additions & 2 deletions Sming/Components/ssl/src/Session.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,7 @@
#include <Network/Ssl/Factory.h>
#include <Network/TcpConnection.h>
#include <Print.h>
#include <Platform/Clocks.h>

namespace Ssl
{
Expand Down Expand Up @@ -111,9 +112,9 @@ void Session::beginHandshake()
debug_d("SSL: handshake start");
#ifndef SSL_SLOW_CONNECT
curFreq = System.getCpuFrequency();
if(curFreq != eCF_160MHz) {
if(curFreq != CpuCycleClockFast::cpuFrequency()) {
debug_d("SSL: Switching to 160 MHz");
System.setCpuFrequency(eCF_160MHz); // For shorter waiting time, more power consumption.
System.setCpuFrequency(CpuCycleClockFast::cpuFrequency()); // For shorter waiting time, more power consumption.
}
#endif
}
Expand Down
2 changes: 1 addition & 1 deletion Sming/Libraries/Adafruit_ILI9341/Adafruit_ILI9341.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -102,7 +102,7 @@ void Adafruit_ILI9341::transmitCmd(uint8_t cmd)

//Set communication using HW SPI Port
void Adafruit_ILI9341::begin(void) {
SPI.SPIDefaultSettings = SPISettings(20000000, MSBFIRST, SPI_MODE0);
SPI.SPIDefaultSettings = SPISettings(24000000, MSBFIRST, SPI_MODE0);
SPI.begin();
TFT_DC_INIT;
TFT_RST_INIT;
Expand Down
12 changes: 5 additions & 7 deletions Sming/Libraries/Adafruit_ILI9341/component.mk
Original file line number Diff line number Diff line change
Expand Up @@ -2,16 +2,14 @@ COMPONENT_DEPENDS := Adafruit_GFX

COMPONENT_RELINK_VARS := TFT_CS_PIN TFT_DC_PIN TFT_RESET_PIN

ifeq ($(SMING_ARCH),Esp8266)
TFT_CS_PIN ?= 15
TFT_DC_PIN ?= 5
TFT_RESET_PIN ?= 4
else ifeq ($(SMING_ARCH),Esp32)
ifeq ($(SMING_ARCH),Esp32)
TFT_CS_PIN ?= 18
TFT_DC_PIN ?= 19
TFT_RESET_PIN ?= 21
else ifndef MAKE_DOCS
$(warning Arch unsupported)
else
TFT_CS_PIN ?= 15
TFT_DC_PIN ?= 5
TFT_RESET_PIN ?= 4
endif

COMPONENT_CXXFLAGS += -DTFT_CS_PIN=$(TFT_CS_PIN) -DTFT_DC_PIN=$(TFT_DC_PIN)
Expand Down
2 changes: 1 addition & 1 deletion Sming/Libraries/LittleFS
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
HWCONFIG := spiffs
HWCONFIG := spiffs-2m
SPIFF_FILES = web/
ARDUINO_LIBRARIES := MultipartParser

Expand Down
2 changes: 2 additions & 0 deletions Sming/Libraries/Ota/component.mk
Original file line number Diff line number Diff line change
@@ -1,3 +1,5 @@
COMPONENT_SOC = esp* host

COMPONENT_ARCH := $(SMING_ARCH)
ifeq ($(COMPONENT_ARCH),Host)
COMPONENT_ARCH := Esp8266
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,5 @@
## User configurable settings
COMPONENT_SOC = esp* host

## [Application id and version] ##
# Application id
Expand Down
248 changes: 247 additions & 1 deletion Sming/Libraries/SPI/src/Arch/Host/SPI.cpp
Original file line number Diff line number Diff line change
@@ -1,18 +1,264 @@
#include "SPI.h"
#include <FIFO.h>
#include <debug_progmem.h>
#include <stringconversion.h>
#include <Data/BitSet.h>

#define SPI_FIFO_DEPTH 8

#define GET_DEVICE(err) \
if(!busAssigned[busId]) { \
debug_e("[SPI] Not Ready"); \
return err; \
} \
auto& dev = getDevice(busId);

SPIClass SPI;

namespace
{
class SpiDevice
{
public:
void init()
{
}

void deinit()
{
}

uint16_t configure(uint8_t data_bits, uint8_t mode, uint16_t clk)
{
return data_bits | mode | clk;
}

void set_data_bits(uint16_t cr0val, uint8_t data_bits)
{
bits = data_bits;
}

bool can_read() const
{
return true;
}

bool can_write() const
{
return true;
}

uint16_t read()
{
auto c = fifo.dequeue();
if(ioCallback) {
ioCallback(c, bits, true);
}
return c;
}

void write(uint16_t c)
{
c &= BIT(bits) - 1;
if(ioCallback) {
ioCallback(c, bits, false);
}
fifo.enqueue(c);
}

uint16_t read_blocking()
{
return read();
}

void write_blocking(uint16_t c)
{
write(c);
}

SPIClass::IoCallback ioCallback;

private:
FIFO<uint16_t, SPI_FIFO_DEPTH> fifo;
uint8_t bits{0};
};

SpiDevice devices[SOC_SPI_PERIPH_NUM];

SpiDevice& getDevice(SpiBus busId)
{
return devices[unsigned(busId) - 1];
}

BitSet<uint8_t, SpiBus, SOC_SPI_PERIPH_NUM + 1> busAssigned;

uint8_t reverseBits(uint8_t n)
{
static constexpr uint8_t rev_nybble[16]{
0b0000, 0b1000, 0b0100, 0b1100, 0b0010, 0b1010, 0b0110, 0b1110,
0b0001, 0b1001, 0b0101, 0b1101, 0b0011, 0b1011, 0b0111, 0b1111,
};
return (rev_nybble[n & 0x0f] << 4) | rev_nybble[n >> 4];
}

uint16_t reverseBits(uint16_t n)
{
return (reverseBits(uint8_t(n)) << 8) | reverseBits(uint8_t(n >> 8));
}

void reverseBits(uint8_t* buffer, size_t length)
{
while(length--) {
*buffer = reverseBits(*buffer);
++buffer;
}
}

} // namespace

SPIClass::SPIClass() : SPIBase({1, 2, 3})
{
}

bool SPIClass::setup(SpiBus busId, SpiPins pins)
{
if(busId < SpiBus::MIN || busId > SpiBus::MAX) {
debug_e("[SPI] Invalid bus");
return false;
}

if(busAssigned[busId]) {
debug_e("[SPI] Bus #%u already assigned", busId);
return false;
}

this->busId = busId;
mPins = pins;
return true;
}

bool SPIClass::begin()
{
return false;
if(busAssigned[busId]) {
debug_e("[SPI] Bus #%u already assigned", busId);
return false;
}

busAssigned += busId;

auto& dev = getDevice(busId);
dev.init();

prepare(SPIDefaultSettings);
return true;
}

void SPIClass::end()
{
GET_DEVICE();
dev.deinit();
busAssigned -= busId;
}

void SPIClass::setDebugIoCallback(IoCallback callback)
{
GET_DEVICE();
dev.ioCallback = callback;
}

uint32_t SPIClass::transfer32(uint32_t data, uint8_t bits)
{
if(bits < 4) {
debug_e("[SPI] Minimum 4 bit transfers");
return 0;
}

GET_DEVICE(0);

auto writeRead = [&](uint16_t data, uint8_t bits) -> uint16_t {
dev.set_data_bits(cr0val, bits);
if(lsbFirst) {
data = reverseBits(data);
data >>= 16 - bits;
}
dev.write(data);
data = dev.read_blocking();
if(lsbFirst) {
data <<= 16 - bits;
data = reverseBits(data);
}
return data;
};

/*
* 0-3: Not supported
* 4-16: One transfer
* 17-24: Two transfers, first is 8 bits
* 25-32: Two transfers, first is 16 bits
*/
uint32_t res;
if(bits <= 16) {
res = writeRead(data, bits);
} else {
uint8_t n = (bits <= 24) ? 8 : 16;
if(lsbFirst) {
res = writeRead(data, n);
res |= writeRead(data >> n, bits - n) << n;
} else {
res = writeRead(data >> n, bits - n) << n;
res |= writeRead(data, n);
}
}

return res;
}

uint8_t SPIClass::read8()
{
return transfer32(0xff, 8);
}

void SPIClass::transfer(uint8_t* buffer, size_t numberBytes)
{
GET_DEVICE();

if(lsbFirst) {
reverseBits(buffer, numberBytes);
}

size_t rx_remaining = numberBytes;
size_t tx_remaining = numberBytes;
const uint8_t* src = buffer;
uint8_t* dst = buffer;

dev.set_data_bits(cr0val, 8);
while(rx_remaining + tx_remaining != 0) {
/*
* Never have more transfers in flight than will fit into the RX FIFO,
* or FIFO will overflow if this code is heavily interrupted.
*/
while(tx_remaining != 0 && rx_remaining < tx_remaining + SPI_FIFO_DEPTH && dev.can_write()) {
dev.write(*src++);
--tx_remaining;
}
if(rx_remaining != 0 && dev.can_read()) {
*dst++ = dev.read();
--rx_remaining;
}
}

if(lsbFirst) {
reverseBits(buffer, numberBytes);
}
}

void SPIClass::prepare(SPISettings& settings)
{
GET_DEVICE();

cr0val = dev.configure(8, settings.dataMode, 0);

lsbFirst = (settings.bitOrder == LSBFIRST);
}

bool SPIClass::loopback(bool enable)
Expand Down
6 changes: 5 additions & 1 deletion Sming/Libraries/SPI/src/Arch/Host/spi_arch.h
Original file line number Diff line number Diff line change
Expand Up @@ -9,13 +9,17 @@

#pragma once

static constexpr uint8_t SOC_SPI_PERIPH_NUM{3};

/**
* @brief Identifies bus selection
*/
enum class SpiBus {
INVALID = 0,
MIN = 1,
SPI1 = 1,
MAX = 1,
SPI2 = 2,
SPI3 = 3,
MAX = SOC_SPI_PERIPH_NUM,
DEFAULT = SPI1,
};
Loading

0 comments on commit 3b10eeb

Please sign in to comment.