summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorVic (Chun-Ju) Yang <victoryang@chromium.org>2014-04-18 12:02:43 +0800
committerchrome-internal-fetch <chrome-internal-fetch@google.com>2014-04-24 11:36:49 +0000
commit632d00509049884918abfc7fc275472592da2c2c (patch)
treef3085530dc5acb3063e947656238895fec004c28
parentd02e8c2090f7cd57098016d520b538e61870beb5 (diff)
downloadchrome-ec-632d00509049884918abfc7fc275472592da2c2c.tar.gz
Keyborg: chip-to-chip SPI communication
This implements a simple SPI driver for the two chips to exchange packets. There are both sync interface and async interface. Sync interface is easier to use, and async interface frees the CPU while the DMA takes care of the communication. BUG=None TEST=Hello test passed BRANCH=None Change-Id: I9823bad5cae6d1fa8f3658d17af4b998d3735a3e Signed-off-by: Vic (Chun-Ju) Yang <victoryang@chromium.org> Reviewed-on: https://chromium-review.googlesource.com/195533 Reviewed-by: Vincent Palatin <vpalatin@chromium.org>
-rw-r--r--board/keyborg/board.c21
-rw-r--r--board/keyborg/build.mk2
-rw-r--r--board/keyborg/hardware.c26
-rw-r--r--board/keyborg/spi_comm.c447
-rw-r--r--board/keyborg/spi_comm.h95
-rw-r--r--chip/stm32/registers.h6
6 files changed, 585 insertions, 12 deletions
diff --git a/board/keyborg/board.c b/board/keyborg/board.c
index 1e4096f90c..7616a0aaac 100644
--- a/board/keyborg/board.c
+++ b/board/keyborg/board.c
@@ -9,6 +9,7 @@
#include "debug.h"
#include "master_slave.h"
#include "registers.h"
+#include "spi_comm.h"
#include "system.h"
#include "task.h"
#include "util.h"
@@ -21,9 +22,27 @@ int main(void)
master_slave_init();
+ /* We want master SPI_NSS low and slave SPI_NSS high */
+ STM32_GPIO_BSRR(GPIO_A) = (1 << (1 + 16)) | (1 << 6);
+
+ master_slave_sync(10);
+
+ if (master_slave_is_master())
+ spi_master_init();
+ else
+ spi_slave_init();
+
+ master_slave_sync(100);
+
while (1) {
i++;
task_wait_event(SECOND);
- debug_printf("Timer check - %d seconds\n", i);
+ if (master_slave_is_master()) {
+ debug_printf("Hello x 50...");
+ if (spi_hello_test(50) == EC_SUCCESS)
+ debug_printf("Passed\n");
+ else
+ debug_printf("Failed\n");
+ }
}
}
diff --git a/board/keyborg/build.mk b/board/keyborg/build.mk
index 39eb64c284..c0ee425972 100644
--- a/board/keyborg/build.mk
+++ b/board/keyborg/build.mk
@@ -9,5 +9,5 @@ CHIP:=stm32
CHIP_FAMILY:=stm32f
CHIP_VARIANT:=stm32ts60
-board-y=board.o hardware.o runtime.o master_slave.o
+board-y=board.o hardware.o runtime.o master_slave.o spi_comm.o
board-$(CONFIG_DEBUG_PRINTF)+=debug.o
diff --git a/board/keyborg/hardware.c b/board/keyborg/hardware.c
index 76c3c5f1f9..3d140533f2 100644
--- a/board/keyborg/hardware.c
+++ b/board/keyborg/hardware.c
@@ -52,11 +52,12 @@ static void power_init(void)
#define OUT50(n) (0x3 << ((n & 0x7) * 4))
#define ANALOG(n) (0x0)
#define FLOAT(n) (0x4 << ((n & 0x7) * 4))
-#define GP_OD(n) (0x4 << ((n & 0x7) * 4))
-#define AF_PP(n) (0x8 << ((n & 0x7) * 4))
-#define AF_OD(n) (0xc << ((n & 0x7) * 4))
+#define GP_OD(n) (0x5 << ((n & 0x7) * 4))
+#define AF_PP(n) (0x9 << ((n & 0x7) * 4))
+#define AF_OD(n) (0xd << ((n & 0x7) * 4))
#define LOW(n) (1 << (n + 16))
#define HIGH(n) (1 << n)
+#define INT(n) (1 << n)
static void pins_init(void)
{
@@ -65,16 +66,21 @@ static void pins_init(void)
| (2 << 24);
/* Pin usage:
- * PA0: SPI_NSS - INPUT/INT_FALLING
- * PA1: N_CHG - OUTPUT/LOW
- * PA6: CS1 - OUTPUT/HIGH
- * PA15: UART TX - OUTPUT/HIGH
- * PI1: SYNC1 - OUTPUT/LOW
- * PI2: SYNC2 - OUTPUT/LOW
+ * PA0: SPI_NSS - INPUT/INT_FALLING
+ * PA1: N_CHG - OUTPUT/LOW
+ * PA3: SPI_CLK - INPUT
+ * PA4: SPI_MISO - INPUT
+ * PA6: CS1 - OUTPUT/HIGH
+ * PA7: SPI_MOSI - INPUT
+ * PA15: UART TX - OUTPUT/HIGH
+ * PI1: SYNC1 - OUTPUT/LOW
+ * PI2: SYNC2 - OUTPUT/LOW
*/
- STM32_GPIO_CRL(GPIO_A) = OUT(1) | OUT(6) | FLOAT(0);
+ STM32_GPIO_CRL(GPIO_A) = FLOAT(0) | OUT(1) | FLOAT(3) | FLOAT(4) |
+ OUT(6) | FLOAT(7);
STM32_GPIO_CRH(GPIO_A) = OUT(15);
STM32_GPIO_BSRR(GPIO_A) = LOW(1) | HIGH(6) | HIGH(15);
+ STM32_EXTI_FTSR |= INT(0);
STM32_GPIO_CRL(GPIO_I) = OUT(1) | OUT(2);
STM32_GPIO_BSRR(GPIO_I) = LOW(1) | LOW(2);
diff --git a/board/keyborg/spi_comm.c b/board/keyborg/spi_comm.c
new file mode 100644
index 0000000000..95f3ac9762
--- /dev/null
+++ b/board/keyborg/spi_comm.c
@@ -0,0 +1,447 @@
+/* Copyright (c) 2014 The Chromium OS Authors. All rights reserved.
+ * Use of this source code is governed by a BSD-style license that can be
+ * found in the LICENSE file.
+ */
+/* Stantum board-specific SPI module */
+
+#include "board.h"
+#include "common.h"
+#include "debug.h"
+#include "dma.h"
+#include "master_slave.h"
+#include "registers.h"
+#include "spi_comm.h"
+#include "task.h"
+#include "timer.h"
+#include "util.h"
+
+#define DUMMY_DATA 0xdd
+
+/* DMA channel option */
+static const struct dma_option dma_tx_option = {
+ STM32_DMAC_SPI1_TX, (void *)&STM32_SPI1_REGS->dr,
+ STM32_DMA_CCR_MSIZE_8_BIT | STM32_DMA_CCR_PSIZE_16_BIT
+};
+
+static const struct dma_option dma_rx_option = {
+ STM32_DMAC_SPI1_RX, (void *)&STM32_SPI1_REGS->dr,
+ STM32_DMA_CCR_MSIZE_8_BIT | STM32_DMA_CCR_PSIZE_16_BIT
+};
+
+static uint8_t out_msg[SPI_PACKET_MAX_SIZE + 2];
+static uint8_t in_msg[SPI_PACKET_MAX_SIZE];
+static uint8_t * const reply_msg = out_msg + 1;
+
+static inline int wait_for_signal(uint32_t port, uint32_t mask,
+ int value, int timeout_us)
+{
+ uint32_t start = get_time().le.lo;
+
+ while ((get_time().le.lo - start) < timeout_us) {
+ if ((!!(STM32_GPIO_IDR(port) & mask)) == value)
+ return EC_SUCCESS;
+ }
+
+ return EC_ERROR_TIMEOUT;
+}
+
+/*****************************************************************************/
+/* Master */
+
+void spi_master_init(void)
+{
+ stm32_spi_regs_t *spi = STM32_SPI1_REGS;
+
+ /*
+ * CLK: AFIO Push-pull
+ * MISO: Input
+ * MOSI: AFIO Push-pull
+ */
+ STM32_GPIO_CRL(GPIO_A) = (STM32_GPIO_CRL(GPIO_A) & 0x0ff00fff) |
+ 0xb004b000;
+
+ /* Set BR in CR1 */
+ spi->cr1 |= STM32_SPI_CR1_BR_DIV4R;
+
+ /* Set CPOL and CPHA */
+ /* Use default: 0, 0 */
+
+ /* Set DFF to 8-bit */
+ /* Use default: 8-bit */
+
+ /* Configure LSBFIRST */
+ /* Use default: MSB first */
+
+ /* Set SSOE */
+ /* Use default: software control */
+
+ /* Enable TX and RX DMA */
+ spi->cr2 |= STM32_SPI_CR2_TXDMAEN | STM32_SPI_CR2_RXDMAEN;
+
+ /* Set SSM and SSI */
+ spi->cr1 |= STM32_SPI_CR1_SSM | STM32_SPI_CR1_SSI;
+
+ /* Enable CRC */
+ spi->cr1 |= STM32_SPI_CR1_CRCEN;
+
+ /* Set MSTR and SPE */
+ spi->cr1 |= STM32_SPI_CR1_MSTR | STM32_SPI_CR1_SPE;
+}
+
+static int spi_master_read_write_byte(uint8_t *in_buf, uint8_t *out_buf, int sz)
+{
+ int ret;
+
+ dma_start_rx(&dma_rx_option, sz, in_buf);
+ dma_prepare_tx(&dma_tx_option, sz, out_buf);
+ dma_go(dma_get_channel(STM32_DMAC_SPI1_TX));
+ ret = dma_wait(STM32_DMAC_SPI1_TX);
+ ret |= dma_wait(STM32_DMAC_SPI1_RX);
+
+ dma_disable(STM32_DMAC_SPI1_TX);
+ dma_disable(STM32_DMAC_SPI1_RX);
+ dma_clear_isr(STM32_DMAC_SPI1_TX);
+ dma_clear_isr(STM32_DMAC_SPI1_RX);
+
+ return ret;
+}
+
+int spi_master_send_command(struct spi_comm_packet *cmd)
+{
+ stm32_spi_regs_t *spi = STM32_SPI1_REGS;
+ int ret;
+
+ if (cmd->size + 3 > SPI_PACKET_MAX_SIZE)
+ return EC_ERROR_OVERFLOW;
+
+ /* Wait for SPI_NSS to go low */
+ if (wait_for_signal(GPIO_A, 1 << 0, 0, 10 * MSEC))
+ return EC_ERROR_TIMEOUT;
+
+ /* Set CS1 (slave SPI_NSS) to low */
+ STM32_GPIO_BSRR(GPIO_A) = 1 << (6 + 16);
+
+ /* Wait for the slave to acknowledge */
+ master_slave_sync(5);
+
+ /* Clock out the packet size. */
+ spi->dr = cmd->size;
+ while (!(spi->sr & STM32_SPI_SR_RXNE))
+ ;
+ ret = spi->dr;
+
+ /* Wait for the slave to acknowledge */
+ master_slave_sync(5);
+
+ /* Clock out command. Don't care about input. */
+ ret = spi_master_read_write_byte(in_msg, ((uint8_t *)cmd) + 1,
+ cmd->size + SPI_PACKET_HEADER_SIZE - 1);
+
+ return ret;
+}
+
+int spi_master_wait_response_async(void)
+{
+ stm32_spi_regs_t *spi = STM32_SPI1_REGS;
+ int size;
+
+ master_slave_sync(40);
+ if (wait_for_signal(GPIO_A, 1 << 0, 1, 40 * MSEC))
+ goto err_wait_resp_async;
+
+ /* Discard potential garbage in SPI DR */
+ if (spi->sr & STM32_SPI_SR_RXNE)
+ in_msg[0] = spi->dr;
+
+ /* Get the packet size */
+ spi->dr = DUMMY_DATA;
+ while (!(spi->sr & STM32_SPI_SR_RXNE))
+ ;
+ in_msg[0] = spi->dr;
+ size = in_msg[0] + SPI_PACKET_HEADER_SIZE;
+
+ master_slave_sync(5);
+
+ dma_clear_isr(STM32_DMAC_SPI1_TX);
+ dma_clear_isr(STM32_DMAC_SPI1_RX);
+
+ /* Get the rest of the packet*/
+ dma_start_rx(&dma_rx_option, size - 1, in_msg + 1);
+ dma_prepare_tx(&dma_tx_option, size - 1, out_msg);
+ dma_go(dma_get_channel(STM32_DMAC_SPI1_TX));
+
+ return EC_SUCCESS;
+err_wait_resp_async:
+ /* Set CS1 (slave SPI_NSS) to high */
+ STM32_GPIO_BSRR(GPIO_A) = 1 << 6;
+ return EC_ERROR_TIMEOUT;
+}
+
+const struct spi_comm_packet *spi_master_wait_response_done(void)
+{
+ const struct spi_comm_packet *resp =
+ (const struct spi_comm_packet *)in_msg;
+ stm32_spi_regs_t *spi = STM32_SPI1_REGS;
+
+ if (dma_wait(STM32_DMAC_SPI1_TX) || dma_wait(STM32_DMAC_SPI1_RX)) {
+ debug_printf("SPI: Incomplete response\n");
+ goto err_wait_response_done;
+ }
+ if (spi->sr & STM32_SPI_SR_CRCERR) {
+ debug_printf("SPI: CRC mismatch\n");
+ goto err_wait_response_done;
+ }
+ if (resp->cmd_sts != EC_SUCCESS) {
+ debug_printf("SPI: Slave error\n");
+ goto err_wait_response_done;
+ }
+
+exit_wait_response_done:
+ dma_disable(STM32_DMAC_SPI1_TX);
+ dma_disable(STM32_DMAC_SPI1_RX);
+ dma_clear_isr(STM32_DMAC_SPI1_TX);
+ dma_clear_isr(STM32_DMAC_SPI1_RX);
+
+ /* Set CS1 (slave SPI_NSS) to high */
+ STM32_GPIO_BSRR(GPIO_A) = 1 << 6;
+
+ return resp;
+err_wait_response_done:
+ resp = NULL;
+ goto exit_wait_response_done;
+}
+
+const struct spi_comm_packet *spi_master_wait_response(void)
+{
+ if (spi_master_wait_response_async() != EC_SUCCESS)
+ return NULL;
+ return spi_master_wait_response_done();
+}
+
+static uint32_t myrnd(void)
+{
+ static uint32_t last = 0x1357;
+ return last = (last * 8001 + 1);
+}
+
+int spi_hello_test(int iteration)
+{
+ int i, j, xv, sz;
+ struct spi_comm_packet *cmd = (struct spi_comm_packet *)out_msg;
+ const struct spi_comm_packet *resp;
+
+ for (i = 0; i < iteration; ++i) {
+ xv = myrnd() & 0xff;
+ cmd->cmd_sts = TS_CMD_HELLO;
+ sz = myrnd() % (sizeof(out_msg) - 10) + 1;
+ cmd->size = sz + 2;
+ cmd->data[0] = sz;
+ cmd->data[1] = xv;
+ for (j = 0; j < sz; ++j)
+ cmd->data[j + 2] = myrnd() & 0xff;
+ if (spi_master_send_command(cmd))
+ return EC_ERROR_UNKNOWN;
+
+ resp = spi_master_wait_response();
+ if (resp == NULL || resp->size != sz)
+ return EC_ERROR_UNKNOWN;
+ for (j = 0; j < sz; ++j)
+ if (cmd->data[j + 2] != resp->data[j])
+ return EC_ERROR_UNKNOWN;
+ resp = spi_master_wait_response();
+ if (resp == NULL || resp->size != sz)
+ return EC_ERROR_UNKNOWN;
+ for (j = 0; j < sz; ++j)
+ if ((cmd->data[j + 2] ^ xv) != resp->data[j])
+ return EC_ERROR_UNKNOWN;
+ }
+
+ return EC_SUCCESS;
+}
+
+/*****************************************************************************/
+/* Slave */
+
+void spi_slave_init(void)
+{
+ stm32_spi_regs_t *spi = STM32_SPI1_REGS;
+
+ /*
+ * MISO: AFIO Push-pull
+ */
+ STM32_GPIO_CRL(GPIO_A) = (STM32_GPIO_CRL(GPIO_A) & 0xfff0ffff) |
+ 0x000b0000;
+
+ /* Set DFF to 8-bit (default) */
+
+ /* Set CPOL and CPHA (default) */
+
+ /* Configure LSBFIRST (default) */
+
+ /* Set SSM and clear SSI */
+ spi->cr1 |= STM32_SPI_CR1_SSM;
+ spi->cr1 &= ~STM32_SPI_CR1_SSI;
+
+ /* Enable RXNE interrupt */
+ spi->cr2 |= STM32_SPI_CR2_RXNEIE;
+ /*task_enable_irq(STM32_IRQ_SPI1);*/
+
+ /* Enable TX and RX DMA */
+ spi->cr2 |= STM32_SPI_CR2_TXDMAEN | STM32_SPI_CR2_RXDMAEN;
+
+ /* Clear MSTR */
+ spi->cr1 &= ~STM32_SPI_CR1_MSTR;
+
+ /* Enable CRC */
+ spi->cr1 |= STM32_SPI_CR1_CRCEN;
+
+ /* Set SPE */
+ spi->cr1 |= STM32_SPI_CR1_SPE;
+
+ /* Dummy byte to clock out when the next packet comes in */
+ spi->dr = DUMMY_DATA;
+
+ /* Enable interrupt on PA0 (GPIO_SPI_NSS) */
+ STM32_AFIO_EXTICR(0) &= ~0xF;
+ STM32_EXTI_IMR |= (1 << 0);
+ task_clear_pending_irq(STM32_IRQ_EXTI0);
+ task_enable_irq(STM32_IRQ_EXTI0);
+}
+
+int spi_slave_send_response(struct spi_comm_packet *resp)
+{
+ if (spi_slave_send_response_async(resp) != EC_SUCCESS)
+ return EC_ERROR_UNKNOWN;
+ return spi_slave_send_response_flush();
+}
+
+int spi_slave_send_response_async(struct spi_comm_packet *resp)
+{
+ int size = resp->size + SPI_PACKET_HEADER_SIZE;
+ stm32_spi_regs_t *spi = STM32_SPI1_REGS;
+
+ if (size > SPI_PACKET_MAX_SIZE)
+ return EC_ERROR_OVERFLOW;
+
+ master_slave_sync(100);
+
+ if (spi->sr & STM32_SPI_SR_RXNE)
+ in_msg[0] = spi->dr;
+ spi->dr = *((uint8_t *)resp);
+
+ /* Set N_CHG (master SPI_NSS) to high */
+ STM32_GPIO_BSRR(GPIO_A) = 1 << 1;
+
+ while (!(spi->sr & STM32_SPI_SR_RXNE))
+ ;
+ in_msg[0] = spi->dr;
+
+ dma_clear_isr(STM32_DMAC_SPI1_TX);
+ dma_clear_isr(STM32_DMAC_SPI1_RX);
+ dma_start_rx(&dma_rx_option, size - 1, in_msg);
+ dma_prepare_tx(&dma_tx_option, size - 1, ((uint8_t *)resp)+1);
+ dma_go(dma_get_channel(STM32_DMAC_SPI1_TX));
+
+ master_slave_sync(5);
+
+ return EC_SUCCESS;
+}
+
+int spi_slave_send_response_flush(void)
+{
+ int ret;
+
+ ret = dma_wait(STM32_DMAC_SPI1_TX);
+ ret |= dma_wait(STM32_DMAC_SPI1_RX);
+ dma_disable(STM32_DMAC_SPI1_TX);
+ dma_disable(STM32_DMAC_SPI1_RX);
+ dma_clear_isr(STM32_DMAC_SPI1_TX);
+ dma_clear_isr(STM32_DMAC_SPI1_RX);
+
+ /* Set N_CHG (master SPI_NSS) to low */
+ STM32_GPIO_BSRR(GPIO_A) = 1 << (1 + 16);
+
+ return ret;
+}
+
+static void spi_slave_nack(void)
+{
+ struct spi_comm_packet *resp = (struct spi_comm_packet *)reply_msg;
+
+ resp->cmd_sts = EC_ERROR_UNKNOWN;
+ resp->size = 0;
+ spi_slave_send_response(resp);
+}
+
+static void spi_slave_hello_back(const struct spi_comm_packet *cmd)
+{
+ struct spi_comm_packet *resp = (struct spi_comm_packet *)reply_msg;
+ uint8_t buf[SPI_PACKET_MAX_SIZE];
+ int i, sz;
+
+ sz = cmd->data[0];
+ memcpy(buf, cmd->data, sz + 2);
+
+ resp->cmd_sts = EC_SUCCESS;
+ resp->size = sz;
+ for (i = 0; i < sz; ++i)
+ resp->data[i] = cmd->data[i + 2];
+ spi_slave_send_response(resp);
+ for (i = 0; i < sz; ++i)
+ resp->data[i] = buf[i + 2] ^ buf[1];
+ spi_slave_send_response(resp);
+}
+
+static void spi_nss_interrupt(void)
+{
+ const struct spi_comm_packet *cmd =
+ (const struct spi_comm_packet *)in_msg;
+ stm32_spi_regs_t *spi = STM32_SPI1_REGS;
+
+ if (spi->sr & STM32_SPI_SR_RXNE)
+ in_msg[0] = spi->dr;
+
+ master_slave_sync(5);
+
+ /* Read in the packet size */
+ while (!(spi->sr & STM32_SPI_SR_RXNE))
+ ;
+ in_msg[0] = spi->dr;
+
+ /* Read in the rest of the packet */
+ dma_clear_isr(STM32_DMAC_SPI1_RX);
+ dma_start_rx(&dma_rx_option, in_msg[0] + SPI_PACKET_HEADER_SIZE - 1,
+ in_msg + 1);
+ dma_prepare_tx(&dma_tx_option, in_msg[0] + SPI_PACKET_HEADER_SIZE - 1,
+ out_msg);
+ dma_go(dma_get_channel(STM32_DMAC_SPI1_TX));
+
+ master_slave_sync(5);
+
+ if (dma_wait(STM32_DMAC_SPI1_RX) != EC_SUCCESS) {
+ debug_printf("SPI: Incomplete packet\n");
+ spi_slave_nack();
+ return;
+ }
+ if (spi->sr & STM32_SPI_SR_CRCERR) {
+ debug_printf("SPI: CRC mismatch\n");
+ spi_slave_nack();
+ return;
+ }
+
+ if (cmd->cmd_sts == TS_CMD_HELLO)
+ spi_slave_hello_back(cmd);
+ else
+ spi_slave_nack();
+}
+
+/* Interrupt handler for PA0 */
+void IRQ_HANDLER(STM32_IRQ_EXTI0)(void)
+{
+ /* Clear the interrupt */
+ STM32_EXTI_PR = STM32_EXTI_PR;
+
+ /* SPI slave interrupt */
+ spi_nss_interrupt();
+}
+
diff --git a/board/keyborg/spi_comm.h b/board/keyborg/spi_comm.h
new file mode 100644
index 0000000000..4a1abb632a
--- /dev/null
+++ b/board/keyborg/spi_comm.h
@@ -0,0 +1,95 @@
+/* Copyright (c) 2014 The Chromium OS Authors. All rights reserved.
+ * Use of this source code is governed by a BSD-style license that can be
+ * found in the LICENSE file.
+ */
+
+#ifndef __BOARD_KEYBORG_SPI_COMM_H
+#define __BOARD_KEYBORG_SPI_COMM_H
+
+#define SPI_PACKET_MAX_SIZE 64
+
+enum ts_command {
+ TS_CMD_HELLO = 0,
+};
+
+struct spi_comm_packet {
+ uint8_t size;
+ uint8_t cmd_sts;
+ uint8_t data[0];
+};
+
+#define SPI_PACKET_HEADER_SIZE 2
+
+/* Initialize SPI interface for the master chip */
+void spi_master_init(void);
+
+/* Initialize SPI interface for the slave chip */
+void spi_slave_init(void);
+
+/*
+ * Calculate checksum and send command packet to the slave.
+ *
+ * @param cmd Pointer to the command packet.
+ *
+ * @return EC_SUCCESS, or non-zero if any error.
+ */
+int spi_master_send_command(struct spi_comm_packet *cmd);
+
+/*
+ * Wait for slave response and verify checksum.
+ *
+ * @return Pointer to the response packet, or NULL if any error.
+ */
+const struct spi_comm_packet *spi_master_wait_response(void);
+
+/*
+ * Start receiving slave response, but don't wait for full transaction.
+ * The caller is responsible for calling spi_master_wait_response_done()
+ * to ensure the response is fully received.
+ *
+ * @return EC_SUCCESS, or non-zero if any error.
+ */
+int spi_master_wait_response_async(void);
+
+/*
+ * Wait for slave response to complete.
+ *
+ * @return Pointer to the response packet, or NULL if any error.
+ */
+const struct spi_comm_packet *spi_master_wait_response_done(void);
+
+/*
+ * Calculate checksum and send response packet to the master.
+ *
+ * @param resp Pointer to the response packet.
+ *
+ * @return EC_SUCCESS, or non-zero if any error.
+ */
+int spi_slave_send_response(struct spi_comm_packet *resp);
+
+/*
+ * Start sending response to the master, but don't block. The caller is
+ * responsible for calling spi_slave_send_response_flush() to ensure
+ * the response is fully transmitted.
+ *
+ * @return EC_SUCCESS, or non-zero if any error.
+ */
+int spi_slave_send_response_async(struct spi_comm_packet *resp);
+
+/*
+ * Wait until the last response is sent out.
+ *
+ * @return EC_SUCCESS, or non-zero if any error.
+ */
+int spi_slave_send_response_flush(void);
+
+/*
+ * Perform random back-to-back hello test. Master only.
+ *
+ * @param iteration Number of hello messages to send.
+ *
+ * @return EC_SUCCESS, or non-zero if any error.
+ */
+int spi_hello_test(int iteration);
+
+#endif /* __BOARD_KEYBORG_SPI_COMM_H */
diff --git a/chip/stm32/registers.h b/chip/stm32/registers.h
index dd4ceb13d6..0752416a2f 100644
--- a/chip/stm32/registers.h
+++ b/chip/stm32/registers.h
@@ -678,6 +678,7 @@ typedef volatile struct stm32_spi_regs stm32_spi_regs_t;
#define STM32_SPI_CR1_BIDIMODE (1 << 15)
#define STM32_SPI_CR1_BIDIOE (1 << 14)
+#define STM32_SPI_CR1_CRCEN (1 << 13)
#define STM32_SPI_CR1_SSM (1 << 9)
#define STM32_SPI_CR1_SSI (1 << 8)
#define STM32_SPI_CR1_LSBFIRST (1 << 7)
@@ -691,6 +692,11 @@ typedef volatile struct stm32_spi_regs stm32_spi_regs_t;
#define STM32_SPI_CR2_TXDMAEN (1 << 1)
#define STM32_SPI_CR2_DATASIZE(n) (((n) - 1) << 8)
+#define STM32_SPI_SR_RXNE (1 << 0)
+#define STM32_SPI_SR_TXE (1 << 1)
+#define STM32_SPI_SR_CRCERR (1 << 4)
+#define STM32_SPI_SR_BSY (1 << 7)
+
/* --- Debug --- */
#ifdef CHIP_FAMILY_STM32F0