• Stars
    star
    103
  • Rank 333,046 (Top 7 %)
  • Language
    C++
  • License
    MIT License
  • Created almost 5 years ago
  • Updated almost 2 years ago

Reviews

There are no reviews yet. Be the first to send feedback to the community and the maintainers!

Repository Details

SPI library for ESP32 which use DMA buffer to send/receive transactions

ESP32DMASPI

SPI library for ESP32 which use DMA buffer to send/receive transactions

ESP32SPISlave

This is the SPI library to send/receive large transaction with DMA. Please use ESP32SPISlave for the simple SPI Slave mode without DMA.

Feature

  • support DMA buffer (more than 64 byte transfer is available)
  • support both SPI Master and Slave mode based on ESP32's SPI Master Driver and SPI Slave Driver
  • Master has two ways to send/receive transactions
    • transfer() to send/receive transaction one by one
    • queue() and yield() to send/receive multiple transactions at once (more efficient than transfer() many times)
  • Slave has two ways to receive/send transactions
    • wait() to receive/send transaction one by one
    • queue() and yield() to receive/send multiple transactions at once (more efficient than wait() many times)
  • Various configurations based on driver APIs

Supported ESP32 Version

IDE ESP32 Board Version
Arduino IDE >= 2.0.0
PlatformIO Currently (<= 3.4.0) NOT Supported

WARNING

  • There is known issue that last 4 bytes are missing if DMA is used with SPI Slave
    • you need to send 4 bytes more to send all required bytes to ESP32 SPI Slave with DMA
  • There is also a known issue that received data is bit shifted depending on the SPI mode
    • Please try SPI mode 0 for this issue
    • But SPI mode 1 or 3 is required based on the official doc
    • Please use this library and SPI modes for your own risk

Usage

Master

#include <ESP32DMASPIMaster.h>

ESP32DMASPI::Master master;

static const uint32_t BUFFER_SIZE = 8192;
uint8_t* spi_master_tx_buf;
uint8_t* spi_master_rx_buf;

void setup() {
    // to use DMA buffer, use these methods to allocate buffer
    spi_master_tx_buf = master.allocDMABuffer(BUFFER_SIZE);
    spi_master_rx_buf = master.allocDMABuffer(BUFFER_SIZE);

    // set buffer data...

    master.setDataMode(SPI_MODE0);           // default: SPI_MODE0
    master.setFrequency(4000000);            // default: 8MHz (too fast for bread board...)
    master.setMaxTransferSize(BUFFER_SIZE);  // default: 4092 bytes

    // begin() after setting
    master.begin();  // HSPI (CS: 15, CLK: 14, MOSI: 13, MISO: 12) -> default
                     // VSPI (CS:  5, CLK: 18, MOSI: 23, MISO: 19)
}

void loop() {
    // start and wait to complete transaction
    master.transfer(spi_master_tx_buf, spi_master_rx_buf, BUFFER_SIZE);

    // do something with received data if you want
}

Slave

#include <ESP32DMASPISlave.h>

ESP32DMASPI::Slave slave;

static const uint32_t BUFFER_SIZE = 8192;
uint8_t* spi_slave_tx_buf;
uint8_t* spi_slave_rx_buf;

void setup() {
    // to use DMA buffer, use these methods to allocate buffer
    spi_slave_tx_buf = slave.allocDMABuffer(BUFFER_SIZE);
    spi_slave_rx_buf = slave.allocDMABuffer(BUFFER_SIZE);

    // set buffer data...

    // slave device configuration
    slave.setDataMode(SPI_MODE0);
    slave.setMaxTransferSize(BUFFER_SIZE);

    // begin() after setting
    slave.begin();  // HSPI = CS: 15, CLK: 14, MOSI: 13, MISO: 12 -> default
                    // VSPI (CS:  5, CLK: 18, MOSI: 23, MISO: 19)
}

void loop() {
    // if there is no transaction in queue, add transaction
    if (slave.remained() == 0) {
        slave.queue(spi_slave_rx_buf, spi_slave_tx_buf, BUFFER_SIZE);
    }

    // if transaction has completed from master,
    // available() returns size of results of transaction,
    // and buffer is automatically updated

    while (slave.available()) {
        // do something with received data: spi_slave_rx_buf

        slave.pop();
    }
}

APIs

Master

// use HSPI or VSPI with default pin assignment
// VSPI (CS:  5, CLK: 18, MOSI: 23, MISO: 19)
// HSPI (CS: 15, CLK: 14, MOSI: 13, MISO: 12) -> default
bool begin(const uint8_t spi_bus = HSPI);
// use HSPI or VSPI with your own pin assignment
bool begin(const uint8_t spi_bus, const int8_t sck, const int8_t miso, const int8_t mosi, const int8_t ss);
bool end();

// DMA requires the memory allocated with this method
uint8_t* allocDMABuffer(const size_t n);

// execute transaction and wait for transmission one by one
size_t transfer(const uint8_t* tx_buf, const size_t size);
size_t transfer(const uint8_t* tx_buf, uint8_t* rx_buf, const size_t size);
size_t transfer(const uint16_t cmd, const uint64_t addr, const uint8_t* tx_buf, const size_t size);
size_t transfer(const uint16_t cmd, const uint64_t addr, const uint8_t* tx_buf, uint8_t* rx_buf, const size_t size);
size_t transfer(const uint8_t command_bits, const uint8_t address_bits, const uint16_t cmd, const uint64_t addr, const uint8_t* tx_buf, uint8_t* rx_buf, const size_t size);
size_t transfer(const uint8_t command_bits, const uint8_t address_bits, const uint8_t dummy_bits, const uint32_t flags, const uint16_t cmd, const uint64_t addr, const uint8_t* tx_buf, uint8_t* rx_buf, const size_t size);

// queueing transaction and execute simultaneously
// wait (blocking) and timeout occurs if queue is full with transaction
// (but designed not to queue transaction more than queue_size, so there is no timeout argument)
bool queue(const uint8_t* tx_buf, const size_t size);
bool queue(const uint8_t* tx_buf, uint8_t* rx_buf, const size_t size);
bool queue(const uint16_t cmd, const uint64_t addr, const uint8_t* tx_buf, const size_t size);
bool queue(const uint16_t cmd, const uint64_t addr, const uint8_t* tx_buf, uint8_t* rx_buf, const size_t size);
bool queue(const uint8_t command_bits, const uint8_t address_bits, const uint16_t cmd, const uint64_t addr, const uint8_t* tx_buf, uint8_t* rx_buf, const size_t size);
bool queue(const uint8_t command_bits, const uint8_t address_bits, const uint8_t dummy_bits, const uint32_t flags, const uint16_t cmd, const uint64_t addr, const uint8_t* tx_buf, uint8_t* rx_buf, const size_t size);
void yield();

// ===== Main Configurations =====
// set these optional parameters before begin() if you want
void setDataMode(const uint8_t m);  // SPI_MODE0, 1, 2, 3
void setFrequency(const size_t f);  // up to 80 MHz
void setMaxTransferSize(const size_t n);

// ===== Optional Configurations =====
// set these optional parameters before begin() if you want
void setCommandBits(const uint8_t n);           // 0-16
void setAddressBits(const uint8_t n);           // 0-64
void setDummyBits(const uint8_t n);
void setDutyCyclePos(const uint8_t n);          // 128 for 50%
void setSpiMode(const uint8_t m);               // SPI_MODE0, 1, 2, 3
void setCsEnaPostTrans(const uint8_t n);
void setClockSpeedHz(const size_t f);           // up to 80 MHz
void setInputDelayNs(const int n);
void setDeviceFlags(const uint32_t flags);      // OR of SPI_DEVICE_* flags
void setQueueSize(const size_t n);              // default: 3
void setPreCb(const transaction_cb_t pre_cb);
void setPostCb(const transaction_cb_t post_cb);
void setDMAChannel(const uint8_t c);            // default: auto

Slave

// use HSPI or VSPI with default pin assignment
// VSPI (CS:  5, CLK: 18, MOSI: 23, MISO: 19)
// HSPI (CS: 15, CLK: 14, MOSI: 13, MISO: 12) -> default
bool begin(const uint8_t spi_bus = HSPI);
// use HSPI or VSPI with your own pin assignment
bool begin(const uint8_t spi_bus, const int8_t sck, const int8_t miso, const int8_t mosi, const int8_t ss);
bool end();

// DMA requires the memory allocated with this method
uint8_t* allocDMABuffer(const size_t s);

// wait for transaction one by one
bool wait(uint8_t* rx_buf, const size_t size);  // no data to master
bool wait(uint8_t* rx_buf, const uint8_t* tx_buf, const size_t size);

// queueing transaction
// wait (blocking) and timeout occurs if queue is full with transaction
// (but designed not to queue transaction more than queue_size, so there is no timeout argument)
bool queue(uint8_t* rx_buf, const size_t size);  // no data to master
bool queue(uint8_t* rx_buf, const uint8_t* tx_buf, const size_t size);

// wait until all queued transaction will be done by master
// if yield is finished, all the buffer is updated to latest
void yield();

// transaction result info
size_t available() const;  // size of completed (received) transaction results
size_t remained() const;   // size of queued (not completed) transactions
uint32_t size() const;     // size of the received bytes of the oldest queued transaction result
void pop();                // pop the oldest transaction result

// ===== Main Configurations =====
// set these optional parameters before begin() if you want
void setDataMode(const uint8_t m);
void setMaxTransferSize(const int n);

// ===== Optional Configurations =====
void setSlaveFlags(const uint32_t flags);  // OR of SPI_SLAVE_* flags
void setQueueSize(const int n);
void setSpiMode(const uint8_t m);
void setDMAChannel(const uint8_t c);  // default: auto

Configuration Flags

#define SPI_DEVICE_TXBIT_LSBFIRST  (1<<0)  ///< Transmit command/address/data LSB first instead of the default MSB first
#define SPI_DEVICE_RXBIT_LSBFIRST  (1<<1)  ///< Receive data LSB first instead of the default MSB first
#define SPI_DEVICE_BIT_LSBFIRST    (SPI_DEVICE_TXBIT_LSBFIRST|SPI_DEVICE_RXBIT_LSBFIRST) ///< Transmit and receive LSB first
#define SPI_DEVICE_3WIRE           (1<<2)  ///< Use MOSI (=spid) for both sending and receiving data
#define SPI_DEVICE_POSITIVE_CS     (1<<3)  ///< Make CS positive during a transaction instead of negative
#define SPI_DEVICE_HALFDUPLEX      (1<<4)  ///< Transmit data before receiving it, instead of simultaneously
#define SPI_DEVICE_CLK_AS_CS       (1<<5)  ///< Output clock on CS line if CS is active
/** There are timing issue when reading at high frequency (the frequency is related to whether iomux pins are used, valid time after slave sees the clock).
  *     - In half-duplex mode, the driver automatically inserts dummy bits before reading phase to fix the timing issue. Set this flag to disable this feature.
  *     - In full-duplex mode, however, the hardware cannot use dummy bits, so there is no way to prevent data being read from getting corrupted.
  *       Set this flag to confirm that you're going to work with output only, or read without dummy bits at your own risk.
  */
#define SPI_DEVICE_NO_DUMMY        (1<<6)
#define SPI_DEVICE_DDRCLK          (1<<7)

https://github.com/espressif/esp-idf/blob/master/components/driver/include/driver/spi_master.h#L32-L45

#define SPI_SLAVE_TXBIT_LSBFIRST          (1<<0)  ///< Transmit command/address/data LSB first instead of the default MSB first
#define SPI_SLAVE_RXBIT_LSBFIRST          (1<<1)  ///< Receive data LSB first instead of the default MSB first
#define SPI_SLAVE_BIT_LSBFIRST            (SPI_SLAVE_TXBIT_LSBFIRST|SPI_SLAVE_RXBIT_LSBFIRST) ///< Transmit and receive LSB first

https://github.com/espressif/esp-idf/blob/733fbd9ecc8ac0780de51b3761a16d1faec63644/components/driver/include/driver/spi_slave.h#L23-L25

Restrictions and Known Issues for SPI with DMA Buffer (Help Wanted)

As mentioned above, in short, there are two restrictions/issues for SPI with DMA buffer.

  1. RX buffer and host transfer length should be aligned to 4 bytes (length must be multiples of 4 bytes)
  2. Correct transfer requires SPI mode 1 and 3; otherwise Slave -> Master data corrupt (maybe MSB of the first byte)

To avoid 2nd issue, I set setDutyCyclePos(96) in examples but it's a workaround and not a good solution. In addition, SPI Mode 1 and 3 do not work correctly with the current configuration if esp32-arduino version > 1.0.4. Also, in the example of esp-idf, SPI mode 1 is used... I hope someone sends PR for a better solution (configuration) someday!

Please refer here for more information and configure your slave by yourself.

TODO (PR welcome!!)

Reference

License

MIT

More Repositories

1

MPU9250

Arduino library for MPU9250 Nine-Axis (Gyro + Accelerometer + Compass) MEMS MotionTrackingâ„¢ Device
C++
229
star
2

ArduinoOSC

OSC subscriber / publisher for Arduino
C++
171
star
3

ArtNet

Art-Net Sender/Receiver for Arduino (Ethernet, WiFi)
C++
162
star
4

MsgPacketizer

msgpack based serializer / deserializer + packetize for Arduino, ROS, and more
C++
61
star
5

Tween

Tween library for Arduino with Robert Penner's easing functions
C++
41
star
6

Packetizer

binary data packetization encoder / decoder based on COBS / SLIP encoding
C++
34
star
7

MsgPack

MessagePack implementation for Arduino (compatible with other C++ apps) / msgpack.org[Arduino]
C++
33
star
8

ArxContainer

C++ container-like classes (vector, map, etc.) for Arduino which cannot use STL
C++
32
star
9

DebugLog

Logging library for Arduino that can output to both Serial and File with one line
C++
28
star
10

ArduinoEigen

Eigen (a C++ template library for linear algebra) for Arduino
C++
25
star
11

ESP32SPISlave

SPI Slave library for ESP32
C++
24
star
12

TaskManager

polling-based cooperative multi-task manager for Arduino
C++
23
star
13

MQTTPubSubClient

MQTT and MQTT over WebSoket Client for Arduino
C++
22
star
14

MCP4728

Arduino library for MCP4728 quad channel, 12-bit voltage output Digital-to-Analog Convertor with non-volatile memory and I2C compatible Serial Interface
C++
18
star
15

Dynamixel

Arduino library for Dynamixel
C++
17
star
16

Debouncer

Debounce library for Arduino
C++
14
star
17

TCS34725

Arduino library for TCS34725 RGB Color Sensor
C++
11
star
18

CRCx

CRC calculation for Arduino
C
10
star
19

TsyDMASPI

SPI library using DMA buffer for Teensy
C
10
star
20

ofxArtnetProtocol

The port of Art-Net protocol parser https://github.com/natcl/Artnet to openFrameworks and mbed.
C++
8
star
21

Filters

Filter utilities for Arduino
C++
8
star
22

L6470Stepper

L6470 / L6480 wrapper for Arduino
C++
8
star
23

FastLEDManager

My FastLED Manager that can generate multiple sequences with layered (mixed) output
C++
7
star
24

ArxTypeTraits

C++ type_traits for Arduino which cannot use it as default
C++
7
star
25

EmbeddedUtils

collections of utility headers for embedded c++
C++
6
star
26

SPIExtension

SPI extension/wrapper for Arduino
C++
6
star
27

Sony9PinRemote

RS422 Sony 9-Pin Protocol Remote Controller of VTRs for Arduino
C++
6
star
28

IM920

Interplan IM920 series wrapper for Arduino and openFrameworks
C++
5
star
29

ADS1x1x

Arduino library for ADS101x / ADS111x Ultra-Small, Low-Power, I2C-Compatible, ADCs
C++
5
star
30

MTCParser

Midi Time Code (MTC) parser
C++
5
star
31

Sketches

sketches
Rust
5
star
32

MAX17048

Arduino library for MAX17048/MAX17049 1-Cell/2-Cell Fuel Gauge with ModelGauge
C++
5
star
33

SPIDaisyChain

Daisy-chained SPI library for Arduino
C++
5
star
34

HyperDeck

BlackMagic Design HyperDeck controller for Arduino via TCP
C++
5
star
35

DRV2667

Arduino library for DRV2667 Piezo Haptic Driver with Boost, Digital Front End, and Internal Waveform Memory
C++
5
star
36

TCA9534

Arduino library for TCA9534 Low Voltage 8-Bit I2C and SMBUS Low-Power I/O Expander with Interrupt Output and Configuration Registers
C++
4
star
37

MPU6050

Arduino library for MPU-6050 Six-Axis (Gyro + Accelerometer) MEMS MotionTrackingâ„¢ Devices
C++
4
star
38

PCA95x5

Arduino library for PCA9535 and PCA9555 (Remote 16-bit I2C and SMBus I/O Expander with Interrupt Output and Configuration Registers).
C++
4
star
39

ArxSmartPtr

C++ smart pointer-like classes for Arduino which can't use standard smart pointers
C++
4
star
40

PollingTimer

Arduino library to manage timing and event in a flexible way with polling
C++
4
star
41

PCA9547

Arduino library for PCA9547 (8-channel I2C-bus multiplexer with reset)
C++
4
star
42

I2CExtension

I2C extension/wrapper for Arduino
C++
3
star
43

Easing

Easing function library for Arduino
C++
3
star
44

VectorXf

Vector class 2f, 3f, 4f (port of ofVecXf (openFrameworks))
C++
3
star
45

TFmini

Arduino library for Benewake TFmini micro LiDAR module
C++
3
star
46

SceneManager

cooperative multi-scene manager for Arduino
C++
3
star
47

PCA9624

Arduino library for PCA9624 8-bit Fm+ I2C-bus 100 mA 40 V LED driver
C++
3
star
48

MsgPackRosInterfaces

ROS2 `common_interfaces` bridge based on MsgPack
C++
3
star
49

ofxSerial

Tiny extension to set options of ofSerial communication
C++
3
star
50

bevy_serial

Serial Port Communication Plugin for Bevy
Rust
2
star
51

GammaTable

Gamma Table for Arduino
C++
2
star
52

SpresenseNeoPixel

NeoPixel library for SPRESENSE (Arduino)
C++
2
star
53

ofxModbusOriental

modbus protocol wrapper for oriental motor
C++
2
star
54

pvoc-mini-plugins

Port of pvoc-plugins that can be available without LADSPA
Rust
1
star
55

rust-esp32-osc-led

Control smart LEDs from OSC via Wi-Fi on ESP32-C3
Rust
1
star
56

ES920

Arduino library for ES920/ES920LR FSK/LoRa wireless module
C++
1
star
57

hideakitai.github.io

1
star
58

hideakitai

1
star
59

rust_gui_iced_introduction

Rust
1
star
60

ArxStringUtils

Arduino String utilities
C++
1
star
61

XBeeATCmds

XBee AT Command Wrapper for Arduino
C++
1
star
62

EmbeddedApp

application template for embedded software
C++
1
star
63

TDCPlusPlusTemplate

touchdesigner CPlusPlus templates for myself
C++
1
star
64

TouchDesigner-GLSL-Sound

Template to use GLSL Sound on TouchDesigner
GLSL
1
star
65

TimeProfiler

Time profiler for Arduino
C++
1
star
66

msgpack-arduino

msgpack-c/c++ for arduino
C++
1
star
67

DS323x

Arduino library for DS3231/DS3232 Extremely Accurate I²C-Integrated RTC/TCXO/Crystal
C++
1
star
68

PCF2129

Arduino library for RTC PCF2129 with integrated quartz crystal
C++
1
star