[PATCH v2 1/3] bsps/xilinx_zynq: Add SPI driver for cadence-spi

Jan Sommer jan.sommer at dlr.de
Sat Feb 13 14:19:11 UTC 2021


---
 bsps/include/dev/spi/cadence-spi-regs.h |  84 +++++
 bsps/include/dev/spi/cadence-spi.h      |  48 +++
 bsps/shared/dev/spi/cadence-spi.c       | 437 ++++++++++++++++++++++++
 3 files changed, 569 insertions(+)
 create mode 100644 bsps/include/dev/spi/cadence-spi-regs.h
 create mode 100644 bsps/include/dev/spi/cadence-spi.h
 create mode 100644 bsps/shared/dev/spi/cadence-spi.c

diff --git a/bsps/include/dev/spi/cadence-spi-regs.h b/bsps/include/dev/spi/cadence-spi-regs.h
new file mode 100644
index 0000000000..2851c88df1
--- /dev/null
+++ b/bsps/include/dev/spi/cadence-spi-regs.h
@@ -0,0 +1,84 @@
+/* SPDX-License-Identifier: BSD-2-Clause */
+
+/*
+ * Copyright (C) 2020 Jan Sommer, Deutsches Zentrum für Luft- und Raumfahrt e. V. (DLR)
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ * 1. Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ *    notice, this list of conditions and the following disclaimer in the
+ *    documentation and/or other materials provided with the distribution.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
+ * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
+ * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
+ * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
+ * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ */
+
+#ifndef LIBBSP_ARM_XILINX_ZYNQ_CADENCE_SPI_REGS_H
+#define LIBBSP_ARM_XILINX_ZYNQ_CADENCE_SPI_REGS_H
+
+#include <bsp/utility.h>
+
+typedef struct {
+    uint32_t config;
+#define CADENCE_SPI_CONFIG_MODEFAIL_EN BSP_BIT32(17)
+#define CADENCE_SPI_CONFIG_MANSTRT BSP_BIT32(16)
+#define CADENCE_SPI_CONFIG_MANSTRT_EN BSP_BIT32(15)
+#define CADENCE_SPI_CONFIG_MANUAL_CS BSP_BIT32(14)
+#define CADENCE_SPI_CONFIG_CS(val) BSP_FLD32(val, 10, 13)
+#define CADENCE_SPI_CONFIG_CS_GET(reg) BSP_FLD32GET(reg, 10, 13)
+#define CADENCE_SPI_CONFIG_CS_SET(reg, val) BSP_FLD32SET(reg, val, 10, 13)
+#define CADENCE_SPI_CONFIG_PERI_SEL BSP_BIT32(9)
+#define CADENCE_SPI_CONFIG_REF_CLK BSP_BIT32(8)
+#define CADENCE_SPI_CONFIG_BAUD_DIV(val) BSP_FLD32(val, 3, 5)
+#define CADENCE_SPI_CONFIG_BAUD_DIV_GET(reg) BSP_FLD32GET(reg, 3, 5)
+#define CADENCE_SPI_CONFIG_BAUD_DIV_SET(reg, val) BSP_FLD32SET(reg, val, 3, 5)
+#define CADENCE_SPI_CONFIG_CLK_PH BSP_BIT32(2)
+#define CADENCE_SPI_CONFIG_CLK_POL BSP_BIT32(1)
+#define CADENCE_SPI_CONFIG_MSTREN BSP_BIT32(0)
+	uint32_t irqstatus;
+	uint32_t irqenable;
+	uint32_t irqdisable;
+	uint32_t irqmask;
+#define CADENCE_SPI_IXR_TXUF BSP_BIT32(6)
+#define CADENCE_SPI_IXR_RXFULL BSP_BIT32(5)
+#define CADENCE_SPI_IXR_RXNEMPTY BSP_BIT32(4)
+#define CADENCE_SPI_IXR_TXFULL BSP_BIT32(3)
+#define CADENCE_SPI_IXR_TXOW BSP_BIT32(2)
+#define CADENCE_SPI_IXR_MODF BSP_BIT32(1)
+#define CADENCE_SPI_IXR_RXOVR BSP_BIT32(0)
+    uint32_t spienable;
+#define CADENCE_SPI_EN BSP_BIT32(0)
+    uint32_t delay;
+#define CADENCE_SPI_DELAY_DNSS(val) BSP_FLD32(val, 24, 31)
+#define CADENCE_SPI_DELAY_DNSS_GET(reg) BSP_FLD32GET(reg, 24, 31)
+#define CADENCE_SPI_DELAY_DNSS_SET(reg, val) BSP_FLD32SET(reg, val, 24, 31)
+#define CADENCE_SPI_DELAY_DBTWN(val) BSP_FLD32(val, 16, 23)
+#define CADENCE_SPI_DELAY_DBTWN_GET(reg) BSP_FLD32GET(reg, 16, 23)
+#define CADENCE_SPI_DELAY_DBTWN_SET(reg, val) BSP_FLD32SET(reg, val, 16, 23)
+#define CADENCE_SPI_DELAY_DAFTER(val) BSP_FLD32(val, 8, 15)
+#define CADENCE_SPI_DELAY_DAFTER_GET(reg) BSP_FLD32GET(reg, 8, 15)
+#define CADENCE_SPI_DELAY_DAFTER_SET(reg, val) BSP_FLD32SET(reg, val, 8, 15)
+#define CADENCE_SPI_DELAY_DINT(val) BSP_FLD32(val, 0, 7)
+#define CADENCE_SPI_DELAY_DINT_GET(reg) BSP_FLD32GET(reg, 0, 7)
+#define CADENCE_SPI_DELAY_DINT_SET(reg, val) BSP_FLD32SET(reg, val, 0, 7)
+	uint32_t txdata;
+	uint32_t rxdata;
+	uint32_t slave_idle_count;
+	uint32_t txthreshold;
+	uint32_t rxthreshold;
+	uint32_t moduleid;
+} cadence_spi;
+
+#endif /* LIBBSP_ARM_XILINX_ZYNQ_CADENCE_SPI_REGS_H */
diff --git a/bsps/include/dev/spi/cadence-spi.h b/bsps/include/dev/spi/cadence-spi.h
new file mode 100644
index 0000000000..7d7ecd3885
--- /dev/null
+++ b/bsps/include/dev/spi/cadence-spi.h
@@ -0,0 +1,48 @@
+/* SPDX-License-Identifier: BSD-2-Clause */
+
+/*
+ * Copyright (C) 2020 Jan Sommer, Deutsches Zentrum für Luft- und Raumfahrt e. V. (DLR)
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ * 1. Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ *    notice, this list of conditions and the following disclaimer in the
+ *    documentation and/or other materials provided with the distribution.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
+ * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
+ * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
+ * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
+ * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ */
+
+#ifndef LIBBSP_ARM_XILINX_ZYNQ_CADENCE_SPI_H
+#define LIBBSP_ARM_XILINX_ZYNQ_CADENCE_SPI_H
+
+#include <rtems.h>
+
+#ifdef __cplusplus
+extern "C" {
+#endif /* __cplusplus */
+
+int spi_bus_register_cadence(
+  const char *bus_path,
+  uintptr_t register_base,
+  uint32_t input_clock,
+  rtems_vector_number irq
+);
+
+#ifdef __cplusplus
+}
+#endif /* __cplusplus */
+
+#endif /* LIBBSP_ARM_XILINX_ZYNQ_CADENCE_SPI_H */
diff --git a/bsps/shared/dev/spi/cadence-spi.c b/bsps/shared/dev/spi/cadence-spi.c
new file mode 100644
index 0000000000..cf09a9d8fe
--- /dev/null
+++ b/bsps/shared/dev/spi/cadence-spi.c
@@ -0,0 +1,437 @@
+/* SPDX-License-Identifier: BSD-2-Clause */
+
+/*
+ * Copyright (C) 2020 Jan Sommer, Deutsches Zentrum für Luft- und Raumfahrt e. V. (DLR)
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ * 1. Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ *    notice, this list of conditions and the following disclaimer in the
+ *    documentation and/or other materials provided with the distribution.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
+ * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
+ * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
+ * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
+ * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ */
+
+
+#include <bsp.h>
+
+#include <rtems/irq-extension.h>
+#include <sys/param.h> /* MAX() */
+
+#include <dev/spi/spi.h>
+#include <dev/spi/cadence-spi.h>
+#include <dev/spi/cadence-spi-regs.h>
+
+#define CADENCE_SPI_FIFO_SIZE 128
+#define CADENCE_SPI_MAX_CHIPSELECTS 3
+#define CADENCE_SPI_CS_NONE 0xF
+
+typedef struct cadence_spi_bus cadence_spi_bus;
+
+struct cadence_spi_bus {
+  spi_bus base;
+  volatile cadence_spi *regs;
+  uint32_t clk_in;
+  uint16_t clk_per_usecs;
+  uint32_t msg_todo;
+  const spi_ioc_transfer *msg;
+  uint32_t todo;
+  uint32_t in_transfer;
+  uint8_t *rx_buf;
+  const uint8_t *tx_buf;
+  rtems_id task_id;
+  rtems_vector_number irq;
+};
+
+
+static void cadence_spi_disable_interrupts(volatile cadence_spi *regs)
+{
+  regs->irqdisable = 0xffff;
+}
+
+static void cadence_spi_clear_irq_status(volatile cadence_spi *regs)
+{
+  regs->irqstatus = regs->irqstatus;
+}
+
+static bool cadence_spi_rx_fifo_not_empty(volatile cadence_spi *regs)
+{
+  return (regs->irqstatus & CADENCE_SPI_IXR_RXNEMPTY) != 0;
+}
+
+static void cadence_spi_reset(cadence_spi_bus *bus)
+{
+  volatile cadence_spi *regs = bus->regs;
+  uint32_t val;
+
+  cadence_spi_disable_interrupts(regs);
+
+  regs->spienable = 0;
+
+  val = regs->config;
+  val &= ~(CADENCE_SPI_CONFIG_MODEFAIL_EN
+         | CADENCE_SPI_CONFIG_MANSTRT_EN
+         | CADENCE_SPI_CONFIG_MANUAL_CS
+         | CADENCE_SPI_CONFIG_PERI_SEL
+         | CADENCE_SPI_CONFIG_REF_CLK);
+
+  val |= CADENCE_SPI_CONFIG_CS(CADENCE_SPI_CS_NONE)
+    | CADENCE_SPI_CONFIG_MSTREN
+    | CADENCE_SPI_CONFIG_MANSTRT;
+  regs->config = val;
+
+  /* Initialize here, will be set for every transfer */
+  regs->txthreshold = 1;
+  /* Set to 1, so we can check when the rx buffer is empty */
+  regs->rxthreshold = 1;
+
+  while (cadence_spi_rx_fifo_not_empty(regs)) {
+    regs->rxdata;
+  }
+  cadence_spi_clear_irq_status(regs);
+}
+
+static void cadence_spi_done(cadence_spi_bus *bus)
+{
+  volatile cadence_spi *regs = bus->regs;
+  regs->spienable = 0;
+  cadence_spi_disable_interrupts(regs);
+  cadence_spi_clear_irq_status(regs);
+  rtems_event_transient_send(bus->task_id);
+}
+
+static void cadence_spi_push(cadence_spi_bus *bus, volatile cadence_spi *regs)
+{
+  while (bus->todo > 0 && bus->in_transfer < CADENCE_SPI_FIFO_SIZE) {
+    uint8_t val = 0;
+    if (bus->tx_buf != NULL) {
+        val = *bus->tx_buf;
+        ++bus->tx_buf;
+    }
+
+    --bus->todo;
+    regs->txdata = val;
+    ++bus->in_transfer;
+  }
+}
+
+static void
+cadence_spi_set_chipsel(cadence_spi_bus *bus, uint32_t cs)
+{
+
+   volatile cadence_spi *regs = bus->regs;
+   uint32_t cs_bit = CADENCE_SPI_CS_NONE;
+   uint32_t config = regs->config;
+
+  if (cs != SPI_NO_CS && cs < CADENCE_SPI_MAX_CHIPSELECTS) {
+      cs_bit >>= (CADENCE_SPI_MAX_CHIPSELECTS - cs);
+  }
+  config = CADENCE_SPI_CONFIG_CS_SET(config, cs_bit);
+
+  regs->config = config;
+}
+
+static uint32_t
+cadence_spi_baud_divider(cadence_spi_bus *bus, 
+                uint32_t speed_hz)
+{
+  uint32_t div;
+  uint32_t clk_in;
+
+  clk_in = bus->clk_in;
+
+  div = clk_in / speed_hz;
+  div = fls((int) div);
+
+  if (clk_in > (speed_hz << div)) {
+      ++div;
+  }
+
+  /* The baud divider needs to be at least 4, i.e. 2^2 */
+  div = MAX(2, div);
+  
+  /* 0b111 is the maximum possible divider value */
+  div =  MIN(7, div-1);
+  return div;
+}
+
+static void cadence_spi_config(
+  cadence_spi_bus *bus,
+  volatile cadence_spi *regs,
+  uint32_t speed_hz,
+  uint32_t mode,
+  uint16_t delay_usecs,
+  uint8_t  cs
+)
+{
+  spi_bus *base = &bus->base;
+  uint32_t config = regs->config;
+  uint32_t delay;
+
+  regs->spienable = 0;
+  
+  if ((mode & SPI_CPHA) != 0) {
+    config |= CADENCE_SPI_CONFIG_CLK_PH;
+  } else {
+    config &= ~CADENCE_SPI_CONFIG_CLK_PH;
+  }
+
+  if ((mode & SPI_CPOL) != 0) {
+    config |= CADENCE_SPI_CONFIG_CLK_POL;
+  } else {
+    config &= ~CADENCE_SPI_CONFIG_CLK_POL;
+  }
+
+  config = CADENCE_SPI_CONFIG_BAUD_DIV_SET(config,
+          cadence_spi_baud_divider(bus, speed_hz));
+
+  regs->config = config;
+  cadence_spi_set_chipsel(bus, cs);
+
+  delay = regs->delay;
+  delay = CADENCE_SPI_DELAY_DBTWN_SET(delay, delay_usecs * bus->clk_per_usecs);
+  regs->delay = delay;
+
+  base->speed_hz = speed_hz;
+  base->mode = mode;
+  base->cs = cs;
+
+}
+
+static void
+cadence_spi_next_msg(cadence_spi_bus *bus, volatile cadence_spi *regs)
+{
+  if (bus->msg_todo > 0) {
+    const spi_ioc_transfer *msg;
+    spi_bus *base = &bus->base;
+
+    msg = bus->msg;
+
+    if (
+      msg->speed_hz != base->speed_hz
+        || msg->mode != base->mode
+        || msg->cs != base->cs
+    ) {
+      cadence_spi_config(
+        bus,
+        regs,
+        msg->speed_hz,
+        msg->mode,
+        msg->delay_usecs,
+        msg->cs
+      );
+    }
+
+    if ((msg->mode & SPI_NO_CS) != 0) {
+      cadence_spi_set_chipsel(bus, CADENCE_SPI_CS_NONE);
+    }
+
+    bus->todo = msg->len;
+    bus->rx_buf = msg->rx_buf;
+    bus->tx_buf = msg->tx_buf;
+    cadence_spi_push(bus, regs);
+    
+    cadence_spi_disable_interrupts(regs);
+    if (bus->todo < CADENCE_SPI_FIFO_SIZE) {
+        /* if the msg fits into the FIFO for empty TX buffer */
+        regs->txthreshold = 1;
+
+    } else {
+        /* if the msg does not fit refill tx_buf when the threshold is hit */
+        regs->txthreshold = CADENCE_SPI_FIFO_SIZE / 2;
+    }
+    regs->irqenable = CADENCE_SPI_IXR_TXOW;
+    regs->spienable = 1;
+  } else {
+    cadence_spi_done(bus);
+  }
+}
+
+static void cadence_spi_interrupt(void *arg)
+{
+  cadence_spi_bus *bus;
+  volatile cadence_spi *regs;
+
+  bus = arg;
+  regs = bus->regs;
+
+  while (cadence_spi_rx_fifo_not_empty(regs)) {
+    uint32_t val = regs->rxdata;
+    if (bus->rx_buf != NULL) {
+        *bus->rx_buf = (uint8_t)val;
+        ++bus->rx_buf;
+    }
+    --bus->in_transfer;
+  }
+
+  if (bus->todo > 0) {
+    cadence_spi_push(bus, regs);
+  } else if (bus->in_transfer > 0) {
+    /* Wait until all bytes have been transfered */
+    regs->txthreshold = 1;
+  } else {
+    --bus->msg_todo;
+    ++bus->msg;
+    cadence_spi_next_msg(bus, regs);
+  }
+}
+
+static int cadence_spi_check_messages(
+  cadence_spi_bus *bus,
+  const spi_ioc_transfer *msg,
+  uint32_t size)
+{
+  while(size > 0) {
+    if (msg->bits_per_word != 8) {
+      return -EINVAL;
+    }
+    if ((msg->mode &
+        ~(SPI_CPHA | SPI_CPOL | SPI_NO_CS)) != 0) {
+      return -EINVAL;
+    }
+    if ((msg->mode & SPI_NO_CS) == 0 &&
+        (msg->cs > CADENCE_SPI_MAX_CHIPSELECTS)) {
+      return -EINVAL;
+    }
+
+    ++msg;
+    --size;
+  }
+
+  return 0;
+}
+
+static int cadence_spi_transfer(
+  spi_bus *base,
+  const spi_ioc_transfer *msgs,
+  uint32_t n
+)
+{
+  cadence_spi_bus *bus;
+  int rv;
+
+  bus = (cadence_spi_bus *) base;
+
+  rv = cadence_spi_check_messages(bus, msgs, n);
+
+  if (rv == 0) {
+    bus->msg_todo = n;
+    bus->msg = &msgs[0];
+    bus->task_id = rtems_task_self();
+
+    cadence_spi_next_msg(bus, bus->regs);
+    rtems_event_transient_receive(RTEMS_WAIT, RTEMS_NO_TIMEOUT);
+    cadence_spi_set_chipsel(bus, CADENCE_SPI_CS_NONE);
+  }
+  return rv;
+}
+
+static void cadence_spi_destroy(spi_bus *base)
+{
+  cadence_spi_bus *bus;
+
+  bus = (cadence_spi_bus *) base;
+  rtems_interrupt_handler_remove(bus->irq, cadence_spi_interrupt, bus);
+  spi_bus_destroy_and_free(&bus->base);
+}
+
+static int cadence_spi_setup(spi_bus *base)
+{
+  cadence_spi_bus *bus;
+  uint32_t mode = base->mode;
+
+  bus = (cadence_spi_bus *) base;
+
+  /* Baud rate divider is at least 4 and at most 256 */
+  if (
+    base->speed_hz > base->max_speed_hz
+      || base->speed_hz < (bus->clk_in / 256)
+      || bus->base.bits_per_word > 8
+  ) {
+    return -EINVAL;
+  }
+
+  /* SPI_CS_HIGH and SPI_LOOP not supported */
+  if ((mode & SPI_CS_HIGH) || (mode & SPI_LOOP)) {
+      return -EINVAL;
+  }
+
+  cadence_spi_config(
+    bus,
+    bus->regs,
+    base->speed_hz,
+    base->mode,
+    base->delay_usecs,
+    base->cs
+  );
+  return 0;
+}
+
+int spi_bus_register_cadence(const char *bus_path,
+        uintptr_t register_base,
+        uint32_t input_clock,
+        rtems_vector_number irq)
+{
+  cadence_spi_bus *bus;
+  spi_bus *base;
+  int sc;
+
+  bus = (cadence_spi_bus *) spi_bus_alloc_and_init(sizeof(*bus));
+  if (bus == NULL){
+    return -1;
+  }
+
+  base = &bus->base;
+  bus->regs = (volatile cadence_spi *) register_base;
+  bus->clk_in = input_clock;
+  bus->clk_per_usecs = input_clock / 1000000;
+  bus->irq = irq;
+
+  /* The minimum clock divider is 4 */
+  base->max_speed_hz = (input_clock + 3) / 4;
+  base->delay_usecs = 0;
+  base->speed_hz = base->max_speed_hz;
+  base->cs = SPI_NO_CS;
+
+  cadence_spi_reset(bus);
+  cadence_spi_config(
+    bus,
+    bus->regs,
+    base->speed_hz,
+    base->mode,
+    base->delay_usecs,
+    base->cs
+    );
+
+
+  sc = rtems_interrupt_handler_install(
+    bus->irq,
+    "CASPI",
+    RTEMS_INTERRUPT_UNIQUE,
+    cadence_spi_interrupt,
+    bus
+  );
+  if (sc != RTEMS_SUCCESSFUL) {
+    (*bus->base.destroy)(&bus->base);
+    rtems_set_errno_and_return_minus_one(EAGAIN);
+  }
+
+  bus->base.transfer = cadence_spi_transfer;
+  bus->base.destroy = cadence_spi_destroy;
+  bus->base.setup = cadence_spi_setup;
+
+  return spi_bus_register(&bus->base, bus_path);
+}
-- 
2.17.1



More information about the devel mailing list