summaryrefslogtreecommitdiff
path: root/chip
diff options
context:
space:
mode:
authorGwendal Grignou <gwendal@chromium.org>2015-07-25 02:14:13 -0700
committerChromeOS Commit Bot <chromeos-commit-bot@chromium.org>2015-07-30 19:57:55 +0000
commit5b71b33aba6cb0108a864cc7000918b8f06b139a (patch)
treeaa49a59a306d91b189e9fcdddc3bbb0e2deba628 /chip
parent9008c7a4fd131a96ccb0078a46ec545cff2f43b1 (diff)
downloadchrome-ec-5b71b33aba6cb0108a864cc7000918b8f06b139a.tar.gz
common: change interface to SPI flash
Allow more than one SPI master. Add CONFIG variables to address the system SPI flash. To have SPI master ports, spi_ports array must be defined. BRANCH=smaug TEST=compile BUG=chrome-os-partner:42304 Change-Id: Id43869f648965c1582b7be1c7fb3a38f175fda95 Signed-off-by: Gwendal Grignou <gwendal@chromium.org> Reviewed-on: https://chromium-review.googlesource.com/288512 Commit-Queue: David James <davidjames@chromium.org>
Diffstat (limited to 'chip')
-rw-r--r--chip/it83xx/spi.c8
-rw-r--r--chip/lm4/spi.c44
-rw-r--r--chip/mec1322/lfw/ec_lfw.c15
-rw-r--r--chip/mec1322/spi.c76
-rw-r--r--chip/mec1322/system.c2
-rw-r--r--chip/npcx/spi.c51
-rw-r--r--chip/stm32/build.mk2
-rw-r--r--chip/stm32/spi_master.c120
-rw-r--r--chip/stm32/usb_spi.c3
9 files changed, 194 insertions, 127 deletions
diff --git a/chip/it83xx/spi.c b/chip/it83xx/spi.c
index 12955c80e3..83eff6efe7 100644
--- a/chip/it83xx/spi.c
+++ b/chip/it83xx/spi.c
@@ -72,7 +72,8 @@ static void sspi_transmission_end(void)
IT83XX_SSPI_SPISTS = 0x02;
}
-int spi_enable(int enable)
+/* We assume only one SPI port in the chip, one SPI device */
+int spi_enable(int port, int enable)
{
if (enable) {
/*
@@ -96,7 +97,8 @@ int spi_enable(int enable)
return EC_SUCCESS;
}
-int spi_transaction(const uint8_t *txdata, int txlen,
+int spi_transaction(const struct spi_device_t *spi_device,
+ const uint8_t *txdata, int txlen,
uint8_t *rxdata, int rxlen)
{
int idx;
@@ -152,6 +154,6 @@ static void sspi_init(void)
IT83XX_SSPI_SPICTRL2 |= 0x02;
/* Disabling spi module */
- spi_enable(0);
+ spi_enable(NULL, 0);
}
DECLARE_HOOK(HOOK_INIT, sspi_init, HOOK_PRIO_DEFAULT);
diff --git a/chip/lm4/spi.c b/chip/lm4/spi.c
index f6afd7cbd8..b0b92d86e6 100644
--- a/chip/lm4/spi.c
+++ b/chip/lm4/spi.c
@@ -19,14 +19,23 @@
#define CPRINTS(format, args...) cprints(CC_SPI, format, ## args)
-int spi_enable(int enable)
+int spi_enable(int port, int enable)
{
+ int i;
+
if (enable) {
gpio_config_module(MODULE_SPI, 1);
- /* Don't use the SSI0 frame output. CS# is a GPIO so we can
- * keep it low during an entire transaction. */
- gpio_set_flags(GPIO_SPI_CS_L, GPIO_OUTPUT);
- gpio_set_level(GPIO_SPI_CS_L, 1);
+ for (i = 0; i < spi_devices_used; i++) {
+ if (spi_devices[i].port != port)
+ continue;
+ /*
+ * Don't use the SSI0 frame output.
+ * CS# is a GPIO so we can keep it low during an entire
+ * transaction.
+ */
+ gpio_set_flags(spi_device[i]->gpio_cs, GPIO_OUTPUT);
+ gpio_set_level(spi_device[i]->gpio_cs, 1);
+ }
/* Enable SSI port */
LM4_SSI_CR1(0) |= 0x02;
@@ -34,9 +43,13 @@ int spi_enable(int enable)
/* Disable SSI port */
LM4_SSI_CR1(0) &= ~0x02;
- /* Make sure CS# is deselected */
- gpio_set_level(GPIO_SPI_CS_L, 1);
- gpio_set_flags(GPIO_SPI_CS_L, GPIO_ODR_HIGH);
+ for (i = 0; i < spi_devices_used; i++) {
+ if (spi_devices[i].port != port)
+ continue;
+ /* Make sure CS# is deselected */
+ gpio_set_level(spi_device[i]->gpio_cs, 1);
+ gpio_set_flags(spi_device->gpio_cs[i], GPIO_ODR_HIGH);
+ }
gpio_config_module(MODULE_SPI, 0);
}
@@ -45,7 +58,8 @@ int spi_enable(int enable)
}
-int spi_transaction(const uint8_t *txdata, int txlen,
+int spi_transaction(const struct spi_device_t *spi_device,
+ const uint8_t *txdata, int txlen,
uint8_t *rxdata, int rxlen)
{
int totallen = txlen + rxlen;
@@ -59,7 +73,7 @@ int spi_transaction(const uint8_t *txdata, int txlen,
/* Start transaction. Need to do this explicitly because the LM4
* SSI controller pulses its frame select every byte, and the EEPROM
* wants the chip select held low during the entire transaction. */
- gpio_set_level(GPIO_SPI_CS_L, 0);
+ gpio_set_level(spi_device->gpio_cs, 0);
while (rxcount < totallen) {
/* Handle received bytes if any. We just checked rxcount <
@@ -89,7 +103,7 @@ int spi_transaction(const uint8_t *txdata, int txlen,
}
/* End transaction */
- gpio_set_level(GPIO_SPI_CS_L, 1);
+ gpio_set_level(spi_device->gpio_cs, 1);
return EC_SUCCESS;
}
@@ -120,7 +134,7 @@ static int spi_init(void)
/* Ensure the SPI port is disabled. This keeps us from interfering
* with the main chipset when we're not explicitly using the SPI
* bus. */
- spi_enable(0);
+ spi_enable(CONFIG_SPI_FLASH_PORT, 0);
return EC_SUCCESS;
}
@@ -136,7 +150,7 @@ static int printrx(const char *desc, const uint8_t *txdata, int txlen,
int rv;
int i;
- rv = spi_transaction(txdata, txlen, rxdata, rxlen);
+ rv = spi_transaction(SPI_FLASH_DEVICE, txdata, txlen, rxdata, rxlen);
if (rv)
return rv;
@@ -156,7 +170,7 @@ static int command_spirom(int argc, char **argv)
uint8_t txsr1[] = {0x05};
uint8_t txsr2[] = {0x35};
- spi_enable(1);
+ spi_enable(CONFIG_SPI_FLASH_PORT, 1);
printrx("Man/Dev ID", txmandev, sizeof(txmandev), 2);
printrx("JEDEC ID", txjedec, sizeof(txjedec), 3);
@@ -164,7 +178,7 @@ static int command_spirom(int argc, char **argv)
printrx("Status reg 1", txsr1, sizeof(txsr1), 1);
printrx("Status reg 2", txsr2, sizeof(txsr2), 1);
- spi_enable(0);
+ spi_enable(CONFIG_SPI_FLASH_PORT, 0);
return EC_SUCCESS;
}
diff --git a/chip/mec1322/lfw/ec_lfw.c b/chip/mec1322/lfw/ec_lfw.c
index 1b9e1c4be2..43cd7c2b0b 100644
--- a/chip/mec1322/lfw/ec_lfw.c
+++ b/chip/mec1322/lfw/ec_lfw.c
@@ -36,6 +36,13 @@ const struct int_vector_t hdr_int_vect = {
&fault_handler /* Bus fault handler */
};
+/* SPI devices - from glados/board.c*/
+const struct spi_device_t spi_devices[] = {
+ { CONFIG_SPI_FLASH_PORT, 0, GPIO_PVT_CS0},
+};
+const unsigned int spi_devices_used = ARRAY_SIZE(spi_devices);
+
+
void timer_init()
{
uint32_t val = 0;
@@ -79,7 +86,7 @@ static int spi_flash_readloc(uint8_t *buf_usr,
if (offset + bytes > CONFIG_SPI_FLASH_SIZE)
return EC_ERROR_INVAL;
- return spi_transaction(cmd, 4, buf_usr, bytes);
+ return spi_transaction(SPI_FLASH_DEVICE, cmd, 4, buf_usr, bytes);
}
int spi_image_load(uint32_t offset)
@@ -90,9 +97,7 @@ int spi_image_load(uint32_t offset)
memset((void *)buf, 0xFF, (CONFIG_FW_IMAGE_SIZE - 4));
for (i = 0; i < CONFIG_FW_IMAGE_SIZE; i += SPI_CHUNK_SIZE)
- spi_flash_readloc(&buf[i],
- offset + i,
- SPI_CHUNK_SIZE);
+ spi_flash_readloc(&buf[i], offset + i, SPI_CHUNK_SIZE);
return 0;
@@ -239,7 +244,7 @@ void lfw_main()
dma_init();
uart_init();
system_init();
- spi_enable(1);
+ spi_enable(CONFIG_SPI_FLASH_PORT, 1);
uart_puts("littlefw");
uart_puts(version_data.version);
diff --git a/chip/mec1322/spi.c b/chip/mec1322/spi.c
index bbd6e36a34..61d04028a3 100644
--- a/chip/mec1322/spi.c
+++ b/chip/mec1322/spi.c
@@ -22,7 +22,7 @@
#define SPI_BYTE_TRANSFER_TIMEOUT_US (3 * MSEC)
#define SPI_BYTE_TRANSFER_POLL_INTERVAL_US 100
-#define SPI_DMA_CHANNEL (MEC1322_DMAC_SPI0_RX + CONFIG_SPI_PORT * 2)
+#define SPI_DMA_CHANNEL(port) (MEC1322_DMAC_SPI0_RX + (port) * 2)
/* only regular image needs mutex, LFW does not have scheduling */
/* TODO: Move SPI locking to common code */
@@ -30,17 +30,19 @@
static struct mutex spi_mutex;
#endif
-static const struct dma_option spi_rx_option = {
- SPI_DMA_CHANNEL, (void *)&MEC1322_SPI_RD(CONFIG_SPI_PORT),
- MEC1322_DMA_XFER_SIZE(1)
+static const struct dma_option spi_rx_option[] = {
+ {
+ SPI_DMA_CHANNEL(0), (void *)&MEC1322_SPI_RD(0),
+ MEC1322_DMA_XFER_SIZE(1)
+ },
};
-static int wait_byte(void)
+static int wait_byte(const int port)
{
timestamp_t deadline;
deadline.val = get_time().val + SPI_BYTE_TRANSFER_TIMEOUT_US;
- while ((MEC1322_SPI_SR(CONFIG_SPI_PORT) & 0x3) != 0x3) {
+ while ((MEC1322_SPI_SR(port) & 0x3) != 0x3) {
if (timestamp_expired(deadline, NULL))
return EC_ERROR_TIMEOUT;
usleep(SPI_BYTE_TRANSFER_POLL_INTERVAL_US);
@@ -48,76 +50,80 @@ static int wait_byte(void)
return EC_SUCCESS;
}
-static int spi_tx(const uint8_t *txdata, int txlen)
+static int spi_tx(const int port, const uint8_t *txdata, int txlen)
{
int i;
int ret = EC_SUCCESS;
uint8_t dummy __attribute__((unused)) = 0;
for (i = 0; i < txlen; ++i) {
- MEC1322_SPI_TD(CONFIG_SPI_PORT) = txdata[i];
- ret = wait_byte();
+ MEC1322_SPI_TD(port) = txdata[i];
+ ret = wait_byte(port);
if (ret != EC_SUCCESS)
return ret;
- dummy = MEC1322_SPI_RD(CONFIG_SPI_PORT);
+ dummy = MEC1322_SPI_RD(port);
}
return ret;
}
-int spi_transaction_async(const uint8_t *txdata, int txlen,
+int spi_transaction_async(const struct spi_device_t *spi_device,
+ const uint8_t *txdata, int txlen,
uint8_t *rxdata, int rxlen)
{
+ int port = spi_device->port;
int ret = EC_SUCCESS;
- gpio_set_level(CONFIG_SPI_CS_GPIO, 0);
+ gpio_set_level(spi_device->gpio_cs, 0);
/* Disable auto read */
- MEC1322_SPI_CR(CONFIG_SPI_PORT) &= ~(1 << 5);
+ MEC1322_SPI_CR(port) &= ~(1 << 5);
- ret = spi_tx(txdata, txlen);
+ ret = spi_tx(port, txdata, txlen);
if (ret != EC_SUCCESS)
return ret;
/* Enable auto read */
- MEC1322_SPI_CR(CONFIG_SPI_PORT) |= 1 << 5;
+ MEC1322_SPI_CR(port) |= 1 << 5;
if (rxlen != 0) {
- dma_start_rx(&spi_rx_option, rxlen, rxdata);
- MEC1322_SPI_TD(CONFIG_SPI_PORT) = 0;
+ dma_start_rx(&spi_rx_option[port], rxlen, rxdata);
+ MEC1322_SPI_TD(port) = 0;
}
return ret;
}
-int spi_transaction_flush(void)
+int spi_transaction_flush(const struct spi_device_t *spi_device)
{
- int ret = dma_wait(SPI_DMA_CHANNEL);
+ int port = spi_device->port;
+ int ret = dma_wait(SPI_DMA_CHANNEL(port));
uint8_t dummy __attribute__((unused)) = 0;
timestamp_t deadline;
/* Disable auto read */
- MEC1322_SPI_CR(CONFIG_SPI_PORT) &= ~(1 << 5);
+ MEC1322_SPI_CR(port) &= ~(1 << 5);
deadline.val = get_time().val + SPI_BYTE_TRANSFER_TIMEOUT_US;
/* Wait for FIFO empty SPISR_TXBE */
- while ((MEC1322_SPI_SR(CONFIG_SPI_PORT) & 0x01) != 0x1) {
+ while ((MEC1322_SPI_SR(port) & 0x01) != 0x1) {
if (timestamp_expired(deadline, NULL))
return EC_ERROR_TIMEOUT;
usleep(SPI_BYTE_TRANSFER_POLL_INTERVAL_US);
}
- dma_disable(SPI_DMA_CHANNEL);
- dma_clear_isr(SPI_DMA_CHANNEL);
- if (MEC1322_SPI_SR(CONFIG_SPI_PORT) & 0x2)
- dummy = MEC1322_SPI_RD(CONFIG_SPI_PORT);
+ dma_disable(SPI_DMA_CHANNEL(port));
+ dma_clear_isr(SPI_DMA_CHANNEL(port));
+ if (MEC1322_SPI_SR(port) & 0x2)
+ dummy = MEC1322_SPI_RD(port);
- gpio_set_level(CONFIG_SPI_CS_GPIO, 1);
+ gpio_set_level(spi_device->gpio_cs, 1);
return ret;
}
-int spi_transaction(const uint8_t *txdata, int txlen,
+int spi_transaction(const struct spi_device_t *spi_device,
+ const uint8_t *txdata, int txlen,
uint8_t *rxdata, int rxlen)
{
int ret;
@@ -125,10 +131,10 @@ int spi_transaction(const uint8_t *txdata, int txlen,
#ifndef LFW
mutex_lock(&spi_mutex);
#endif
- ret = spi_transaction_async(txdata, txlen, rxdata, rxlen);
+ ret = spi_transaction_async(spi_device, txdata, txlen, rxdata, rxlen);
if (ret)
return ret;
- ret = spi_transaction_flush();
+ ret = spi_transaction_flush(spi_device);
#ifndef LFW
mutex_unlock(&spi_mutex);
@@ -136,25 +142,25 @@ int spi_transaction(const uint8_t *txdata, int txlen,
return ret;
}
-int spi_enable(int enable)
+int spi_enable(int port, int enable)
{
if (enable) {
gpio_config_module(MODULE_SPI, 1);
/* Set enable bit in SPI_AR */
- MEC1322_SPI_AR(CONFIG_SPI_PORT) |= 0x1;
+ MEC1322_SPI_AR(port) |= 0x1;
/* Set SPDIN to 0 -> Full duplex */
- MEC1322_SPI_CR(CONFIG_SPI_PORT) &= ~(0x3 << 2);
+ MEC1322_SPI_CR(port) &= ~(0x3 << 2);
/* Set CLKPOL, TCLKPH, RCLKPH to 0 */
- MEC1322_SPI_CC(CONFIG_SPI_PORT) &= ~0x7;
+ MEC1322_SPI_CC(port) &= ~0x7;
/* Set LSBF to 0 -> MSB first */
- MEC1322_SPI_CR(CONFIG_SPI_PORT) &= ~0x1;
+ MEC1322_SPI_CR(port) &= ~0x1;
} else {
/* Clear enable bit in SPI_AR */
- MEC1322_SPI_AR(CONFIG_SPI_PORT) &= ~0x1;
+ MEC1322_SPI_AR(port) &= ~0x1;
gpio_config_module(MODULE_SPI, 0);
}
diff --git a/chip/mec1322/system.c b/chip/mec1322/system.c
index e7b8b43b6b..acbbe0320f 100644
--- a/chip/mec1322/system.c
+++ b/chip/mec1322/system.c
@@ -88,7 +88,7 @@ void system_pre_init(void)
/* Deassert nSIO_RESET */
MEC1322_PCR_PWR_RST_CTL &= ~(1 << 0);
- spi_enable(1);
+ spi_enable(CONFIG_SPI_FLASH_PORT, 1);
}
void _system_reset(int flags, int wake_from_hibernate)
diff --git a/chip/npcx/spi.c b/chip/npcx/spi.c
index 82a1b31dbb..b3d6ec07d7 100644
--- a/chip/npcx/spi.c
+++ b/chip/npcx/spi.c
@@ -68,29 +68,43 @@ DECLARE_HOOK(HOOK_FREQ_CHANGE, spi_freq_changed, HOOK_PRIO_FIRST);
/**
* Set SPI enabled.
*
+ * @spi_port port to act on. Only one port supported, one gpio.
* @param enable enabled flag
* @return success
*/
-int spi_enable(int enable)
+int spi_enable(int port, int enable)
{
+ int i;
+ enum gpio_signal gpio;
+
if (enable) {
/* Enabling spi module for gpio configuration */
gpio_config_module(MODULE_SPI, 1);
/* GPIO No SPI Select */
CLEAR_BIT(NPCX_DEVALT(0), NPCX_DEVALT0_GPIO_NO_SPIP);
- /* Make sure CS# is a GPIO output mode. */
- gpio_set_flags(GPIO_SPI_CS_L, GPIO_OUTPUT);
- /* Make sure CS# is deselected */
- gpio_set_level(GPIO_SPI_CS_L, 1);
+ for (i = 0; i < spi_devices_used; i++) {
+ if (spi_devices[i].port != port)
+ continue;
+ gpio = spi_devices[i].gpio_cs;
+ /* Make sure CS# is a GPIO output mode. */
+ gpio_set_flags(gpio, GPIO_OUTPUT);
+ /* Make sure CS# is deselected */
+ gpio_set_level(gpio, 1);
+ }
/* Enabling spi module */
SET_BIT(NPCX_SPI_CTL1, NPCX_SPI_CTL1_SPIEN);
} else {
/* Disabling spi module */
CLEAR_BIT(NPCX_SPI_CTL1, NPCX_SPI_CTL1_SPIEN);
- /* Make sure CS# is deselected */
- gpio_set_level(GPIO_SPI_CS_L, 1);
- gpio_set_flags(GPIO_SPI_CS_L, GPIO_ODR_HIGH);
+ for (i = 0; i < spi_devices_used; i++) {
+ if (spi_devices[i].port != port)
+ continue;
+ gpio = spi_devices[i].gpio_cs;
+ /* Make sure CS# is deselected */
+ gpio_set_level(gpio, 1);
+ gpio_set_flags(gpio, GPIO_ODR_HIGH);
+ }
/* Disabling spi module for gpio configuration */
gpio_config_module(MODULE_SPI, 0);
/* GPIO No SPI Select */
@@ -103,6 +117,7 @@ int spi_enable(int enable)
/**
* Flush an SPI transaction and receive data from slave.
*
+ * @param spi_device device to talk to
* @param txdata transfer data
* @param txlen transfer length
* @param rxdata receive data
@@ -110,19 +125,21 @@ int spi_enable(int enable)
* @return success
* @notes set master transaction mode in npcx chip
*/
-int spi_transaction(const uint8_t *txdata, int txlen,
+int spi_transaction(const struct spi_device_t *spi_device,
+ const uint8_t *txdata, int txlen,
uint8_t *rxdata, int rxlen)
{
int i = 0;
+ enum gpio_signal gpio = spi_device->gpio_cs;
/* Make sure CS# is a GPIO output mode. */
- gpio_set_flags(GPIO_SPI_CS_L, GPIO_OUTPUT);
+ gpio_set_flags(gpio, GPIO_OUTPUT);
/* Make sure CS# is deselected */
- gpio_set_level(GPIO_SPI_CS_L, 1);
+ gpio_set_level(gpio, 1);
/* Cleaning junk data in the buffer */
clear_databuf();
/* Assert CS# to start transaction */
- gpio_set_level(GPIO_SPI_CS_L, 0);
+ gpio_set_level(gpio, 0);
CPRINTS("NPCX_SPI_DATA=%x", NPCX_SPI_DATA);
CPRINTS("NPCX_SPI_CTL1=%x", NPCX_SPI_CTL1);
CPRINTS("NPCX_SPI_STAT=%x", NPCX_SPI_STAT);
@@ -156,7 +173,7 @@ int spi_transaction(const uint8_t *txdata, int txlen,
CPRINTS("rxdata[i]=%x", rxdata[i]);
}
/* Deassert CS# (high) to end transaction */
- gpio_set_level(GPIO_SPI_CS_L, 1);
+ gpio_set_level(gpio, 1);
return EC_SUCCESS;
}
@@ -174,7 +191,7 @@ static void spi_init(void)
CGC_MODE_RUN | CGC_MODE_SLEEP);
/* Disabling spi module */
- spi_enable(0);
+ spi_enable(CONFIG_SPI_FLASH_PORT, 0);
/* Disabling spi irq */
CLEAR_BIT(NPCX_SPI_CTL1, NPCX_SPI_CTL1_EIR);
@@ -208,7 +225,7 @@ static int printrx(const char *desc, const uint8_t *txdata, int txlen,
int rv;
int i;
- rv = spi_transaction(txdata, txlen, rxdata, rxlen);
+ rv = spi_transaction(SPI_FLASH_DEVICE, txdata, txlen, rxdata, rxlen);
if (rv)
return rv;
@@ -228,7 +245,7 @@ static int command_spirom(int argc, char **argv)
uint8_t txsr1[] = {0x05};
uint8_t txsr2[] = {0x35};
- spi_enable(1);
+ spi_enable(CONFIG_SPI_FLASH_PORT, 1);
printrx("Man/Dev ID", txmandev, sizeof(txmandev), 2);
printrx("JEDEC ID", txjedec, sizeof(txjedec), 3);
@@ -236,7 +253,7 @@ static int command_spirom(int argc, char **argv)
printrx("Status reg 1", txsr1, sizeof(txsr1), 1);
printrx("Status reg 2", txsr2, sizeof(txsr2), 1);
- spi_enable(0);
+ spi_enable(CONFIG_SPI_FLASH_PORT, 0);
return EC_SUCCESS;
}
diff --git a/chip/stm32/build.mk b/chip/stm32/build.mk
index 8ec6191397..72be7eb6d4 100644
--- a/chip/stm32/build.mk
+++ b/chip/stm32/build.mk
@@ -30,7 +30,7 @@ chip-y=dma.o
chip-$(CONFIG_COMMON_RUNTIME)+=system.o
chip-y+=jtag-$(CHIP_FAMILY).o clock-$(CHIP_FAMILY).o
chip-$(CONFIG_SPI)+=spi.o
-chip-$(CONFIG_SPI_MASTER_PORT)+=spi_master.o
+chip-$(CONFIG_SPI_MASTER)+=spi_master.o
chip-$(CONFIG_COMMON_GPIO)+=gpio.o gpio-$(CHIP_FAMILY).o
chip-$(CONFIG_COMMON_TIMER)+=hwtimer$(TIMER_TYPE).o
chip-$(CONFIG_I2C)+=i2c-$(CHIP_FAMILY).o
diff --git a/chip/stm32/spi_master.c b/chip/stm32/spi_master.c
index ab95ca6594..858fede3f0 100644
--- a/chip/stm32/spi_master.c
+++ b/chip/stm32/spi_master.c
@@ -14,38 +14,50 @@
#include "timer.h"
#include "util.h"
-#define SPI_REG_ADDR CONCAT3(STM32_SPI, CONFIG_SPI_MASTER_PORT, _BASE)
-#define SPI_REG ((stm32_spi_regs_t *)SPI_REG_ADDR)
-#define DMAC_SPI_TX CONCAT3(STM32_DMAC_SPI, CONFIG_SPI_MASTER_PORT, _TX)
-#define DMAC_SPI_RX CONCAT3(STM32_DMAC_SPI, CONFIG_SPI_MASTER_PORT, _RX)
+/* The second (and third if available) SPI port are used as master */
+static stm32_spi_regs_t *SPI_REGS[] = {
+ STM32_SPI2_REGS,
+};
#define SPI_TRANSACTION_TIMEOUT_USEC (800 * MSEC)
/* Default DMA channel options */
-static const struct dma_option dma_tx_option = {
- DMAC_SPI_TX, (void *)&SPI_REG->dr,
- STM32_DMA_CCR_MSIZE_8_BIT | STM32_DMA_CCR_PSIZE_8_BIT
+static const struct dma_option dma_tx_option[] = {
+ {
+ STM32_DMAC_SPI2_TX, (void *)&STM32_SPI2_REGS->dr,
+ STM32_DMA_CCR_MSIZE_8_BIT | STM32_DMA_CCR_PSIZE_8_BIT
+ },
};
-static const struct dma_option dma_rx_option = {
- DMAC_SPI_RX, (void *)&SPI_REG->dr,
- STM32_DMA_CCR_MSIZE_8_BIT | STM32_DMA_CCR_PSIZE_8_BIT
+static const struct dma_option dma_rx_option[] = {
+ {
+ STM32_DMAC_SPI2_RX, (void *)&STM32_SPI2_REGS->dr,
+ STM32_DMA_CCR_MSIZE_8_BIT | STM32_DMA_CCR_PSIZE_8_BIT
+ },
};
-static uint8_t spi_enabled;
+static uint8_t spi_enabled[ARRAY_SIZE(SPI_REGS)];
/**
* Initialize SPI module, registers, and clocks
+ *
+ * - port: which port to initialize.
*/
-static int spi_master_initialize(void)
+static int spi_master_initialize(int port)
{
- stm32_spi_regs_t *spi = SPI_REG;
+ int i, div = 0;
+
+ stm32_spi_regs_t *spi = SPI_REGS[port];
/*
* Set SPI master, baud rate, and software slave control.
- * Set SPI clock rate to DIV2R = 24 MHz
* */
- spi->cr1 = STM32_SPI_CR1_MSTR | STM32_SPI_CR1_SSM | STM32_SPI_CR1_SSI;
+ for (i = 0; i < spi_devices_used; i++)
+ if ((spi_devices[i].port == port) &&
+ (div < spi_devices[i].div))
+ div = spi_devices[i].div;
+ spi->cr1 = STM32_SPI_CR1_MSTR | STM32_SPI_CR1_SSM | STM32_SPI_CR1_SSI |
+ (div << 3);
/*
* Configure 8-bit datasize, set FRXTH, enable DMA,
@@ -57,11 +69,15 @@ static int spi_master_initialize(void)
/* Enable SPI */
spi->cr1 |= STM32_SPI_CR1_SPE;
- /* Drive SS high */
- gpio_set_level(CONFIG_SPI_CS_GPIO, 1);
+ for (i = 0; i < spi_devices_used; i++) {
+ if (spi_devices[i].port != port)
+ continue;
+ /* Drive SS high */
+ gpio_set_level(spi_devices[i].gpio_cs, 1);
+ }
/* Set flag */
- spi_enabled = 1;
+ spi_enabled[port] = 1;
return EC_SUCCESS;
}
@@ -69,18 +85,19 @@ static int spi_master_initialize(void)
/**
* Shutdown SPI module
*/
-static int spi_master_shutdown(void)
+static int spi_master_shutdown(int port)
{
int rv = EC_SUCCESS;
- stm32_spi_regs_t *spi = SPI_REG;
+
+ stm32_spi_regs_t *spi = SPI_REGS[port];
char dummy __attribute__((unused));
/* Set flag */
- spi_enabled = 0;
+ spi_enabled[port] = 0;
/* Disable DMA streams */
- dma_disable(dma_tx_option.channel);
- dma_disable(dma_rx_option.channel);
+ dma_disable(dma_tx_option[port].channel);
+ dma_disable(dma_rx_option[port].channel);
/* Disable SPI */
spi->cr1 &= ~STM32_SPI_CR1_SPE;
@@ -95,39 +112,40 @@ static int spi_master_shutdown(void)
return rv;
}
-int spi_enable(int enable)
+int spi_enable(int port, int enable)
{
- if (enable == spi_enabled)
+ if (enable == spi_enabled[port])
return EC_SUCCESS;
if (enable)
- return spi_master_initialize();
+ return spi_master_initialize(port);
else
- return spi_master_shutdown();
+ return spi_master_shutdown(port);
}
-static int spi_dma_start(const uint8_t *txdata, uint8_t *rxdata, int len)
+static int spi_dma_start(int port, const uint8_t *txdata,
+ uint8_t *rxdata, int len)
{
stm32_dma_chan_t *txdma;
/* Set up RX DMA */
- dma_start_rx(&dma_rx_option, len, rxdata);
+ dma_start_rx(&dma_rx_option[port], len, rxdata);
/* Set up TX DMA */
- txdma = dma_get_channel(dma_tx_option.channel);
- dma_prepare_tx(&dma_tx_option, len, txdata);
+ txdma = dma_get_channel(dma_tx_option[port].channel);
+ dma_prepare_tx(&dma_tx_option[port], len, txdata);
dma_go(txdma);
return EC_SUCCESS;
}
-static int spi_dma_wait(void)
+static int spi_dma_wait(int port)
{
timestamp_t timeout;
- stm32_spi_regs_t *spi = SPI_REG;
+ stm32_spi_regs_t *spi = SPI_REGS[port];
int rv = EC_SUCCESS;
/* Wait for DMA transmission to complete */
- rv = dma_wait(dma_tx_option.channel);
+ rv = dma_wait(dma_tx_option[port].channel);
if (rv)
return rv;
@@ -138,10 +156,10 @@ static int spi_dma_wait(void)
return EC_ERROR_TIMEOUT;
/* Disable TX DMA */
- dma_disable(dma_tx_option.channel);
+ dma_disable(dma_tx_option[port].channel);
/* Wait for DMA reception to complete */
- rv = dma_wait(dma_rx_option.channel);
+ rv = dma_wait(dma_rx_option[port].channel);
if (rv)
return rv;
@@ -152,16 +170,19 @@ static int spi_dma_wait(void)
return EC_ERROR_TIMEOUT;
/* Disable RX DMA */
- dma_disable(dma_rx_option.channel);
+ dma_disable(dma_rx_option[port].channel);
return rv;
}
-int spi_transaction_async(const uint8_t *txdata, int txlen,
+int spi_transaction_async(const struct spi_device_t *spi_device,
+ const uint8_t *txdata, int txlen,
uint8_t *rxdata, int rxlen)
{
int rv = EC_SUCCESS;
- stm32_spi_regs_t *spi = SPI_REG;
+ int port = spi_device->port;
+
+ stm32_spi_regs_t *spi = SPI_REGS[port];
char *buf;
rv = shared_mem_acquire(MAX(txlen, rxlen), &buf);
@@ -169,22 +190,22 @@ int spi_transaction_async(const uint8_t *txdata, int txlen,
return rv;
/* Drive SS low */
- gpio_set_level(CONFIG_SPI_CS_GPIO, 0);
+ gpio_set_level(spi_device->gpio_cs, 0);
/* Clear out the FIFO. */
while (spi->sr & STM32_SPI_SR_FRLVL)
(void) (uint8_t) spi->dr;
- rv = spi_dma_start(txdata, buf, txlen);
+ rv = spi_dma_start(port, txdata, buf, txlen);
if (rv != EC_SUCCESS)
goto err_free;
- rv = spi_dma_wait();
+ rv = spi_dma_wait(port);
if (rv != EC_SUCCESS)
goto err_free;
if (rxlen) {
- rv = spi_dma_start(buf, rxdata, rxlen);
+ rv = spi_dma_start(port, buf, rxdata, rxlen);
if (rv != EC_SUCCESS)
goto err_free;
}
@@ -194,23 +215,24 @@ err_free:
return rv;
}
-int spi_transaction_flush(void)
+int spi_transaction_flush(const struct spi_device_t *spi_device)
{
- int rv = spi_dma_wait();
+ int rv = spi_dma_wait(spi_device->port);
/* Drive SS high */
- gpio_set_level(CONFIG_SPI_CS_GPIO, 1);
+ gpio_set_level(spi_device->gpio_cs, 1);
return rv;
}
-int spi_transaction(const uint8_t *txdata, int txlen,
+int spi_transaction(const struct spi_device_t *spi_device,
+ const uint8_t *txdata, int txlen,
uint8_t *rxdata, int rxlen)
{
int rv;
- rv = spi_transaction_async(txdata, txlen, rxdata, rxlen);
- rv |= spi_transaction_flush();
+ rv = spi_transaction_async(spi_device, txdata, txlen, rxdata, rxlen);
+ rv |= spi_transaction_flush(spi_device);
return rv;
}
diff --git a/chip/stm32/usb_spi.c b/chip/stm32/usb_spi.c
index c81f01ac23..3998b429d2 100644
--- a/chip/stm32/usb_spi.c
+++ b/chip/stm32/usb_spi.c
@@ -98,7 +98,8 @@ void usb_spi_deferred(struct usb_spi_config const *config)
config->buffer[0] = USB_SPI_READ_COUNT_INVALID;
} else {
config->buffer[0] = usb_spi_map_error(
- spi_transaction((uint8_t *)(config->buffer + 1),
+ spi_transaction(SPI_FLASH_DEVICE,
+ (uint8_t *)(config->buffer + 1),
write_count,
(uint8_t *)(config->buffer + 1),
read_count));