summaryrefslogtreecommitdiff
path: root/src/soc/intel/common/block/gspi
diff options
context:
space:
mode:
authorFurquan Shaikh <furquan@chromium.org>2017-03-31 17:10:02 -0700
committerFurquan Shaikh <furquan@google.com>2017-04-06 00:45:11 +0200
commit108f87262bf47ce3549fa0c5ed16a40fe916656f (patch)
treecf982de0bd09d7d9e3c06903355cddbe52404141 /src/soc/intel/common/block/gspi
parent340908aecf01093d35aaf0b71c55ed65c3ebbeac (diff)
downloadcoreboot-108f87262bf47ce3549fa0c5ed16a40fe916656f.tar.xz
soc/intel/common: Add support for common GSPI controller
Add support for GSPI controller in Intel PCH. This controller is compliant with PXA2xx SPI controller with some additional registers to provide more fine-grained control of the SPI bus. Currently, DMA is not enabled as this driver might be used before memory is up (e.g. TPM on SPI). Also, provide common GSPI config structure that can be included by SoCs in chip config to allow mainboards to configure GSPI bus. Additionally, provide an option for SoCs to configure BAR for GSPI controllers before memory is up. BUG=b:35583330 Change-Id: I0eb91eba2c523be457fee8922c44fb500a9fa140 Signed-off-by: Furquan Shaikh <furquan@chromium.org> Reviewed-on: https://review.coreboot.org/19098 Tested-by: build bot (Jenkins) Reviewed-by: Aaron Durbin <adurbin@chromium.org>
Diffstat (limited to 'src/soc/intel/common/block/gspi')
-rw-r--r--src/soc/intel/common/block/gspi/Kconfig12
-rw-r--r--src/soc/intel/common/block/gspi/Makefile.inc4
-rw-r--r--src/soc/intel/common/block/gspi/gspi.c635
3 files changed, 651 insertions, 0 deletions
diff --git a/src/soc/intel/common/block/gspi/Kconfig b/src/soc/intel/common/block/gspi/Kconfig
new file mode 100644
index 0000000000..a5455a38db
--- /dev/null
+++ b/src/soc/intel/common/block/gspi/Kconfig
@@ -0,0 +1,12 @@
+config SOC_INTEL_COMMON_BLOCK_GSPI
+ bool
+ help
+ Intel Processor Common GSPI support
+
+config SOC_INTEL_COMMON_BLOCK_GSPI_MAX
+ int
+ depends on SOC_INTEL_COMMON_BLOCK_GSPI
+ help
+ Maximum number of GSPI controllers supported by the PCH. SoC
+ must define this config if SOC_INTEL_COMMON_BLOCK_GSPI is
+ selected.
diff --git a/src/soc/intel/common/block/gspi/Makefile.inc b/src/soc/intel/common/block/gspi/Makefile.inc
new file mode 100644
index 0000000000..85cb18ebb8
--- /dev/null
+++ b/src/soc/intel/common/block/gspi/Makefile.inc
@@ -0,0 +1,4 @@
+bootblock-$(CONFIG_SOC_INTEL_COMMON_BLOCK_GSPI) += gspi.c
+romstage-$(CONFIG_SOC_INTEL_COMMON_BLOCK_GSPI) += gspi.c
+ramstage-$(CONFIG_SOC_INTEL_COMMON_BLOCK_GSPI) += gspi.c
+verstage-$(CONFIG_SOC_INTEL_COMMON_BLOCK_GSPI) += gspi.c
diff --git a/src/soc/intel/common/block/gspi/gspi.c b/src/soc/intel/common/block/gspi/gspi.c
new file mode 100644
index 0000000000..f3c146057e
--- /dev/null
+++ b/src/soc/intel/common/block/gspi/gspi.c
@@ -0,0 +1,635 @@
+/*
+ * This file is part of the coreboot project.
+ *
+ * Copyright 2017 Google Inc.
+ *
+ * This program is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ */
+
+#include <arch/early_variables.h>
+#include <arch/io.h>
+#include <assert.h>
+#include <console/console.h>
+#include <delay.h>
+#include <device/device.h>
+#include <device/pci_def.h>
+#include <intelblocks/gspi.h>
+#include <string.h>
+#include <timer.h>
+
+/* GSPI Memory Mapped Registers */
+#define SSCR0 0x0 /* SSP Control Register 0 */
+#define SSCR0_EDSS_0 (0 << 20)
+#define SSCR0_EDSS_1 (1 << 20)
+#define SSCR0_SCR_SHIFT (8)
+#define SSCR0_SCR_MASK (0xFFF)
+#define SSCR0_SSE_DISABLE (0 << 7)
+#define SSCR0_SSE_ENABLE (1 << 7)
+#define SSCR0_ECS_ON_CHIP (0 << 6)
+#define SSCR0_FRF_MOTOROLA (0 << 4)
+#define SSCR0_DSS_SHIFT (0)
+#define SSCR0_DSS_MASK (0xF)
+#define SSCR1 0x4 /* SSP Control Register 1 */
+#define SSCR1_IFS_LOW (0 << 16)
+#define SSCR1_IFS_HIGH (1 << 16)
+#define SSCR1_SPH_FIRST (0 << 4)
+#define SSCR1_SPH_SECOND (1 << 4)
+#define SSCR1_SPO_LOW (0 << 3)
+#define SSCR1_SPO_HIGH (1 << 3)
+#define SSSR 0x8 /* SSP Status Register */
+#define SSSR_TUR (1 << 21) /* Tx FIFO underrun */
+#define SSSR_TINT (1 << 19) /* Rx Time-out interrupt */
+#define SSSR_PINT (1 << 18) /* Peripheral trailing byte
+ interrupt */
+#define SSSR_ROR (1 << 7) /* Rx FIFO Overrun */
+#define SSSR_BSY (1 << 4) /* SSP Busy */
+#define SSSR_RNE (1 << 3) /* Receive FIFO not empty */
+#define SSSR_TNF (1 << 2) /* Transmit FIFO not full */
+#define SSDR 0x10 /* SSP Data Register */
+#define SSTO 0x28 /* SSP Time out */
+#define SITF 0x44 /* SPI Transmit FIFO */
+#define SITF_LEVEL_SHIFT (16)
+#define SITF_LEVEL_MASK (0x3f)
+#define SITF_LWM_SHIFT (8)
+#define SITF_LWM_MASK (0x3f)
+#define SITF_LWM(x) ((((x) - 1) & SITF_LWM_MASK) << SITF_LWM_SHIFT)
+#define SITF_HWM_SHIFT (0)
+#define SITF_HWM_MASK (0x3f)
+#define SITF_HWM(x) ((((x) - 1) & SITF_HWM_MASK) << SITF_HWM_SHIFT)
+#define SIRF 0x48 /* SPI Receive FIFO */
+#define SIRF_LEVEL_SHIFT (8)
+#define SIRF_LEVEL_MASK (0x3f)
+#define SIRF_WM_SHIFT (0)
+#define SIRF_WM_MASK (0x3f)
+#define SIRF_WM(x) ((((x) - 1) & SIRF_WM_MASK) << SIRF_WM_SHIFT)
+
+/* GSPI Additional Registers */
+#define CLOCKS 0x200 /* Clocks */
+#define CLOCKS_UPDATE (1 << 31)
+#define CLOCKS_N_SHIFT (16)
+#define CLOCKS_N_MASK (0x7fff)
+#define CLOCKS_M_SHIFT (1)
+#define CLOCKS_M_MASK (0x7fff)
+#define CLOCKS_DISABLE (0 << 0)
+#define CLOCKS_ENABLE (1 << 0)
+#define RESETS 0x204 /* Resets */
+#define DMA_RESET (0 << 2)
+#define DMA_ACTIVE (1 << 2)
+#define CTRLR_RESET (0 << 0)
+#define CTRLR_ACTIVE (3 << 0)
+#define ACTIVELTR_VALUE 0x210 /* Active LTR */
+#define IDLELTR_VALUE 0x214 /* Idle LTR Value */
+#define TX_BIT_COUNT 0x218 /* Tx Bit Count */
+#define RX_BIT_COUNT 0x21c /* Rx Bit Count */
+#define SSP_REG 0x220 /* SSP Reg */
+#define DMA_FINISH_DISABLE (1 << 0)
+#define SPI_CS_CONTROL 0x224 /* SPI CS Control */
+#define CS_POLARITY_LOW (0 << 12)
+#define CS_POLARITY_HIGH (1 << 12)
+#define CS_0 (0 << 8)
+#define CS_STATE_LOW (0 << 1)
+#define CS_STATE_HIGH (1 << 1)
+#define CS_STATE_MASK (1 << 1)
+#define CS_MODE_HW (0 << 0)
+#define CS_MODE_SW (1 << 0)
+
+#define GSPI_DATA_BIT_LENGTH (8)
+#define GSPI_BUS_BASE(bar, bus) ((bar) + (bus) * 4 * KiB)
+
+#if defined(__SIMPLE_DEVICE__)
+
+static uintptr_t gspi_get_base_addr(int devfn,
+ ROMSTAGE_CONST struct device *dev)
+{
+ pci_devfn_t pci_dev = PCI_DEV(0, PCI_SLOT(devfn), PCI_FUNC(devfn));
+ return ALIGN_DOWN(pci_read_config32(pci_dev, PCI_BASE_ADDRESS_0), 16);
+}
+
+static void gspi_set_base_addr(int devfn, ROMSTAGE_CONST struct device *dev,
+ uintptr_t base)
+{
+ pci_devfn_t pci_dev = PCI_DEV(0, PCI_SLOT(devfn), PCI_FUNC(devfn));
+ pci_write_config32(pci_dev, PCI_BASE_ADDRESS_0, base);
+ pci_write_config32(pci_dev, PCI_COMMAND, PCI_COMMAND_MEMORY |
+ PCI_COMMAND_MASTER);
+}
+
+void gspi_early_bar_init(void)
+{
+ unsigned int gspi_bus;
+ const unsigned int gspi_max = CONFIG_SOC_INTEL_COMMON_BLOCK_GSPI_MAX;
+ const struct gspi_cfg *cfg = gspi_get_soc_cfg();
+ int devfn;
+ uintptr_t gspi_base_addr;
+
+ assert(gspi_max != 0);
+ if (!cfg) {
+ printk(BIOS_ERR, "%s: No GSPI config provided by SoC!\n",
+ __func__);
+ return;
+ }
+
+ gspi_base_addr = gspi_get_soc_early_base();
+ if (!gspi_base_addr) {
+ printk(BIOS_ERR, "%s: GSPI base address provided is NULL!\n",
+ __func__);
+ return;
+ }
+
+ for (gspi_bus = 0; gspi_bus < gspi_max; gspi_bus++) {
+ if (!cfg[gspi_bus].early_init)
+ continue;
+ devfn = gspi_soc_bus_to_devfn(gspi_bus);
+ gspi_set_base_addr(devfn, NULL,
+ GSPI_BUS_BASE(gspi_base_addr, gspi_bus));
+ }
+}
+
+#else
+
+static uintptr_t gspi_get_base_addr(int devfn, struct device *dev)
+{
+ return ALIGN_DOWN(pci_read_config32(dev, PCI_BASE_ADDRESS_0), 16);
+}
+
+static void gspi_set_base_addr(int devfn, struct device *dev, uintptr_t base)
+{
+ pci_write_config32(dev, PCI_BASE_ADDRESS_0, base);
+ pci_write_config32(dev, PCI_COMMAND, PCI_COMMAND_MEMORY |
+ PCI_COMMAND_MASTER);
+}
+
+#endif
+
+static uintptr_t gspi_calc_base_addr(unsigned int gspi_bus)
+{
+ uintptr_t bus_base, gspi_base_addr;
+ ROMSTAGE_CONST struct device *dev;
+ int devfn = gspi_soc_bus_to_devfn(gspi_bus);
+
+ if (devfn < 0)
+ return 0;
+
+ dev = dev_find_slot(0, devfn);
+ if (!dev || !dev->enabled)
+ return 0;
+
+ bus_base = gspi_get_base_addr(devfn, dev);
+ if (bus_base)
+ return bus_base;
+
+ gspi_base_addr = gspi_get_soc_early_base();
+ if (!gspi_base_addr)
+ return 0;
+
+ bus_base = GSPI_BUS_BASE(gspi_base_addr, gspi_bus);
+
+ gspi_set_base_addr(devfn, dev, bus_base);
+ return bus_base;
+}
+
+static uint32_t gspi_get_bus_clk_mhz(unsigned int gspi_bus)
+{
+ const struct gspi_cfg *cfg = gspi_get_soc_cfg();
+ if (!cfg)
+ return 0;
+ return cfg[gspi_bus].speed_mhz;
+}
+
+static uintptr_t gspi_base[CONFIG_SOC_INTEL_COMMON_BLOCK_GSPI_MAX] CAR_GLOBAL;
+static uintptr_t gspi_get_bus_base_addr(unsigned int gspi_bus)
+{
+ uintptr_t *base = car_get_var_ptr(gspi_base);
+
+ if (!base[gspi_bus])
+ base[gspi_bus] = gspi_calc_base_addr(gspi_bus);
+
+ return base[gspi_bus];
+}
+
+/* Parameters for GSPI controller operation. */
+struct gspi_ctrlr_params {
+ uintptr_t mmio_base;
+ unsigned int gspi_bus;
+ uint8_t *in;
+ size_t bytesin;
+ const uint8_t *out;
+ size_t bytesout;
+};
+
+static uint32_t gspi_read_mmio_reg(const struct gspi_ctrlr_params *p,
+ uint32_t offset)
+{
+ assert(p->mmio_base != 0);
+ return read32((void *)(p->mmio_base + offset));
+}
+
+static void gspi_write_mmio_reg(const struct gspi_ctrlr_params *p,
+ uint32_t offset, uint32_t value)
+{
+ assert(p->mmio_base != 0);
+ write32((void *)(p->mmio_base + offset), value);
+}
+
+static int gspi_ctrlr_params_init(struct gspi_ctrlr_params *p,
+ unsigned int spi_bus)
+{
+ memset(p, 0, sizeof(*p));
+
+ if (gspi_soc_spi_to_gspi_bus(spi_bus, &p->gspi_bus)) {
+ printk(BIOS_ERR, "%s: No GSPI bus available for SPI bus %u.\n",
+ __func__, spi_bus);
+ return -1;
+ }
+
+ p->mmio_base = gspi_get_bus_base_addr(p->gspi_bus);
+ if (!p->mmio_base) {
+ printk(BIOS_ERR, "%s: Base addr is 0 for GSPI bus=%u.\n",
+ __func__, p->gspi_bus);
+ return -1;
+ }
+
+ return 0;
+}
+
+enum cs_assert {
+ CS_ASSERT,
+ CS_DEASSERT,
+};
+
+static void __gspi_cs_change(const struct gspi_ctrlr_params *p,
+ enum cs_assert cs_assert)
+{
+ uint32_t cs_ctrl, state;
+ cs_ctrl = gspi_read_mmio_reg(p, SPI_CS_CONTROL);
+
+ cs_ctrl &= ~CS_STATE_MASK;
+
+ if (cs_ctrl & CS_POLARITY_HIGH)
+ state = (cs_assert == CS_ASSERT) ? CS_STATE_HIGH : CS_STATE_LOW;
+ else
+ state = (cs_assert == CS_ASSERT) ? CS_STATE_LOW : CS_STATE_HIGH;
+
+ cs_ctrl |= state;
+
+ gspi_write_mmio_reg(p, SPI_CS_CONTROL, cs_ctrl);
+}
+
+static int gspi_cs_change(const struct spi_slave *dev, enum cs_assert cs_assert)
+{
+ struct gspi_ctrlr_params params, *p = &params;
+
+ if (gspi_ctrlr_params_init(p, dev->bus))
+ return -1;
+
+ __gspi_cs_change(p, cs_assert);
+
+ return 0;
+}
+
+int __attribute__((weak)) gspi_get_soc_spi_cfg(unsigned int gspi_bus,
+ struct spi_cfg *cfg)
+{
+ cfg->clk_phase = SPI_CLOCK_PHASE_FIRST;
+ cfg->clk_polarity = SPI_POLARITY_LOW;
+ cfg->cs_polarity = SPI_POLARITY_LOW;
+ cfg->wire_mode = SPI_4_WIRE_MODE;
+ cfg->data_bit_length = GSPI_DATA_BIT_LENGTH;
+
+ return 0;
+}
+
+static int gspi_ctrlr_get_config(const struct spi_slave *dev,
+ struct spi_cfg *cfg)
+{
+ unsigned int gspi_bus;
+
+ /* Currently, only chip select 0 is supported. */
+ if (dev->cs != 0) {
+ printk(BIOS_ERR, "%s: Invalid CS value: cs=%u.\n", __func__,
+ dev->cs);
+ return -1;
+ }
+
+ if (gspi_soc_spi_to_gspi_bus(dev->bus, &gspi_bus)) {
+ printk(BIOS_ERR, "%s: Failed to find GSPI bus for SPI %u.\n",
+ __func__, dev->bus);
+ return -1;
+ }
+ return gspi_get_soc_spi_cfg(gspi_bus, cfg);
+}
+
+static int gspi_cs_assert(const struct spi_slave *dev)
+{
+ return gspi_cs_change(dev, CS_ASSERT);
+}
+
+static void gspi_cs_deassert(const struct spi_slave *dev)
+{
+ gspi_cs_change(dev, CS_DEASSERT);
+}
+
+static uint32_t gspi_get_clk_div(unsigned int gspi_bus)
+{
+ const uint32_t ref_clk_mhz = CONFIG_SOC_INTEL_COMMON_LPSS_CLOCK_MHZ;
+ const uint32_t gspi_clk_mhz = gspi_get_bus_clk_mhz(gspi_bus);
+
+ assert(gspi_clk_mhz != 0);
+ assert(ref_clk_mhz != 0);
+ return (DIV_ROUND_UP(ref_clk_mhz, gspi_clk_mhz) - 1) & SSCR0_SCR_MASK;
+}
+
+static int gspi_ctrlr_setup(const struct spi_slave *dev)
+{
+ struct spi_cfg cfg;
+ uint32_t cs_ctrl, sscr0, sscr1, clocks, sitf, sirf;
+ struct gspi_ctrlr_params params, *p = &params;
+
+ /* Only chip select 0 is supported. */
+ if (dev->cs != 0) {
+ printk(BIOS_ERR, "%s: Invalid CS value: cs=%u.\n", __func__,
+ dev->cs);
+ return -1;
+ }
+
+ if (gspi_ctrlr_params_init(p, dev->bus))
+ return -1;
+
+ /* Obtain SPI bus configuration for the device. */
+ if (gspi_get_soc_spi_cfg(p->gspi_bus, &cfg)) {
+ printk(BIOS_ERR, "%s: Failed to get config for bus=%u.\n",
+ __func__, p->gspi_bus);
+ return -1;
+ }
+
+ /* Take controller out of reset, keeping DMA in reset. */
+ gspi_write_mmio_reg(p, RESETS, CTRLR_ACTIVE | DMA_RESET);
+
+ /* De-assert chip select. */
+ __gspi_cs_change(p, CS_DEASSERT);
+
+ /*
+ * CS control:
+ * - Set SW mode.
+ * - Set chip select to 0.
+ * - Set polarity based on device configuration.
+ * - Do not assert CS.
+ */
+ cs_ctrl = CS_MODE_SW | CS_0;
+ if (cfg.cs_polarity == SPI_POLARITY_LOW)
+ cs_ctrl |= CS_POLARITY_LOW | CS_STATE_HIGH;
+ else
+ cs_ctrl |= CS_POLARITY_HIGH | CS_STATE_LOW;
+ gspi_write_mmio_reg(p, SPI_CS_CONTROL, cs_ctrl);
+
+ /* Disable SPI controller. */
+ gspi_write_mmio_reg(p, SSCR0, SSCR0_SSE_DISABLE);
+
+ /*
+ * SSCR0 configuration:
+ * clk_div - Based on reference clock and expected clock frequency.
+ * data bit length - assumed to be 8, hence EDSS = 0.
+ * ECS - Use on-chip clock
+ * FRF - Frame format set to Motorola SPI
+ */
+ sscr0 = gspi_get_clk_div(p->gspi_bus) << SSCR0_SCR_SHIFT;
+ assert(GSPI_DATA_BIT_LENGTH == 8);
+ sscr0 |= ((GSPI_DATA_BIT_LENGTH - 1) << SSCR0_DSS_SHIFT) | SSCR0_EDSS_0;
+ sscr0 |= SSCR0_ECS_ON_CHIP | SSCR0_FRF_MOTOROLA;
+ gspi_write_mmio_reg(p, SSCR0, sscr0);
+
+ /*
+ * SSCR1 configuration:
+ * - Chip select polarity
+ * - Clock phase setting
+ * - Clock polarity
+ */
+ sscr1 = (cfg.cs_polarity == SPI_POLARITY_LOW) ? SSCR1_IFS_LOW :
+ SSCR1_IFS_HIGH;
+ sscr1 |= (cfg.clk_phase == SPI_CLOCK_PHASE_FIRST) ? SSCR1_SPH_FIRST :
+ SSCR1_SPH_SECOND;
+ sscr1 |= (cfg.clk_polarity == SPI_POLARITY_LOW) ? SSCR1_SPO_LOW :
+ SSCR1_SPO_HIGH;
+ gspi_write_mmio_reg(p, SSCR1, sscr1);
+
+ /*
+ * Program m/n divider.
+ * Set m and n to 1, so that this divider acts as a pass-through.
+ */
+ clocks = (1 << CLOCKS_N_SHIFT) | (1 << CLOCKS_M_SHIFT) | CLOCKS_ENABLE;
+ gspi_write_mmio_reg(p, CLOCKS, clocks);
+ udelay(10);
+
+ /*
+ * Tx FIFO Threshold.
+ * Low watermark threshold = 1
+ * High watermark threshold = 1
+ */
+ sitf = SITF_LWM(1) | SITF_HWM(1);
+ gspi_write_mmio_reg(p, SITF, sitf);
+
+ /* Rx FIFO Threshold (set to 1). */
+ sirf = SIRF_WM(1);
+ gspi_write_mmio_reg(p, SIRF, sirf);
+
+ /* Enable GSPI controller. */
+ sscr0 |= SSCR0_SSE_ENABLE;
+ gspi_write_mmio_reg(p, SSCR0, sscr0);
+
+ return 0;
+}
+
+static uint32_t gspi_read_status(const struct gspi_ctrlr_params *p)
+{
+ return gspi_read_mmio_reg(p, SSSR);
+}
+
+static void gspi_clear_status(const struct gspi_ctrlr_params *p)
+{
+ const uint32_t sssr = SSSR_TUR | SSSR_TINT | SSSR_PINT | SSSR_ROR;
+ gspi_write_mmio_reg(p, SSSR, sssr);
+}
+
+static bool gspi_rx_fifo_empty(const struct gspi_ctrlr_params *p)
+{
+ return !(gspi_read_status(p) & SSSR_RNE);
+}
+
+static bool gspi_tx_fifo_full(const struct gspi_ctrlr_params *p)
+{
+ return !(gspi_read_status(p) & SSSR_TNF);
+}
+
+static bool gspi_rx_fifo_overrun(const struct gspi_ctrlr_params *p)
+{
+ if (gspi_read_status(p) & SSSR_ROR) {
+ printk(BIOS_ERR, "%s:GSPI receive FIFO overrun!"
+ " (bus=%u).\n", __func__, p->gspi_bus);
+ return true;
+ }
+
+ return false;
+}
+
+/* Read SSDR and return lowest byte. */
+static uint8_t gspi_read_byte(const struct gspi_ctrlr_params *p)
+{
+ return gspi_read_mmio_reg(p, SSDR) & 0xFF;
+}
+
+/* Write 32-bit word with "data" in lowest byte to SSDR. */
+static void gspi_write_byte(const struct gspi_ctrlr_params *p, uint8_t data)
+{
+ return gspi_write_mmio_reg(p, SSDR, data);
+}
+
+static void gspi_read_data(struct gspi_ctrlr_params *p)
+{
+ *(p->in) = gspi_read_byte(p);
+ p->in++;
+ p->bytesin--;
+}
+
+static void gspi_write_data(struct gspi_ctrlr_params *p)
+{
+ gspi_write_byte(p, *(p->out));
+ p->out++;
+ p->bytesout--;
+}
+
+static void gspi_read_dummy(struct gspi_ctrlr_params *p)
+{
+ gspi_read_byte(p);
+ p->bytesin--;
+}
+
+static void gspi_write_dummy(struct gspi_ctrlr_params *p)
+{
+ gspi_write_byte(p, 0);
+ p->bytesout--;
+}
+
+static int gspi_ctrlr_flush(const struct gspi_ctrlr_params *p)
+{
+ const uint32_t timeout_ms = 500;
+ struct stopwatch sw;
+
+ /* Wait 500ms to allow Rx FIFO to be empty. */
+ stopwatch_init_msecs_expire(&sw, timeout_ms);
+
+ while (!gspi_rx_fifo_empty(p)) {
+ if (stopwatch_expired(&sw)) {
+ printk(BIOS_ERR, "%s: Rx FIFO not empty after 500ms! "
+ "(bus=%u)\n", __func__, p->gspi_bus);
+ return -1;
+ }
+
+ gspi_read_byte(p);
+ }
+
+ return 0;
+}
+
+static int __gspi_xfer(struct gspi_ctrlr_params *p)
+{
+ /*
+ * If bytesin is non-zero, then use gspi_read_data to perform
+ * byte-by-byte read of data from SSDR and save it to "in" buffer. Else
+ * discard the read data using gspi_read_dummy.
+ */
+ void (*fn_read)(struct gspi_ctrlr_params *p) = gspi_read_data;
+
+ /*
+ * If bytesout is non-zero, then use gspi_write_data to perform
+ * byte-by-byte write of data from "out" buffer to SSDR. Else, use
+ * gspi_write_dummy to write dummy "0" data to SSDR in order to trigger
+ * read from slave.
+ */
+ void (*fn_write)(struct gspi_ctrlr_params *p) = gspi_write_data;
+
+ if (!p->bytesin) {
+ p->bytesin = p->bytesout;
+ fn_read = gspi_read_dummy;
+ }
+
+ if (!p->bytesout) {
+ p->bytesout = p->bytesin;
+ fn_write = gspi_write_dummy;
+ }
+
+ while (p->bytesout || p->bytesin) {
+ if (p->bytesout && !gspi_tx_fifo_full(p))
+ fn_write(p);
+ if (p->bytesin && !gspi_rx_fifo_empty(p)) {
+ if (gspi_rx_fifo_overrun(p))
+ return -1;
+ fn_read(p);
+ }
+ }
+
+ return 0;
+}
+
+static int gspi_ctrlr_xfer(const struct spi_slave *dev,
+ const void *dout, size_t bytesout,
+ void *din, size_t bytesin)
+{
+ struct gspi_ctrlr_params params;
+ struct gspi_ctrlr_params *p = &params;
+
+ /*
+ * Assumptions about in and out transfers:
+ * 1. Both bytesin and bytesout cannot be 0.
+ * 2. If both bytesin and bytesout are non-zero, then they should be
+ * equal i.e. if both in and out transfers are to be done in same
+ * transaction, then they should be equal in length.
+ * 3. Buffer corresponding to non-zero bytes (bytesin/bytesout) cannot
+ * be NULL.
+ */
+ if (!bytesin && !bytesout) {
+ printk(BIOS_ERR, "%s: Both in and out bytes cannot be zero!\n",
+ __func__);
+ return -1;
+ } else if (bytesin && bytesout && (bytesin != bytesout)) {
+ printk(BIOS_ERR, "%s: bytesin(%zd) != bytesout(%zd)\n",
+ __func__, bytesin, bytesout);
+ return -1;
+ }
+ if ((bytesin && !din) || (bytesout && !dout)) {
+ printk(BIOS_ERR, "%s: in/out buffer is NULL!\n", __func__);
+ return -1;
+ }
+
+ if (gspi_ctrlr_params_init(p, dev->bus))
+ return -1;
+
+ /* Flush out any stale data in Rx FIFO. */
+ if (gspi_ctrlr_flush(p))
+ return -1;
+
+ /* Clear status bits. */
+ gspi_clear_status(p);
+
+ p->in = din;
+ p->bytesin = bytesin;
+ p->out = dout;
+ p->bytesout = bytesout;
+
+ return __gspi_xfer(p);
+}
+
+const struct spi_ctrlr gspi_ctrlr = {
+ .get_config = gspi_ctrlr_get_config,
+ .claim_bus = gspi_cs_assert,
+ .release_bus = gspi_cs_deassert,
+ .setup = gspi_ctrlr_setup,
+ .xfer = gspi_ctrlr_xfer,
+};