xtensa/esp32: Improve SPI transmission

Master:
  1. add DMA RX/TX support
  2. add software chip selection
  3. add user defined chip selection
  4. add IOMUX check and IO map

Slave:
  1. add DMA RX/TX support
  2. add IOMUX check and IO map
  3. use full 256 bit SPI TX/RX cache in non-DMA mode
This commit is contained in:
Dong Heng 2020-07-09 13:18:34 +08:00 committed by Abdelatif Guettouche
parent b3e01168db
commit 39539be149
9 changed files with 1382 additions and 208 deletions

View File

@ -382,11 +382,43 @@ endmenu # I2C configuration
menu "SPI configuration"
depends on ESP32_SPI
config ESP32_SPI_SWCS
bool "SPI software CS"
default y
---help---
Use SPI software CS.
config ESP32_SPI_UDCS
bool "User defined CS"
default n
depends on ESP32_SPI_SWCS
---help---
Use user defined CS.
config ESP32_SPI2_DMA
bool "SPI2 use DMA"
default y
depends on ESP32_SPI2
config ESP32_SPI3_DMA
bool "SPI3 use DMA"
default y
depends on ESP32_SPI3
config SPI_DMADESC_NUM
int "SPI master DMA description number"
default 2
config SPI_SLAVE_BUFSIZE
int "SPI slave buffer size"
default 2048
depends on SPI_SLAVE
if ESP32_SPI2
config ESP32_SPI2_CSPIN
int "SPI2 CS Pin"
default 13
default 15
range 0 39
config ESP32_SPI2_CLKPIN
@ -396,12 +428,12 @@ config ESP32_SPI2_CLKPIN
config ESP32_SPI2_MOSIPIN
int "SPI2 MOSI Pin"
default 15
default 13
range 0 39
config ESP32_SPI2_MISOPIN
int "SPI2 MISO Pin"
default 2
default 12
range 0 39
endif # ESP32_SPI2
@ -410,22 +442,22 @@ if ESP32_SPI3
config ESP32_SPI3_CSPIN
int "SPI3 CS Pin"
default 13
default 5
range 0 39
config ESP32_SPI3_CLKPIN
int "SPI3 CLK Pin"
default 14
default 18
range 0 39
config ESP32_SPI3_MOSIPIN
int "SPI3 MOSI Pin"
default 15
default 23
range 0 39
config ESP32_SPI3_MISOPIN
int "SPI3 MISO Pin"
default 2
default 19
range 0 39
endif # ESP32_SPI3

View File

@ -87,6 +87,7 @@ CHIP_CSRCS = esp32_allocateheap.c esp32_clockconfig.c esp32_cpuint.c
CHIP_CSRCS += esp32_gpio.c esp32_intdecode.c esp32_irq.c esp32_region.c
CHIP_CSRCS += esp32_timerisr.c
CHIP_CSRCS += esp32_user.c
CHIP_CSRCS += esp32_dma.c
ifeq ($(CONFIG_ESP32_I2C),y)
CHIP_CSRCS += esp32_i2c.c

View File

@ -0,0 +1,105 @@
/****************************************************************************
* arch/xtensa/src/esp32/esp32_dma.c
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership. The
* ASF licenses this file to you under the Apache License, Version 2.0 (the
* "License"); you may not use this file except in compliance with the
* License. You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations
* under the License.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <string.h>
#include <debug.h>
#include <errno.h>
#include <assert.h>
#include <sys/types.h>
#include <nuttx/kmalloc.h>
#include <nuttx/irq.h>
#include "hardware/esp32_dma.h"
#include "esp32_dma.h"
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: esp32_dma_init
*
* Description:
* Initialize DMA descriptions and bind the target
* buffer to these DMA descriptions.
*
* Input Parameters:
* dmadesc - DMA descriptions pointer
* num - DMA descriptions number
* pbuf - RX/TX buffer pointer
* len - RX/TX buffer length
* isrx - true: RX DMA descriptions. false: TX DMA descriptions
*
* Returned Value:
* Binded pbuf data bytes
*
****************************************************************************/
uint32_t esp32_dma_init(struct esp32_dmadesc_s *dmadesc, uint32_t num,
uint8_t *pbuf, uint32_t len, int isrx)
{
int i;
uint32_t bytes = len;
uint8_t *pdata = pbuf;
uint32_t n;
DEBUGASSERT(pbuf && len);
if (isrx)
{
DEBUGASSERT((len % 3) == 0);
}
for (i = 0; i < num; i++)
{
if (bytes < ESP32_DMA_DATALEN_MAX)
{
n = bytes;
}
else
{
n = ESP32_DMA_DATALEN_MAX;
}
dmadesc[i].ctrl = (n << DMA_CTRL_DATALEN_S) |
(n << DMA_CTRL_BUFLEN_S) |
DMA_CTRL_OWN;
dmadesc[i].pbuf = pdata;
dmadesc[i].next = &dmadesc[i + 1];
bytes -= n;
if (!bytes)
{
break;
}
pdata += n;
}
dmadesc[i].ctrl |= DMA_CTRL_EOF;
dmadesc[i].next = NULL;
return len - bytes;
}

View File

@ -0,0 +1,99 @@
/****************************************************************************
* arch/xtensa/src/esp32/esp32_dma.h
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership. The
* ASF licenses this file to you under the Apache License, Version 2.0 (the
* "License"); you may not use this file except in compliance with the
* License. You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations
* under the License.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#ifndef __ARCH_XTENSA_SRC_ESP32_ESP32_DMA_H
#define __ARCH_XTENSA_SRC_ESP32_ESP32_DMA_H
#include <nuttx/config.h>
#include <stdint.h>
#ifndef __ASSEMBLY__
#undef EXTERN
#if defined(__cplusplus)
#define EXTERN extern "C"
extern "C"
{
#else
#define EXTERN extern
#endif
/****************************************************************************
* Pre-processor Macros
****************************************************************************/
/* DMA max data length */
#define ESP32_DMA_DATALEN_MAX (0x1000 - 4)
/* DMA max buffer length */
#define ESP32_DMA_BUFLEN_MAX ESP32_DMA_DATALEN_MAX
/****************************************************************************
* Public Types
****************************************************************************/
/* DMA description type */
struct esp32_dmadesc_s
{
uint32_t ctrl; /* DMA control block */
uint8_t *pbuf; /* DMA TX/RX buffer address */
struct esp32_dmadesc_s *next; /* Next DMA description address */
};
/****************************************************************************
* Public Function Prototypes
****************************************************************************/
/****************************************************************************
* Name: esp32_dma_init
*
* Description:
* Initialize ESP32 DMA descriptions and bind the target
* buffer to these ESP32 DMA descriptions.
*
* Input Parameters:
* dmadesc - DMA descriptions pointer
* num - DMA descriptions number
* pbuf - RX/TX buffer pointer
* len - RX/TX buffer length
* isrx - true: RX DMA descriptions. false: TX DMA descriptions
*
* Returned Value:
* Bind pbuf data bytes
*
****************************************************************************/
uint32_t esp32_dma_init(struct esp32_dmadesc_s *dmadesc, uint32_t num,
uint8_t *pbuf, uint32_t len, int isrx);
#ifdef __cplusplus
}
#endif
#undef EXTERN
#endif /* __ASSEMBLY__ */
#endif /* __ARCH_XTENSA_SRC_ESP32_ESP32_SPI_H */

View File

@ -46,18 +46,33 @@
#include "esp32_spi.h"
#include "esp32_gpio.h"
#include "esp32_cpuint.h"
#include "esp32_dma.h"
#include "xtensa.h"
#include "hardware/esp32_gpio_sigmap.h"
#include "hardware/esp32_dport.h"
#include "hardware/esp32_spi.h"
#include "hardware/esp32_soc.h"
#include "hardware/esp32_pinmap.h"
#include "rom/esp32_gpio.h"
/****************************************************************************
* Private Types
****************************************************************************/
/* SPI DMA RX/TX description number */
#define SPI_DMADESC_NUM (CONFIG_SPI_DMADESC_NUM)
/* SPI DMA channel number */
#define SPI_DMA_CHANNEL_MAX (2)
/* SPI DMA reset before exchange */
#define SPI_DMA_RESET_MASK (SPI_AHBM_RST_M | SPI_AHBM_FIFO_RST_M | \
SPI_OUT_RST_M | SPI_IN_RST_M)
/* SPI Default speed (limited by clock divider) */
#define SPI_FREQ_DEFAULT 400000
@ -83,6 +98,12 @@ struct esp32_spi_config_s
uint32_t clk_bit; /* Clock enable bit */
uint32_t rst_bit; /* SPI reset bit */
bool use_dma; /* Use DMA */
uint8_t dma_chan_s; /* DMA channel regitser shift */
uint8_t dma_chan; /* DMA channel */
uint32_t dma_clk_bit; /* DMA clock enable bit */
uint32_t dma_rst_bit; /* DMA reset bit */
uint32_t cs_insig; /* SPI CS input signal index */
uint32_t cs_outsig; /* SPI CS output signal index */
uint32_t mosi_insig; /* SPI MOSI input signal index */
@ -109,6 +130,12 @@ struct esp32_spi_priv_s
sem_t exclsem;
/* Interrupt wait semaphore */
sem_t sem_isr;
uint32_t cpuint; /* SPI interrupt ID */
uint32_t frequency; /* Requested clock frequency */
uint32_t actual; /* Actual clock frequency */
@ -117,6 +144,10 @@ struct esp32_spi_priv_s
/* Actual SPI send/receive bits once transmission */
uint8_t nbits;
/* Copy from config to speed up checking */
uint8_t dma_chan;
};
/****************************************************************************
@ -124,9 +155,11 @@ struct esp32_spi_priv_s
****************************************************************************/
static int esp32_spi_lock(FAR struct spi_dev_s *dev, bool lock);
#ifndef CONFIG_ESP32_SPI_UDCS
static void esp32_spi_select(FAR struct spi_dev_s *dev,
uint32_t devid,
bool selected);
#endif
static uint32_t esp32_spi_setfrequency(FAR struct spi_dev_s *dev,
uint32_t frequency);
static void esp32_spi_setmode(FAR struct spi_dev_s *dev,
@ -154,10 +187,6 @@ static int esp32_spi_trigger(FAR struct spi_dev_s *dev);
static void esp32_spi_init(FAR struct spi_dev_s *dev);
static void esp32_spi_deinit(FAR struct spi_dev_s *dev);
/****************************************************************************
* Public Function Prototypes
****************************************************************************/
/****************************************************************************
* Private Data
****************************************************************************/
@ -177,6 +206,15 @@ static const struct esp32_spi_config_s esp32_spi2_config =
.irq = ESP32_IRQ_SPI2,
.clk_bit = DPORT_SPI_CLK_EN_2,
.rst_bit = DPORT_SPI_RST_2,
#ifdef CONFIG_ESP32_SPI2_DMA
.use_dma = true,
#else
.use_dma = false,
#endif
.dma_chan_s = 2,
.dma_chan = 1,
.dma_clk_bit = DPORT_SPI_DMA_CLK_EN,
.dma_rst_bit = DPORT_SPI_DMA_RST,
.cs_insig = HSPICS0_IN_IDX,
.cs_outsig = HSPICS0_OUT_IDX,
.mosi_insig = HSPID_IN_IDX,
@ -190,7 +228,11 @@ static const struct esp32_spi_config_s esp32_spi2_config =
static const struct spi_ops_s esp32_spi2_ops =
{
.lock = esp32_spi_lock,
#ifdef CONFIG_ESP32_SPI_UDCS
.select = esp32_spi2_select,
#else
.select = esp32_spi_select,
#endif
.setfrequency = esp32_spi_setfrequency,
.setmode = esp32_spi_setmode,
.setbits = esp32_spi_setbits,
@ -239,6 +281,15 @@ static const struct esp32_spi_config_s esp32_spi3_config =
.irq = ESP32_IRQ_SPI3,
.clk_bit = DPORT_SPI_CLK_EN,
.rst_bit = DPORT_SPI_RST,
#ifdef CONFIG_ESP32_SPI3_DMA
.use_dma = true,
#else
.use_dma = false,
#endif
.dma_chan_s = 4,
.dma_chan = 2,
.dma_clk_bit = DPORT_SPI_DMA_CLK_EN,
.dma_rst_bit = DPORT_SPI_DMA_RST,
.cs_insig = VSPICS0_IN_IDX,
.cs_outsig = VSPICS0_OUT_IDX,
.mosi_insig = VSPID_IN_IDX,
@ -252,7 +303,11 @@ static const struct esp32_spi_config_s esp32_spi3_config =
static const struct spi_ops_s esp32_spi3_ops =
{
.lock = esp32_spi_lock,
#ifdef CONFIG_ESP32_SPI_UDCS
.select = esp32_spi3_select,
#else
.select = esp32_spi_select,
#endif
.setfrequency = esp32_spi_setfrequency,
.setmode = esp32_spi_setmode,
.setbits = esp32_spi_setbits,
@ -286,6 +341,11 @@ static struct esp32_spi_priv_s esp32_spi3_priv =
};
#endif /* CONFIG_ESP32_SPI3 */
/* SPI DMA RX/TX description */
struct esp32_dmadesc_s s_dma_rxdesc[SPI_DMA_CHANNEL_MAX][SPI_DMADESC_NUM];
struct esp32_dmadesc_s s_dma_txdesc[SPI_DMA_CHANNEL_MAX][SPI_DMADESC_NUM];
/****************************************************************************
* Private Functions
****************************************************************************/
@ -384,6 +444,53 @@ static inline void esp32_spi_reset_regbits(struct esp32_spi_priv_s *priv,
putreg32(tmp & (~bits), priv->config->reg_base + offset);
}
/****************************************************************************
* Name: esp32_spi_iomux
*
* Description:
* Check if the option SPI GPIO pins can use IOMUX directly
*
* Input Parameters:
* priv - Private SPI device structure
*
* Returned Value:
* True if can use IOMUX or false if can't.
*
****************************************************************************/
static inline bool esp32_spi_iomux(struct esp32_spi_priv_s *priv)
{
bool mapped = false;
const struct esp32_spi_config_s *cfg = priv->config;
if (REG_SPI_BASE(2) == cfg->reg_base)
{
if (cfg->mosi_pin == SPI2_IOMUX_MOSIPIN &&
#ifndef CONFIG_ESP32_SPI_SWCS
cfg->cs_pin == SPI2_IOMUX_CSPIN &&
#endif
cfg->miso_pin == SPI2_IOMUX_MISOPIN &&
cfg->clk_pin == SPI2_IOMUX_CLKPIN)
{
mapped = true;
}
}
else if (REG_SPI_BASE(3) == cfg->reg_base)
{
if (cfg->mosi_pin == SPI3_IOMUX_MOSIPIN &&
#ifndef CONFIG_ESP32_SPI_SWCS
cfg->cs_pin == SPI3_IOMUX_CSPIN &&
#endif
cfg->miso_pin == SPI3_IOMUX_MISOPIN &&
cfg->clk_pin == SPI3_IOMUX_CLKPIN)
{
mapped = true;
}
}
return mapped;
}
/****************************************************************************
* Name: esp32_spi_lock
*
@ -416,6 +523,68 @@ static int esp32_spi_lock(FAR struct spi_dev_s *dev, bool lock)
return ret;
}
/****************************************************************************
* Name: esp32_spi_sem_waitdone
*
* Description:
* Wait for a transfer to complete
*
****************************************************************************/
static int esp32_spi_sem_waitdone(FAR struct esp32_spi_priv_s *priv)
{
int ret;
struct timespec abstime;
clock_gettime(CLOCK_REALTIME, &abstime);
abstime.tv_sec += 10;
abstime.tv_nsec += 0;
ret = nxsem_timedwait_uninterruptible(&priv->sem_isr, &abstime);
return ret;
}
/****************************************************************************
* Name: esp32_spi_select
*
* Description:
* Enable/disable the SPI chip select. The implementation of this method
* must include handshaking: If a device is selected, it must hold off
* all other attempts to select the device until the device is deselected.
*
* If disable ESP32_SPI_SWCS, driver will use hardware CS so that when
* once transmission is started, hardware select the device and when this
* transmission is done, hardware deselect the device automatically. And
* the function will do nothing.
*
* Input Parameters:
* priv - Private SPI device structure
* devid - Identifies the device to select
* selected - true: slave selected, false: slave de-selected
*
* Returned Value:
* None
*
****************************************************************************/
#ifndef CONFIG_ESP32_SPI_UDCS
static void esp32_spi_select(FAR struct spi_dev_s *dev,
uint32_t devid,
bool selected)
{
#ifdef CONFIG_ESP32_SPI_SWCS
FAR struct esp32_spi_priv_s *priv = (FAR struct esp32_spi_priv_s *)dev;
bool value = selected ? false : true;
esp32_gpiowrite(priv->config->cs_pin, value);
#endif
spiinfo("devid: %08lx CS: %s\n", devid, selected ? "select" : "free");
}
#endif
/****************************************************************************
* Name: esp32_spi_setfrequency
*
@ -624,10 +793,18 @@ static void esp32_spi_setbits(FAR struct spi_dev_s *dev, int nbits)
priv->nbits = nbits;
esp32_spi_set_reg(priv, SPI_MISO_DLEN_OFFSET,
(priv->nbits - 1) << SPI_USR_MISO_DBITLEN_S);
esp32_spi_set_reg(priv, SPI_MOSI_DLEN_OFFSET,
(priv->nbits - 1) << SPI_USR_MOSI_DBITLEN_S);
/**
* Each DMA transmission will set these value according to
* calculate buffer length.
*/
if (!priv->dma_chan)
{
esp32_spi_set_reg(priv, SPI_MISO_DLEN_OFFSET,
(priv->nbits - 1) << SPI_USR_MISO_DBITLEN_S);
esp32_spi_set_reg(priv, SPI_MOSI_DLEN_OFFSET,
(priv->nbits - 1) << SPI_USR_MOSI_DBITLEN_S);
}
}
}
@ -657,6 +834,194 @@ static int esp32_spi_hwfeatures(FAR struct spi_dev_s *dev,
}
#endif
/****************************************************************************
* Name: esp32_spi_cmddata
*
* Description:
* Some devices require and additional out-of-band bit to specify if the
* next word sent to the device is a command or data. This is typical, for
* example, in "9-bit" displays where the 9th bit is the CMD/DATA bit.
* This function provides selection of command or data.
*
* This "latches" the CMD/DATA state. It does not have to be called before
* every word is transferred; only when the CMD/DATA state changes. This
* method is required if CONFIG_SPI_CMDDATA is selected in the NuttX
* configuration
*
* Input Parameters:
* dev - Device-specific state data
* cmd - true: The following word is a command; fals: the following words
* are data.
*
* Returned Value:
* OK unless an error occurs. Then a negated errno value is returned.
*
****************************************************************************/
#ifdef CONFIG_SPI_CMDDATA
static int esp32_spi_cmddata(FAR struct spi_dev_s *dev,
uint32_t devid,
bool cmd)
{
return -ENODEV;
}
#endif
/****************************************************************************
* Name: esp32_spi_dma_exchange
*
* Description:
* Exchange a block of data from SPI by DMA.
*
* Input Parameters:
* priv - SPI private state data
* txbuffer - A pointer to the buffer of data to be sent
* rxbuffer - A pointer to the buffer in which to receive data
* nwords - the length of data that to be exchanged in units of words.
* The wordsize is determined by the number of bits-per-word
* selected for the SPI interface. If nbits <= 8, the data is
* packed into uint8_t's; if nbits >8, the data is packed into
* uint16_t's
*
* Returned Value:
* None
*
****************************************************************************/
static void esp32_spi_dma_exchange(FAR struct esp32_spi_priv_s *priv,
FAR const void *txbuffer,
FAR void *rxbuffer,
uint32_t nwords)
{
uint32_t bytes = nwords * (priv->nbits / 8);
uint8_t *tp = (uint8_t *)txbuffer;
uint8_t *rp = (uint8_t *)rxbuffer;
uint32_t n;
uint32_t regval;
if (!tp)
{
tp = rp;
}
while (bytes)
{
esp32_spi_set_reg(priv, SPI_DMA_IN_LINK_OFFSET, 0);
esp32_spi_set_reg(priv, SPI_DMA_OUT_LINK_OFFSET, 0);
esp32_spi_set_regbits(priv, SPI_SLAVE_OFFSET, SPI_SYNC_RESET_M);
esp32_spi_reset_regbits(priv, SPI_SLAVE_OFFSET, SPI_SYNC_RESET_M);
esp32_spi_set_reg(priv, SPI_DMA_CONF_OFFSET, SPI_DMA_RESET_MASK);
esp32_spi_reset_regbits(priv, SPI_DMA_CONF_OFFSET, SPI_DMA_RESET_MASK);
n = esp32_dma_init(s_dma_txdesc[priv->dma_chan - 1],
SPI_DMADESC_NUM, tp, bytes, 0);
regval = (uint32_t)s_dma_txdesc[priv->dma_chan - 1] &
SPI_OUTLINK_ADDR_V;
esp32_spi_set_reg(priv, SPI_DMA_OUT_LINK_OFFSET,
regval | SPI_OUTLINK_START_M);
esp32_spi_set_reg(priv, SPI_MOSI_DLEN_OFFSET, bytes * 8 - 1);
if (tp)
{
esp32_spi_set_regbits(priv, SPI_USER_OFFSET, SPI_USR_MOSI_M);
}
else
{
esp32_spi_reset_regbits(priv, SPI_USER_OFFSET, SPI_USR_MOSI_M);
}
if (rp)
{
esp32_dma_init(s_dma_rxdesc[priv->dma_chan - 1],
SPI_DMADESC_NUM, rp, bytes, 1);
regval = (uint32_t)s_dma_rxdesc[priv->dma_chan - 1] &
SPI_INLINK_ADDR_V;
esp32_spi_set_reg(priv, SPI_DMA_IN_LINK_OFFSET,
regval | SPI_INLINK_START_M);
esp32_spi_set_reg(priv, SPI_MISO_DLEN_OFFSET, bytes * 8 - 1);
esp32_spi_set_regbits(priv, SPI_USER_OFFSET, SPI_USR_MISO_M);
}
else
{
esp32_spi_reset_regbits(priv, SPI_USER_OFFSET, SPI_USR_MISO_M);
}
esp32_spi_set_regbits(priv, SPI_CMD_OFFSET, SPI_USR_M);
esp32_spi_sem_waitdone(priv);
bytes -= n;
tp += n;
rp += n;
}
}
/****************************************************************************
* Name: esp32_spi_poll_send
*
* Description:
* Exchange one word on SPI by polling mode.
*
* Input Parameters:
* priv - SPI private state data
* wd - The word to send. the size of the data is determined by the
* number of bits selected for the SPI interface.
*
* Returned Value:
* Received value
*
****************************************************************************/
static uint32_t esp32_spi_poll_send(FAR struct esp32_spi_priv_s *priv,
uint32_t wd)
{
uint32_t val;
esp32_spi_set_reg(priv, SPI_W0_OFFSET, wd);
esp32_spi_set_regbits(priv, SPI_CMD_OFFSET, SPI_USR_M);
while (esp32_spi_get_reg(priv, SPI_CMD_OFFSET) & SPI_USR_M)
{
;
}
val = esp32_spi_get_reg(priv, SPI_W0_OFFSET);
spiinfo("send=%x and recv=%x\n", wd, val);
return val;
}
/****************************************************************************
* Name: esp32_spi_dma_send
*
* Description:
* Exchange one word on SPI by SPI DMA mode.
*
* Input Parameters:
* dev - Device-specific state data
* wd - The word to send. the size of the data is determined by the
* number of bits selected for the SPI interface.
*
* Returned Value:
* Received value
*
****************************************************************************/
static uint32_t esp32_spi_dma_send(FAR struct esp32_spi_priv_s *priv,
uint32_t wd)
{
uint32_t rd;
esp32_spi_dma_exchange(priv, &wd, &rd, 1);
return rd;
}
/****************************************************************************
* Name: esp32_spi_send
*
@ -675,23 +1040,80 @@ static int esp32_spi_hwfeatures(FAR struct spi_dev_s *dev,
static uint32_t esp32_spi_send(FAR struct spi_dev_s *dev, uint32_t wd)
{
uint32_t val;
FAR struct esp32_spi_priv_s *priv = (FAR struct esp32_spi_priv_s *)dev;
uint32_t rd;
esp32_spi_set_reg(priv, SPI_W0_OFFSET, wd);
esp32_spi_set_regbits(priv, SPI_CMD_OFFSET, SPI_USR_M);
while (esp32_spi_get_reg(priv, SPI_CMD_OFFSET) & SPI_USR_M)
if (priv->dma_chan)
{
;
rd = esp32_spi_dma_send(priv, wd);
}
else
{
rd = esp32_spi_poll_send(priv, wd);
}
val = esp32_spi_get_reg(priv, SPI_W0_OFFSET);
return rd;
}
spiinfo("send=%x and recv=%x\n", wd, val);
/****************************************************************************
* Name: esp32_spi_poll_exchange
*
* Description:
* Exchange a block of data from SPI.
*
* Input Parameters:
* priv - SPI private state data
* txbuffer - A pointer to the buffer of data to be sent
* rxbuffer - A pointer to the buffer in which to receive data
* nwords - the length of data that to be exchanged in units of words.
* The wordsize is determined by the number of bits-per-word
* selected for the SPI interface. If nbits <= 8, the data is
* packed into uint8_t's; if nbits >8, the data is packed into
* uint16_t's
*
* Returned Value:
* None
*
****************************************************************************/
return val;
static void esp32_spi_poll_exchange(FAR struct esp32_spi_priv_s *priv,
FAR const void *txbuffer,
FAR void *rxbuffer,
size_t nwords)
{
int i;
for (i = 0 ; i < nwords; i++)
{
uint32_t w_wd = 0;
uint32_t r_wd;
if (txbuffer)
{
if (priv->nbits == 8)
{
w_wd = ((uint8_t *)txbuffer)[i];
}
else
{
w_wd = ((uint16_t *)txbuffer)[i];
}
}
r_wd = esp32_spi_poll_send(priv, w_wd);
if (rxbuffer)
{
if (priv->nbits == 8)
{
((uint8_t *)rxbuffer)[i] = r_wd;
}
else
{
((uint16_t *)rxbuffer)[i] = r_wd;
}
}
}
}
/****************************************************************************
@ -720,39 +1142,15 @@ static void esp32_spi_exchange(FAR struct spi_dev_s *dev,
FAR void *rxbuffer,
size_t nwords)
{
int i;
FAR struct esp32_spi_priv_s *priv = (FAR struct esp32_spi_priv_s *)dev;
for (i = 0 ; i < nwords; i++)
if (priv->dma_chan)
{
uint32_t w_wd = 0;
uint32_t r_wd;
if (txbuffer)
{
if (priv->nbits == 8)
{
w_wd = ((uint8_t *)txbuffer)[i];
}
else
{
w_wd = ((uint16_t *)txbuffer)[i];
}
}
r_wd = esp32_spi_send(dev, w_wd);
if (rxbuffer)
{
if (priv->nbits == 8)
{
((uint8_t *)rxbuffer)[i] = r_wd;
}
else
{
((uint16_t *)rxbuffer)[i] = r_wd;
}
}
esp32_spi_dma_exchange(priv, txbuffer, rxbuffer, nwords);
}
else
{
esp32_spi_poll_exchange(priv, txbuffer, rxbuffer, nwords);
}
}
@ -868,21 +1266,42 @@ static void esp32_spi_init(FAR struct spi_dev_s *dev)
esp32_gpiowrite(config->miso_pin, 1);
esp32_gpiowrite(config->clk_pin, 1);
esp32_configgpio(config->cs_pin, OUTPUT | PULLUP | FUNCTION_2);
gpio_matrix_out(config->cs_pin, config->cs_outsig, 0, 0);
gpio_matrix_in(config->cs_pin, config->cs_insig, 0);
#ifdef CONFIG_ESP32_SPI_SWCS
esp32_configgpio(config->cs_pin, OUTPUT);
gpio_matrix_out(config->cs_pin, SIG_GPIO_OUT_IDX, 0, 0);
#endif
esp32_configgpio(config->mosi_pin, OUTPUT | PULLUP | FUNCTION_2);
gpio_matrix_out(config->mosi_pin, config->mosi_outsig, 0, 0);
gpio_matrix_in(config->mosi_pin, config->mosi_insig, 0);
if (esp32_spi_iomux(priv))
{
#ifndef CONFIG_ESP32_SPI_SWCS
esp32_configgpio(config->cs_pin, OUTPUT_FUNCTION_1);
gpio_matrix_out(config->cs_pin, SIG_GPIO_OUT_IDX, 0, 0);
#endif
esp32_configgpio(config->mosi_pin, OUTPUT_FUNCTION_1);
gpio_matrix_out(config->mosi_pin, SIG_GPIO_OUT_IDX, 0, 0);
esp32_configgpio(config->miso_pin, INPUT | PULLUP | FUNCTION_2);
gpio_matrix_out(config->miso_pin, config->miso_outsig, 0, 0);
gpio_matrix_in(config->miso_pin, config->miso_insig, 0);
esp32_configgpio(config->miso_pin, INPUT_FUNCTION_1 | PULLUP);
gpio_matrix_out(config->miso_pin, SIG_GPIO_OUT_IDX, 0, 0);
esp32_configgpio(config->clk_pin, OUTPUT | PULLUP | FUNCTION_2);
gpio_matrix_out(config->clk_pin, config->clk_outsig, 0, 0);
gpio_matrix_in(config->clk_pin, config->clk_insig, 0);
esp32_configgpio(config->clk_pin, OUTPUT_FUNCTION_1);
gpio_matrix_out(config->clk_pin, SIG_GPIO_OUT_IDX, 0, 0);
}
else
{
#ifndef CONFIG_ESP32_SPI_SWCS
esp32_configgpio(config->cs_pin, OUTPUT_FUNCTION_2);
gpio_matrix_out(config->cs_pin, config->cs_outsig, 0, 0);
#endif
esp32_configgpio(config->mosi_pin, OUTPUT_FUNCTION_2);
gpio_matrix_out(config->mosi_pin, config->mosi_outsig, 0, 0);
esp32_configgpio(config->miso_pin, INPUT_FUNCTION_2 | PULLUP);
gpio_matrix_in(config->miso_pin, config->miso_insig, 0);
esp32_configgpio(config->clk_pin, OUTPUT_FUNCTION_2);
gpio_matrix_out(config->clk_pin, config->clk_outsig, 0, 0);
}
modifyreg32(DPORT_PERIP_CLK_EN_REG, 0, config->clk_bit);
modifyreg32(DPORT_PERIP_RST_EN_REG, config->rst_bit, 0);
@ -894,9 +1313,30 @@ static void esp32_spi_init(FAR struct spi_dev_s *dev)
esp32_spi_set_reg(priv, SPI_USER1_OFFSET, 0);
esp32_spi_set_reg(priv, SPI_SLAVE_OFFSET, 0);
esp32_spi_set_reg(priv, SPI_PIN_OFFSET, SPI_CS1_DIS_M | SPI_CS2_DIS_M);
#ifdef CONFIG_ESP32_SPI_SWCS
esp32_spi_set_regbits(priv, SPI_PIN_OFFSET, SPI_CS0_DIS_M);
#endif
esp32_spi_set_reg(priv, SPI_CTRL_OFFSET, 0);
esp32_spi_set_reg(priv, SPI_CTRL2_OFFSET, (0 << SPI_HOLD_TIME_S));
if (priv->dma_chan)
{
nxsem_init(&priv->sem_isr, 0, 0);
nxsem_set_protocol(&priv->sem_isr, SEM_PRIO_NONE);
modifyreg32(DPORT_PERIP_CLK_EN_REG, 0, config->dma_clk_bit);
modifyreg32(DPORT_PERIP_RST_EN_REG, config->dma_rst_bit, 0);
modifyreg32(DPORT_SPI_DMA_CHAN_SEL_REG, 0,
(config->dma_chan << config->dma_chan_s));
esp32_spi_set_reg(priv, SPI_DMA_CONF_OFFSET, SPI_OUT_DATA_BURST_EN_M |
SPI_INDSCR_BURST_EN_M |
SPI_OUTDSCR_BURST_EN_M);
esp32_spi_set_regbits(priv, SPI_SLAVE_OFFSET, SPI_INT_EN_M);
}
esp32_spi_setfrequency(dev, config->clk_freq);
esp32_spi_setbits(dev, 8);
esp32_spi_setmode(dev, config->mode);
@ -920,9 +1360,38 @@ static void esp32_spi_deinit(FAR struct spi_dev_s *dev)
{
FAR struct esp32_spi_priv_s *priv = (FAR struct esp32_spi_priv_s *)dev;
if (priv->dma_chan)
{
modifyreg32(DPORT_PERIP_CLK_EN_REG, priv->config->dma_clk_bit, 0);
}
modifyreg32(DPORT_PERIP_CLK_EN_REG, priv->config->clk_bit, 0);
}
/****************************************************************************
* Name: esp32_spi_interrupt
*
* Description:
* Common SPI DMA interrupt handler
*
* Input Parameters:
* arg - SPI controller private data
*
* Returned Value:
* Standard interrupt return value.
*
****************************************************************************/
static int esp32_spi_interrupt(int irq, void *context, FAR void *arg)
{
FAR struct esp32_spi_priv_s *priv = (FAR struct esp32_spi_priv_s *)arg;
esp32_spi_reset_regbits(priv, SPI_SLAVE_OFFSET, SPI_TRANS_DONE_M);
nxsem_post(&priv->sem_isr);
return 0;
}
/****************************************************************************
* Name: esp32_spibus_initialize
*
@ -939,6 +1408,7 @@ static void esp32_spi_deinit(FAR struct spi_dev_s *dev)
FAR struct spi_dev_s *esp32_spibus_initialize(int port)
{
int ret;
FAR struct spi_dev_s *spi_dev;
FAR struct esp32_spi_priv_s *priv;
irqstate_t flags;
@ -963,15 +1433,54 @@ FAR struct spi_dev_s *esp32_spibus_initialize(int port)
flags = enter_critical_section();
if ((volatile int)priv->refs++ != 0)
if ((volatile int)priv->refs != 0)
{
leave_critical_section(flags);
return spi_dev;
}
if (priv->config->use_dma)
{
priv->dma_chan = priv->config->dma_chan;
}
else
{
priv->dma_chan = 0;
}
if (priv->dma_chan)
{
priv->cpuint = esp32_alloc_levelint(1);
if (priv->cpuint < 0)
{
leave_critical_section(flags);
return NULL;
}
up_disable_irq(priv->cpuint);
esp32_attach_peripheral(priv->config->cpu,
priv->config->periph,
priv->cpuint);
ret = irq_attach(priv->config->irq, esp32_spi_interrupt, priv);
if (ret != OK)
{
esp32_detach_peripheral(priv->config->cpu,
priv->config->periph,
priv->cpuint);
esp32_free_cpuint(priv->cpuint);
leave_critical_section(flags);
return NULL;
}
up_enable_irq(priv->cpuint);
}
esp32_spi_init(spi_dev);
priv->refs++;
leave_critical_section(flags);
return spi_dev;
@ -1007,6 +1516,17 @@ int esp32_spibus_uninitialize(FAR struct spi_dev_s *dev)
leave_critical_section(flags);
if (priv->dma_chan)
{
up_disable_irq(priv->cpuint);
esp32_detach_peripheral(priv->config->cpu,
priv->config->periph,
priv->cpuint);
esp32_free_cpuint(priv->cpuint);
nxsem_destroy(&priv->sem_isr);
}
esp32_spi_deinit(dev);
nxsem_destroy(&priv->exclsem);

View File

@ -31,6 +31,7 @@
#include <stdlib.h>
#include <stdint.h>
#include <stdbool.h>
#include <string.h>
#include <errno.h>
#include <debug.h>
#include <time.h>
@ -47,22 +48,46 @@
#include "esp32_spi.h"
#include "esp32_gpio.h"
#include "esp32_cpuint.h"
#include "esp32_dma.h"
#include "xtensa.h"
#include "hardware/esp32_gpio_sigmap.h"
#include "hardware/esp32_dport.h"
#include "hardware/esp32_spi.h"
#include "hardware/esp32_soc.h"
#include "hardware/esp32_pinmap.h"
#include "rom/esp32_gpio.h"
/****************************************************************************
* Private Types
****************************************************************************/
#ifndef CONFIG_ESP_SPI_SLAVE_QSIZE
#define CONFIG_ESP_SPI_SLAVE_QSIZE 1024
#define SPI_SLAVE_BUFSIZE (CONFIG_SPI_SLAVE_BUFSIZE)
/* SPI DMA channel number */
#define SPI_DMA_CHANNEL_MAX (2)
/* SPI DMA RX/TX description number */
#if SPI_SLAVE_BUFSIZE % ESP32_DMA_BUFLEN_MAX
# define SPI_DMADESC_NUM (SPI_SLAVE_BUFSIZE / ESP32_DMA_BUFLEN_MAX + 1)
#else
# define SPI_DMADESC_NUM (SPI_SLAVE_BUFSIZE / ESP32_DMA_BUFLEN_MAX)
#endif
/* SPI DMA reset before exchange */
#define SPI_DMA_RESET_MASK (SPI_AHBM_RST_M | SPI_AHBM_FIFO_RST_M | \
SPI_OUT_RST_M | SPI_IN_RST_M)
#ifndef MIN
# define MIN(a,b) (((a) < (b)) ? (a) : (b))
#endif
#define WORDS2BYTES(_priv, _wn) (_wn * ((_priv)->nbits / 8))
#define BYTES2WORDS(_priv, _bn) (_bn / ((_priv)->nbits / 8))
/* SPI Device hardware configuration */
struct esp32_spislv_config_s
@ -83,6 +108,12 @@ struct esp32_spislv_config_s
uint32_t clk_bit; /* Clock enable bit */
uint32_t rst_bit; /* I2C reset bit */
bool use_dma; /* Use DMA */
uint8_t dma_chan_s; /* DMA channel regitser shift */
uint8_t dma_chan; /* DMA channel */
uint32_t dma_clk_bit; /* DMA clock enable bit */
uint32_t dma_rst_bit; /* DMA reset bit */
uint32_t cs_insig; /* SPI CS input signal index */
uint32_t cs_outsig; /* SPI CS output signal index */
uint32_t mosi_insig; /* SPI MOSI input signal index */
@ -109,16 +140,27 @@ struct esp32_spislv_priv_s
uint8_t nbits; /* Actual SPI send/receive bits once transmission */
int refs; /* Check if it is initialized */
uint32_t head; /* Location of next value */
uint32_t tail; /* Index of first value */
uint32_t txlen; /* Location of next RX value */
/* SPI slave output queue buffer */
/* SPI slave TX queue buffer */
uint16_t outq[CONFIG_ESP_SPI_SLAVE_QSIZE];
uint8_t txbuffer[SPI_SLAVE_BUFSIZE];
uint32_t rxlen; /* Location of next RX value */
/* SPI slave RX queue buffer */
uint8_t rxbuffer[SPI_SLAVE_BUFSIZE];
uint32_t outval; /* Default shift-out value */
bool process; /* If SPI Slave process */
bool txen; /* Enable TX */
/* Copy from config to speed up checking */
bool dma_chan;
};
/****************************************************************************
@ -140,6 +182,7 @@ static int esp32_spislv_enqueue(struct spi_sctrlr_s *sctrlr,
size_t nwords);
static bool esp32_spislv_qfull(struct spi_sctrlr_s *sctrlr);
static void esp32_spislv_qflush(struct spi_sctrlr_s *sctrlr);
static size_t esp32_spislv_qpoll(FAR struct spi_sctrlr_s *sctrlr);
/****************************************************************************
* Private Data
@ -159,6 +202,15 @@ static const struct esp32_spislv_config_s esp32_spi2_config =
.irq = ESP32_IRQ_SPI2,
.clk_bit = DPORT_SPI_CLK_EN_2,
.rst_bit = DPORT_SPI_RST_2,
#ifdef CONFIG_ESP32_SPI2_DMA
.use_dma = true,
#else
.use_dma = false,
#endif
.dma_chan_s = 2,
.dma_chan = 1,
.dma_clk_bit = DPORT_SPI_DMA_CLK_EN,
.dma_rst_bit = DPORT_SPI_DMA_RST,
.cs_insig = HSPICS0_IN_IDX,
.cs_outsig = HSPICS0_OUT_IDX,
.mosi_insig = HSPID_IN_IDX,
@ -175,7 +227,8 @@ static const struct spi_sctrlrops_s esp32_spi2slv_ops =
.unbind = esp32_spislv_unbind,
.enqueue = esp32_spislv_enqueue,
.qfull = esp32_spislv_qfull,
.qflush = esp32_spislv_qflush
.qflush = esp32_spislv_qflush,
.qpoll = esp32_spislv_qpoll
};
static struct esp32_spislv_priv_s esp32_spi2slv_priv =
@ -203,6 +256,15 @@ static const struct esp32_spislv_config_s esp32_spi3_config =
.irq = ESP32_IRQ_SPI3,
.clk_bit = DPORT_SPI_CLK_EN,
.rst_bit = DPORT_SPI_RST,
#ifdef CONFIG_ESP32_SPI3_DMA
.use_dma = true,
#else
.use_dma = false,
#endif
.dma_chan_s = 4,
.dma_chan = 2,
.dma_clk_bit = DPORT_SPI_DMA_CLK_EN,
.dma_rst_bit = DPORT_SPI_DMA_RST,
.cs_insig = VSPICS0_IN_IDX,
.cs_outsig = VSPICS0_OUT_IDX,
.mosi_insig = VSPID_IN_IDX,
@ -233,6 +295,11 @@ static struct esp32_spislv_priv_s esp32_spi3slv_priv =
};
#endif /* CONFIG_ESP32_SPI3 */
/* SPI DMA RX/TX description */
struct esp32_dmadesc_s s_rx_desc[SPI_DMA_CHANNEL_MAX][SPI_DMADESC_NUM];
struct esp32_dmadesc_s s_tx_desc[SPI_DMA_CHANNEL_MAX][SPI_DMADESC_NUM];
/****************************************************************************
* Private Functions
****************************************************************************/
@ -331,6 +398,49 @@ static inline void esp32_spi_reset_regbits(struct esp32_spislv_priv_s *priv,
putreg32(tmp & (~bits), priv->config->reg_base + offset);
}
/****************************************************************************
* Name: esp32_spi_iomux
*
* Description:
* Check if the option SPI GPIO pins can use IOMUX directly
*
* Input Parameters:
* priv - Private SPI device structure
*
* Returned Value:
* True if can use IOMUX or false if can't.
*
****************************************************************************/
static inline bool esp32_spi_iomux(struct esp32_spislv_priv_s *priv)
{
bool mapped = false;
const struct esp32_spislv_config_s *cfg = priv->config;
if (REG_SPI_BASE(2) == cfg->reg_base)
{
if (cfg->mosi_pin == SPI2_IOMUX_MOSIPIN &&
cfg->cs_pin == SPI2_IOMUX_CSPIN &&
cfg->miso_pin == SPI2_IOMUX_MISOPIN &&
cfg->clk_pin == SPI2_IOMUX_CLKPIN)
{
mapped = true;
}
}
else if (REG_SPI_BASE(3) == cfg->reg_base)
{
if (cfg->mosi_pin == SPI3_IOMUX_MOSIPIN &&
cfg->cs_pin == SPI3_IOMUX_CSPIN &&
cfg->miso_pin == SPI3_IOMUX_MISOPIN &&
cfg->clk_pin == SPI3_IOMUX_CLKPIN)
{
mapped = true;
}
}
return mapped;
}
/****************************************************************************
* Name: esp32_spislv_setmode
*
@ -365,16 +475,28 @@ static void esp32_spislv_setmode(FAR struct spi_sctrlr_s *dev,
{
switch (mode)
{
case SPIDEV_MODE0: /* CPOL=0; CPHA=0 */
ck_idle_edge = 1;
ck_in_edge = 0;
miso_delay_mode = 0;
miso_delay_num = 0;
mosi_delay_mode = 2;
mosi_delay_num = 2;
case SPISLAVE_MODE0: /* CPOL=0; CPHA=0 */
if (priv->dma_chan)
{
ck_idle_edge = 0;
ck_in_edge = 1;
miso_delay_mode = 0;
miso_delay_num = 1;
mosi_delay_mode = 0;
mosi_delay_num = 1;
}
else
{
ck_idle_edge = 1;
ck_in_edge = 0;
miso_delay_mode = 0;
miso_delay_num = 0;
mosi_delay_mode = 2;
mosi_delay_num = 2;
}
break;
case SPIDEV_MODE1: /* CPOL=0; CPHA=1 */
case SPISLAVE_MODE1: /* CPOL=0; CPHA=1 */
ck_idle_edge = 1;
ck_in_edge = 1;
miso_delay_mode = 2;
@ -383,16 +505,28 @@ static void esp32_spislv_setmode(FAR struct spi_sctrlr_s *dev,
mosi_delay_num = 0;
break;
case SPIDEV_MODE2: /* CPOL=1; CPHA=0 */
ck_idle_edge = 0;
ck_in_edge = 1;
miso_delay_mode = 0;
miso_delay_num = 0;
mosi_delay_mode = 1;
mosi_delay_num = 2;
case SPISLAVE_MODE2: /* CPOL=1; CPHA=0 */
if (priv->dma_chan)
{
ck_idle_edge = 1;
ck_in_edge = 0;
miso_delay_mode = 0;
miso_delay_num = 1;
mosi_delay_mode = 0;
mosi_delay_num = 1;
}
else
{
ck_idle_edge = 0;
ck_in_edge = 1;
miso_delay_mode = 0;
miso_delay_num = 0;
mosi_delay_mode = 1;
mosi_delay_num = 2;
}
break;
case SPIDEV_MODE3: /* CPOL=1; CPHA=1 */
case SPISLAVE_MODE3: /* CPOL=1; CPHA=1 */
ck_idle_edge = 0;
ck_in_edge = 0;
miso_delay_mode = 1;
@ -460,54 +594,9 @@ static void esp32_spislv_setbits(FAR struct spi_sctrlr_s *dev, int nbits)
if (nbits != priv->nbits)
{
priv->nbits = nbits;
esp32_spi_set_reg(priv, SPI_SLV_WRBUF_DLEN_OFFSET, nbits - 1);
esp32_spi_set_reg(priv, SPI_SLV_RDBUF_DLEN_OFFSET, nbits - 1);
}
}
/****************************************************************************
* Name: spi_dequeue
*
* Description:
* Get the next queued output value.
*
* Input Parameters:
* priv - SPI controller CS state
* pdata - output data buffer
*
* Returned Value:
* true if there is data or fail
*
* Assumptions:
* Called only from the SPI interrupt handler so all interrupts are
* disabled.
*
****************************************************************************/
static int spi_dequeue(struct esp32_spislv_priv_s *priv, uint32_t *pdata)
{
int ret = false;
int next;
if (priv->head != priv->tail)
{
*pdata = priv->outq[priv->tail];
next = priv->tail + 1;
if (next >= CONFIG_ESP_SPI_SLAVE_QSIZE)
{
next = 0;
}
priv->tail = next;
ret = true;
}
return ret;
}
/****************************************************************************
* Name: esp32_io_interrupt
*
@ -526,12 +615,129 @@ static int esp32_io_interrupt(int irq, void *context, FAR void *arg)
{
struct esp32_spislv_priv_s *priv = (struct esp32_spislv_priv_s *)arg;
priv->process = false;
SPI_SDEV_SELECT(priv->sdev, false);
if (priv->process == true)
{
priv->process = false;
SPI_SDEV_SELECT(priv->sdev, false);
}
return 0;
}
/****************************************************************************
* Name: esp32_spislv_tx
*
* Description:
* Process SPI slave TX.
*
* DMA mode : Initliaze register to prepare for TX
* Non-DMA mode: Fill data to TX register
*
* Input Parameters:
* priv - Private SPI device structure
*
* Returned Value:
* None
*
****************************************************************************/
static void esp32_spislv_tx(struct esp32_spislv_priv_s *priv)
{
int i;
uint32_t regval;
if (priv->dma_chan)
{
esp32_dma_init(s_tx_desc[priv->dma_chan - 1], SPI_DMADESC_NUM,
priv->txbuffer, priv->txlen, 0);
regval = (uint32_t)s_tx_desc[priv->dma_chan - 1] & SPI_OUTLINK_ADDR_V;
esp32_spi_set_reg(priv, SPI_DMA_OUT_LINK_OFFSET,
regval | SPI_OUTLINK_START_M);
esp32_spi_set_reg(priv, SPI_SLV_WRBUF_DLEN_OFFSET,
priv->txlen * 8 - 1);
esp32_spi_set_regbits(priv, SPI_USER_OFFSET, SPI_USR_MISO_M);
}
else
{
for (i = 0; i < priv->txlen; i += 4)
{
esp32_spi_set_reg(priv, SPI_W8_OFFSET + i,
*(uint32_t *)(&priv->txbuffer[i]));
}
esp32_spi_set_regbits(priv, SPI_USER_OFFSET, SPI_USR_MISO_M);
}
}
/****************************************************************************
* Name: esp32_spislv_rx
*
* Description:
* Process SPI slave RX. Process SPI slave device receive callback by
* calling SPI_SDEV_RECEIVE and prepare for next RX.
*
* DMA mode : Initliaze register to prepare for RX
*
* Input Parameters:
* priv - Private SPI device structure
*
* Returned Value:
* None
*
****************************************************************************/
static void esp32_spislv_rx(struct esp32_spislv_priv_s *priv)
{
uint32_t tmp;
uint32_t recv_n;
uint32_t regval;
tmp = SPI_SDEV_RECEIVE(priv->sdev, priv->rxbuffer,
BYTES2WORDS(priv, priv->rxlen));
recv_n = WORDS2BYTES(priv, tmp);
if (priv->dma_chan)
{
DEBUGASSERT((recv_n % 4) == 0);
}
if (recv_n < priv->rxlen)
{
/** If upper layer does not receive all data of receive
* buffer, move the rest data to head of the buffer
*/
priv->rxlen -= recv_n;
memmove(priv->rxbuffer, priv->rxbuffer + recv_n, priv->rxlen);
}
else
{
priv->rxlen = 0;
}
if (priv->dma_chan)
{
tmp = SPI_SLAVE_BUFSIZE - priv->rxlen;
if (tmp)
{
/* Start to receive next block of data */
esp32_dma_init(s_rx_desc[priv->dma_chan - 1], SPI_DMADESC_NUM,
priv->rxbuffer + priv->rxlen, tmp, 1);
regval = (uint32_t)s_rx_desc[priv->dma_chan - 1] &
SPI_INLINK_ADDR_V;
esp32_spi_set_reg(priv, SPI_DMA_IN_LINK_OFFSET,
regval | SPI_INLINK_START_M);
esp32_spi_set_reg(priv, SPI_SLV_RDBUF_DLEN_OFFSET, tmp * 8 - 1);
esp32_spi_set_regbits(priv, SPI_USER_OFFSET, SPI_USR_MOSI_M);
}
}
}
/****************************************************************************
* Name: esp32_spislv_interrupt
*
@ -548,37 +754,79 @@ static int esp32_io_interrupt(int irq, void *context, FAR void *arg)
static int esp32_spislv_interrupt(int irq, void *context, FAR void *arg)
{
uint32_t rd;
uint32_t wd;
struct esp32_spislv_priv_s *priv = (struct esp32_spislv_priv_s *)arg;
irqstate_t flags;
flags = enter_critical_section();
uint32_t n;
uint32_t tmp;
int i;
esp32_spi_reset_regbits(priv, SPI_SLAVE_OFFSET, SPI_TRANS_DONE_M);
if (!priv->process)
if (priv->dma_chan)
{
esp32_spi_set_reg(priv, SPI_DMA_CONF_OFFSET, SPI_DMA_RESET_MASK);
esp32_spi_reset_regbits(priv, SPI_DMA_CONF_OFFSET,
SPI_DMA_RESET_MASK);
}
if (priv->process == false)
{
SPI_SDEV_SELECT(priv->sdev, true);
priv->process = true;
}
rd = esp32_spi_get_reg(priv, SPI_W0_OFFSET);
if (spi_dequeue(priv, &wd))
/* Read and calculate read bytes */
n = (esp32_spi_get_reg(priv, SPI_SLV_RD_BIT_OFFSET) + 1) / 8;
esp32_spi_set_regbits(priv, SPI_USER_OFFSET, SPI_USR_MOSI_M);
/* RX process */
if (!priv->dma_chan)
{
esp32_spi_set_reg(priv, SPI_W0_OFFSET, wd);
esp32_spi_set_regbits(priv, SPI_CMD_OFFSET, SPI_USR_M);
/** With DMA, software should copy data from regitser
* to receive buffer
*/
for (i = 0; i < n; i += 4)
{
tmp = esp32_spi_get_reg(priv, SPI_W0_OFFSET + i);
memcpy(priv->rxbuffer + priv->rxlen + i, &tmp, n);
}
}
SPI_SDEV_RECEIVE(priv->sdev, &rd, 1);
priv->rxlen += n;
if (priv->process == false)
esp32_spislv_rx(priv);
/* TX process */
if (priv->txen)
{
if (n < priv->txlen)
{
priv->txlen -= n;
memmove(priv->txbuffer, priv->txbuffer + n, priv->txlen);
}
else
{
priv->txlen = 0;
priv->txen = false;
}
}
if (priv->txlen)
{
esp32_spislv_tx(priv);
priv->txen = true;
}
if (priv->process == true && esp32_gpioread(priv->config->cs_pin))
{
priv->process = false;
SPI_SDEV_SELECT(priv->sdev, false);
}
leave_critical_section(flags);
return 0;
}
@ -600,34 +848,46 @@ static void esp32_spislv_initialize(FAR struct spi_sctrlr_s *dev)
{
struct esp32_spislv_priv_s *priv = (struct esp32_spislv_priv_s *)dev;
const struct esp32_spislv_config_s *config = priv->config;
uint32_t regval;
esp32_gpiowrite(config->cs_pin, 1);
esp32_gpiowrite(config->mosi_pin, 1);
esp32_gpiowrite(config->miso_pin, 1);
esp32_gpiowrite(config->clk_pin, 1);
esp32_configgpio(config->cs_pin, INPUT | PULLUP | FUNCTION_2);
gpio_matrix_out(config->cs_pin, config->cs_outsig, 0, 0);
gpio_matrix_in(config->cs_pin, config->cs_insig, 0);
if (esp32_spi_iomux(priv))
{
esp32_configgpio(config->cs_pin, INPUT_FUNCTION_1 | PULLUP);
esp32_configgpio(config->mosi_pin, INPUT_FUNCTION_1 | PULLUP);
esp32_configgpio(config->miso_pin, OUTPUT_FUNCTION_1);
esp32_configgpio(config->clk_pin, INPUT_FUNCTION_1 | PULLUP);
}
else
{
esp32_configgpio(config->cs_pin, INPUT_FUNCTION_2 | PULLUP);
gpio_matrix_out(config->cs_pin, config->cs_outsig, 0, 0);
gpio_matrix_in(config->cs_pin, config->cs_insig, 0);
esp32_configgpio(config->mosi_pin, INPUT | PULLUP | FUNCTION_2);
gpio_matrix_out(config->mosi_pin, config->mosi_outsig, 0, 0);
gpio_matrix_in(config->mosi_pin, config->mosi_insig, 0);
esp32_configgpio(config->mosi_pin, INPUT_FUNCTION_2 | PULLUP);
gpio_matrix_out(config->mosi_pin, config->mosi_outsig, 0, 0);
gpio_matrix_in(config->mosi_pin, config->mosi_insig, 0);
esp32_configgpio(config->miso_pin, OUTPUT | PULLUP | FUNCTION_2);
gpio_matrix_out(config->miso_pin, config->miso_outsig, 0, 0);
gpio_matrix_in(config->miso_pin, config->miso_insig, 0);
esp32_configgpio(config->miso_pin, OUTPUT_FUNCTION_2);
gpio_matrix_out(config->miso_pin, config->miso_outsig, 0, 0);
gpio_matrix_in(config->miso_pin, config->miso_insig, 0);
esp32_configgpio(config->clk_pin, INPUT | PULLUP | FUNCTION_2);
gpio_matrix_out(config->clk_pin, config->clk_outsig, 0, 0);
gpio_matrix_in(config->clk_pin, config->clk_insig, 0);
esp32_configgpio(config->clk_pin, INPUT_FUNCTION_2 | PULLUP);
gpio_matrix_out(config->clk_pin, config->clk_outsig, 0, 0);
gpio_matrix_in(config->clk_pin, config->clk_insig, 0);
}
modifyreg32(DPORT_PERIP_CLK_EN_REG, 0, config->clk_bit);
modifyreg32(DPORT_PERIP_RST_EN_REG, config->rst_bit, 0);
esp32_spi_set_reg(priv, SPI_USER_OFFSET, SPI_DOUTDIN_M |
SPI_USR_MOSI_M |
SPI_USR_MISO_M);
SPI_USR_MISO_M |
SPI_USR_MISO_HIGHPART_M);
esp32_spi_set_reg(priv, SPI_USER1_OFFSET, 0);
esp32_spi_set_reg(priv, SPI_PIN_OFFSET, SPI_CS1_DIS_M | SPI_CS2_DIS_M);
esp32_spi_set_reg(priv, SPI_CTRL_OFFSET, 0);
@ -638,6 +898,39 @@ static void esp32_spislv_initialize(FAR struct spi_sctrlr_s *dev)
SPI_SLV_WR_RD_BUF_EN_M |
SPI_INT_EN_M);
if (priv->dma_chan)
{
modifyreg32(DPORT_PERIP_CLK_EN_REG, 0, config->dma_clk_bit);
modifyreg32(DPORT_PERIP_RST_EN_REG, config->dma_rst_bit, 0);
modifyreg32(DPORT_SPI_DMA_CHAN_SEL_REG, 0,
(config->dma_chan << config->dma_chan_s));
esp32_spi_set_reg(priv, SPI_DMA_CONF_OFFSET, SPI_OUT_DATA_BURST_EN_M |
SPI_INDSCR_BURST_EN_M |
SPI_OUTDSCR_BURST_EN_M);
esp32_dma_init(s_rx_desc[priv->dma_chan - 1], SPI_DMADESC_NUM,
priv->rxbuffer, SPI_SLAVE_BUFSIZE, 1);
regval = (uint32_t)s_rx_desc[priv->dma_chan - 1] & SPI_INLINK_ADDR_V;
esp32_spi_set_reg(priv, SPI_DMA_IN_LINK_OFFSET,
regval | SPI_INLINK_START_M);
esp32_spi_set_reg(priv, SPI_SLV_RDBUF_DLEN_OFFSET,
SPI_SLAVE_BUFSIZE * 8 - 1);
esp32_spi_set_reg(priv, SPI_SLV_WRBUF_DLEN_OFFSET,
SPI_SLAVE_BUFSIZE * 8 - 1);
esp32_spi_set_regbits(priv, SPI_USER_OFFSET, SPI_USR_MOSI_M);
}
else
{
/* TX/RX hardware fill can cache 4 words = 32 bytes = 256 bits */
esp32_spi_set_reg(priv, SPI_SLV_WRBUF_DLEN_OFFSET, 256 - 1);
esp32_spi_set_reg(priv, SPI_SLV_RDBUF_DLEN_OFFSET, 256 - 1);
}
esp32_spislv_setmode(dev, config->mode);
esp32_spislv_setbits(dev, 8);
@ -645,6 +938,8 @@ static void esp32_spislv_initialize(FAR struct spi_sctrlr_s *dev)
esp32_spi_reset_regbits(priv, SPI_SLAVE_OFFSET, SPI_SYNC_RESET_M);
esp32_gpioirqenable(ESP32_PIN2IRQ(config->cs_pin), RISING);
esp32_spi_reset_regbits(priv, SPI_SLAVE_OFFSET, SPI_TRANS_DONE_M);
}
/****************************************************************************
@ -697,10 +992,8 @@ static void esp32_spislv_bind(struct spi_sctrlr_s *sctrlr,
{
struct esp32_spislv_priv_s *priv = (struct esp32_spislv_priv_s *)sctrlr;
irqstate_t flags;
FAR const void *data;
int ret;
spiinfo("sdev=%p mode=%d nbits=%d\n", sdv, mode, nbits);
spiinfo("sdev=%p mode=%d nbits=%d\n", sdev, mode, nbits);
DEBUGASSERT(priv != NULL && priv->sdev == NULL && sdev != NULL);
@ -712,21 +1005,18 @@ static void esp32_spislv_bind(struct spi_sctrlr_s *sctrlr,
SPI_SDEV_CMDDATA(sdev, false);
priv->rxlen = 0;
priv->txlen = 0;
priv->txen = false;
esp32_spislv_initialize(sctrlr);
esp32_spislv_setmode(sctrlr, mode);
esp32_spislv_setbits(sctrlr, nbits);
priv->head = 0;
priv->tail = 0;
up_enable_irq(priv->cpuint);
ret = SPI_SDEV_GETDATA(sdev, &data);
if (ret == 1)
{
priv->outval = *(const uint16_t *)data;
}
esp32_spi_set_reg(priv, SPI_W0_OFFSET, priv->outval);
esp32_spi_set_regbits(priv, SPI_CMD_OFFSET, SPI_USR_M);
leave_critical_section(flags);
@ -761,12 +1051,19 @@ static void esp32_spislv_unbind(struct spi_sctrlr_s *sctrlr)
flags = enter_critical_section();
priv->sdev = NULL;
up_disable_irq(priv->cpuint);
esp32_gpioirqdisable(ESP32_PIN2IRQ(priv->config->cs_pin));
esp32_spi_reset_regbits(priv, SPI_SLAVE_OFFSET, SPI_INT_EN_M);
if (priv->dma_chan)
{
modifyreg32(DPORT_PERIP_CLK_EN_REG, priv->config->dma_clk_bit, 0);
}
modifyreg32(DPORT_PERIP_CLK_EN_REG, priv->config->clk_bit, 0);
priv->sdev = NULL;
leave_critical_section(flags);
}
@ -796,39 +1093,33 @@ static int esp32_spislv_enqueue(struct spi_sctrlr_s *sctrlr,
size_t nwords)
{
struct esp32_spislv_priv_s *priv = (struct esp32_spislv_priv_s *)sctrlr;
size_t n = WORDS2BYTES(priv, nwords);
size_t bufsize;
irqstate_t flags;
uint32_t next;
int ret;
spiinfo("spi_enqueue(sctrlr=%p, data=%p, nwords=%d)\n",
sctrlr, data, nwords);
DEBUGASSERT(priv != NULL && priv->sdev != NULL);
if (!nwords || nwords > 1)
{
return -EINVAL;
}
flags = enter_critical_section();
next = priv->head + 1;
if (next >= CONFIG_ESP_SPI_SLAVE_QSIZE)
{
next = 0;
}
if (next == priv->tail)
bufsize = SPI_SLAVE_BUFSIZE - priv->txlen;
if (!bufsize)
{
ret = -ENOSPC;
}
else
{
priv->outq[priv->head] = *(uint16_t *)data;
priv->head = next;
n = MIN(n, bufsize);
memcpy(priv->txbuffer + priv->txlen, data, n);
priv->txlen += n;
ret = OK;
if (!priv->process)
if (priv->process == false)
{
esp32_spi_set_regbits(priv, SPI_SLAVE_OFFSET, SPI_TRANS_DONE_M);
esp32_spislv_tx(priv);
priv->txen = true;
}
}
@ -856,21 +1147,14 @@ static bool esp32_spislv_qfull(struct spi_sctrlr_s *sctrlr)
{
struct esp32_spislv_priv_s *priv = (struct esp32_spislv_priv_s *)sctrlr;
irqstate_t flags;
uint32_t next;
bool ret;
bool ret = 0;
DEBUGASSERT(priv != NULL && priv->sdev != NULL);
spiinfo("spi_qfull(sctrlr=%p)\n", sctrlr);
flags = enter_critical_section();
next = priv->head + 1;
if (next >= CONFIG_ESP_SPI_SLAVE_QSIZE)
{
next = 0;
}
ret = (next == priv->tail);
ret = priv->txlen == SPI_SLAVE_BUFSIZE;
leave_critical_section(flags);
return ret;
@ -897,14 +1181,46 @@ static void esp32_spislv_qflush(struct spi_sctrlr_s *sctrlr)
struct esp32_spislv_priv_s *priv = (struct esp32_spislv_priv_s *)sctrlr;
irqstate_t flags;
spiinfo("data=%04x\n", data);
DEBUGASSERT(priv != NULL && priv->sdev != NULL);
flags = enter_critical_section();
priv->rxlen = 0;
priv->txlen = 0;
priv->txen = false;
leave_critical_section(flags);
}
/****************************************************************************
* Name: esp32_spislv_qpoll
*
* Description:
* Tell the controller to output all the receive queue data.
*
* Input Parameters:
* sctrlr - SPI slave controller interface instance
*
* Returned Value:
* Number of units of width "nbits" left in the rx queue. If the device
* accepted all the data, the return value will be 0
*
****************************************************************************/
static size_t esp32_spislv_qpoll(FAR struct spi_sctrlr_s *sctrlr)
{
struct esp32_spislv_priv_s *priv = (struct esp32_spislv_priv_s *)sctrlr;
irqstate_t flags;
uint32_t n;
DEBUGASSERT(priv != NULL && priv->sdev != NULL);
flags = enter_critical_section();
priv->head = 0;
priv->tail = 0;
esp32_spislv_rx(priv);
n = priv->rxlen;
leave_critical_section(flags);
return n;
}
/****************************************************************************
@ -948,13 +1264,22 @@ FAR struct spi_sctrlr_s *esp32_spislv_sctrlr_initialize(int port)
flags = enter_critical_section();
if ((volatile int)priv->refs++ != 0)
if ((volatile int)priv->refs != 0)
{
leave_critical_section(flags);
return spislv_dev;
}
if (priv->config->use_dma)
{
priv->dma_chan = priv->config->dma_chan;
}
else
{
priv->dma_chan = 0;
}
DEBUGVERIFY(irq_attach(ESP32_PIN2IRQ(priv->config->cs_pin),
esp32_io_interrupt,
priv));
@ -985,7 +1310,7 @@ FAR struct spi_sctrlr_s *esp32_spislv_sctrlr_initialize(int port)
return NULL;
}
up_enable_irq(priv->cpuint);
priv->refs++;
leave_critical_section(flags);

View File

@ -0,0 +1,36 @@
/****************************************************************************
* arch/xtensa/src/esp32/hardware/esp32_dma.h
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership. The
* ASF licenses this file to you under the Apache License, Version 2.0 (the
* "License"); you may not use this file except in compliance with the
* License. You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations
* under the License.
*
****************************************************************************/
#ifndef __ARCH_XTENSA_SRC_ESP32_HARDWARE_ESP32_DMA_H
#define __ARCH_XTENSA_SRC_ESP32_HARDWARE_ESP32_DMA_H
/* DMA description */
#define DMA_CTRL_OWN (1 << 31) /* Owned by DMA */
#define DMA_CTRL_EOF (1 << 30) /* End of frame */
#define DMA_CTRL_SOSF (1 << 29) /* Start of sub-frame */
#define DMA_CTRL_OFFSET_S (24) /* buffer offset shift */
#define DMA_CTRL_OFFSET_V (0x1f) /* buffer offset value */
#define DMA_CTRL_DATALEN_S (12) /* received/sent data length shift */
#define DMA_CTRL_DATALEN_V (0xfff) /* received/sent data length value */
#define DMA_CTRL_BUFLEN_S (0) /* received/sent buffer length shift */
#define DMA_CTRL_BUFLEN_V (0xfff) /* received/sent buffer length value */
#endif /* __ARCH_XTENSA_SRC_ESP32_HARDWARE_ESP32_DMA_H */

View File

@ -435,5 +435,6 @@
#define SIG_IN_FUNC226_IDX 226
#define SIG_IN_FUNC227_IDX 227
#define SIG_IN_FUNC228_IDX 228
#define SIG_GPIO_OUT_IDX 256
#endif /* __ARCH_XTENSA_SRC_ESP32_HARDWARE_ESP32_GPIO_SIGMAP_H */

View File

@ -0,0 +1,55 @@
/****************************************************************************
* arch/xtensa/src/esp32/hardware/esp32_pinmap.h
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership. The
* ASF licenses this file to you under the Apache License, Version 2.0 (the
* "License"); you may not use this file except in compliance with the
* License. You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations
* under the License.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#ifndef __ARCH_XTENSA_SRC_ESP32_HARDWARE_ESP32_PINMAP_H
#define __ARCH_XTENSA_SRC_ESP32_HARDWARE_ESP32_PINMAP_H
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/**
* Peripheral' fixed mapped pins by IOMUX, these GPIO pins can have better
* speed performance.
*/
/* SPI2 */
#define SPI2_IOMUX_MISOPIN (12)
#define SPI2_IOMUX_MOSIPIN (13)
#define SPI2_IOMUX_CLKPIN (14)
#define SPI2_IOMUX_CSPIN (15)
#define SPI2_IOMUX_WPPIN (2)
#define SPI2_IOMUX_HDPIN (4)
/* SPI3 */
#define SPI3_IOMUX_MISOPIN (19)
#define SPI3_IOMUX_MOSIPIN (23)
#define SPI3_IOMUX_CLKPIN (18)
#define SPI3_IOMUX_CSPIN (5)
#define SPI3_IOMUX_WPPIN (22)
#define SPI3_IOMUX_HDPIN (21)
#endif /* __ARCH_XTENSA_SRC_ESP32_HARDWARE_ESP32_PINMAP_H */