Skip to content

How to make use of DMA SPI in Arduino? #2271

@techtoys

Description

@techtoys

Hardware:

Board: ESP32 Pico Kit
Core Installation/update date: 1.0.0 (GIT_VER 0x30b3eeba)
IDE name: Arduino IDE v1.8.1
Flash Frequency: 40Mhz
PSRAM enabled: no
Upload Speed: 115200
Computer OS: Windows 7 Pro

Description:

Trying to use spi_device_transmit() from ..\sdk\include\driver\driver\spi_master.h.
Comparing to writeBytes(uint8_t * data, uint32_t size), spi_device_transmit() can accept a max. byte stream of length 4092 as defined in SPI_MAX_DMA_LEN. Proven to be much faster than conventional SPI.write() and SPI.writeBytes() with a logic analyzer and actual LCD refresh. Unfortunately my driver is highly unstable, in the sense that it crashes with other arduino libraries very often. Another weird behavior is that, when spi_device_transmit() is used for SPI transfer, it won't be possible to program in conventional Arduino sketch structure as set(){...} loop(){...}; otherwise, the program crashes. Something like the program below just crashes! It could be due to something like task created nature of setup()...loop(). Not sure.

//This simple sketch will crash for some unknown reason. 
#include "SSD2805.h"
void setup(){
ssd2805.begin();
}

void loop(){
    ssd2805.clearLCD(0xf800);delay(500);
    ssd2805.clearLCD(0x07f0);delay(500);
    ssd2805.clearLCD(0x001f);delay(500);
}

Instead, I need to divide it into tasks and use xTaskCreatePinnedToCore() to pin the task involving spi_device_transmit() to avoid crashing. Below is the Arduino sketch. Although this particular sketch is working well, as I have mentioned, ssd2805.h is highly unstable when it co-work with other libraries. I believe something is not correct here.

Hope somebody have tried SPI DMA send in Arduino and give me a hint on the current problem.

Sketch:

//This is the Arduino Sketch SimpeDemo.ino working
#include "GuiTask.h"

void setup() {
  // put your setup code here, to run once:
  Serial.begin(115200);

  //Everything related to GUI stays in GuiTask.h
  xTaskCreatePinnedToCore(
    GuiTask,
    "GuiTask",
    10000,
    NULL,
    1,
    &Gui,
    1); //CPU core 1 in use for GuiTask
}

void loop() {
  printf("Pesudo code in another task, counter=%d\n", counter++);
  delay(1000);
}
//GuiTask.h in the same folder of SimpleDemo.ino
#ifndef _GUITASK_H
#define _GUITASK_H

#include <SSD2805.h>
//#include "AppleWatch.h"

TaskHandle_t Gui;
//SSD2805Class from SSD2805.h below
SSD2805Class ssd2805;

void GuiTask(void *pvParameters)
{
  ssd2805.begin();

  for(;;){  
    //ssd2805.dispFlush(0,0,AppleWatch.width-1, AppleWatch.height-1,(const uint16_t *)AppleWatch.data); delay(1000);  
    ssd2805.clearLCD(0xf800);delay(500);
    ssd2805.clearLCD(0x07f0);delay(500);
    ssd2805.clearLCD(0x001f);delay(500);
    }
  }
#endif
//SSD2805.h mipi bridge driver with ESP32 SPI DMA transfer 
#ifndef SSD2805_H
#define SSD2805_H

#include <Arduino.h>
#include "driver/spi_master.h"

//Attaching VSPI/HSPI module to SSD2805
#define SPI_NUM  HSPI

#if (SPI_NUM==VSPI)
  #define PIN_NUM_MOSI 23
  #define PIN_NUM_MISO 19
  #define PIN_NUM_SCK  18
  #define PIN_NUM_CS   5
#else //if not VSPI, it should be a HSPI
  #define PIN_NUM_MOSI 13
  #define PIN_NUM_MISO 4
  #define PIN_NUM_SCK  14
  #define PIN_NUM_CS   15
#endif

#define PIN_NUM_SDC  25 //data(1)/command(0) selection pin (for 8 Bit 4 Wire only)
#define PIN_NUM_RST  27  //manual reset pin for SSD2805
#define PIN_NUM_TE   37 //input pin for TE signal

//DSC commands
#define DCS_NOP                 0x00
#define DCS_SWRESET             0x01    //soft reset
#define DCS_RDDPM               0x0A    //Read display power mode
#define DCS_RDDMADCTL           0x0B    //Read display MADCTL
#define DCS_RDDCOLMOD           0x0C    //Read Display COLMOD
#define DCS_RDDIM               0x0D    //Read display image mode
#define DCS_RDDSM               0x0E    //Read display signal mode
#define DCS_RDDSDR              0x0F    //Read display self-diagnostic result
#define DCS_SLPIN               0x10
#define DCS_SLPOUT              0x11
#define DCS_NORON               0x13    //Normal display mode on
#define DCS_INVOFF              0x20
#define DCS_INVON               0x21
#define DCS_DISPOFF             0x28
#define DCS_DISPON              0x29

#define DCS_COL_SET             0x2A
#define DCS_PAGE_SET            0x2B
#define DCS_RAMWR               0x2C    //command to transfer data from MPU to frame memory
#define DCS_RAMRD               0x2E
#define DCS_TE_OFF              0x34
#define DCS_TE_ON               0x35
#define DCS_MEM_ACC_CTL         0x36    //memory access control for frame buffer scanning direction etc
#define DCS_IDLE_MODE_OFF       0x38
#define DCS_IDLE_MODE_ON        0x39
#define DCS_COLMOD              0x3A    //interface pixel format set
#define DCS_RAMWRC              0x3C    //continue memory write after DCS_RAMWR
#define DCS_READ_MEMORY_CNTU    0x3E

//Display size (in pixels)
#define DISP_HOR_SIZE 240
#define DISP_VER_SIZE 240

#define MAX_DMA_LEN SPI_MAX_DMA_LEN //SPI_MAX_DMA_LEN define in spi_common.h

class SSD2805Class
{
    public:
    void begin(uint8_t spi_num=SPI_NUM);
    void hwReset(void);
    void write8(uint8_t data8);
    void writeBuffer(const void *buffer, uint32_t len);
    void clearLCD(uint16_t color);
    
    private:
    inline void setDC(bool v){(v==1)?(digitalWrite(PIN_NUM_SDC,HIGH)):(digitalWrite(PIN_NUM_SDC,LOW));}
    inline void setCS(bool v){(v==1)?(digitalWrite(PIN_NUM_CS,HIGH)):(digitalWrite(PIN_NUM_CS,LOW));}
    void setRST(bool v){(v==1)?(digitalWrite(PIN_NUM_RST,HIGH)):(digitalWrite(PIN_NUM_RST,LOW));}
    void writeRegister(uint8_t reg, const uint8_t *data8, uint32_t len);
    void setTDCSize(uint32_t byteCount);
    void setRectangle(uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2);
    
    spi_device_handle_t ssd2805;
};


void SSD2805Class::begin(uint8_t spi_num)
{
    esp_err_t err;
    spi_bus_config_t  bus_config;
    spi_host_device_t host;
    spi_device_interface_config_t dev_config;
    
    pinMode(PIN_NUM_SDC, OUTPUT);
    digitalWrite(PIN_NUM_SDC, HIGH);    //default for data
    pinMode(PIN_NUM_RST, OUTPUT);
    digitalWrite(PIN_NUM_RST, HIGH);
    pinMode(PIN_NUM_CS, OUTPUT);
    digitalWrite(PIN_NUM_CS, HIGH);
    
    hwReset();  //toggle PIN_NUM_RST for hardware reset
    (spi_num==VSPI)?(host=VSPI_HOST):(host=HSPI_HOST);
    
    {
      bus_config.mosi_io_num = PIN_NUM_MOSI;
      bus_config.miso_io_num = PIN_NUM_MISO;
      bus_config.sclk_io_num = PIN_NUM_SCK;
    }

    dev_config.flags = SPI_DEVICE_HALFDUPLEX;
    dev_config.mode = 0;
    dev_config.clock_speed_hz = 2000000UL; //40MHz works with SPI_DEVICE_HALFDUPLEX, useful for speeding up block write after PLL enabled
    dev_config.spics_io_num = -1; //use GPIO for chip select
    dev_config.queue_size = 7;
    
    err=spi_bus_initialize(host, &bus_config, 1);
    ESP_ERROR_CHECK(err);
    err = spi_bus_add_device(host, &dev_config, &ssd2805);
    ESP_ERROR_CHECK(err);
    
    
    //Step 1: set PLL
    uint8_t txbuffer[12];
    txbuffer[0]=0x0f; txbuffer[1]=0x00;

    writeRegister(0xba, (const uint8_t *)&txbuffer, 2); 
    txbuffer[0]=0x01; txbuffer[1]=0x00;
    writeRegister(0xb9, (const uint8_t *)&txbuffer, 2);       //enable PLL
    
    vTaskDelay(2/portTICK_PERIOD_MS);  ;   //delay 2ms to wait for PLL stablize
  
    //Step 2: Now it is safe to set SPI up to 40MHz (remove it for now with strip wire prototype )
    //equivalent to calling SPI.setFrequency(40000000UL);   //now we can set SPI clock up to 40MHz (PLL clock=320/8)
    spi_bus_remove_device(ssd2805); //has to remove device before switching to a faster SPI clock
    spi_bus_free(host);
    dev_config.clock_speed_hz = 40000000UL;
    err=spi_bus_initialize(host, &bus_config, 1); ESP_ERROR_CHECK(err);
    err = spi_bus_add_device(host, &dev_config, &ssd2805); ESP_ERROR_CHECK(err);
  
    clearLCD(0x0000); //clearLCD after DCS_DISPON if TE pin is to sync with MCU write
    
    setTDCSize(0);
    writeRegister(DCS_DISPON, NULL, 0);                  //display ON DCS command to panel    
}


void SSD2805Class::write8(uint8_t data8)
{
  spi_transaction_t t;
  
  memset(&t, 0, sizeof(t));
  
  t.length = 8;  //length in bits
  t.tx_buffer = (const uint8_t *)&data8;
  esp_err_t err = spi_device_transmit(ssd2805, &t);
  assert(err==ESP_OK);
}


void SSD2805Class::writeBuffer(const void *buffer, uint32_t len)
{
  if(!len) return;
  
  spi_transaction_t t;

  memset(&t, 0, sizeof(t));

  t.length = len*8;  //length in bits
  t.tx_buffer = buffer;
  esp_err_t err = spi_device_transmit(ssd2805, &t);
  assert(err==ESP_OK);
}


void SSD2805Class::writeRegister(uint8_t reg, const uint8_t *data8, uint32_t len)
{
    setDC(0); //set command
    setCS(0); //chip select
    write8(reg);
    
    if(len!=0){
        setDC(1); //set data
        writeBuffer((const uint8_t *)data8, len); //low byte write first, that means data8[0] write first, then data8[1]...
    }
    setCS(1);
}

void SSD2805Class::setTDCSize(uint32_t byteCount)
{
    uint8_t txbuffer[2];
    txbuffer[0] = (uint8_t)byteCount;
    txbuffer[1] = (uint8_t)(byteCount>>8);

    writeRegister(0xbc, (const uint8_t *)&txbuffer, 2); //Set packet size TDC[15:0]

    txbuffer[0] = (uint8_t)(byteCount>>16);
    txbuffer[1] = (uint8_t)(byteCount>>24);   

    writeRegister(0xbd, (const uint8_t *)&txbuffer, 2); //Set packet size TDC[31:16]
}

void SSD2805Class::setRectangle(uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2)
{
  if((x1>x2) || (y1>y2)) return;

  uint8_t txbuffer[4];
  
  uint16_t sc = min(x1, DISP_HOR_SIZE-1);
  uint16_t sp = min(y1, DISP_VER_SIZE-1);
  uint16_t ec = min(x2, DISP_HOR_SIZE-1);
  uint16_t ep = min(y2, DISP_VER_SIZE-1);
 
  setTDCSize(4);

  txbuffer[0] = (uint8_t)(sc>>8);  //SC[15:8]  start column
  txbuffer[1] = (uint8_t)sc;       //SC[7:0]
  txbuffer[2] = (uint8_t)(ec>>8);  //EC[15:8] end column
  txbuffer[3] = (uint8_t)ec;       //EC[7:0] 
  writeRegister(DCS_COL_SET, (const uint8_t *)&txbuffer, 4);

  txbuffer[0] = (uint8_t)(sp>>8); //SP[15:8]  start page
  txbuffer[1] = (uint8_t)sp;      //SP[7:0]
  txbuffer[2] = (uint8_t)(ep>>8); //EP[15:8] end page
  txbuffer[3] = (uint8_t)ep;      //EP[7:0]
  writeRegister(DCS_PAGE_SET, (const uint8_t *)&txbuffer, 4);
}


void SSD2805Class::hwReset(void)
{
  setRST(0);
  vTaskDelay(10/portTICK_PERIOD_MS);
  setRST(1);
  vTaskDelay(10/portTICK_PERIOD_MS);
}

void SSD2805Class::clearLCD(uint16_t color)
{  
  uint16_t *vdb = (uint16_t *)heap_caps_malloc(MAX_DMA_LEN, MALLOC_CAP_DMA);
  assert(vdb!=NULL);

  for(uint32_t i=0; i<MAX_DMA_LEN/2; i++)
    vdb[i] = color;
    
  uint32_t byteCount2Flush = DISP_HOR_SIZE*DISP_VER_SIZE*2UL;
  setRectangle(0,0,(DISP_HOR_SIZE-1),(DISP_VER_SIZE-1));
  setTDCSize(byteCount2Flush);

  uint32_t dmaBlockCount = 0;
  if(byteCount2Flush > MAX_DMA_LEN)
    dmaBlockCount = byteCount2Flush/MAX_DMA_LEN; 

  byteCount2Flush %= MAX_DMA_LEN; //find the remainder
    
  setDC(0); //set command
  setCS(0); //chip select
  write8(DCS_RAMWR);
  setDC(1); //set data
  
  while(dmaBlockCount--){
    writeBuffer((const uint16_t *)vdb, MAX_DMA_LEN);  //write in full DMA blocks. We cannot simply write writeBuffer((const uint16_t *)&color, MAX_DMA_LEN); othewise,
                                                      //it would be only the first word sent in uint16_t color but the remaining words sent by random
  }
  writeBuffer((const uint16_t *)vdb, byteCount2Flush);  //fill up the remainder
  setCS(1); //chip deselect  
  free(vdb);
}
#endif

Debug Messages:

Enable Core debug level: Debug on tools menu of Arduino IDE, then put the serial output here 

Metadata

Metadata

Assignees

No one assigned

    Labels

    No labels
    No labels

    Type

    No type

    Projects

    No projects

    Milestone

    No milestone

    Relationships

    None yet

    Development

    No branches or pull requests

    Issue actions