Page MenuHomeFreeBSD

D45211.id139697.diff
No OneTemporary

D45211.id139697.diff

diff --git a/sys/arm/arm/pl022.h b/sys/arm/arm/pl022.h
new file mode 100644
--- /dev/null
+++ b/sys/arm/arm/pl022.h
@@ -0,0 +1,88 @@
+/*-
+ * Copyright (c) 2019, Juniper Networks, Inc.
+ * All rights reserved.
+ *
+ * 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 AUTHOR 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 AUTHOR 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 __ARM_PL022_H__
+#define __ARM_PL022_H__
+
+#define PL022_SSP_CR0 0x00
+#define PL022_SSP_CR0_DSS(_n) ((_n-1) & 0xf)
+#define PL022_SSP_CR0_TI (1 << 4)
+#define PL022_SSP_CR0_MICROWIRE (1 << 5)
+#define PL022_SSP_CR0_CPOL (1 << 6)
+#define PL022_SSP_CR0_CPHA (1 << 7)
+#define PL022_SSP_CR0_SCR(_n) ((_n & 0xff) << 8)
+#define PL022_SSP_CR1 0x04
+#define PL022_SSP_CR1_LBM (1 << 0)
+#define PL022_SSP_CR1_SSE (1 << 1)
+#define PL022_SSP_CR1_MS (1 << 2)
+#define PL022_SSP_CR1_SOD (1 << 3)
+#define PL022_SSP_DR 0x08
+#define PL022_SSP_SR 0x0c
+#define PL022_SSP_SR_TFE (1 << 0)
+#define PL022_SSP_SR_TNF (1 << 1)
+#define PL022_SSP_SR_RNE (1 << 2)
+#define PL022_SSP_SR_RFF (1 << 3)
+#define PL022_SSP_SR_BSY (1 << 4)
+#define PL022_SSP_CPSR 0x10
+#define PL022_SSP_IMSC 0x14
+#define PL022_SSP_IMSC_RORIM (1 << 0)
+#define PL022_SSP_IMSC_RTIM (1 << 1)
+#define PL022_SSP_IMSC_RXIM (1 << 2)
+#define PL022_SSP_IMSC_TXIM (1 << 3)
+#define PL022_SSP_RIS 0x18
+#define PL022_SSP_RIS_RORRIS (1 << 0)
+#define PL022_SSP_RIS_RTRIS (1 << 1)
+#define PL022_SSP_RIS_RXRIS (1 << 2)
+#define PL022_SSP_RIS_TXRIS (1 << 3)
+#define PL022_SSP_MIS 0x1c
+#define PL022_SSP_ICR 0x20
+#define PL022_SSP_DMACR 0x24
+#define PL022_SSPPERIPHID0 0xfe0
+#define PL022_SSPPERIPHID1 0xfe4
+#define PL022_SSPPERIPHID2 0xfe8
+#define PL022_SSPPERIPHID3 0xfec
+#define PL022_SSPPCELLID0 0xff0
+#define PL022_SSPPCELLID1 0xff4
+#define PL022_SSPPCELLID2 0xff8
+#define PL022_SSPPCELLID3 0xffc
+
+/*
+ * SSP Clock Defaults
+ */
+
+#define PL022_SSP_DEFAULT_CLKRATE 0x2
+#define PL022_SSP_DEFAULT_PRESCALE 0x40
+
+/*
+ * SSP Clock Parameter ranges
+ */
+
+#define CPSDVR_MIN 0x02
+#define CPSDVR_MAX 0xFE
+#define SCR_MIN 0x00
+#define SCR_MAX 0xFF
+
+#endif /* __ARM_PL022_H__ */
diff --git a/sys/arm/arm/pl022.c b/sys/arm/arm/pl022.c
new file mode 100644
--- /dev/null
+++ b/sys/arm/arm/pl022.c
@@ -0,0 +1,556 @@
+/*-
+ * Copyright (c) 2019, Juniper Networks, Inc.
+ * All rights reserved.
+ *
+ * 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 AUTHOR 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 AUTHOR 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 <sys/cdefs.h>
+__FBSDID("$FreeBSD$");
+
+#include <sys/param.h>
+#include <sys/systm.h>
+#include <sys/bio.h>
+#include <sys/bus.h>
+#include <sys/conf.h>
+#include <sys/endian.h>
+#include <sys/kernel.h>
+#include <sys/kthread.h>
+#include <sys/lock.h>
+#include <sys/malloc.h>
+#include <sys/module.h>
+#include <sys/mutex.h>
+#include <sys/queue.h>
+#include <sys/resource.h>
+#include <sys/rman.h>
+#include <sys/time.h>
+#include <sys/timetc.h>
+#include <sys/watchdog.h>
+
+#include <machine/bus.h>
+#include <machine/resource.h>
+#include <machine/intr.h>
+
+#include <dev/spibus/spi.h>
+#include <dev/spibus/spibusvar.h>
+#include <dev/ofw/ofw_bus.h>
+#include <dev/ofw/ofw_bus_subr.h>
+
+#include <dev/clk/clk.h>
+
+#include <dev/gpio/gpiobusvar.h>
+
+
+#include "spibus_if.h"
+#include "pl022.h"
+
+static struct ofw_compat_data compat_data[] = {
+ { "arm,pl022", 1 },
+ { NULL, 0 }
+};
+
+static struct resource_spec pl022_spec[] = {
+ { SYS_RES_MEMORY, 0, RF_ACTIVE },
+ { SYS_RES_IRQ, 0, RF_ACTIVE | RF_SHAREABLE },
+ { -1, 0 }
+};
+
+#define PL022_BUSY 0x1
+
+struct pl022_softc {
+ device_t sc_dev;
+ device_t sc_bus;
+ device_t sc_gpio;
+ struct thread *sc_owntd;
+ clk_t sc_sspclk;
+ struct resource *res[2];
+ struct mtx sc_mtx;
+ uint64_t sc_modfreq;
+ void * sc_cookie;
+ struct spi_command *sc_cmd;
+ uint32_t sc_len;
+ uint32_t sc_read;
+ uint32_t sc_flags;
+ uint32_t sc_written;
+ bool sc_ignore_cs;
+};
+
+#define PL022_LOCK(sc) mtx_lock(&(sc)->sc_mtx)
+#define PL022_UNLOCK(sc) mtx_unlock(&(sc)->sc_mtx)
+#define PL022_ASSERT_LOCKED(sc) mtx_assert(&(sc)->sc_mtx, MA_OWNED)
+#define PL022_READ_1(sc, reg) bus_read_1((sc)->res[0], (reg))
+#define PL022_WRITE_1(sc, reg, val) bus_write_1((sc)->res[0], \
+ (reg), (val))
+#define PL022_READ_2(sc, reg) bus_read_2((sc)->res[0], (reg))
+#define PL022_WRITE_2(sc, reg, val) bus_write_2((sc)->res[0], \
+ (reg), (val))
+#define PL022_READ_4(sc, reg) bus_read_4((sc)->res[0], (reg))
+#define PL022_WRITE_4(sc, reg, val) bus_write_4((sc)->res[0], \
+ (reg), (val))
+
+static int pl022_probe(device_t);
+static int pl022_attach(device_t);
+static int pl022_detach(device_t);
+static void pl022_intr(void *arg);
+static int pl022_transfer(device_t, device_t, struct spi_command *);
+
+static phandle_t
+pl022_get_node(device_t bus, device_t dev)
+{
+ /* Share controller node with spibus device */
+ return (ofw_bus_get_node(bus));
+}
+
+/* CS assert is active low, so invert. */
+static void
+pl022_assert_cs(struct pl022_softc *sc, uint32_t cs,
+ bool enable)
+{
+ if (!sc->sc_ignore_cs)
+ GPIO_PIN_SET(sc->sc_gpio, cs, !enable);
+}
+
+static inline uint32_t
+pl022_rate(uint32_t rate, uint16_t cpsdvsr, uint16_t scr)
+{
+ return (rate / (cpsdvsr * (1 + scr)));
+}
+
+static void
+pl022_calculate_effective_freq(struct pl022_softc *sc,
+ uint64_t freq, uint16_t * cr0scr, uint8_t * cpsrcpsdvr )
+{
+ /* Lets calculate the frequency parameters */
+ uint16_t cpsdvsr = CPSDVR_MIN, scr = SCR_MIN;
+ uint32_t rate, max_tclk, min_tclk, best_freq = 0;
+ uint32_t best_scr = 0, tmp, found = 0, best_cpsdvsr = 0;
+
+ rate = (uint32_t)sc->sc_modfreq;
+
+ /* cpsdvscr = 2 & scr 0 */
+ max_tclk = pl022_rate(rate, CPSDVR_MIN, SCR_MIN);
+ /* cpsdvsr = 254 & scr = 255 */
+ min_tclk = pl022_rate(rate, CPSDVR_MAX, SCR_MAX);
+
+ if (freq > max_tclk)
+ device_printf(sc->sc_dev, "Max speed %d, rqst %jd\n",
+ max_tclk, (uintmax_t)freq);
+
+ if (freq < min_tclk) {
+ device_printf(sc->sc_dev, "Rqst: %jd is less %d\n",
+ (uintmax_t)freq, min_tclk);
+ return;
+ }
+
+ /*
+ * best_freq will give closest possible available rate (<= requested
+ * freq) for all values of scr & cpsdvsr.
+ */
+ while ((cpsdvsr <= CPSDVR_MAX) && !found) {
+ while (scr <= SCR_MAX) {
+ tmp = pl022_rate(rate, cpsdvsr, scr);
+
+ if (tmp > freq) {
+ /* we need lower freq */
+ scr++;
+ continue;
+ }
+
+ /*
+ * If found exact value, mark found and break.
+ * If found more closer value, update and break.
+ */
+ if (tmp > best_freq) {
+ best_freq = tmp;
+ best_cpsdvsr = cpsdvsr;
+ best_scr = scr;
+
+ if (tmp == freq)
+ found = 1;
+ }
+ /*
+ * increased scr will give lower rates, which are not
+ * required
+ */
+ break;
+ }
+ cpsdvsr += 2;
+ scr = SCR_MIN;
+ }
+
+ if (!best_freq) {
+ device_printf(sc->sc_dev, "pl022: Matching not found %jd\n",
+ (uintmax_t)freq);
+ }
+
+ *cpsrcpsdvr = (uint8_t) (best_cpsdvsr & 0xFF);
+ *cr0scr = (uint8_t) (best_scr & 0xFF);
+ return;
+}
+
+static int
+pl022_txfifo_full(struct pl022_softc *sc)
+{
+ uint16_t sspsr;
+
+ sspsr = PL022_READ_2(sc, PL022_SSP_SR);
+ if ((sspsr & PL022_SSP_SR_TNF) != 0)
+ return (0);
+ else
+ return (1);
+
+}
+
+static int
+pl022_rxfifo_empty(struct pl022_softc *sc)
+{
+ uint16_t sspsr;
+
+ sspsr = PL022_READ_2(sc, PL022_SSP_SR);
+ if ((sspsr & PL022_SSP_SR_RNE) != 0)
+ return (0);
+ else
+ return (1);
+}
+
+static void
+pl022_fill_tx_fifo(struct pl022_softc *sc)
+{
+ struct spi_command *cmd;
+ uint32_t written;
+ uint8_t *data;
+
+ cmd = sc->sc_cmd;
+ while (sc->sc_written < sc->sc_len && !pl022_txfifo_full(sc)) {
+ data = (uint8_t *)cmd->tx_cmd;
+ written = sc->sc_written++;
+ if (written >= cmd->tx_cmd_sz) {
+ data = (uint8_t *)cmd->tx_data;
+ written -= cmd->tx_cmd_sz;
+ }
+ PL022_WRITE_1(sc, PL022_SSP_DR, data[written]);
+ }
+}
+
+static void
+pl022_drain_rx_fifo(struct pl022_softc *sc)
+{
+ struct spi_command *cmd;
+ uint32_t read;
+ uint8_t *data;
+
+ cmd = sc->sc_cmd;
+
+ while (sc->sc_read < sc->sc_len && !pl022_rxfifo_empty(sc)) {
+ data = (uint8_t *)cmd->rx_cmd;
+ read = sc->sc_read++;
+ if (read >= cmd->rx_cmd_sz) {
+ read -= cmd->rx_cmd_sz;
+ data = (uint8_t *)cmd->rx_data;
+ }
+ data[read] = PL022_READ_1(sc, PL022_SSP_DR);
+ }
+}
+
+static void
+pl022_intr(void *arg)
+{
+ struct pl022_softc *sc;
+ uint16_t reg;
+
+ sc = (struct pl022_softc *)arg;
+
+ /* Clear interrupts. */
+ PL022_WRITE_2(sc, PL022_SSP_ICR, 0x0003);
+
+ mtx_lock(&sc->sc_mtx);
+ if ((sc->sc_flags & PL022_BUSY) == 0) {
+ mtx_unlock(&sc->sc_mtx);
+ return;
+ }
+
+ /* TX - Fill up the FIFO. */
+ pl022_fill_tx_fifo(sc);
+
+ pl022_drain_rx_fifo(sc);
+
+ /* Check for end of transfer. */
+ if (sc->sc_written == sc->sc_len && sc->sc_read == sc->sc_len) {
+ /* Disable interrupts */
+ reg = PL022_READ_2(sc, PL022_SSP_IMSC);
+ reg &= ~(PL022_SSP_IMSC_TXIM |
+ PL022_SSP_IMSC_RXIM | PL022_SSP_IMSC_RTIM);
+ PL022_WRITE_2(sc, PL022_SSP_IMSC, reg);
+ wakeup(sc->sc_dev);
+ }
+
+ mtx_unlock(&sc->sc_mtx);
+}
+
+static void
+pl022_init(struct pl022_softc *sc)
+{
+
+ /* Disable SSP module */
+ PL022_WRITE_2(sc, PL022_SSP_CR1, 0);
+
+ /* Set SPI to default 8bit date size */
+ PL022_WRITE_2(sc, PL022_SSP_CR0, PL022_SSP_CR0_DSS(8));
+}
+
+static int
+pl022_transfer(device_t dev, device_t child, struct spi_command *cmd)
+{
+ struct pl022_softc *sc;
+ uint32_t clock, cs, mode;
+ int err = 0;
+ uint16_t cr1, imsc;
+ uint16_t reg, scr;
+ uint8_t cpsdvr;
+
+ sc = device_get_softc(dev);
+
+ cs = 0;
+ if (!sc->sc_ignore_cs)
+ spibus_get_cs(child, &cs);
+
+ spibus_get_clock(child, &clock);
+ spibus_get_mode(child, &mode);
+
+ /* Take ownership of the controller. */
+ if (sc->sc_owntd != curthread) {
+ mtx_lock(&sc->sc_mtx);
+
+ /* If the controller is in use wait until it is available. */
+ while ((sc->sc_flags & PL022_BUSY) != 0)
+ err = mtx_sleep(dev, &sc->sc_mtx, 0, "ssp", 0);
+
+ sc->sc_owntd = curthread;
+ }
+
+ /* Now we have control over SPI controller. */
+ sc->sc_flags = PL022_BUSY;
+
+ /* 8bit data ? or 16bit and motorola mode*/
+ reg = PL022_SSP_CR0_DSS(8);
+
+ /* Setup the modes */
+ if ((mode & SPIBUS_MODE_CPHA) != 0)
+ reg |= PL022_SSP_CR0_CPHA;
+ if ((mode & SPIBUS_MODE_CPOL) != 0)
+ reg |= PL022_SSP_CR0_CPOL;
+
+ pl022_calculate_effective_freq(sc, clock, &scr, &cpsdvr);
+
+ /* Set scr */
+ reg |= (scr << 8);
+ PL022_WRITE_2(sc, PL022_SSP_CR0, reg);
+
+
+ /* Set cpsdvr */
+ PL022_WRITE_2(sc, PL022_SSP_CPSR, cpsdvr);
+
+ /* Assert CS to wake up the slave. */
+ pl022_assert_cs(sc, cs, true);
+
+ /* Save a pointer to the SPI command. */
+ sc->sc_cmd = cmd;
+ sc->sc_read = 0;
+ sc->sc_written = 0;
+ sc->sc_len = cmd->tx_cmd_sz + cmd->tx_data_sz;
+
+ /* Wait for FIFO to be ready */
+ while ((PL022_READ_2(sc, PL022_SSP_SR) & PL022_SSP_SR_TNF) == 0)
+ ;
+
+ /* Enable interrupts to kick this off */
+ imsc = PL022_READ_2(sc, PL022_SSP_IMSC);
+ imsc |= (PL022_SSP_IMSC_TXIM | PL022_SSP_IMSC_RXIM | PL022_SSP_IMSC_RTIM);
+ PL022_WRITE_2(sc, PL022_SSP_IMSC, imsc);
+
+ /* Enable SSP */
+ PL022_WRITE_2(sc, PL022_SSP_CR1,
+ PL022_READ_2(sc, PL022_SSP_CR1) | PL022_SSP_CR1_SSE);
+
+ /* Wait for the transaction to complete. */
+ err = mtx_sleep(dev, &sc->sc_mtx, 0, "bcm_spi", hz * 2);
+
+ /* Clear transaction details */
+ sc->sc_cmd = NULL;
+
+ /* Make sure the SPI engine and interrupts are disabled. */
+ /* Only do this if this is the end of the transaction */
+ if (!(cmd->flags & SPI_FLAG_KEEP_CS) || err != 0) {
+ /* Set CS inactive */
+ pl022_assert_cs(sc, cs, false);
+ cr1 = PL022_READ_2(sc, PL022_SSP_CR1);
+ cr1 &= ~PL022_SSP_CR1_SSE;
+ PL022_WRITE_2(sc, PL022_SSP_CR1, cr1);
+
+ imsc = PL022_READ_2(sc, PL022_SSP_IMSC);
+ imsc &= ~(PL022_SSP_IMSC_TXIM | PL022_SSP_IMSC_RXIM | PL022_SSP_IMSC_RTIM);
+ PL022_WRITE_2(sc, PL022_SSP_IMSC, imsc);
+
+ /* Release the controller and wakeup the next thread waiting for it. */
+ sc->sc_owntd = NULL;
+ sc->sc_flags = 0;
+ wakeup_one(dev);
+ mtx_unlock(&sc->sc_mtx);
+ }
+
+ /*
+ * Check for transfer timeout. The SPI controller doesn't
+ * return errors.
+ */
+ if (err == EAGAIN) {
+ device_printf(sc->sc_dev, "transfer timeout\n");
+ err = EIO;
+ }
+ return (err);
+}
+
+static int
+pl022_probe(device_t dev)
+{
+ if (!ofw_bus_status_okay(dev))
+ return (ENXIO);
+
+ if (!ofw_bus_search_compatible(dev, compat_data)->ocd_data)
+ return (ENXIO);
+
+ device_set_desc(dev, "PL022 SPI/SSP controller");
+ return (BUS_PROBE_DEFAULT);
+}
+
+static int
+pl022_attach(device_t dev)
+{
+ struct pl022_softc *sc = device_get_softc(dev);
+ phandle_t node;
+ pcell_t spi_freq;
+ uint32_t gpio_handle;
+ int error;
+
+ sc->sc_dev = dev;
+ mtx_init(&sc->sc_mtx, device_get_nameunit(dev), NULL, MTX_DEF);
+
+ if (bus_alloc_resources(dev, pl022_spec, sc->res) != 0) {
+ device_printf(dev, "cannot allocate resources for device\n");
+ error = ENXIO;
+ goto fail;
+ }
+
+ if (bus_setup_intr(dev, sc->res[1],
+ INTR_TYPE_MISC | INTR_MPSAFE, NULL, pl022_intr, sc,
+ &sc->sc_cookie)) {
+ bus_release_resources(dev, pl022_spec, sc->res);
+ device_printf(dev, "cannot setup interrupt handler\n");
+ return (ENXIO);
+ }
+
+ /* Register a xref for the node so others can find us */
+ node = ofw_bus_get_node(dev);
+ OF_device_register_xref(node, dev);
+
+ OF_getencprop(OF_child(node), "clock-frequency",&spi_freq,
+ sizeof(spi_freq));
+ sc->sc_modfreq = spi_freq;
+ /* If no clock is explicitly set, use the first clock. */
+ if (spi_freq == 0) {
+ error = clk_get_by_ofw_name(dev, 0, "sspclk", &sc->sc_sspclk);
+ if (error != 0)
+ error = clk_get_by_ofw_index(dev, 0, 0, &sc->sc_sspclk);
+ if (error != 0)
+ device_printf(dev, "No usable clock found!\n");
+ clk_get_freq(sc->sc_sspclk, &sc->sc_modfreq);
+ }
+ if (OF_hasprop(node, "ignore-cs"))
+ sc->sc_ignore_cs = true;
+ else {
+ sc->sc_ignore_cs = false;
+ if (OF_getencprop(node, "gpio", &gpio_handle, sizeof(gpio_handle)) <= 0) {
+ device_printf(dev, "No GPIO property found!\n");
+ error = ENXIO;
+ goto fail;
+ }
+ sc->sc_gpio = OF_device_from_xref(gpio_handle);
+ if (sc->sc_gpio == NULL) {
+ device_printf(dev, "No GPIO resource found!\n");
+ error = ENXIO;
+ goto fail;
+ }
+ }
+
+ pl022_init(sc);
+
+ sc->sc_bus = device_add_child(dev, "spibus", -1);
+ return (bus_generic_attach(dev));
+
+fail:
+ pl022_detach(dev);
+ return (error);
+}
+
+static int
+pl022_detach(device_t dev)
+{
+ struct pl022_softc *sc;
+
+ sc = device_get_softc(dev);
+
+ bus_generic_detach(sc->sc_dev);
+ if (sc->sc_bus != NULL)
+ device_delete_child(dev, sc->sc_bus);
+ if (sc->sc_cookie != NULL)
+ bus_teardown_intr(sc->sc_dev, sc->res[1], sc->sc_cookie);
+
+ bus_release_resources(dev, pl022_spec, sc->res);
+ mtx_destroy(&sc->sc_mtx);
+
+ return (0);
+}
+
+
+static device_method_t pl022_methods[] = {
+ /* Device interface */
+ DEVMETHOD(device_probe, pl022_probe),
+ DEVMETHOD(device_attach, pl022_attach),
+ DEVMETHOD(device_detach, pl022_detach),
+
+ /* OFW methods */
+ DEVMETHOD(ofw_bus_get_node, pl022_get_node),
+
+ /* SPI interface */
+ DEVMETHOD(spibus_transfer, pl022_transfer),
+
+ DEVMETHOD_END
+};
+
+static driver_t pl022_driver = {
+ .name = "spi",
+ .methods = pl022_methods,
+ .size = sizeof(struct pl022_softc),
+};
+
+DRIVER_MODULE(pl022, simplebus, pl022_driver, 0, 0);
+MODULE_DEPEND(pl022, ofw_spibus, 1, 1, 1);
+MODULE_VERSION(pl022, 1);
diff --git a/sys/arm/conf/GENERIC b/sys/arm/conf/GENERIC
--- a/sys/arm/conf/GENERIC
+++ b/sys/arm/conf/GENERIC
@@ -162,6 +162,7 @@
device spigen
device bcm2835_spi
device mv_spi
+device pl022 # ARM PL022 SSP controller
device zy7_qspi # Xilinx Zynq QSPI controller
# PWM
diff --git a/sys/arm64/conf/std.dev b/sys/arm64/conf/std.dev
--- a/sys/arm64/conf/std.dev
+++ b/sys/arm64/conf/std.dev
@@ -37,6 +37,7 @@
# SPI
device spibus
+device pl022 # ARM PL022 SSP controller
# PWM
device pwm
diff --git a/sys/conf/files.arm b/sys/conf/files.arm
--- a/sys/conf/files.arm
+++ b/sys/conf/files.arm
@@ -50,6 +50,7 @@
arm/arm/mpcore_timer.c optional mpcore_timer
arm/arm/nexus.c standard
arm/arm/ofw_machdep.c optional fdt
+arm/arm/pl022.c optional pl022 fdt
arm/arm/pl190.c optional pl190
arm/arm/pl310.c optional pl310
arm/arm/platform.c optional platform
diff --git a/sys/conf/files.arm64 b/sys/conf/files.arm64
--- a/sys/conf/files.arm64
+++ b/sys/conf/files.arm64
@@ -16,6 +16,7 @@
arm/arm/gic_acpi.c optional acpi
arm/arm/gic_fdt.c optional fdt
arm/arm/gic_if.m standard
+arm/arm/pl022.c optional pl022 fdt
arm/arm/pmu.c standard
arm/arm/pmu_acpi.c optional acpi
arm/arm/pmu_fdt.c optional fdt

File Metadata

Mime Type
text/plain
Expires
Tue, Jan 20, 3:11 AM (13 h, 55 m)
Storage Engine
blob
Storage Format
Raw Data
Storage Handle
27758292
Default Alt Text
D45211.id139697.diff (18 KB)

Event Timeline