2014-04-03 11:10:44

by Harini Katakam

[permalink] [raw]
Subject: [PATCH v2 1/2] SPI: Add driver for Cadence SPI controller

Add driver for Cadence SPI controller. This is used in Xilinx Zynq.

Signed-off-by: Harini Katakam <[email protected]>
---

v2 changes:
- Use xilinx compatible string too.
- Changes read register and write register functions to static inline.
- Removed unecessary dev_info and dev_dbg prints.
- Return IRQ_HANDLED only when interrupt is handled.
- Use a default num-cs value.
- Do init_hardware before requesting irq.
- Remove unecessary master_put()
- Set master->max_speed_hz
- Check for busy in cdns_setup().
Retained this function with this check as opposed to removing.
The reason for this is clock configuration needs to be done for
the first time before enable is done in prepare_hardware;
prepare_hardware however, doesn't receive spi_device structure.
- Implememnt transfer_one instead of transfer_one_message.
Remove wait_for_completion as this is done by core.
- Implement set_cs.
- Clock enable/disable in prepare/unprepare respectively.
- In suspend, remove reset of hardware; simply call unprepare_hardware.
- In suspend/resume call master_suspend/resume respectively.
- Check for irq<=0 in probe.
- Remove MODULE_ALIAS.

---
drivers/spi/Kconfig | 7 +
drivers/spi/Makefile | 1 +
drivers/spi/spi-cadence.c | 677 +++++++++++++++++++++++++++++++++++++++++++++
3 files changed, 685 insertions(+)
create mode 100644 drivers/spi/spi-cadence.c

diff --git a/drivers/spi/Kconfig b/drivers/spi/Kconfig
index 581ee2a..aeae44a 100644
--- a/drivers/spi/Kconfig
+++ b/drivers/spi/Kconfig
@@ -148,6 +148,13 @@ config SPI_BUTTERFLY
inexpensive battery powered microcontroller evaluation board.
This same cable can be used to flash new firmware.

+config SPI_CADENCE
+ tristate "Cadence SPI controller"
+ depends on SPI_MASTER
+ help
+ This selects the Cadence SPI controller master driver
+ used by Xilinx Zynq.
+
config SPI_CLPS711X
tristate "CLPS711X host SPI controller"
depends on ARCH_CLPS711X
diff --git a/drivers/spi/Makefile b/drivers/spi/Makefile
index 95af48d..1be2ed7 100644
--- a/drivers/spi/Makefile
+++ b/drivers/spi/Makefile
@@ -22,6 +22,7 @@ obj-$(CONFIG_SPI_BFIN_V3) += spi-bfin-v3.o
obj-$(CONFIG_SPI_BFIN_SPORT) += spi-bfin-sport.o
obj-$(CONFIG_SPI_BITBANG) += spi-bitbang.o
obj-$(CONFIG_SPI_BUTTERFLY) += spi-butterfly.o
+obj-$(CONFIG_SPI_CADENCE) += spi-cadence.o
obj-$(CONFIG_SPI_CLPS711X) += spi-clps711x.o
obj-$(CONFIG_SPI_COLDFIRE_QSPI) += spi-coldfire-qspi.o
obj-$(CONFIG_SPI_DAVINCI) += spi-davinci.o
diff --git a/drivers/spi/spi-cadence.c b/drivers/spi/spi-cadence.c
new file mode 100644
index 0000000..071642d
--- /dev/null
+++ b/drivers/spi/spi-cadence.c
@@ -0,0 +1,677 @@
+/*
+ * Cadence SPI controller driver (master mode only)
+ *
+ * Copyright (C) 2008 - 2014 Xilinx, Inc.
+ *
+ * based on Blackfin On-Chip SPI Driver (spi_bfin5xx.c)
+ *
+ * This program is free software; you can redistribute it and/or modify it under
+ * the terms of the GNU General Public License version 2 as published by the
+ * Free Software Foundation; either version 2 of the License, or (at your
+ * option) any later version.
+ */
+
+#include <linux/clk.h>
+#include <linux/delay.h>
+#include <linux/interrupt.h>
+#include <linux/io.h>
+#include <linux/module.h>
+#include <linux/of_irq.h>
+#include <linux/of_address.h>
+#include <linux/platform_device.h>
+#include <linux/spi/spi.h>
+
+/* Name of this driver */
+#define CDNS_SPI_NAME "cdns-spi"
+
+/* Register offset definitions */
+#define CDNS_SPI_CR_OFFSET 0x00 /* Configuration Register, RW */
+#define CDNS_SPI_ISR_OFFSET 0x04 /* Interrupt Status Register, RO */
+#define CDNS_SPI_IER_OFFSET 0x08 /* Interrupt Enable Register, WO */
+#define CDNS_SPI_IDR_OFFSET 0x0c /* Interrupt Disable Register, WO */
+#define CDNS_SPI_IMR_OFFSET 0x10 /* Interrupt Enabled Mask Register, RO */
+#define CDNS_SPI_ER_OFFSET 0x14 /* Enable/Disable Register, RW */
+#define CDNS_SPI_DR_OFFSET 0x18 /* Delay Register, RW */
+#define CDNS_SPI_TXD_OFFSET 0x1C /* Data Transmit Register, WO */
+#define CDNS_SPI_RXD_OFFSET 0x20 /* Data Receive Register, RO */
+#define CDNS_SPI_SICR_OFFSET 0x24 /* Slave Idle Count Register, RW */
+#define CDNS_SPI_THLD_OFFSET 0x28 /* Transmit FIFO Watermark Register,RW */
+
+/*
+ * SPI Configuration Register bit Masks
+ *
+ * This register contains various control bits that affect the operation
+ * of the SPI controller
+ */
+#define CDNS_SPI_CR_MANSTRT_MASK 0x00010000 /* Manual TX Start */
+#define CDNS_SPI_CR_CPHA_MASK 0x00000004 /* Clock Phase Control */
+#define CDNS_SPI_CR_CPOL_MASK 0x00000002 /* Clock Polarity Control */
+#define CDNS_SPI_CR_SSCTRL_MASK 0x00003C00 /* Slave Select Mask */
+#define CDNS_SPI_CR_BAUD_DIV_MASK 0x00000038 /* Baud Rate Divisor Mask */
+#define CDNS_SPI_CR_MSTREN_MASK 0x00000001 /* Master Enable Mask */
+#define CDNS_SPI_CR_MANSTRTEN_MASK 0x00008000 /* Manual TX Enable Mask */
+#define CDNS_SPI_CR_SSFORCE_MASK 0x00004000 /* Manual SS Enable Mask */
+#define CDNS_SPI_CR_BAUD_DIV_4_MASK 0x00000008 /* Default Baud Div Mask */
+#define CDNS_SPI_CR_DEFAULT_MASK (CDNS_SPI_CR_MSTREN_MASK | \
+ CDNS_SPI_CR_SSCTRL_MASK | \
+ CDNS_SPI_CR_SSFORCE_MASK | \
+ CDNS_SPI_CR_BAUD_DIV_4_MASK)
+
+/*
+ * SPI Configuration Register - Baud rate and slave select
+ *
+ * These are the values used in the calculation of baud rate divisor and
+ * setting the slave select.
+ */
+
+#define CDNS_SPI_BAUD_DIV_MAX 7 /* Baud rate divisor maximum */
+#define CDNS_SPI_BAUD_DIV_MIN 1 /* Baud rate divisor minimum */
+#define CDNS_SPI_BAUD_DIV_SHIFT 3 /* Baud rate divisor shift in CR */
+#define CDNS_SPI_SS_SHIFT 10 /* Slave Select field shift in CR */
+#define CDNS_SPI_SS0 0x1 /* Slave Select zero */
+
+/*
+ * SPI Interrupt Registers bit Masks
+ *
+ * All the four interrupt registers (Status/Mask/Enable/Disable) have the same
+ * bit definitions.
+ */
+#define CDNS_SPI_IXR_TXOW_MASK 0x00000004 /* SPI TX FIFO Overwater */
+#define CDNS_SPI_IXR_MODF_MASK 0x00000002 /* SPI Mode Fault */
+#define CDNS_SPI_IXR_RXNEMTY_MASK 0x00000010 /* SPI RX FIFO Not Empty */
+#define CDNS_SPI_IXR_DEFAULT_MASK (CDNS_SPI_IXR_TXOW_MASK | \
+ CDNS_SPI_IXR_MODF_MASK)
+#define CDNS_SPI_IXR_TXFULL_MASK 0x00000008 /* SPI TX Full */
+#define CDNS_SPI_IXR_ALL_MASK 0x0000007F /* SPI all interrupts */
+
+/*
+ * SPI Enable Register bit Masks
+ *
+ * This register is used to enable or disable the SPI controller
+ */
+#define CDNS_SPI_ER_ENABLE_MASK 0x00000001 /* SPI Enable Bit Mask */
+#define CDNS_SPI_ER_DISABLE_MASK 0x0 /* SPI Disable Bit Mask */
+
+/* SPI timeout value */
+#define CDNS_SPI_TIMEOUT (5 * HZ)
+
+/* SPI FIFO depth in bytes */
+#define CDNS_SPI_FIFO_DEPTH 128
+
+/* Default number of chip select lines */
+#define CDNS_SPI_DEFAULT_NUM_CS 4
+
+/* Driver state - suspend/ready */
+enum driver_state_val {
+ CDNS_SPI_DRIVER_STATE_READY = 0,
+ CDNS_SPI_DRIVER_STATE_SUSPEND
+};
+
+/**
+ * struct cdns_spi - This definition defines spi driver instance
+ * @regs: Virtual address of the SPI controller registers
+ * @ref_clk: Pointer to the peripheral clock
+ * @pclk: Pointer to the APB clock
+ * @speed_hz: Current SPI bus clock speed in Hz
+ * @txbuf: Pointer to the TX buffer
+ * @rxbuf: Pointer to the RX buffer
+ * @remaining_bytes: Number of bytes left to transfer
+ * @requested_bytes: Number of bytes requested
+ * @dev_busy: Device busy flag
+ * @done: Transfer complete status
+ * @driver_state: Describes driver state - ready/suspended
+ */
+struct cdns_spi {
+ void __iomem *regs;
+ struct clk *ref_clk;
+ struct clk *pclk;
+ u32 speed_hz;
+ const u8 *txbuf;
+ u8 *rxbuf;
+ int remaining_bytes;
+ int requested_bytes;
+ u8 dev_busy;
+ enum driver_state_val driver_state;
+};
+
+/* Macros for the SPI controller read/write */
+static inline u32 cdns_spi_read(struct cdns_spi *xspi, u32 offset)
+{
+ return readl_relaxed(xspi->regs + offset);
+}
+
+static inline void cdns_spi_write(struct cdns_spi *xspi, u32 offset, u32 val)
+{
+ writel_relaxed(val, xspi->regs + offset);
+}
+
+/**
+ * cdns_spi_init_hw - Initialize the hardware and configure the SPI controller
+ * @xspi: Pointer to the cdns_spi structure
+ *
+ * On reset the SPI controller is configured to be in master mode, baud rate
+ * divisor is set to 4, threshold value for TX FIFO not full interrupt is set
+ * to 1 and size of the word to be transferred as 8 bit.
+ * This function initializes the SPI controller to disable and clear all the
+ * interrupts, enable manual slave select and manual start, deselect all the
+ * chip select lines, and enable the SPI controller.
+ */
+static void cdns_spi_init_hw(struct cdns_spi *xspi)
+{
+ cdns_spi_write(xspi, CDNS_SPI_ER_OFFSET,
+ CDNS_SPI_ER_DISABLE_MASK);
+ cdns_spi_write(xspi, CDNS_SPI_IDR_OFFSET,
+ CDNS_SPI_IXR_ALL_MASK);
+
+ /* Clear the RX FIFO */
+ while (cdns_spi_read(xspi, CDNS_SPI_ISR_OFFSET) &
+ CDNS_SPI_IXR_RXNEMTY_MASK)
+ cdns_spi_read(xspi, CDNS_SPI_RXD_OFFSET);
+
+ cdns_spi_write(xspi, CDNS_SPI_ISR_OFFSET,
+ CDNS_SPI_IXR_ALL_MASK);
+ cdns_spi_write(xspi, CDNS_SPI_CR_OFFSET,
+ CDNS_SPI_CR_DEFAULT_MASK);
+ cdns_spi_write(xspi, CDNS_SPI_ER_OFFSET,
+ CDNS_SPI_ER_ENABLE_MASK);
+}
+
+/**
+ * cdns_spi_chipselect - Select or deselect the chip select line
+ * @spi: Pointer to the spi_device structure
+ * @is_on: Select(0) or deselect (1) the chip select line
+ */
+static void cdns_spi_chipselect(struct spi_device *spi, bool is_high)
+{
+ struct cdns_spi *xspi = spi_master_get_devdata(spi->master);
+ u32 ctrl_reg;
+
+ ctrl_reg = cdns_spi_read(xspi, CDNS_SPI_CR_OFFSET);
+
+ if (is_high) {
+ /* Deselect the slave */
+ ctrl_reg |= CDNS_SPI_CR_SSCTRL_MASK;
+ } else {
+ /* Select the slave */
+ ctrl_reg &= ~CDNS_SPI_CR_SSCTRL_MASK;
+ ctrl_reg |= ((~(CDNS_SPI_SS0 << spi->chip_select)) <<
+ CDNS_SPI_SS_SHIFT) & CDNS_SPI_CR_SSCTRL_MASK;
+ }
+
+ cdns_spi_write(xspi, CDNS_SPI_CR_OFFSET, ctrl_reg);
+}
+
+/**
+ * cdns_spi_config_clock - Sets clock polarity, phase and frequency
+ * @spi: Pointer to the spi_device structure
+ * @transfer: Pointer to the spi_transfer structure which provides
+ * information about next transfer setup parameters
+ *
+ * Sets the requested clock polarity, phase and frequency.
+ * Note: If the requested frequency is not an exact match with what can be
+ * obtained using the prescalar value the driver sets the clock frequency which
+ * is lower than the requested frequency (maximum lower) for the transfer. If
+ * the requested frequency is higher or lower than that is supported by the SPI
+ * controller the driver will set the highest or lowest frequency supported by
+ * controller.
+ */
+static void cdns_spi_config_clock(struct spi_device *spi,
+ struct spi_transfer *transfer)
+{
+ struct cdns_spi *xspi = spi_master_get_devdata(spi->master);
+ u32 ctrl_reg, req_hz, baud_rate_val;
+ unsigned long frequency;
+
+ if (transfer)
+ req_hz = transfer->speed_hz;
+ else
+ req_hz = spi->max_speed_hz;
+
+ frequency = clk_get_rate(xspi->ref_clk);
+
+ ctrl_reg = cdns_spi_read(xspi, CDNS_SPI_CR_OFFSET);
+
+ /* Set the SPI clock phase and clock polarity */
+ ctrl_reg &= ~(CDNS_SPI_CR_CPHA_MASK | CDNS_SPI_CR_CPOL_MASK);
+ if (spi->mode & SPI_CPHA)
+ ctrl_reg |= CDNS_SPI_CR_CPHA_MASK;
+ if (spi->mode & SPI_CPOL)
+ ctrl_reg |= CDNS_SPI_CR_CPOL_MASK;
+
+ /* Set the clock frequency */
+ if (xspi->speed_hz != req_hz) {
+ /* first valid value is 1 */
+ baud_rate_val = CDNS_SPI_BAUD_DIV_MIN;
+ while ((baud_rate_val < CDNS_SPI_BAUD_DIV_MAX) &&
+ (frequency / (2 << baud_rate_val)) > req_hz)
+ baud_rate_val++;
+
+ ctrl_reg &= ~CDNS_SPI_CR_BAUD_DIV_MASK;
+ ctrl_reg |= baud_rate_val << CDNS_SPI_BAUD_DIV_SHIFT;
+
+ xspi->speed_hz = frequency / (2 << baud_rate_val);
+ }
+ cdns_spi_write(xspi, CDNS_SPI_CR_OFFSET, ctrl_reg);
+}
+
+/**
+ * cdns_spi_setup_transfer - Configure SPI controller for specified transfer
+ * @spi: Pointer to the spi_device structure
+ * @transfer: Pointer to the spi_transfer structure which provides
+ * information about next transfer setup parameters
+ *
+ * Sets the operational mode of SPI controller for the next SPI transfer and
+ * sets the requested clock frequency.
+ *
+ * Return: Always 0
+ */
+static int cdns_spi_setup_transfer(struct spi_device *spi,
+ struct spi_transfer *transfer)
+{
+ struct cdns_spi *xspi = spi_master_get_devdata(spi->master);
+
+ cdns_spi_config_clock(spi, transfer);
+
+ dev_dbg(&spi->dev, "%s, mode %d, %u bits/w, %u clock speed\n",
+ __func__, spi->mode, spi->bits_per_word,
+ xspi->speed_hz);
+
+ return 0;
+}
+
+/**
+ * cdns_spi_setup - Configure the SPI controller
+ * @spi: Pointer to the spi_device structure
+ *
+ * Sets the operational mode of SPI controller for the next SPI transfer, sets
+ * the baud rate and divisor value to setup the requested spi clock.
+ *
+ * Return: 0 on success and error value on error
+ */
+static int cdns_spi_setup(struct spi_device *spi)
+{
+ if (spi->master->busy)
+ return -EBUSY;
+
+ return cdns_spi_setup_transfer(spi, NULL);
+}
+
+/**
+ * cdns_spi_fill_tx_fifo - Fills the TX FIFO with as many bytes as possible
+ * @xspi: Pointer to the cdns_spi structure
+ */
+static void cdns_spi_fill_tx_fifo(struct cdns_spi *xspi)
+{
+ unsigned long trans_cnt = 0;
+
+ while ((trans_cnt < CDNS_SPI_FIFO_DEPTH) &&
+ (xspi->remaining_bytes > 0)) {
+ if (xspi->txbuf)
+ cdns_spi_write(xspi, CDNS_SPI_TXD_OFFSET,
+ *xspi->txbuf++);
+ else
+ cdns_spi_write(xspi, CDNS_SPI_TXD_OFFSET, 0);
+
+ xspi->remaining_bytes--;
+ trans_cnt++;
+ }
+}
+
+/**
+ * cdns_spi_irq - Interrupt service routine of the SPI controller
+ * @irq: IRQ number
+ * @dev_id: Pointer to the xspi structure
+ *
+ * This function handles TX empty and Mode Fault interrupts only.
+ * On TX empty interrupt this function reads the received data from RX FIFO and
+ * fills the TX FIFO if there is any data remaining to be transferred.
+ * On Mode Fault interrupt this function indicates that transfer is completed,
+ * the SPI subsystem will identify the error as the remaining bytes to be
+ * transferred is non-zero.
+ *
+ * Return: IRQ_HANDLED when handled; IRQ_NONE otherwise.
+ */
+static irqreturn_t cdns_spi_irq(int irq, void *dev_id)
+{
+ struct spi_master *master = dev_id;
+ struct cdns_spi *xspi = spi_master_get_devdata(master);
+ u32 intr_status, status;
+
+ status = IRQ_NONE;
+ intr_status = cdns_spi_read(xspi, CDNS_SPI_ISR_OFFSET);
+ cdns_spi_write(xspi, CDNS_SPI_ISR_OFFSET, intr_status);
+
+ if (intr_status & CDNS_SPI_IXR_MODF_MASK) {
+ /* Indicate that transfer is completed, the SPI subsystem will
+ * identify the error as the remaining bytes to be
+ * transferred is non-zero
+ */
+ cdns_spi_write(xspi, CDNS_SPI_IDR_OFFSET,
+ CDNS_SPI_IXR_DEFAULT_MASK);
+ spi_finalize_current_transfer(master);
+ status = IRQ_HANDLED;
+ } else if (intr_status & CDNS_SPI_IXR_TXOW_MASK) {
+ unsigned long trans_cnt;
+
+ trans_cnt = xspi->requested_bytes - xspi->remaining_bytes;
+
+ /* Read out the data from the RX FIFO */
+ while (trans_cnt) {
+ u8 data;
+
+ data = cdns_spi_read(xspi, CDNS_SPI_RXD_OFFSET);
+ if (xspi->rxbuf)
+ *xspi->rxbuf++ = data;
+
+ xspi->requested_bytes--;
+ trans_cnt--;
+ }
+
+ if (xspi->remaining_bytes) {
+ /* There is more data to send */
+ cdns_spi_fill_tx_fifo(xspi);
+ } else {
+ /* Transfer is completed */
+ cdns_spi_write(xspi, CDNS_SPI_IDR_OFFSET,
+ CDNS_SPI_IXR_DEFAULT_MASK);
+ spi_finalize_current_transfer(master);
+ }
+ status = IRQ_HANDLED;
+ }
+
+ return status;
+}
+
+/**
+ * cdns_transfer_one - Initiates the SPI transfer
+ * @master: Pointer to spi_master structure
+ * @spi: Pointer to the spi_device structure
+ * @transfer: Pointer to the spi_transfer structure which provides
+ * information about next transfer parameters
+ *
+ * This function fills the TX FIFO, starts the SPI transfer and
+ * returns a positive transfer count so that core will wait for completion.
+ *
+ * Return: Number of bytes transferred in the last transfer
+ */
+static int cdns_transfer_one(struct spi_master *master,
+ struct spi_device *spi,
+ struct spi_transfer *transfer)
+{
+ struct cdns_spi *xspi = spi_master_get_devdata(master);
+
+ xspi->txbuf = transfer->tx_buf;
+ xspi->rxbuf = transfer->rx_buf;
+ xspi->remaining_bytes = transfer->len;
+ xspi->requested_bytes = transfer->len;
+
+ cdns_spi_setup_transfer(spi, transfer);
+
+ cdns_spi_fill_tx_fifo(xspi);
+
+ cdns_spi_write(xspi, CDNS_SPI_IER_OFFSET,
+ CDNS_SPI_IXR_DEFAULT_MASK);
+ return transfer->len;
+}
+
+/**
+ * cdns_prepare_transfer_hardware - Prepares hardware for transfer.
+ * @master: Pointer to the spi_master structure which provides
+ * information about the controller.
+ *
+ * This function enables SPI master controller.
+ *
+ * Return: 0 always
+ */
+static int cdns_prepare_transfer_hardware(struct spi_master *master)
+{
+ struct cdns_spi *xspi = spi_master_get_devdata(master);
+
+ clk_enable(xspi->ref_clk);
+ clk_enable(xspi->pclk);
+ cdns_spi_write(xspi, CDNS_SPI_ER_OFFSET,
+ CDNS_SPI_ER_ENABLE_MASK);
+
+ return 0;
+}
+
+/**
+ * cdns_unprepare_transfer_hardware - Relaxes hardware after transfer
+ * @master: Pointer to the spi_master structure which provides
+ * information about the controller.
+ *
+ * This function disables the SPI master controller.
+ *
+ * Return: 0 always
+ */
+static int cdns_unprepare_transfer_hardware(struct spi_master *master)
+{
+ struct cdns_spi *xspi = spi_master_get_devdata(master);
+
+ cdns_spi_write(xspi, CDNS_SPI_ER_OFFSET,
+ CDNS_SPI_ER_DISABLE_MASK);
+ clk_disable(xspi->ref_clk);
+ clk_disable(xspi->pclk);
+
+ return 0;
+}
+
+/**
+ * cdns_spi_probe - Probe method for the SPI driver
+ * @pdev: Pointer to the platform_device structure
+ *
+ * This function initializes the driver data structures and the hardware.
+ *
+ * Return: 0 on success and error value on error
+ */
+static int cdns_spi_probe(struct platform_device *pdev)
+{
+ int ret = 0, irq;
+ struct spi_master *master;
+ struct cdns_spi *xspi;
+ struct resource *res;
+
+ master = spi_alloc_master(&pdev->dev, sizeof(*xspi));
+ if (master == NULL)
+ return -ENOMEM;
+
+ xspi = spi_master_get_devdata(master);
+ master->dev.of_node = pdev->dev.of_node;
+ platform_set_drvdata(pdev, master);
+
+ res = platform_get_resource(pdev, IORESOURCE_MEM, 0);
+ xspi->regs = devm_ioremap_resource(&pdev->dev, res);
+ if (IS_ERR(xspi->regs)) {
+ ret = PTR_ERR(xspi->regs);
+ goto remove_master;
+ }
+
+ xspi->pclk = devm_clk_get(&pdev->dev, "pclk");
+ if (IS_ERR(xspi->pclk)) {
+ dev_err(&pdev->dev, "pclk clock not found.\n");
+ ret = PTR_ERR(xspi->pclk);
+ goto remove_master;
+ }
+
+ xspi->ref_clk = devm_clk_get(&pdev->dev, "ref_clk");
+ if (IS_ERR(xspi->ref_clk)) {
+ dev_err(&pdev->dev, "ref_clk clock not found.\n");
+ ret = PTR_ERR(xspi->ref_clk);
+ goto remove_master;
+ }
+
+ ret = clk_prepare_enable(xspi->pclk);
+ if (ret) {
+ dev_err(&pdev->dev, "Unable to enable APB clock.\n");
+ goto remove_master;
+ }
+
+ ret = clk_prepare_enable(xspi->ref_clk);
+ if (ret) {
+ dev_err(&pdev->dev, "Unable to enable device clock.\n");
+ goto clk_dis_apb;
+ }
+
+ /* SPI controller initializations */
+ cdns_spi_init_hw(xspi);
+
+ irq = platform_get_irq(pdev, 0);
+ if (irq <= 0) {
+ ret = -ENXIO;
+ dev_err(&pdev->dev, "irq number is invalid\n");
+ goto remove_master;
+ }
+
+ ret = devm_request_irq(&pdev->dev, irq, cdns_spi_irq,
+ 0, pdev->name, master);
+ if (ret != 0) {
+ ret = -ENXIO;
+ dev_err(&pdev->dev, "request_irq failed\n");
+ goto remove_master;
+ }
+
+ ret = of_property_read_u16(pdev->dev.of_node, "num-cs",
+ &master->num_chipselect);
+ if (ret < 0)
+ master->num_chipselect = CDNS_SPI_DEFAULT_NUM_CS;
+
+ master->setup = cdns_spi_setup;
+ master->prepare_transfer_hardware = cdns_prepare_transfer_hardware;
+ master->transfer_one = cdns_transfer_one;
+ master->unprepare_transfer_hardware = cdns_unprepare_transfer_hardware;
+ master->set_cs = cdns_spi_chipselect;
+ master->mode_bits = SPI_CPOL | SPI_CPHA;
+
+ /* Set to default valid value */
+ master->max_speed_hz = clk_get_rate(xspi->ref_clk) / 4;
+ xspi->speed_hz = master->max_speed_hz;
+
+ master->bits_per_word_mask = SPI_BPW_MASK(8);
+
+ xspi->driver_state = CDNS_SPI_DRIVER_STATE_READY;
+
+ ret = spi_register_master(master);
+ if (ret) {
+ dev_err(&pdev->dev, "spi_register_master failed\n");
+ goto clk_dis_all;
+ }
+
+ return ret;
+
+clk_dis_all:
+ clk_disable_unprepare(xspi->ref_clk);
+clk_dis_apb:
+ clk_disable_unprepare(xspi->pclk);
+remove_master:
+ spi_master_put(master);
+ return ret;
+}
+
+/**
+ * cdns_spi_remove - Remove method for the SPI driver
+ * @pdev: Pointer to the platform_device structure
+ *
+ * This function is called if a device is physically removed from the system or
+ * if the driver module is being unloaded. It frees all resources allocated to
+ * the device.
+ *
+ * Return: 0 on success and error value on error
+ */
+static int cdns_spi_remove(struct platform_device *pdev)
+{
+ struct spi_master *master = platform_get_drvdata(pdev);
+ struct cdns_spi *xspi = spi_master_get_devdata(master);
+
+ cdns_spi_write(xspi, CDNS_SPI_ER_OFFSET,
+ CDNS_SPI_ER_DISABLE_MASK);
+
+ clk_disable_unprepare(xspi->ref_clk);
+ clk_disable_unprepare(xspi->pclk);
+
+ spi_unregister_master(master);
+
+ return 0;
+}
+
+/**
+ * cdns_spi_suspend - Suspend method for the SPI driver
+ * @dev: Address of the platform_device structure
+ *
+ * This function disables the SPI controller and
+ * changes the driver state to "suspend"
+ *
+ * Return: Always 0
+ */
+static int __maybe_unused cdns_spi_suspend(struct device *dev)
+{
+ struct platform_device *pdev = container_of(dev,
+ struct platform_device, dev);
+ struct spi_master *master = platform_get_drvdata(pdev);
+
+ spi_master_suspend(master);
+
+ cdns_unprepare_transfer_hardware(master);
+
+ return 0;
+}
+
+/**
+ * cdns_spi_resume - Resume method for the SPI driver
+ * @dev: Address of the platform_device structure
+ *
+ * This function changes the driver state to "ready"
+ *
+ * Return: 0 on success and error value on error
+ */
+static int __maybe_unused cdns_spi_resume(struct device *dev)
+{
+ struct platform_device *pdev = container_of(dev,
+ struct platform_device, dev);
+ struct spi_master *master = platform_get_drvdata(pdev);
+ struct cdns_spi *xspi = spi_master_get_devdata(master);
+ int ret = 0;
+
+ ret = clk_enable(xspi->pclk);
+ if (ret) {
+ dev_err(dev, "Cannot enable APB clock.\n");
+ return ret;
+ }
+
+ ret = clk_enable(xspi->ref_clk);
+ if (ret) {
+ dev_err(dev, "Cannot enable device clock.\n");
+ clk_disable(xspi->pclk);
+ return ret;
+ }
+ spi_master_resume(master);
+
+ return 0;
+}
+
+static SIMPLE_DEV_PM_OPS(cdns_spi_dev_pm_ops, cdns_spi_suspend,
+ cdns_spi_resume);
+
+static struct of_device_id cdns_spi_of_match[] = {
+ { .compatible = "xlnx,zynq-spi-r1p6" },
+ { .compatible = "cdns,spi-r1p6" },
+ { /* end of table */ }
+};
+MODULE_DEVICE_TABLE(of, cdns_spi_of_match);
+
+/* cdns_spi_driver - This structure defines the SPI subsystem platform driver */
+static struct platform_driver cdns_spi_driver = {
+ .probe = cdns_spi_probe,
+ .remove = cdns_spi_remove,
+ .driver = {
+ .name = CDNS_SPI_NAME,
+ .owner = THIS_MODULE,
+ .of_match_table = cdns_spi_of_match,
+ .pm = &cdns_spi_dev_pm_ops,
+ },
+};
+
+module_platform_driver(cdns_spi_driver);
+
+MODULE_AUTHOR("Xilinx, Inc.");
+MODULE_DESCRIPTION("Cadence SPI driver");
+MODULE_LICENSE("GPL");
--
1.7.9.5


2014-04-03 11:11:07

by Harini Katakam

[permalink] [raw]
Subject: [PATCH v2 2/2] devicetree: Add devicetree bindings documentation for Cadence SPI

Add spi-cadence bindings documentation.

Signed-off-by: Harini Katakam <[email protected]>
---

v2 changes:
- Separate patch for bindings.
- Add xilinx compatible string; Make compatible string first in the node.
- Use property name num-cs. Make this property optional.

---
.../devicetree/bindings/spi/spi-cadence.txt | 27 ++++++++++++++++++++
1 file changed, 27 insertions(+)
create mode 100644 Documentation/devicetree/bindings/spi/spi-cadence.txt

diff --git a/Documentation/devicetree/bindings/spi/spi-cadence.txt b/Documentation/devicetree/bindings/spi/spi-cadence.txt
new file mode 100644
index 0000000..ccb7599
--- /dev/null
+++ b/Documentation/devicetree/bindings/spi/spi-cadence.txt
@@ -0,0 +1,27 @@
+Cadence SPI controller Device Tree Bindings
+-------------------------------------------
+
+Required properties:
+- compatible : Should be "cdns,spi-r1p6" or "xlnx,zynq-spi-r1p6".
+- reg : Physical base address and size of SPI registers map.
+- interrupts : Property with a value describing the interrupt
+ number.
+- interrupt-parent : Must be core interrupt controller
+- clock-names : List of input clock names - "ref_clk", "pclk"
+ (See clock bindings for details).
+- clocks : Clock phandles (see clock bindings for details).
+
+Optional properties:
+- num-cs : Number of chip selects used.
+
+Example:
+
+ spi@e0007000 {
+ compatible = "xlnx,zynq-spi-r1p6";
+ clock-names = "ref_clk", "pclk";
+ clocks = <&clkc 26>, <&clkc 35>;
+ interrupt-parent = <&intc>;
+ interrupts = <0 49 4>;
+ num-cs = /bits/ 16 <4>;
+ reg = <0xe0007000 0x1000>;
+ } ;
--
1.7.9.5

2014-04-03 21:35:14

by Mark Brown

[permalink] [raw]
Subject: Re: [PATCH v2 2/2] devicetree: Add devicetree bindings documentation for Cadence SPI

On Thu, Apr 03, 2014 at 04:40:31PM +0530, Harini Katakam wrote:

> +Optional properties:
> +- num-cs : Number of chip selects used.

How does this translate to the hardware?

> + num-cs = /bits/ 16 <4>;

What's going on with the /bits/ - is this something that's required for
the property?


Attachments:
(No filename) (292.00 B)
signature.asc (836.00 B)
Digital signature
Download all attachments

2014-04-03 21:43:48

by Mark Brown

[permalink] [raw]
Subject: Re: [PATCH v2 1/2] SPI: Add driver for Cadence SPI controller

On Thu, Apr 03, 2014 at 04:40:30PM +0530, Harini Katakam wrote:
> Add driver for Cadence SPI controller. This is used in Xilinx Zynq.

I just reviewed a driver for "Zynq Quad SPI controller" from Punnaiah
Choudary Kalluri (CCed) which seems *very* similar to this one. Are
there opportunities for code sharing here (I'm not entirely sure the
hardware blocks are different, though I didn't check in detail).

I've left the entire context in for the benefit of those I just CCed in.

> Signed-off-by: Harini Katakam <[email protected]>
> ---
>
> v2 changes:
> - Use xilinx compatible string too.
> - Changes read register and write register functions to static inline.
> - Removed unecessary dev_info and dev_dbg prints.
> - Return IRQ_HANDLED only when interrupt is handled.
> - Use a default num-cs value.
> - Do init_hardware before requesting irq.
> - Remove unecessary master_put()
> - Set master->max_speed_hz
> - Check for busy in cdns_setup().
> Retained this function with this check as opposed to removing.
> The reason for this is clock configuration needs to be done for
> the first time before enable is done in prepare_hardware;
> prepare_hardware however, doesn't receive spi_device structure.
> - Implememnt transfer_one instead of transfer_one_message.
> Remove wait_for_completion as this is done by core.
> - Implement set_cs.
> - Clock enable/disable in prepare/unprepare respectively.
> - In suspend, remove reset of hardware; simply call unprepare_hardware.
> - In suspend/resume call master_suspend/resume respectively.
> - Check for irq<=0 in probe.
> - Remove MODULE_ALIAS.
>
> ---
> drivers/spi/Kconfig | 7 +
> drivers/spi/Makefile | 1 +
> drivers/spi/spi-cadence.c | 677 +++++++++++++++++++++++++++++++++++++++++++++
> 3 files changed, 685 insertions(+)
> create mode 100644 drivers/spi/spi-cadence.c
>
> diff --git a/drivers/spi/Kconfig b/drivers/spi/Kconfig
> index 581ee2a..aeae44a 100644
> --- a/drivers/spi/Kconfig
> +++ b/drivers/spi/Kconfig
> @@ -148,6 +148,13 @@ config SPI_BUTTERFLY
> inexpensive battery powered microcontroller evaluation board.
> This same cable can be used to flash new firmware.
>
> +config SPI_CADENCE
> + tristate "Cadence SPI controller"
> + depends on SPI_MASTER
> + help
> + This selects the Cadence SPI controller master driver
> + used by Xilinx Zynq.
> +
> config SPI_CLPS711X
> tristate "CLPS711X host SPI controller"
> depends on ARCH_CLPS711X
> diff --git a/drivers/spi/Makefile b/drivers/spi/Makefile
> index 95af48d..1be2ed7 100644
> --- a/drivers/spi/Makefile
> +++ b/drivers/spi/Makefile
> @@ -22,6 +22,7 @@ obj-$(CONFIG_SPI_BFIN_V3) += spi-bfin-v3.o
> obj-$(CONFIG_SPI_BFIN_SPORT) += spi-bfin-sport.o
> obj-$(CONFIG_SPI_BITBANG) += spi-bitbang.o
> obj-$(CONFIG_SPI_BUTTERFLY) += spi-butterfly.o
> +obj-$(CONFIG_SPI_CADENCE) += spi-cadence.o
> obj-$(CONFIG_SPI_CLPS711X) += spi-clps711x.o
> obj-$(CONFIG_SPI_COLDFIRE_QSPI) += spi-coldfire-qspi.o
> obj-$(CONFIG_SPI_DAVINCI) += spi-davinci.o
> diff --git a/drivers/spi/spi-cadence.c b/drivers/spi/spi-cadence.c
> new file mode 100644
> index 0000000..071642d
> --- /dev/null
> +++ b/drivers/spi/spi-cadence.c
> @@ -0,0 +1,677 @@
> +/*
> + * Cadence SPI controller driver (master mode only)
> + *
> + * Copyright (C) 2008 - 2014 Xilinx, Inc.
> + *
> + * based on Blackfin On-Chip SPI Driver (spi_bfin5xx.c)
> + *
> + * This program is free software; you can redistribute it and/or modify it under
> + * the terms of the GNU General Public License version 2 as published by the
> + * Free Software Foundation; either version 2 of the License, or (at your
> + * option) any later version.
> + */
> +
> +#include <linux/clk.h>
> +#include <linux/delay.h>
> +#include <linux/interrupt.h>
> +#include <linux/io.h>
> +#include <linux/module.h>
> +#include <linux/of_irq.h>
> +#include <linux/of_address.h>
> +#include <linux/platform_device.h>
> +#include <linux/spi/spi.h>
> +
> +/* Name of this driver */
> +#define CDNS_SPI_NAME "cdns-spi"
> +
> +/* Register offset definitions */
> +#define CDNS_SPI_CR_OFFSET 0x00 /* Configuration Register, RW */
> +#define CDNS_SPI_ISR_OFFSET 0x04 /* Interrupt Status Register, RO */
> +#define CDNS_SPI_IER_OFFSET 0x08 /* Interrupt Enable Register, WO */
> +#define CDNS_SPI_IDR_OFFSET 0x0c /* Interrupt Disable Register, WO */
> +#define CDNS_SPI_IMR_OFFSET 0x10 /* Interrupt Enabled Mask Register, RO */
> +#define CDNS_SPI_ER_OFFSET 0x14 /* Enable/Disable Register, RW */
> +#define CDNS_SPI_DR_OFFSET 0x18 /* Delay Register, RW */
> +#define CDNS_SPI_TXD_OFFSET 0x1C /* Data Transmit Register, WO */
> +#define CDNS_SPI_RXD_OFFSET 0x20 /* Data Receive Register, RO */
> +#define CDNS_SPI_SICR_OFFSET 0x24 /* Slave Idle Count Register, RW */
> +#define CDNS_SPI_THLD_OFFSET 0x28 /* Transmit FIFO Watermark Register,RW */
> +
> +/*
> + * SPI Configuration Register bit Masks
> + *
> + * This register contains various control bits that affect the operation
> + * of the SPI controller
> + */
> +#define CDNS_SPI_CR_MANSTRT_MASK 0x00010000 /* Manual TX Start */
> +#define CDNS_SPI_CR_CPHA_MASK 0x00000004 /* Clock Phase Control */
> +#define CDNS_SPI_CR_CPOL_MASK 0x00000002 /* Clock Polarity Control */
> +#define CDNS_SPI_CR_SSCTRL_MASK 0x00003C00 /* Slave Select Mask */
> +#define CDNS_SPI_CR_BAUD_DIV_MASK 0x00000038 /* Baud Rate Divisor Mask */
> +#define CDNS_SPI_CR_MSTREN_MASK 0x00000001 /* Master Enable Mask */
> +#define CDNS_SPI_CR_MANSTRTEN_MASK 0x00008000 /* Manual TX Enable Mask */
> +#define CDNS_SPI_CR_SSFORCE_MASK 0x00004000 /* Manual SS Enable Mask */
> +#define CDNS_SPI_CR_BAUD_DIV_4_MASK 0x00000008 /* Default Baud Div Mask */
> +#define CDNS_SPI_CR_DEFAULT_MASK (CDNS_SPI_CR_MSTREN_MASK | \
> + CDNS_SPI_CR_SSCTRL_MASK | \
> + CDNS_SPI_CR_SSFORCE_MASK | \
> + CDNS_SPI_CR_BAUD_DIV_4_MASK)
> +
> +/*
> + * SPI Configuration Register - Baud rate and slave select
> + *
> + * These are the values used in the calculation of baud rate divisor and
> + * setting the slave select.
> + */
> +
> +#define CDNS_SPI_BAUD_DIV_MAX 7 /* Baud rate divisor maximum */
> +#define CDNS_SPI_BAUD_DIV_MIN 1 /* Baud rate divisor minimum */
> +#define CDNS_SPI_BAUD_DIV_SHIFT 3 /* Baud rate divisor shift in CR */
> +#define CDNS_SPI_SS_SHIFT 10 /* Slave Select field shift in CR */
> +#define CDNS_SPI_SS0 0x1 /* Slave Select zero */
> +
> +/*
> + * SPI Interrupt Registers bit Masks
> + *
> + * All the four interrupt registers (Status/Mask/Enable/Disable) have the same
> + * bit definitions.
> + */
> +#define CDNS_SPI_IXR_TXOW_MASK 0x00000004 /* SPI TX FIFO Overwater */
> +#define CDNS_SPI_IXR_MODF_MASK 0x00000002 /* SPI Mode Fault */
> +#define CDNS_SPI_IXR_RXNEMTY_MASK 0x00000010 /* SPI RX FIFO Not Empty */
> +#define CDNS_SPI_IXR_DEFAULT_MASK (CDNS_SPI_IXR_TXOW_MASK | \
> + CDNS_SPI_IXR_MODF_MASK)
> +#define CDNS_SPI_IXR_TXFULL_MASK 0x00000008 /* SPI TX Full */
> +#define CDNS_SPI_IXR_ALL_MASK 0x0000007F /* SPI all interrupts */
> +
> +/*
> + * SPI Enable Register bit Masks
> + *
> + * This register is used to enable or disable the SPI controller
> + */
> +#define CDNS_SPI_ER_ENABLE_MASK 0x00000001 /* SPI Enable Bit Mask */
> +#define CDNS_SPI_ER_DISABLE_MASK 0x0 /* SPI Disable Bit Mask */
> +
> +/* SPI timeout value */
> +#define CDNS_SPI_TIMEOUT (5 * HZ)
> +
> +/* SPI FIFO depth in bytes */
> +#define CDNS_SPI_FIFO_DEPTH 128
> +
> +/* Default number of chip select lines */
> +#define CDNS_SPI_DEFAULT_NUM_CS 4
> +
> +/* Driver state - suspend/ready */
> +enum driver_state_val {
> + CDNS_SPI_DRIVER_STATE_READY = 0,
> + CDNS_SPI_DRIVER_STATE_SUSPEND
> +};
> +
> +/**
> + * struct cdns_spi - This definition defines spi driver instance
> + * @regs: Virtual address of the SPI controller registers
> + * @ref_clk: Pointer to the peripheral clock
> + * @pclk: Pointer to the APB clock
> + * @speed_hz: Current SPI bus clock speed in Hz
> + * @txbuf: Pointer to the TX buffer
> + * @rxbuf: Pointer to the RX buffer
> + * @remaining_bytes: Number of bytes left to transfer
> + * @requested_bytes: Number of bytes requested
> + * @dev_busy: Device busy flag
> + * @done: Transfer complete status
> + * @driver_state: Describes driver state - ready/suspended
> + */
> +struct cdns_spi {
> + void __iomem *regs;
> + struct clk *ref_clk;
> + struct clk *pclk;
> + u32 speed_hz;
> + const u8 *txbuf;
> + u8 *rxbuf;
> + int remaining_bytes;
> + int requested_bytes;
> + u8 dev_busy;
> + enum driver_state_val driver_state;
> +};
> +
> +/* Macros for the SPI controller read/write */
> +static inline u32 cdns_spi_read(struct cdns_spi *xspi, u32 offset)
> +{
> + return readl_relaxed(xspi->regs + offset);
> +}
> +
> +static inline void cdns_spi_write(struct cdns_spi *xspi, u32 offset, u32 val)
> +{
> + writel_relaxed(val, xspi->regs + offset);
> +}
> +
> +/**
> + * cdns_spi_init_hw - Initialize the hardware and configure the SPI controller
> + * @xspi: Pointer to the cdns_spi structure
> + *
> + * On reset the SPI controller is configured to be in master mode, baud rate
> + * divisor is set to 4, threshold value for TX FIFO not full interrupt is set
> + * to 1 and size of the word to be transferred as 8 bit.
> + * This function initializes the SPI controller to disable and clear all the
> + * interrupts, enable manual slave select and manual start, deselect all the
> + * chip select lines, and enable the SPI controller.
> + */
> +static void cdns_spi_init_hw(struct cdns_spi *xspi)
> +{
> + cdns_spi_write(xspi, CDNS_SPI_ER_OFFSET,
> + CDNS_SPI_ER_DISABLE_MASK);
> + cdns_spi_write(xspi, CDNS_SPI_IDR_OFFSET,
> + CDNS_SPI_IXR_ALL_MASK);
> +
> + /* Clear the RX FIFO */
> + while (cdns_spi_read(xspi, CDNS_SPI_ISR_OFFSET) &
> + CDNS_SPI_IXR_RXNEMTY_MASK)
> + cdns_spi_read(xspi, CDNS_SPI_RXD_OFFSET);
> +
> + cdns_spi_write(xspi, CDNS_SPI_ISR_OFFSET,
> + CDNS_SPI_IXR_ALL_MASK);
> + cdns_spi_write(xspi, CDNS_SPI_CR_OFFSET,
> + CDNS_SPI_CR_DEFAULT_MASK);
> + cdns_spi_write(xspi, CDNS_SPI_ER_OFFSET,
> + CDNS_SPI_ER_ENABLE_MASK);
> +}
> +
> +/**
> + * cdns_spi_chipselect - Select or deselect the chip select line
> + * @spi: Pointer to the spi_device structure
> + * @is_on: Select(0) or deselect (1) the chip select line
> + */
> +static void cdns_spi_chipselect(struct spi_device *spi, bool is_high)
> +{
> + struct cdns_spi *xspi = spi_master_get_devdata(spi->master);
> + u32 ctrl_reg;
> +
> + ctrl_reg = cdns_spi_read(xspi, CDNS_SPI_CR_OFFSET);
> +
> + if (is_high) {
> + /* Deselect the slave */
> + ctrl_reg |= CDNS_SPI_CR_SSCTRL_MASK;
> + } else {
> + /* Select the slave */
> + ctrl_reg &= ~CDNS_SPI_CR_SSCTRL_MASK;
> + ctrl_reg |= ((~(CDNS_SPI_SS0 << spi->chip_select)) <<
> + CDNS_SPI_SS_SHIFT) & CDNS_SPI_CR_SSCTRL_MASK;
> + }
> +
> + cdns_spi_write(xspi, CDNS_SPI_CR_OFFSET, ctrl_reg);
> +}
> +
> +/**
> + * cdns_spi_config_clock - Sets clock polarity, phase and frequency
> + * @spi: Pointer to the spi_device structure
> + * @transfer: Pointer to the spi_transfer structure which provides
> + * information about next transfer setup parameters
> + *
> + * Sets the requested clock polarity, phase and frequency.
> + * Note: If the requested frequency is not an exact match with what can be
> + * obtained using the prescalar value the driver sets the clock frequency which
> + * is lower than the requested frequency (maximum lower) for the transfer. If
> + * the requested frequency is higher or lower than that is supported by the SPI
> + * controller the driver will set the highest or lowest frequency supported by
> + * controller.
> + */
> +static void cdns_spi_config_clock(struct spi_device *spi,
> + struct spi_transfer *transfer)
> +{
> + struct cdns_spi *xspi = spi_master_get_devdata(spi->master);
> + u32 ctrl_reg, req_hz, baud_rate_val;
> + unsigned long frequency;
> +
> + if (transfer)
> + req_hz = transfer->speed_hz;
> + else
> + req_hz = spi->max_speed_hz;
> +
> + frequency = clk_get_rate(xspi->ref_clk);
> +
> + ctrl_reg = cdns_spi_read(xspi, CDNS_SPI_CR_OFFSET);
> +
> + /* Set the SPI clock phase and clock polarity */
> + ctrl_reg &= ~(CDNS_SPI_CR_CPHA_MASK | CDNS_SPI_CR_CPOL_MASK);
> + if (spi->mode & SPI_CPHA)
> + ctrl_reg |= CDNS_SPI_CR_CPHA_MASK;
> + if (spi->mode & SPI_CPOL)
> + ctrl_reg |= CDNS_SPI_CR_CPOL_MASK;
> +
> + /* Set the clock frequency */
> + if (xspi->speed_hz != req_hz) {
> + /* first valid value is 1 */
> + baud_rate_val = CDNS_SPI_BAUD_DIV_MIN;
> + while ((baud_rate_val < CDNS_SPI_BAUD_DIV_MAX) &&
> + (frequency / (2 << baud_rate_val)) > req_hz)
> + baud_rate_val++;
> +
> + ctrl_reg &= ~CDNS_SPI_CR_BAUD_DIV_MASK;
> + ctrl_reg |= baud_rate_val << CDNS_SPI_BAUD_DIV_SHIFT;
> +
> + xspi->speed_hz = frequency / (2 << baud_rate_val);
> + }
> + cdns_spi_write(xspi, CDNS_SPI_CR_OFFSET, ctrl_reg);
> +}
> +
> +/**
> + * cdns_spi_setup_transfer - Configure SPI controller for specified transfer
> + * @spi: Pointer to the spi_device structure
> + * @transfer: Pointer to the spi_transfer structure which provides
> + * information about next transfer setup parameters
> + *
> + * Sets the operational mode of SPI controller for the next SPI transfer and
> + * sets the requested clock frequency.
> + *
> + * Return: Always 0
> + */
> +static int cdns_spi_setup_transfer(struct spi_device *spi,
> + struct spi_transfer *transfer)
> +{
> + struct cdns_spi *xspi = spi_master_get_devdata(spi->master);
> +
> + cdns_spi_config_clock(spi, transfer);
> +
> + dev_dbg(&spi->dev, "%s, mode %d, %u bits/w, %u clock speed\n",
> + __func__, spi->mode, spi->bits_per_word,
> + xspi->speed_hz);
> +
> + return 0;
> +}
> +
> +/**
> + * cdns_spi_setup - Configure the SPI controller
> + * @spi: Pointer to the spi_device structure
> + *
> + * Sets the operational mode of SPI controller for the next SPI transfer, sets
> + * the baud rate and divisor value to setup the requested spi clock.
> + *
> + * Return: 0 on success and error value on error
> + */
> +static int cdns_spi_setup(struct spi_device *spi)
> +{
> + if (spi->master->busy)
> + return -EBUSY;
> +
> + return cdns_spi_setup_transfer(spi, NULL);
> +}
> +
> +/**
> + * cdns_spi_fill_tx_fifo - Fills the TX FIFO with as many bytes as possible
> + * @xspi: Pointer to the cdns_spi structure
> + */
> +static void cdns_spi_fill_tx_fifo(struct cdns_spi *xspi)
> +{
> + unsigned long trans_cnt = 0;
> +
> + while ((trans_cnt < CDNS_SPI_FIFO_DEPTH) &&
> + (xspi->remaining_bytes > 0)) {
> + if (xspi->txbuf)
> + cdns_spi_write(xspi, CDNS_SPI_TXD_OFFSET,
> + *xspi->txbuf++);
> + else
> + cdns_spi_write(xspi, CDNS_SPI_TXD_OFFSET, 0);
> +
> + xspi->remaining_bytes--;
> + trans_cnt++;
> + }
> +}
> +
> +/**
> + * cdns_spi_irq - Interrupt service routine of the SPI controller
> + * @irq: IRQ number
> + * @dev_id: Pointer to the xspi structure
> + *
> + * This function handles TX empty and Mode Fault interrupts only.
> + * On TX empty interrupt this function reads the received data from RX FIFO and
> + * fills the TX FIFO if there is any data remaining to be transferred.
> + * On Mode Fault interrupt this function indicates that transfer is completed,
> + * the SPI subsystem will identify the error as the remaining bytes to be
> + * transferred is non-zero.
> + *
> + * Return: IRQ_HANDLED when handled; IRQ_NONE otherwise.
> + */
> +static irqreturn_t cdns_spi_irq(int irq, void *dev_id)
> +{
> + struct spi_master *master = dev_id;
> + struct cdns_spi *xspi = spi_master_get_devdata(master);
> + u32 intr_status, status;
> +
> + status = IRQ_NONE;
> + intr_status = cdns_spi_read(xspi, CDNS_SPI_ISR_OFFSET);
> + cdns_spi_write(xspi, CDNS_SPI_ISR_OFFSET, intr_status);
> +
> + if (intr_status & CDNS_SPI_IXR_MODF_MASK) {
> + /* Indicate that transfer is completed, the SPI subsystem will
> + * identify the error as the remaining bytes to be
> + * transferred is non-zero
> + */
> + cdns_spi_write(xspi, CDNS_SPI_IDR_OFFSET,
> + CDNS_SPI_IXR_DEFAULT_MASK);
> + spi_finalize_current_transfer(master);
> + status = IRQ_HANDLED;
> + } else if (intr_status & CDNS_SPI_IXR_TXOW_MASK) {
> + unsigned long trans_cnt;
> +
> + trans_cnt = xspi->requested_bytes - xspi->remaining_bytes;
> +
> + /* Read out the data from the RX FIFO */
> + while (trans_cnt) {
> + u8 data;
> +
> + data = cdns_spi_read(xspi, CDNS_SPI_RXD_OFFSET);
> + if (xspi->rxbuf)
> + *xspi->rxbuf++ = data;
> +
> + xspi->requested_bytes--;
> + trans_cnt--;
> + }
> +
> + if (xspi->remaining_bytes) {
> + /* There is more data to send */
> + cdns_spi_fill_tx_fifo(xspi);
> + } else {
> + /* Transfer is completed */
> + cdns_spi_write(xspi, CDNS_SPI_IDR_OFFSET,
> + CDNS_SPI_IXR_DEFAULT_MASK);
> + spi_finalize_current_transfer(master);
> + }
> + status = IRQ_HANDLED;
> + }
> +
> + return status;
> +}
> +
> +/**
> + * cdns_transfer_one - Initiates the SPI transfer
> + * @master: Pointer to spi_master structure
> + * @spi: Pointer to the spi_device structure
> + * @transfer: Pointer to the spi_transfer structure which provides
> + * information about next transfer parameters
> + *
> + * This function fills the TX FIFO, starts the SPI transfer and
> + * returns a positive transfer count so that core will wait for completion.
> + *
> + * Return: Number of bytes transferred in the last transfer
> + */
> +static int cdns_transfer_one(struct spi_master *master,
> + struct spi_device *spi,
> + struct spi_transfer *transfer)
> +{
> + struct cdns_spi *xspi = spi_master_get_devdata(master);
> +
> + xspi->txbuf = transfer->tx_buf;
> + xspi->rxbuf = transfer->rx_buf;
> + xspi->remaining_bytes = transfer->len;
> + xspi->requested_bytes = transfer->len;
> +
> + cdns_spi_setup_transfer(spi, transfer);
> +
> + cdns_spi_fill_tx_fifo(xspi);
> +
> + cdns_spi_write(xspi, CDNS_SPI_IER_OFFSET,
> + CDNS_SPI_IXR_DEFAULT_MASK);
> + return transfer->len;
> +}
> +
> +/**
> + * cdns_prepare_transfer_hardware - Prepares hardware for transfer.
> + * @master: Pointer to the spi_master structure which provides
> + * information about the controller.
> + *
> + * This function enables SPI master controller.
> + *
> + * Return: 0 always
> + */
> +static int cdns_prepare_transfer_hardware(struct spi_master *master)
> +{
> + struct cdns_spi *xspi = spi_master_get_devdata(master);
> +
> + clk_enable(xspi->ref_clk);
> + clk_enable(xspi->pclk);
> + cdns_spi_write(xspi, CDNS_SPI_ER_OFFSET,
> + CDNS_SPI_ER_ENABLE_MASK);
> +
> + return 0;
> +}
> +
> +/**
> + * cdns_unprepare_transfer_hardware - Relaxes hardware after transfer
> + * @master: Pointer to the spi_master structure which provides
> + * information about the controller.
> + *
> + * This function disables the SPI master controller.
> + *
> + * Return: 0 always
> + */
> +static int cdns_unprepare_transfer_hardware(struct spi_master *master)
> +{
> + struct cdns_spi *xspi = spi_master_get_devdata(master);
> +
> + cdns_spi_write(xspi, CDNS_SPI_ER_OFFSET,
> + CDNS_SPI_ER_DISABLE_MASK);
> + clk_disable(xspi->ref_clk);
> + clk_disable(xspi->pclk);
> +
> + return 0;
> +}
> +
> +/**
> + * cdns_spi_probe - Probe method for the SPI driver
> + * @pdev: Pointer to the platform_device structure
> + *
> + * This function initializes the driver data structures and the hardware.
> + *
> + * Return: 0 on success and error value on error
> + */
> +static int cdns_spi_probe(struct platform_device *pdev)
> +{
> + int ret = 0, irq;
> + struct spi_master *master;
> + struct cdns_spi *xspi;
> + struct resource *res;
> +
> + master = spi_alloc_master(&pdev->dev, sizeof(*xspi));
> + if (master == NULL)
> + return -ENOMEM;
> +
> + xspi = spi_master_get_devdata(master);
> + master->dev.of_node = pdev->dev.of_node;
> + platform_set_drvdata(pdev, master);
> +
> + res = platform_get_resource(pdev, IORESOURCE_MEM, 0);
> + xspi->regs = devm_ioremap_resource(&pdev->dev, res);
> + if (IS_ERR(xspi->regs)) {
> + ret = PTR_ERR(xspi->regs);
> + goto remove_master;
> + }
> +
> + xspi->pclk = devm_clk_get(&pdev->dev, "pclk");
> + if (IS_ERR(xspi->pclk)) {
> + dev_err(&pdev->dev, "pclk clock not found.\n");
> + ret = PTR_ERR(xspi->pclk);
> + goto remove_master;
> + }
> +
> + xspi->ref_clk = devm_clk_get(&pdev->dev, "ref_clk");
> + if (IS_ERR(xspi->ref_clk)) {
> + dev_err(&pdev->dev, "ref_clk clock not found.\n");
> + ret = PTR_ERR(xspi->ref_clk);
> + goto remove_master;
> + }
> +
> + ret = clk_prepare_enable(xspi->pclk);
> + if (ret) {
> + dev_err(&pdev->dev, "Unable to enable APB clock.\n");
> + goto remove_master;
> + }
> +
> + ret = clk_prepare_enable(xspi->ref_clk);
> + if (ret) {
> + dev_err(&pdev->dev, "Unable to enable device clock.\n");
> + goto clk_dis_apb;
> + }
> +
> + /* SPI controller initializations */
> + cdns_spi_init_hw(xspi);
> +
> + irq = platform_get_irq(pdev, 0);
> + if (irq <= 0) {
> + ret = -ENXIO;
> + dev_err(&pdev->dev, "irq number is invalid\n");
> + goto remove_master;
> + }
> +
> + ret = devm_request_irq(&pdev->dev, irq, cdns_spi_irq,
> + 0, pdev->name, master);
> + if (ret != 0) {
> + ret = -ENXIO;
> + dev_err(&pdev->dev, "request_irq failed\n");
> + goto remove_master;
> + }
> +
> + ret = of_property_read_u16(pdev->dev.of_node, "num-cs",
> + &master->num_chipselect);
> + if (ret < 0)
> + master->num_chipselect = CDNS_SPI_DEFAULT_NUM_CS;
> +
> + master->setup = cdns_spi_setup;
> + master->prepare_transfer_hardware = cdns_prepare_transfer_hardware;
> + master->transfer_one = cdns_transfer_one;
> + master->unprepare_transfer_hardware = cdns_unprepare_transfer_hardware;
> + master->set_cs = cdns_spi_chipselect;
> + master->mode_bits = SPI_CPOL | SPI_CPHA;
> +
> + /* Set to default valid value */
> + master->max_speed_hz = clk_get_rate(xspi->ref_clk) / 4;
> + xspi->speed_hz = master->max_speed_hz;
> +
> + master->bits_per_word_mask = SPI_BPW_MASK(8);
> +
> + xspi->driver_state = CDNS_SPI_DRIVER_STATE_READY;
> +
> + ret = spi_register_master(master);
> + if (ret) {
> + dev_err(&pdev->dev, "spi_register_master failed\n");
> + goto clk_dis_all;
> + }
> +
> + return ret;
> +
> +clk_dis_all:
> + clk_disable_unprepare(xspi->ref_clk);
> +clk_dis_apb:
> + clk_disable_unprepare(xspi->pclk);
> +remove_master:
> + spi_master_put(master);
> + return ret;
> +}
> +
> +/**
> + * cdns_spi_remove - Remove method for the SPI driver
> + * @pdev: Pointer to the platform_device structure
> + *
> + * This function is called if a device is physically removed from the system or
> + * if the driver module is being unloaded. It frees all resources allocated to
> + * the device.
> + *
> + * Return: 0 on success and error value on error
> + */
> +static int cdns_spi_remove(struct platform_device *pdev)
> +{
> + struct spi_master *master = platform_get_drvdata(pdev);
> + struct cdns_spi *xspi = spi_master_get_devdata(master);
> +
> + cdns_spi_write(xspi, CDNS_SPI_ER_OFFSET,
> + CDNS_SPI_ER_DISABLE_MASK);
> +
> + clk_disable_unprepare(xspi->ref_clk);
> + clk_disable_unprepare(xspi->pclk);
> +
> + spi_unregister_master(master);
> +
> + return 0;
> +}
> +
> +/**
> + * cdns_spi_suspend - Suspend method for the SPI driver
> + * @dev: Address of the platform_device structure
> + *
> + * This function disables the SPI controller and
> + * changes the driver state to "suspend"
> + *
> + * Return: Always 0
> + */
> +static int __maybe_unused cdns_spi_suspend(struct device *dev)
> +{
> + struct platform_device *pdev = container_of(dev,
> + struct platform_device, dev);
> + struct spi_master *master = platform_get_drvdata(pdev);
> +
> + spi_master_suspend(master);
> +
> + cdns_unprepare_transfer_hardware(master);
> +
> + return 0;
> +}
> +
> +/**
> + * cdns_spi_resume - Resume method for the SPI driver
> + * @dev: Address of the platform_device structure
> + *
> + * This function changes the driver state to "ready"
> + *
> + * Return: 0 on success and error value on error
> + */
> +static int __maybe_unused cdns_spi_resume(struct device *dev)
> +{
> + struct platform_device *pdev = container_of(dev,
> + struct platform_device, dev);
> + struct spi_master *master = platform_get_drvdata(pdev);
> + struct cdns_spi *xspi = spi_master_get_devdata(master);
> + int ret = 0;
> +
> + ret = clk_enable(xspi->pclk);
> + if (ret) {
> + dev_err(dev, "Cannot enable APB clock.\n");
> + return ret;
> + }
> +
> + ret = clk_enable(xspi->ref_clk);
> + if (ret) {
> + dev_err(dev, "Cannot enable device clock.\n");
> + clk_disable(xspi->pclk);
> + return ret;
> + }
> + spi_master_resume(master);
> +
> + return 0;
> +}
> +
> +static SIMPLE_DEV_PM_OPS(cdns_spi_dev_pm_ops, cdns_spi_suspend,
> + cdns_spi_resume);
> +
> +static struct of_device_id cdns_spi_of_match[] = {
> + { .compatible = "xlnx,zynq-spi-r1p6" },
> + { .compatible = "cdns,spi-r1p6" },
> + { /* end of table */ }
> +};
> +MODULE_DEVICE_TABLE(of, cdns_spi_of_match);
> +
> +/* cdns_spi_driver - This structure defines the SPI subsystem platform driver */
> +static struct platform_driver cdns_spi_driver = {
> + .probe = cdns_spi_probe,
> + .remove = cdns_spi_remove,
> + .driver = {
> + .name = CDNS_SPI_NAME,
> + .owner = THIS_MODULE,
> + .of_match_table = cdns_spi_of_match,
> + .pm = &cdns_spi_dev_pm_ops,
> + },
> +};
> +
> +module_platform_driver(cdns_spi_driver);
> +
> +MODULE_AUTHOR("Xilinx, Inc.");
> +MODULE_DESCRIPTION("Cadence SPI driver");
> +MODULE_LICENSE("GPL");
> --
> 1.7.9.5
>
>


Attachments:
(No filename) (24.83 kB)
signature.asc (836.00 B)
Digital signature
Download all attachments

2014-04-04 03:00:45

by Harini Katakam

[permalink] [raw]
Subject: Re: [PATCH v2 2/2] devicetree: Add devicetree bindings documentation for Cadence SPI

Hi Mark,

On Fri, Apr 4, 2014 at 3:04 AM, Mark Brown <[email protected]> wrote:
> On Thu, Apr 03, 2014 at 04:40:31PM +0530, Harini Katakam wrote:
>
>> +Optional properties:
>> +- num-cs : Number of chip selects used.
>
> How does this translate to the hardware?

This IP can drive 4 slaves.
The CS line to be driven is selected in spi device structure and
that is driven by the software.

>
>> + num-cs = /bits/ 16 <4>;
>
> What's going on with the /bits/ - is this something that's required for
> the property?

The master->num-chipselect property is 16 bit but writing <4> here directly
leads to 0 being read in of_property_read (because it's big endian).
Instead using of property read u32 and then copying, we decided to do this.
This was discussed on v2 between Michal and Rob:
>>>> + num-chip-select = /bits/ 16 <4>;
>>
>> I was expecting you will comment this a little bit. :-)
>> Because all just reading this num-cs as 32bit and then
>> assigning this value to master->num_chipselect which is 16bit.
>
> Well, everyone else has that problem then. Obviously it takes a bit
> more care than just reading into a u32, but that is a kernel problem
> and not a problem of the binding.
They are not reading it directly with read_u32 but they are using
intermediate u32 value which is assigned to u16 which is fine.
This pattern is in most drivers(maybe all).
The point is if binding should or can't simplify driver code.
And from your reaction above I expect that it is up to driver
owner and binding doc how you want to do it.

Regards,
Harini

2014-04-04 03:49:51

by Harini Katakam

[permalink] [raw]
Subject: Re: [PATCH v2 1/2] SPI: Add driver for Cadence SPI controller

Hi Mark

On Fri, Apr 4, 2014 at 3:13 AM, Mark Brown <[email protected]> wrote:
> On Thu, Apr 03, 2014 at 04:40:30PM +0530, Harini Katakam wrote:
>> Add driver for Cadence SPI controller. This is used in Xilinx Zynq.
>
> I just reviewed a driver for "Zynq Quad SPI controller" from Punnaiah
> Choudary Kalluri (CCed) which seems *very* similar to this one. Are
> there opportunities for code sharing here (I'm not entirely sure the
> hardware blocks are different, though I didn't check in detail).
>

Thanks for the review.

QSPI is a Xilinx IP built on top of cadence SPI with
considerable functional changes.
As explained in the QSPI patch, there are three configurations
QSPI supports :

- A single flash device connected with 1 CS and 4 IO lines
- Two flash devices connected over two separate sets of 4 IO lines
and two CS lines which are driven together.
- Two flash devices connected with two separate CS line and one
common set of 4 IO lines.

This first set of QSPI patches is only for the single flash configuration.
As the next two configurations follow, QSPI driver will differ from SPI
even more. That's why it might be better to have two separate drivers.
It will avoid a lot of "if spi/ if qspi" checks.

I will send an RFC with proposed changes for all QSPI configurations.

Also, I've replied to your comments on the QSPI driver.
(The QSPI driver already addresses the comments for SPI v1)
Except in two places where the comment was only applicable to QSPI driver,
the replies hold good for both SPI and QSPI drivers.
If you would like to continue the discussion on that thread, I'm ok with it.
FYI, I'll be sending the next versions for both drivers after further
discussion concludes.

Regards,
Harini

2014-04-04 08:09:58

by Geert Uytterhoeven

[permalink] [raw]
Subject: Re: [PATCH v2 2/2] devicetree: Add devicetree bindings documentation for Cadence SPI

Hi Harini,

On Fri, Apr 4, 2014 at 5:00 AM, Harini Katakam
<[email protected]> wrote:
>>> + num-cs = /bits/ 16 <4>;
>>
>> What's going on with the /bits/ - is this something that's required for
>> the property?
>
> The master->num-chipselect property is 16 bit but writing <4> here directly
> leads to 0 being read in of_property_read (because it's big endian).
> Instead using of property read u32 and then copying, we decided to do this.
> This was discussed on v2 between Michal and Rob:
>>>>> + num-chip-select = /bits/ 16 <4>;
>>>
>>> I was expecting you will comment this a little bit. :-)
>>> Because all just reading this num-cs as 32bit and then
>>> assigning this value to master->num_chipselect which is 16bit.
>>
>> Well, everyone else has that problem then. Obviously it takes a bit
>> more care than just reading into a u32, but that is a kernel problem
>> and not a problem of the binding.
> They are not reading it directly with read_u32 but they are using
> intermediate u32 value which is assigned to u16 which is fine.
> This pattern is in most drivers(maybe all).
> The point is if binding should or can't simplify driver code.
> And from your reaction above I expect that it is up to driver
> owner and binding doc how you want to do it.

IMHO this "/bits/ 16" doesn't simplify the binding.

As "num-cs" is a generic spi subsystem binding, it should not be
restricted to 16 bits for the sake of a driver. As your hardware can drive 4
chip selects, you could represent it in 3 bits (don't!).

Simple integers are 32 bit in DT, so use a temporary.

Gr{oetje,eeting}s,

Geert

--
Geert Uytterhoeven -- There's lots of Linux beyond ia32 -- [email protected]

In personal conversations with technical people, I call myself a hacker. But
when I'm talking to journalists I just say "programmer" or something like that.
-- Linus Torvalds

2014-04-04 09:04:43

by Sourav Poddar

[permalink] [raw]
Subject: Re: [PATCH v2 1/2] SPI: Add driver for Cadence SPI controller

Hi Harini,
On Thursday 03 April 2014 04:40 PM, Harini Katakam wrote:
> Add driver for Cadence SPI controller. This is used in Xilinx Zynq.
>
> Signed-off-by: Harini Katakam<[email protected]>
> ---
I had looked at cadence qspi controller. What I can see is that your
patch implements "normal spi ode of operation" ? and the patch looks fine.
But, to avail the maximum throughput, I see cadence qspi supports
direct/indirect mode of operations, as well as read data capture logic.

So, do you intent to add any of the above in your driver?

Thanks,
Sourav

>
> v2 changes:
> - Use xilinx compatible string too.
> - Changes read register and write register functions to static inline.
> - Removed unecessary dev_info and dev_dbg prints.
> - Return IRQ_HANDLED only when interrupt is handled.
> - Use a default num-cs value.
> - Do init_hardware before requesting irq.
> - Remove unecessary master_put()
> - Set master->max_speed_hz
> - Check for busy in cdns_setup().
> Retained this function with this check as opposed to removing.
> The reason for this is clock configuration needs to be done for
> the first time before enable is done in prepare_hardware;
> prepare_hardware however, doesn't receive spi_device structure.
> - Implememnt transfer_one instead of transfer_one_message.
> Remove wait_for_completion as this is done by core.
> - Implement set_cs.
> - Clock enable/disable in prepare/unprepare respectively.
> - In suspend, remove reset of hardware; simply call unprepare_hardware.
> - In suspend/resume call master_suspend/resume respectively.
> - Check for irq<=0 in probe.
> - Remove MODULE_ALIAS.
>
> ---
> drivers/spi/Kconfig | 7 +
> drivers/spi/Makefile | 1 +
> drivers/spi/spi-cadence.c | 677 +++++++++++++++++++++++++++++++++++++++++++++
> 3 files changed, 685 insertions(+)
> create mode 100644 drivers/spi/spi-cadence.c
>
> diff --git a/drivers/spi/Kconfig b/drivers/spi/Kconfig
> index 581ee2a..aeae44a 100644
> --- a/drivers/spi/Kconfig
> +++ b/drivers/spi/Kconfig
> @@ -148,6 +148,13 @@ config SPI_BUTTERFLY
> inexpensive battery powered microcontroller evaluation board.
> This same cable can be used to flash new firmware.
>
> +config SPI_CADENCE
> + tristate "Cadence SPI controller"
> + depends on SPI_MASTER
> + help
> + This selects the Cadence SPI controller master driver
> + used by Xilinx Zynq.
> +
> config SPI_CLPS711X
> tristate "CLPS711X host SPI controller"
> depends on ARCH_CLPS711X
> diff --git a/drivers/spi/Makefile b/drivers/spi/Makefile
> index 95af48d..1be2ed7 100644
> --- a/drivers/spi/Makefile
> +++ b/drivers/spi/Makefile
> @@ -22,6 +22,7 @@ obj-$(CONFIG_SPI_BFIN_V3) += spi-bfin-v3.o
> obj-$(CONFIG_SPI_BFIN_SPORT) += spi-bfin-sport.o
> obj-$(CONFIG_SPI_BITBANG) += spi-bitbang.o
> obj-$(CONFIG_SPI_BUTTERFLY) += spi-butterfly.o
> +obj-$(CONFIG_SPI_CADENCE) += spi-cadence.o
> obj-$(CONFIG_SPI_CLPS711X) += spi-clps711x.o
> obj-$(CONFIG_SPI_COLDFIRE_QSPI) += spi-coldfire-qspi.o
> obj-$(CONFIG_SPI_DAVINCI) += spi-davinci.o
> diff --git a/drivers/spi/spi-cadence.c b/drivers/spi/spi-cadence.c
> new file mode 100644
> index 0000000..071642d
> --- /dev/null
> +++ b/drivers/spi/spi-cadence.c
> @@ -0,0 +1,677 @@
> +/*
> + * Cadence SPI controller driver (master mode only)
> + *
> + * Copyright (C) 2008 - 2014 Xilinx, Inc.
> + *
> + * based on Blackfin On-Chip SPI Driver (spi_bfin5xx.c)
> + *
> + * This program is free software; you can redistribute it and/or modify it under
> + * the terms of the GNU General Public License version 2 as published by the
> + * Free Software Foundation; either version 2 of the License, or (at your
> + * option) any later version.
> + */
> +
> +#include<linux/clk.h>
> +#include<linux/delay.h>
> +#include<linux/interrupt.h>
> +#include<linux/io.h>
> +#include<linux/module.h>
> +#include<linux/of_irq.h>
> +#include<linux/of_address.h>
> +#include<linux/platform_device.h>
> +#include<linux/spi/spi.h>
> +
> +/* Name of this driver */
> +#define CDNS_SPI_NAME "cdns-spi"
> +
> +/* Register offset definitions */
> +#define CDNS_SPI_CR_OFFSET 0x00 /* Configuration Register, RW */
> +#define CDNS_SPI_ISR_OFFSET 0x04 /* Interrupt Status Register, RO */
> +#define CDNS_SPI_IER_OFFSET 0x08 /* Interrupt Enable Register, WO */
> +#define CDNS_SPI_IDR_OFFSET 0x0c /* Interrupt Disable Register, WO */
> +#define CDNS_SPI_IMR_OFFSET 0x10 /* Interrupt Enabled Mask Register, RO */
> +#define CDNS_SPI_ER_OFFSET 0x14 /* Enable/Disable Register, RW */
> +#define CDNS_SPI_DR_OFFSET 0x18 /* Delay Register, RW */
> +#define CDNS_SPI_TXD_OFFSET 0x1C /* Data Transmit Register, WO */
> +#define CDNS_SPI_RXD_OFFSET 0x20 /* Data Receive Register, RO */
> +#define CDNS_SPI_SICR_OFFSET 0x24 /* Slave Idle Count Register, RW */
> +#define CDNS_SPI_THLD_OFFSET 0x28 /* Transmit FIFO Watermark Register,RW */
> +
> +/*
> + * SPI Configuration Register bit Masks
> + *
> + * This register contains various control bits that affect the operation
> + * of the SPI controller
> + */
> +#define CDNS_SPI_CR_MANSTRT_MASK 0x00010000 /* Manual TX Start */
> +#define CDNS_SPI_CR_CPHA_MASK 0x00000004 /* Clock Phase Control */
> +#define CDNS_SPI_CR_CPOL_MASK 0x00000002 /* Clock Polarity Control */
> +#define CDNS_SPI_CR_SSCTRL_MASK 0x00003C00 /* Slave Select Mask */
> +#define CDNS_SPI_CR_BAUD_DIV_MASK 0x00000038 /* Baud Rate Divisor Mask */
> +#define CDNS_SPI_CR_MSTREN_MASK 0x00000001 /* Master Enable Mask */
> +#define CDNS_SPI_CR_MANSTRTEN_MASK 0x00008000 /* Manual TX Enable Mask */
> +#define CDNS_SPI_CR_SSFORCE_MASK 0x00004000 /* Manual SS Enable Mask */
> +#define CDNS_SPI_CR_BAUD_DIV_4_MASK 0x00000008 /* Default Baud Div Mask */
> +#define CDNS_SPI_CR_DEFAULT_MASK (CDNS_SPI_CR_MSTREN_MASK | \
> + CDNS_SPI_CR_SSCTRL_MASK | \
> + CDNS_SPI_CR_SSFORCE_MASK | \
> + CDNS_SPI_CR_BAUD_DIV_4_MASK)
> +
> +/*
> + * SPI Configuration Register - Baud rate and slave select
> + *
> + * These are the values used in the calculation of baud rate divisor and
> + * setting the slave select.
> + */
> +
> +#define CDNS_SPI_BAUD_DIV_MAX 7 /* Baud rate divisor maximum */
> +#define CDNS_SPI_BAUD_DIV_MIN 1 /* Baud rate divisor minimum */
> +#define CDNS_SPI_BAUD_DIV_SHIFT 3 /* Baud rate divisor shift in CR */
> +#define CDNS_SPI_SS_SHIFT 10 /* Slave Select field shift in CR */
> +#define CDNS_SPI_SS0 0x1 /* Slave Select zero */
> +
> +/*
> + * SPI Interrupt Registers bit Masks
> + *
> + * All the four interrupt registers (Status/Mask/Enable/Disable) have the same
> + * bit definitions.
> + */
> +#define CDNS_SPI_IXR_TXOW_MASK 0x00000004 /* SPI TX FIFO Overwater */
> +#define CDNS_SPI_IXR_MODF_MASK 0x00000002 /* SPI Mode Fault */
> +#define CDNS_SPI_IXR_RXNEMTY_MASK 0x00000010 /* SPI RX FIFO Not Empty */
> +#define CDNS_SPI_IXR_DEFAULT_MASK (CDNS_SPI_IXR_TXOW_MASK | \
> + CDNS_SPI_IXR_MODF_MASK)
> +#define CDNS_SPI_IXR_TXFULL_MASK 0x00000008 /* SPI TX Full */
> +#define CDNS_SPI_IXR_ALL_MASK 0x0000007F /* SPI all interrupts */
> +
> +/*
> + * SPI Enable Register bit Masks
> + *
> + * This register is used to enable or disable the SPI controller
> + */
> +#define CDNS_SPI_ER_ENABLE_MASK 0x00000001 /* SPI Enable Bit Mask */
> +#define CDNS_SPI_ER_DISABLE_MASK 0x0 /* SPI Disable Bit Mask */
> +
> +/* SPI timeout value */
> +#define CDNS_SPI_TIMEOUT (5 * HZ)
> +
> +/* SPI FIFO depth in bytes */
> +#define CDNS_SPI_FIFO_DEPTH 128
> +
> +/* Default number of chip select lines */
> +#define CDNS_SPI_DEFAULT_NUM_CS 4
> +
> +/* Driver state - suspend/ready */
> +enum driver_state_val {
> + CDNS_SPI_DRIVER_STATE_READY = 0,
> + CDNS_SPI_DRIVER_STATE_SUSPEND
> +};
> +
> +/**
> + * struct cdns_spi - This definition defines spi driver instance
> + * @regs: Virtual address of the SPI controller registers
> + * @ref_clk: Pointer to the peripheral clock
> + * @pclk: Pointer to the APB clock
> + * @speed_hz: Current SPI bus clock speed in Hz
> + * @txbuf: Pointer to the TX buffer
> + * @rxbuf: Pointer to the RX buffer
> + * @remaining_bytes: Number of bytes left to transfer
> + * @requested_bytes: Number of bytes requested
> + * @dev_busy: Device busy flag
> + * @done: Transfer complete status
> + * @driver_state: Describes driver state - ready/suspended
> + */
> +struct cdns_spi {
> + void __iomem *regs;
> + struct clk *ref_clk;
> + struct clk *pclk;
> + u32 speed_hz;
> + const u8 *txbuf;
> + u8 *rxbuf;
> + int remaining_bytes;
> + int requested_bytes;
> + u8 dev_busy;
> + enum driver_state_val driver_state;
> +};
> +
> +/* Macros for the SPI controller read/write */
> +static inline u32 cdns_spi_read(struct cdns_spi *xspi, u32 offset)
> +{
> + return readl_relaxed(xspi->regs + offset);
> +}
> +
> +static inline void cdns_spi_write(struct cdns_spi *xspi, u32 offset, u32 val)
> +{
> + writel_relaxed(val, xspi->regs + offset);
> +}
> +
> +/**
> + * cdns_spi_init_hw - Initialize the hardware and configure the SPI controller
> + * @xspi: Pointer to the cdns_spi structure
> + *
> + * On reset the SPI controller is configured to be in master mode, baud rate
> + * divisor is set to 4, threshold value for TX FIFO not full interrupt is set
> + * to 1 and size of the word to be transferred as 8 bit.
> + * This function initializes the SPI controller to disable and clear all the
> + * interrupts, enable manual slave select and manual start, deselect all the
> + * chip select lines, and enable the SPI controller.
> + */
> +static void cdns_spi_init_hw(struct cdns_spi *xspi)
> +{
> + cdns_spi_write(xspi, CDNS_SPI_ER_OFFSET,
> + CDNS_SPI_ER_DISABLE_MASK);
> + cdns_spi_write(xspi, CDNS_SPI_IDR_OFFSET,
> + CDNS_SPI_IXR_ALL_MASK);
> +
> + /* Clear the RX FIFO */
> + while (cdns_spi_read(xspi, CDNS_SPI_ISR_OFFSET)&
> + CDNS_SPI_IXR_RXNEMTY_MASK)
> + cdns_spi_read(xspi, CDNS_SPI_RXD_OFFSET);
> +
> + cdns_spi_write(xspi, CDNS_SPI_ISR_OFFSET,
> + CDNS_SPI_IXR_ALL_MASK);
> + cdns_spi_write(xspi, CDNS_SPI_CR_OFFSET,
> + CDNS_SPI_CR_DEFAULT_MASK);
> + cdns_spi_write(xspi, CDNS_SPI_ER_OFFSET,
> + CDNS_SPI_ER_ENABLE_MASK);
> +}
> +
> +/**
> + * cdns_spi_chipselect - Select or deselect the chip select line
> + * @spi: Pointer to the spi_device structure
> + * @is_on: Select(0) or deselect (1) the chip select line
> + */
> +static void cdns_spi_chipselect(struct spi_device *spi, bool is_high)
> +{
> + struct cdns_spi *xspi = spi_master_get_devdata(spi->master);
> + u32 ctrl_reg;
> +
> + ctrl_reg = cdns_spi_read(xspi, CDNS_SPI_CR_OFFSET);
> +
> + if (is_high) {
> + /* Deselect the slave */
> + ctrl_reg |= CDNS_SPI_CR_SSCTRL_MASK;
> + } else {
> + /* Select the slave */
> + ctrl_reg&= ~CDNS_SPI_CR_SSCTRL_MASK;
> + ctrl_reg |= ((~(CDNS_SPI_SS0<< spi->chip_select))<<
> + CDNS_SPI_SS_SHIFT)& CDNS_SPI_CR_SSCTRL_MASK;
> + }
> +
> + cdns_spi_write(xspi, CDNS_SPI_CR_OFFSET, ctrl_reg);
> +}
> +
> +/**
> + * cdns_spi_config_clock - Sets clock polarity, phase and frequency
> + * @spi: Pointer to the spi_device structure
> + * @transfer: Pointer to the spi_transfer structure which provides
> + * information about next transfer setup parameters
> + *
> + * Sets the requested clock polarity, phase and frequency.
> + * Note: If the requested frequency is not an exact match with what can be
> + * obtained using the prescalar value the driver sets the clock frequency which
> + * is lower than the requested frequency (maximum lower) for the transfer. If
> + * the requested frequency is higher or lower than that is supported by the SPI
> + * controller the driver will set the highest or lowest frequency supported by
> + * controller.
> + */
> +static void cdns_spi_config_clock(struct spi_device *spi,
> + struct spi_transfer *transfer)
> +{
> + struct cdns_spi *xspi = spi_master_get_devdata(spi->master);
> + u32 ctrl_reg, req_hz, baud_rate_val;
> + unsigned long frequency;
> +
> + if (transfer)
> + req_hz = transfer->speed_hz;
> + else
> + req_hz = spi->max_speed_hz;
> +
> + frequency = clk_get_rate(xspi->ref_clk);
> +
> + ctrl_reg = cdns_spi_read(xspi, CDNS_SPI_CR_OFFSET);
> +
> + /* Set the SPI clock phase and clock polarity */
> + ctrl_reg&= ~(CDNS_SPI_CR_CPHA_MASK | CDNS_SPI_CR_CPOL_MASK);
> + if (spi->mode& SPI_CPHA)
> + ctrl_reg |= CDNS_SPI_CR_CPHA_MASK;
> + if (spi->mode& SPI_CPOL)
> + ctrl_reg |= CDNS_SPI_CR_CPOL_MASK;
> +
> + /* Set the clock frequency */
> + if (xspi->speed_hz != req_hz) {
> + /* first valid value is 1 */
> + baud_rate_val = CDNS_SPI_BAUD_DIV_MIN;
> + while ((baud_rate_val< CDNS_SPI_BAUD_DIV_MAX)&&
> + (frequency / (2<< baud_rate_val))> req_hz)
> + baud_rate_val++;
> +
> + ctrl_reg&= ~CDNS_SPI_CR_BAUD_DIV_MASK;
> + ctrl_reg |= baud_rate_val<< CDNS_SPI_BAUD_DIV_SHIFT;
> +
> + xspi->speed_hz = frequency / (2<< baud_rate_val);
> + }
> + cdns_spi_write(xspi, CDNS_SPI_CR_OFFSET, ctrl_reg);
> +}
> +
> +/**
> + * cdns_spi_setup_transfer - Configure SPI controller for specified transfer
> + * @spi: Pointer to the spi_device structure
> + * @transfer: Pointer to the spi_transfer structure which provides
> + * information about next transfer setup parameters
> + *
> + * Sets the operational mode of SPI controller for the next SPI transfer and
> + * sets the requested clock frequency.
> + *
> + * Return: Always 0
> + */
> +static int cdns_spi_setup_transfer(struct spi_device *spi,
> + struct spi_transfer *transfer)
> +{
> + struct cdns_spi *xspi = spi_master_get_devdata(spi->master);
> +
> + cdns_spi_config_clock(spi, transfer);
> +
> + dev_dbg(&spi->dev, "%s, mode %d, %u bits/w, %u clock speed\n",
> + __func__, spi->mode, spi->bits_per_word,
> + xspi->speed_hz);
> +
> + return 0;
> +}
> +
> +/**
> + * cdns_spi_setup - Configure the SPI controller
> + * @spi: Pointer to the spi_device structure
> + *
> + * Sets the operational mode of SPI controller for the next SPI transfer, sets
> + * the baud rate and divisor value to setup the requested spi clock.
> + *
> + * Return: 0 on success and error value on error
> + */
> +static int cdns_spi_setup(struct spi_device *spi)
> +{
> + if (spi->master->busy)
> + return -EBUSY;
> +
> + return cdns_spi_setup_transfer(spi, NULL);
> +}
> +
> +/**
> + * cdns_spi_fill_tx_fifo - Fills the TX FIFO with as many bytes as possible
> + * @xspi: Pointer to the cdns_spi structure
> + */
> +static void cdns_spi_fill_tx_fifo(struct cdns_spi *xspi)
> +{
> + unsigned long trans_cnt = 0;
> +
> + while ((trans_cnt< CDNS_SPI_FIFO_DEPTH)&&
> + (xspi->remaining_bytes> 0)) {
> + if (xspi->txbuf)
> + cdns_spi_write(xspi, CDNS_SPI_TXD_OFFSET,
> + *xspi->txbuf++);
> + else
> + cdns_spi_write(xspi, CDNS_SPI_TXD_OFFSET, 0);
> +
> + xspi->remaining_bytes--;
> + trans_cnt++;
> + }
> +}
> +
> +/**
> + * cdns_spi_irq - Interrupt service routine of the SPI controller
> + * @irq: IRQ number
> + * @dev_id: Pointer to the xspi structure
> + *
> + * This function handles TX empty and Mode Fault interrupts only.
> + * On TX empty interrupt this function reads the received data from RX FIFO and
> + * fills the TX FIFO if there is any data remaining to be transferred.
> + * On Mode Fault interrupt this function indicates that transfer is completed,
> + * the SPI subsystem will identify the error as the remaining bytes to be
> + * transferred is non-zero.
> + *
> + * Return: IRQ_HANDLED when handled; IRQ_NONE otherwise.
> + */
> +static irqreturn_t cdns_spi_irq(int irq, void *dev_id)
> +{
> + struct spi_master *master = dev_id;
> + struct cdns_spi *xspi = spi_master_get_devdata(master);
> + u32 intr_status, status;
> +
> + status = IRQ_NONE;
> + intr_status = cdns_spi_read(xspi, CDNS_SPI_ISR_OFFSET);
> + cdns_spi_write(xspi, CDNS_SPI_ISR_OFFSET, intr_status);
> +
> + if (intr_status& CDNS_SPI_IXR_MODF_MASK) {
> + /* Indicate that transfer is completed, the SPI subsystem will
> + * identify the error as the remaining bytes to be
> + * transferred is non-zero
> + */
> + cdns_spi_write(xspi, CDNS_SPI_IDR_OFFSET,
> + CDNS_SPI_IXR_DEFAULT_MASK);
> + spi_finalize_current_transfer(master);
> + status = IRQ_HANDLED;
> + } else if (intr_status& CDNS_SPI_IXR_TXOW_MASK) {
> + unsigned long trans_cnt;
> +
> + trans_cnt = xspi->requested_bytes - xspi->remaining_bytes;
> +
> + /* Read out the data from the RX FIFO */
> + while (trans_cnt) {
> + u8 data;
> +
> + data = cdns_spi_read(xspi, CDNS_SPI_RXD_OFFSET);
> + if (xspi->rxbuf)
> + *xspi->rxbuf++ = data;
> +
> + xspi->requested_bytes--;
> + trans_cnt--;
> + }
> +
> + if (xspi->remaining_bytes) {
> + /* There is more data to send */
> + cdns_spi_fill_tx_fifo(xspi);
> + } else {
> + /* Transfer is completed */
> + cdns_spi_write(xspi, CDNS_SPI_IDR_OFFSET,
> + CDNS_SPI_IXR_DEFAULT_MASK);
> + spi_finalize_current_transfer(master);
> + }
> + status = IRQ_HANDLED;
> + }
> +
> + return status;
> +}
> +
> +/**
> + * cdns_transfer_one - Initiates the SPI transfer
> + * @master: Pointer to spi_master structure
> + * @spi: Pointer to the spi_device structure
> + * @transfer: Pointer to the spi_transfer structure which provides
> + * information about next transfer parameters
> + *
> + * This function fills the TX FIFO, starts the SPI transfer and
> + * returns a positive transfer count so that core will wait for completion.
> + *
> + * Return: Number of bytes transferred in the last transfer
> + */
> +static int cdns_transfer_one(struct spi_master *master,
> + struct spi_device *spi,
> + struct spi_transfer *transfer)
> +{
> + struct cdns_spi *xspi = spi_master_get_devdata(master);
> +
> + xspi->txbuf = transfer->tx_buf;
> + xspi->rxbuf = transfer->rx_buf;
> + xspi->remaining_bytes = transfer->len;
> + xspi->requested_bytes = transfer->len;
> +
> + cdns_spi_setup_transfer(spi, transfer);
> +
> + cdns_spi_fill_tx_fifo(xspi);
> +
> + cdns_spi_write(xspi, CDNS_SPI_IER_OFFSET,
> + CDNS_SPI_IXR_DEFAULT_MASK);
> + return transfer->len;
> +}
> +
> +/**
> + * cdns_prepare_transfer_hardware - Prepares hardware for transfer.
> + * @master: Pointer to the spi_master structure which provides
> + * information about the controller.
> + *
> + * This function enables SPI master controller.
> + *
> + * Return: 0 always
> + */
> +static int cdns_prepare_transfer_hardware(struct spi_master *master)
> +{
> + struct cdns_spi *xspi = spi_master_get_devdata(master);
> +
> + clk_enable(xspi->ref_clk);
> + clk_enable(xspi->pclk);
> + cdns_spi_write(xspi, CDNS_SPI_ER_OFFSET,
> + CDNS_SPI_ER_ENABLE_MASK);
> +
> + return 0;
> +}
> +
> +/**
> + * cdns_unprepare_transfer_hardware - Relaxes hardware after transfer
> + * @master: Pointer to the spi_master structure which provides
> + * information about the controller.
> + *
> + * This function disables the SPI master controller.
> + *
> + * Return: 0 always
> + */
> +static int cdns_unprepare_transfer_hardware(struct spi_master *master)
> +{
> + struct cdns_spi *xspi = spi_master_get_devdata(master);
> +
> + cdns_spi_write(xspi, CDNS_SPI_ER_OFFSET,
> + CDNS_SPI_ER_DISABLE_MASK);
> + clk_disable(xspi->ref_clk);
> + clk_disable(xspi->pclk);
> +
> + return 0;
> +}
> +
> +/**
> + * cdns_spi_probe - Probe method for the SPI driver
> + * @pdev: Pointer to the platform_device structure
> + *
> + * This function initializes the driver data structures and the hardware.
> + *
> + * Return: 0 on success and error value on error
> + */
> +static int cdns_spi_probe(struct platform_device *pdev)
> +{
> + int ret = 0, irq;
> + struct spi_master *master;
> + struct cdns_spi *xspi;
> + struct resource *res;
> +
> + master = spi_alloc_master(&pdev->dev, sizeof(*xspi));
> + if (master == NULL)
> + return -ENOMEM;
> +
> + xspi = spi_master_get_devdata(master);
> + master->dev.of_node = pdev->dev.of_node;
> + platform_set_drvdata(pdev, master);
> +
> + res = platform_get_resource(pdev, IORESOURCE_MEM, 0);
> + xspi->regs = devm_ioremap_resource(&pdev->dev, res);
> + if (IS_ERR(xspi->regs)) {
> + ret = PTR_ERR(xspi->regs);
> + goto remove_master;
> + }
> +
> + xspi->pclk = devm_clk_get(&pdev->dev, "pclk");
> + if (IS_ERR(xspi->pclk)) {
> + dev_err(&pdev->dev, "pclk clock not found.\n");
> + ret = PTR_ERR(xspi->pclk);
> + goto remove_master;
> + }
> +
> + xspi->ref_clk = devm_clk_get(&pdev->dev, "ref_clk");
> + if (IS_ERR(xspi->ref_clk)) {
> + dev_err(&pdev->dev, "ref_clk clock not found.\n");
> + ret = PTR_ERR(xspi->ref_clk);
> + goto remove_master;
> + }
> +
> + ret = clk_prepare_enable(xspi->pclk);
> + if (ret) {
> + dev_err(&pdev->dev, "Unable to enable APB clock.\n");
> + goto remove_master;
> + }
> +
> + ret = clk_prepare_enable(xspi->ref_clk);
> + if (ret) {
> + dev_err(&pdev->dev, "Unable to enable device clock.\n");
> + goto clk_dis_apb;
> + }
> +
> + /* SPI controller initializations */
> + cdns_spi_init_hw(xspi);
> +
> + irq = platform_get_irq(pdev, 0);
> + if (irq<= 0) {
> + ret = -ENXIO;
> + dev_err(&pdev->dev, "irq number is invalid\n");
> + goto remove_master;
> + }
> +
> + ret = devm_request_irq(&pdev->dev, irq, cdns_spi_irq,
> + 0, pdev->name, master);
> + if (ret != 0) {
> + ret = -ENXIO;
> + dev_err(&pdev->dev, "request_irq failed\n");
> + goto remove_master;
> + }
> +
> + ret = of_property_read_u16(pdev->dev.of_node, "num-cs",
> + &master->num_chipselect);
> + if (ret< 0)
> + master->num_chipselect = CDNS_SPI_DEFAULT_NUM_CS;
> +
> + master->setup = cdns_spi_setup;
> + master->prepare_transfer_hardware = cdns_prepare_transfer_hardware;
> + master->transfer_one = cdns_transfer_one;
> + master->unprepare_transfer_hardware = cdns_unprepare_transfer_hardware;
> + master->set_cs = cdns_spi_chipselect;
> + master->mode_bits = SPI_CPOL | SPI_CPHA;
> +
> + /* Set to default valid value */
> + master->max_speed_hz = clk_get_rate(xspi->ref_clk) / 4;
> + xspi->speed_hz = master->max_speed_hz;
> +
> + master->bits_per_word_mask = SPI_BPW_MASK(8);
> +
> + xspi->driver_state = CDNS_SPI_DRIVER_STATE_READY;
> +
> + ret = spi_register_master(master);
> + if (ret) {
> + dev_err(&pdev->dev, "spi_register_master failed\n");
> + goto clk_dis_all;
> + }
> +
> + return ret;
> +
> +clk_dis_all:
> + clk_disable_unprepare(xspi->ref_clk);
> +clk_dis_apb:
> + clk_disable_unprepare(xspi->pclk);
> +remove_master:
> + spi_master_put(master);
> + return ret;
> +}
> +
> +/**
> + * cdns_spi_remove - Remove method for the SPI driver
> + * @pdev: Pointer to the platform_device structure
> + *
> + * This function is called if a device is physically removed from the system or
> + * if the driver module is being unloaded. It frees all resources allocated to
> + * the device.
> + *
> + * Return: 0 on success and error value on error
> + */
> +static int cdns_spi_remove(struct platform_device *pdev)
> +{
> + struct spi_master *master = platform_get_drvdata(pdev);
> + struct cdns_spi *xspi = spi_master_get_devdata(master);
> +
> + cdns_spi_write(xspi, CDNS_SPI_ER_OFFSET,
> + CDNS_SPI_ER_DISABLE_MASK);
> +
> + clk_disable_unprepare(xspi->ref_clk);
> + clk_disable_unprepare(xspi->pclk);
> +
> + spi_unregister_master(master);
> +
> + return 0;
> +}
> +
> +/**
> + * cdns_spi_suspend - Suspend method for the SPI driver
> + * @dev: Address of the platform_device structure
> + *
> + * This function disables the SPI controller and
> + * changes the driver state to "suspend"
> + *
> + * Return: Always 0
> + */
> +static int __maybe_unused cdns_spi_suspend(struct device *dev)
> +{
> + struct platform_device *pdev = container_of(dev,
> + struct platform_device, dev);
> + struct spi_master *master = platform_get_drvdata(pdev);
> +
> + spi_master_suspend(master);
> +
> + cdns_unprepare_transfer_hardware(master);
> +
> + return 0;
> +}
> +
> +/**
> + * cdns_spi_resume - Resume method for the SPI driver
> + * @dev: Address of the platform_device structure
> + *
> + * This function changes the driver state to "ready"
> + *
> + * Return: 0 on success and error value on error
> + */
> +static int __maybe_unused cdns_spi_resume(struct device *dev)
> +{
> + struct platform_device *pdev = container_of(dev,
> + struct platform_device, dev);
> + struct spi_master *master = platform_get_drvdata(pdev);
> + struct cdns_spi *xspi = spi_master_get_devdata(master);
> + int ret = 0;
> +
> + ret = clk_enable(xspi->pclk);
> + if (ret) {
> + dev_err(dev, "Cannot enable APB clock.\n");
> + return ret;
> + }
> +
> + ret = clk_enable(xspi->ref_clk);
> + if (ret) {
> + dev_err(dev, "Cannot enable device clock.\n");
> + clk_disable(xspi->pclk);
> + return ret;
> + }
> + spi_master_resume(master);
> +
> + return 0;
> +}
> +
> +static SIMPLE_DEV_PM_OPS(cdns_spi_dev_pm_ops, cdns_spi_suspend,
> + cdns_spi_resume);
> +
> +static struct of_device_id cdns_spi_of_match[] = {
> + { .compatible = "xlnx,zynq-spi-r1p6" },
> + { .compatible = "cdns,spi-r1p6" },
> + { /* end of table */ }
> +};
> +MODULE_DEVICE_TABLE(of, cdns_spi_of_match);
> +
> +/* cdns_spi_driver - This structure defines the SPI subsystem platform driver */
> +static struct platform_driver cdns_spi_driver = {
> + .probe = cdns_spi_probe,
> + .remove = cdns_spi_remove,
> + .driver = {
> + .name = CDNS_SPI_NAME,
> + .owner = THIS_MODULE,
> + .of_match_table = cdns_spi_of_match,
> + .pm =&cdns_spi_dev_pm_ops,
> + },
> +};
> +
> +module_platform_driver(cdns_spi_driver);
> +
> +MODULE_AUTHOR("Xilinx, Inc.");
> +MODULE_DESCRIPTION("Cadence SPI driver");
> +MODULE_LICENSE("GPL");

2014-04-04 09:24:43

by Sourav Poddar

[permalink] [raw]
Subject: Re: [PATCH v2 1/2] SPI: Add driver for Cadence SPI controller

HI,
On Friday 04 April 2014 02:34 PM, sourav wrote:
> Hi Harini,
> On Thursday 03 April 2014 04:40 PM, Harini Katakam wrote:
>> Add driver for Cadence SPI controller. This is used in Xilinx Zynq.
>>
>> Signed-off-by: Harini Katakam<[email protected]>
>> ---
> I had looked at cadence qspi controller. What I can see is that your
> patch implements "normal spi ode of operation" ? and the patch looks
> fine.
> But, to avail the maximum throughput, I see cadence qspi supports
> direct/indirect mode of operations, as well as read data capture logic.
>
> So, do you intent to add any of the above in your driver?
>
Looks like, I got a bit confused. This is not cadence QSPI controller
but only SPI controller.
Sorry for the noise.

> Thanks,
> Sourav
>
>>
>> v2 changes:
>> - Use xilinx compatible string too.
>> - Changes read register and write register functions to static inline.
>> - Removed unecessary dev_info and dev_dbg prints.
>> - Return IRQ_HANDLED only when interrupt is handled.
>> - Use a default num-cs value.
>> - Do init_hardware before requesting irq.
>> - Remove unecessary master_put()
>> - Set master->max_speed_hz
>> - Check for busy in cdns_setup().
>> Retained this function with this check as opposed to removing.
>> The reason for this is clock configuration needs to be done for
>> the first time before enable is done in prepare_hardware;
>> prepare_hardware however, doesn't receive spi_device structure.
>> - Implememnt transfer_one instead of transfer_one_message.
>> Remove wait_for_completion as this is done by core.
>> - Implement set_cs.
>> - Clock enable/disable in prepare/unprepare respectively.
>> - In suspend, remove reset of hardware; simply call unprepare_hardware.
>> - In suspend/resume call master_suspend/resume respectively.
>> - Check for irq<=0 in probe.
>> - Remove MODULE_ALIAS.
>>
>> ---
>> drivers/spi/Kconfig | 7 +
>> drivers/spi/Makefile | 1 +
>> drivers/spi/spi-cadence.c | 677
>> +++++++++++++++++++++++++++++++++++++++++++++
>> 3 files changed, 685 insertions(+)
>> create mode 100644 drivers/spi/spi-cadence.c
>>
>> diff --git a/drivers/spi/Kconfig b/drivers/spi/Kconfig
>> index 581ee2a..aeae44a 100644
>> --- a/drivers/spi/Kconfig
>> +++ b/drivers/spi/Kconfig
>> @@ -148,6 +148,13 @@ config SPI_BUTTERFLY
>> inexpensive battery powered microcontroller evaluation board.
>> This same cable can be used to flash new firmware.
>>
>> +config SPI_CADENCE
>> + tristate "Cadence SPI controller"
>> + depends on SPI_MASTER
>> + help
>> + This selects the Cadence SPI controller master driver
>> + used by Xilinx Zynq.
>> +
>> config SPI_CLPS711X
>> tristate "CLPS711X host SPI controller"
>> depends on ARCH_CLPS711X
>> diff --git a/drivers/spi/Makefile b/drivers/spi/Makefile
>> index 95af48d..1be2ed7 100644
>> --- a/drivers/spi/Makefile
>> +++ b/drivers/spi/Makefile
>> @@ -22,6 +22,7 @@ obj-$(CONFIG_SPI_BFIN_V3) +=
>> spi-bfin-v3.o
>> obj-$(CONFIG_SPI_BFIN_SPORT) += spi-bfin-sport.o
>> obj-$(CONFIG_SPI_BITBANG) += spi-bitbang.o
>> obj-$(CONFIG_SPI_BUTTERFLY) += spi-butterfly.o
>> +obj-$(CONFIG_SPI_CADENCE) += spi-cadence.o
>> obj-$(CONFIG_SPI_CLPS711X) += spi-clps711x.o
>> obj-$(CONFIG_SPI_COLDFIRE_QSPI) += spi-coldfire-qspi.o
>> obj-$(CONFIG_SPI_DAVINCI) += spi-davinci.o
>> diff --git a/drivers/spi/spi-cadence.c b/drivers/spi/spi-cadence.c
>> new file mode 100644
>> index 0000000..071642d
>> --- /dev/null
>> +++ b/drivers/spi/spi-cadence.c
>> @@ -0,0 +1,677 @@
>> +/*
>> + * Cadence SPI controller driver (master mode only)
>> + *
>> + * Copyright (C) 2008 - 2014 Xilinx, Inc.
>> + *
>> + * based on Blackfin On-Chip SPI Driver (spi_bfin5xx.c)
>> + *
>> + * This program is free software; you can redistribute it and/or
>> modify it under
>> + * the terms of the GNU General Public License version 2 as
>> published by the
>> + * Free Software Foundation; either version 2 of the License, or (at
>> your
>> + * option) any later version.
>> + */
>> +
>> +#include<linux/clk.h>
>> +#include<linux/delay.h>
>> +#include<linux/interrupt.h>
>> +#include<linux/io.h>
>> +#include<linux/module.h>
>> +#include<linux/of_irq.h>
>> +#include<linux/of_address.h>
>> +#include<linux/platform_device.h>
>> +#include<linux/spi/spi.h>
>> +
>> +/* Name of this driver */
>> +#define CDNS_SPI_NAME "cdns-spi"
>> +
>> +/* Register offset definitions */
>> +#define CDNS_SPI_CR_OFFSET 0x00 /* Configuration Register, RW */
>> +#define CDNS_SPI_ISR_OFFSET 0x04 /* Interrupt Status Register, RO */
>> +#define CDNS_SPI_IER_OFFSET 0x08 /* Interrupt Enable Register, WO */
>> +#define CDNS_SPI_IDR_OFFSET 0x0c /* Interrupt Disable Register,
>> WO */
>> +#define CDNS_SPI_IMR_OFFSET 0x10 /* Interrupt Enabled Mask
>> Register, RO */
>> +#define CDNS_SPI_ER_OFFSET 0x14 /* Enable/Disable Register, RW */
>> +#define CDNS_SPI_DR_OFFSET 0x18 /* Delay Register, RW */
>> +#define CDNS_SPI_TXD_OFFSET 0x1C /* Data Transmit Register, WO */
>> +#define CDNS_SPI_RXD_OFFSET 0x20 /* Data Receive Register, RO */
>> +#define CDNS_SPI_SICR_OFFSET 0x24 /* Slave Idle Count Register,
>> RW */
>> +#define CDNS_SPI_THLD_OFFSET 0x28 /* Transmit FIFO Watermark
>> Register,RW */
>> +
>> +/*
>> + * SPI Configuration Register bit Masks
>> + *
>> + * This register contains various control bits that affect the
>> operation
>> + * of the SPI controller
>> + */
>> +#define CDNS_SPI_CR_MANSTRT_MASK 0x00010000 /* Manual TX Start */
>> +#define CDNS_SPI_CR_CPHA_MASK 0x00000004 /* Clock Phase
>> Control */
>> +#define CDNS_SPI_CR_CPOL_MASK 0x00000002 /* Clock Polarity
>> Control */
>> +#define CDNS_SPI_CR_SSCTRL_MASK 0x00003C00 /* Slave Select
>> Mask */
>> +#define CDNS_SPI_CR_BAUD_DIV_MASK 0x00000038 /* Baud Rate Divisor
>> Mask */
>> +#define CDNS_SPI_CR_MSTREN_MASK 0x00000001 /* Master Enable
>> Mask */
>> +#define CDNS_SPI_CR_MANSTRTEN_MASK 0x00008000 /* Manual TX Enable
>> Mask */
>> +#define CDNS_SPI_CR_SSFORCE_MASK 0x00004000 /* Manual SS Enable
>> Mask */
>> +#define CDNS_SPI_CR_BAUD_DIV_4_MASK 0x00000008 /* Default Baud
>> Div Mask */
>> +#define CDNS_SPI_CR_DEFAULT_MASK (CDNS_SPI_CR_MSTREN_MASK | \
>> + CDNS_SPI_CR_SSCTRL_MASK | \
>> + CDNS_SPI_CR_SSFORCE_MASK | \
>> + CDNS_SPI_CR_BAUD_DIV_4_MASK)
>> +
>> +/*
>> + * SPI Configuration Register - Baud rate and slave select
>> + *
>> + * These are the values used in the calculation of baud rate divisor
>> and
>> + * setting the slave select.
>> + */
>> +
>> +#define CDNS_SPI_BAUD_DIV_MAX 7 /* Baud rate divisor maximum */
>> +#define CDNS_SPI_BAUD_DIV_MIN 1 /* Baud rate divisor minimum */
>> +#define CDNS_SPI_BAUD_DIV_SHIFT 3 /* Baud rate divisor shift
>> in CR */
>> +#define CDNS_SPI_SS_SHIFT 10 /* Slave Select field shift in
>> CR */
>> +#define CDNS_SPI_SS0 0x1 /* Slave Select zero */
>> +
>> +/*
>> + * SPI Interrupt Registers bit Masks
>> + *
>> + * All the four interrupt registers (Status/Mask/Enable/Disable)
>> have the same
>> + * bit definitions.
>> + */
>> +#define CDNS_SPI_IXR_TXOW_MASK 0x00000004 /* SPI TX FIFO
>> Overwater */
>> +#define CDNS_SPI_IXR_MODF_MASK 0x00000002 /* SPI Mode Fault */
>> +#define CDNS_SPI_IXR_RXNEMTY_MASK 0x00000010 /* SPI RX FIFO Not
>> Empty */
>> +#define CDNS_SPI_IXR_DEFAULT_MASK (CDNS_SPI_IXR_TXOW_MASK | \
>> + CDNS_SPI_IXR_MODF_MASK)
>> +#define CDNS_SPI_IXR_TXFULL_MASK 0x00000008 /* SPI TX Full */
>> +#define CDNS_SPI_IXR_ALL_MASK 0x0000007F /* SPI all interrupts */
>> +
>> +/*
>> + * SPI Enable Register bit Masks
>> + *
>> + * This register is used to enable or disable the SPI controller
>> + */
>> +#define CDNS_SPI_ER_ENABLE_MASK 0x00000001 /* SPI Enable Bit Mask */
>> +#define CDNS_SPI_ER_DISABLE_MASK 0x0 /* SPI Disable Bit Mask */
>> +
>> +/* SPI timeout value */
>> +#define CDNS_SPI_TIMEOUT (5 * HZ)
>> +
>> +/* SPI FIFO depth in bytes */
>> +#define CDNS_SPI_FIFO_DEPTH 128
>> +
>> +/* Default number of chip select lines */
>> +#define CDNS_SPI_DEFAULT_NUM_CS 4
>> +
>> +/* Driver state - suspend/ready */
>> +enum driver_state_val {
>> + CDNS_SPI_DRIVER_STATE_READY = 0,
>> + CDNS_SPI_DRIVER_STATE_SUSPEND
>> +};
>> +
>> +/**
>> + * struct cdns_spi - This definition defines spi driver instance
>> + * @regs: Virtual address of the SPI controller registers
>> + * @ref_clk: Pointer to the peripheral clock
>> + * @pclk: Pointer to the APB clock
>> + * @speed_hz: Current SPI bus clock speed in Hz
>> + * @txbuf: Pointer to the TX buffer
>> + * @rxbuf: Pointer to the RX buffer
>> + * @remaining_bytes: Number of bytes left to transfer
>> + * @requested_bytes: Number of bytes requested
>> + * @dev_busy: Device busy flag
>> + * @done: Transfer complete status
>> + * @driver_state: Describes driver state - ready/suspended
>> + */
>> +struct cdns_spi {
>> + void __iomem *regs;
>> + struct clk *ref_clk;
>> + struct clk *pclk;
>> + u32 speed_hz;
>> + const u8 *txbuf;
>> + u8 *rxbuf;
>> + int remaining_bytes;
>> + int requested_bytes;
>> + u8 dev_busy;
>> + enum driver_state_val driver_state;
>> +};
>> +
>> +/* Macros for the SPI controller read/write */
>> +static inline u32 cdns_spi_read(struct cdns_spi *xspi, u32 offset)
>> +{
>> + return readl_relaxed(xspi->regs + offset);
>> +}
>> +
>> +static inline void cdns_spi_write(struct cdns_spi *xspi, u32 offset,
>> u32 val)
>> +{
>> + writel_relaxed(val, xspi->regs + offset);
>> +}
>> +
>> +/**
>> + * cdns_spi_init_hw - Initialize the hardware and configure the SPI
>> controller
>> + * @xspi: Pointer to the cdns_spi structure
>> + *
>> + * On reset the SPI controller is configured to be in master mode,
>> baud rate
>> + * divisor is set to 4, threshold value for TX FIFO not full
>> interrupt is set
>> + * to 1 and size of the word to be transferred as 8 bit.
>> + * This function initializes the SPI controller to disable and clear
>> all the
>> + * interrupts, enable manual slave select and manual start, deselect
>> all the
>> + * chip select lines, and enable the SPI controller.
>> + */
>> +static void cdns_spi_init_hw(struct cdns_spi *xspi)
>> +{
>> + cdns_spi_write(xspi, CDNS_SPI_ER_OFFSET,
>> + CDNS_SPI_ER_DISABLE_MASK);
>> + cdns_spi_write(xspi, CDNS_SPI_IDR_OFFSET,
>> + CDNS_SPI_IXR_ALL_MASK);
>> +
>> + /* Clear the RX FIFO */
>> + while (cdns_spi_read(xspi, CDNS_SPI_ISR_OFFSET)&
>> + CDNS_SPI_IXR_RXNEMTY_MASK)
>> + cdns_spi_read(xspi, CDNS_SPI_RXD_OFFSET);
>> +
>> + cdns_spi_write(xspi, CDNS_SPI_ISR_OFFSET,
>> + CDNS_SPI_IXR_ALL_MASK);
>> + cdns_spi_write(xspi, CDNS_SPI_CR_OFFSET,
>> + CDNS_SPI_CR_DEFAULT_MASK);
>> + cdns_spi_write(xspi, CDNS_SPI_ER_OFFSET,
>> + CDNS_SPI_ER_ENABLE_MASK);
>> +}
>> +
>> +/**
>> + * cdns_spi_chipselect - Select or deselect the chip select line
>> + * @spi: Pointer to the spi_device structure
>> + * @is_on: Select(0) or deselect (1) the chip select line
>> + */
>> +static void cdns_spi_chipselect(struct spi_device *spi, bool is_high)
>> +{
>> + struct cdns_spi *xspi = spi_master_get_devdata(spi->master);
>> + u32 ctrl_reg;
>> +
>> + ctrl_reg = cdns_spi_read(xspi, CDNS_SPI_CR_OFFSET);
>> +
>> + if (is_high) {
>> + /* Deselect the slave */
>> + ctrl_reg |= CDNS_SPI_CR_SSCTRL_MASK;
>> + } else {
>> + /* Select the slave */
>> + ctrl_reg&= ~CDNS_SPI_CR_SSCTRL_MASK;
>> + ctrl_reg |= ((~(CDNS_SPI_SS0<< spi->chip_select))<<
>> + CDNS_SPI_SS_SHIFT)& CDNS_SPI_CR_SSCTRL_MASK;
>> + }
>> +
>> + cdns_spi_write(xspi, CDNS_SPI_CR_OFFSET, ctrl_reg);
>> +}
>> +
>> +/**
>> + * cdns_spi_config_clock - Sets clock polarity, phase and frequency
>> + * @spi: Pointer to the spi_device structure
>> + * @transfer: Pointer to the spi_transfer structure which provides
>> + * information about next transfer setup parameters
>> + *
>> + * Sets the requested clock polarity, phase and frequency.
>> + * Note: If the requested frequency is not an exact match with what
>> can be
>> + * obtained using the prescalar value the driver sets the clock
>> frequency which
>> + * is lower than the requested frequency (maximum lower) for the
>> transfer. If
>> + * the requested frequency is higher or lower than that is supported
>> by the SPI
>> + * controller the driver will set the highest or lowest frequency
>> supported by
>> + * controller.
>> + */
>> +static void cdns_spi_config_clock(struct spi_device *spi,
>> + struct spi_transfer *transfer)
>> +{
>> + struct cdns_spi *xspi = spi_master_get_devdata(spi->master);
>> + u32 ctrl_reg, req_hz, baud_rate_val;
>> + unsigned long frequency;
>> +
>> + if (transfer)
>> + req_hz = transfer->speed_hz;
>> + else
>> + req_hz = spi->max_speed_hz;
>> +
>> + frequency = clk_get_rate(xspi->ref_clk);
>> +
>> + ctrl_reg = cdns_spi_read(xspi, CDNS_SPI_CR_OFFSET);
>> +
>> + /* Set the SPI clock phase and clock polarity */
>> + ctrl_reg&= ~(CDNS_SPI_CR_CPHA_MASK | CDNS_SPI_CR_CPOL_MASK);
>> + if (spi->mode& SPI_CPHA)
>> + ctrl_reg |= CDNS_SPI_CR_CPHA_MASK;
>> + if (spi->mode& SPI_CPOL)
>> + ctrl_reg |= CDNS_SPI_CR_CPOL_MASK;
>> +
>> + /* Set the clock frequency */
>> + if (xspi->speed_hz != req_hz) {
>> + /* first valid value is 1 */
>> + baud_rate_val = CDNS_SPI_BAUD_DIV_MIN;
>> + while ((baud_rate_val< CDNS_SPI_BAUD_DIV_MAX)&&
>> + (frequency / (2<< baud_rate_val))> req_hz)
>> + baud_rate_val++;
>> +
>> + ctrl_reg&= ~CDNS_SPI_CR_BAUD_DIV_MASK;
>> + ctrl_reg |= baud_rate_val<< CDNS_SPI_BAUD_DIV_SHIFT;
>> +
>> + xspi->speed_hz = frequency / (2<< baud_rate_val);
>> + }
>> + cdns_spi_write(xspi, CDNS_SPI_CR_OFFSET, ctrl_reg);
>> +}
>> +
>> +/**
>> + * cdns_spi_setup_transfer - Configure SPI controller for specified
>> transfer
>> + * @spi: Pointer to the spi_device structure
>> + * @transfer: Pointer to the spi_transfer structure which provides
>> + * information about next transfer setup parameters
>> + *
>> + * Sets the operational mode of SPI controller for the next SPI
>> transfer and
>> + * sets the requested clock frequency.
>> + *
>> + * Return: Always 0
>> + */
>> +static int cdns_spi_setup_transfer(struct spi_device *spi,
>> + struct spi_transfer *transfer)
>> +{
>> + struct cdns_spi *xspi = spi_master_get_devdata(spi->master);
>> +
>> + cdns_spi_config_clock(spi, transfer);
>> +
>> + dev_dbg(&spi->dev, "%s, mode %d, %u bits/w, %u clock speed\n",
>> + __func__, spi->mode, spi->bits_per_word,
>> + xspi->speed_hz);
>> +
>> + return 0;
>> +}
>> +
>> +/**
>> + * cdns_spi_setup - Configure the SPI controller
>> + * @spi: Pointer to the spi_device structure
>> + *
>> + * Sets the operational mode of SPI controller for the next SPI
>> transfer, sets
>> + * the baud rate and divisor value to setup the requested spi clock.
>> + *
>> + * Return: 0 on success and error value on error
>> + */
>> +static int cdns_spi_setup(struct spi_device *spi)
>> +{
>> + if (spi->master->busy)
>> + return -EBUSY;
>> +
>> + return cdns_spi_setup_transfer(spi, NULL);
>> +}
>> +
>> +/**
>> + * cdns_spi_fill_tx_fifo - Fills the TX FIFO with as many bytes as
>> possible
>> + * @xspi: Pointer to the cdns_spi structure
>> + */
>> +static void cdns_spi_fill_tx_fifo(struct cdns_spi *xspi)
>> +{
>> + unsigned long trans_cnt = 0;
>> +
>> + while ((trans_cnt< CDNS_SPI_FIFO_DEPTH)&&
>> + (xspi->remaining_bytes> 0)) {
>> + if (xspi->txbuf)
>> + cdns_spi_write(xspi, CDNS_SPI_TXD_OFFSET,
>> + *xspi->txbuf++);
>> + else
>> + cdns_spi_write(xspi, CDNS_SPI_TXD_OFFSET, 0);
>> +
>> + xspi->remaining_bytes--;
>> + trans_cnt++;
>> + }
>> +}
>> +
>> +/**
>> + * cdns_spi_irq - Interrupt service routine of the SPI controller
>> + * @irq: IRQ number
>> + * @dev_id: Pointer to the xspi structure
>> + *
>> + * This function handles TX empty and Mode Fault interrupts only.
>> + * On TX empty interrupt this function reads the received data from
>> RX FIFO and
>> + * fills the TX FIFO if there is any data remaining to be transferred.
>> + * On Mode Fault interrupt this function indicates that transfer is
>> completed,
>> + * the SPI subsystem will identify the error as the remaining bytes
>> to be
>> + * transferred is non-zero.
>> + *
>> + * Return: IRQ_HANDLED when handled; IRQ_NONE otherwise.
>> + */
>> +static irqreturn_t cdns_spi_irq(int irq, void *dev_id)
>> +{
>> + struct spi_master *master = dev_id;
>> + struct cdns_spi *xspi = spi_master_get_devdata(master);
>> + u32 intr_status, status;
>> +
>> + status = IRQ_NONE;
>> + intr_status = cdns_spi_read(xspi, CDNS_SPI_ISR_OFFSET);
>> + cdns_spi_write(xspi, CDNS_SPI_ISR_OFFSET, intr_status);
>> +
>> + if (intr_status& CDNS_SPI_IXR_MODF_MASK) {
>> + /* Indicate that transfer is completed, the SPI subsystem will
>> + * identify the error as the remaining bytes to be
>> + * transferred is non-zero
>> + */
>> + cdns_spi_write(xspi, CDNS_SPI_IDR_OFFSET,
>> + CDNS_SPI_IXR_DEFAULT_MASK);
>> + spi_finalize_current_transfer(master);
>> + status = IRQ_HANDLED;
>> + } else if (intr_status& CDNS_SPI_IXR_TXOW_MASK) {
>> + unsigned long trans_cnt;
>> +
>> + trans_cnt = xspi->requested_bytes - xspi->remaining_bytes;
>> +
>> + /* Read out the data from the RX FIFO */
>> + while (trans_cnt) {
>> + u8 data;
>> +
>> + data = cdns_spi_read(xspi, CDNS_SPI_RXD_OFFSET);
>> + if (xspi->rxbuf)
>> + *xspi->rxbuf++ = data;
>> +
>> + xspi->requested_bytes--;
>> + trans_cnt--;
>> + }
>> +
>> + if (xspi->remaining_bytes) {
>> + /* There is more data to send */
>> + cdns_spi_fill_tx_fifo(xspi);
>> + } else {
>> + /* Transfer is completed */
>> + cdns_spi_write(xspi, CDNS_SPI_IDR_OFFSET,
>> + CDNS_SPI_IXR_DEFAULT_MASK);
>> + spi_finalize_current_transfer(master);
>> + }
>> + status = IRQ_HANDLED;
>> + }
>> +
>> + return status;
>> +}
>> +
>> +/**
>> + * cdns_transfer_one - Initiates the SPI transfer
>> + * @master: Pointer to spi_master structure
>> + * @spi: Pointer to the spi_device structure
>> + * @transfer: Pointer to the spi_transfer structure which provides
>> + * information about next transfer parameters
>> + *
>> + * This function fills the TX FIFO, starts the SPI transfer and
>> + * returns a positive transfer count so that core will wait for
>> completion.
>> + *
>> + * Return: Number of bytes transferred in the last transfer
>> + */
>> +static int cdns_transfer_one(struct spi_master *master,
>> + struct spi_device *spi,
>> + struct spi_transfer *transfer)
>> +{
>> + struct cdns_spi *xspi = spi_master_get_devdata(master);
>> +
>> + xspi->txbuf = transfer->tx_buf;
>> + xspi->rxbuf = transfer->rx_buf;
>> + xspi->remaining_bytes = transfer->len;
>> + xspi->requested_bytes = transfer->len;
>> +
>> + cdns_spi_setup_transfer(spi, transfer);
>> +
>> + cdns_spi_fill_tx_fifo(xspi);
>> +
>> + cdns_spi_write(xspi, CDNS_SPI_IER_OFFSET,
>> + CDNS_SPI_IXR_DEFAULT_MASK);
>> + return transfer->len;
>> +}
>> +
>> +/**
>> + * cdns_prepare_transfer_hardware - Prepares hardware for transfer.
>> + * @master: Pointer to the spi_master structure which provides
>> + * information about the controller.
>> + *
>> + * This function enables SPI master controller.
>> + *
>> + * Return: 0 always
>> + */
>> +static int cdns_prepare_transfer_hardware(struct spi_master *master)
>> +{
>> + struct cdns_spi *xspi = spi_master_get_devdata(master);
>> +
>> + clk_enable(xspi->ref_clk);
>> + clk_enable(xspi->pclk);
>> + cdns_spi_write(xspi, CDNS_SPI_ER_OFFSET,
>> + CDNS_SPI_ER_ENABLE_MASK);
>> +
>> + return 0;
>> +}
>> +
>> +/**
>> + * cdns_unprepare_transfer_hardware - Relaxes hardware after transfer
>> + * @master: Pointer to the spi_master structure which provides
>> + * information about the controller.
>> + *
>> + * This function disables the SPI master controller.
>> + *
>> + * Return: 0 always
>> + */
>> +static int cdns_unprepare_transfer_hardware(struct spi_master *master)
>> +{
>> + struct cdns_spi *xspi = spi_master_get_devdata(master);
>> +
>> + cdns_spi_write(xspi, CDNS_SPI_ER_OFFSET,
>> + CDNS_SPI_ER_DISABLE_MASK);
>> + clk_disable(xspi->ref_clk);
>> + clk_disable(xspi->pclk);
>> +
>> + return 0;
>> +}
>> +
>> +/**
>> + * cdns_spi_probe - Probe method for the SPI driver
>> + * @pdev: Pointer to the platform_device structure
>> + *
>> + * This function initializes the driver data structures and the
>> hardware.
>> + *
>> + * Return: 0 on success and error value on error
>> + */
>> +static int cdns_spi_probe(struct platform_device *pdev)
>> +{
>> + int ret = 0, irq;
>> + struct spi_master *master;
>> + struct cdns_spi *xspi;
>> + struct resource *res;
>> +
>> + master = spi_alloc_master(&pdev->dev, sizeof(*xspi));
>> + if (master == NULL)
>> + return -ENOMEM;
>> +
>> + xspi = spi_master_get_devdata(master);
>> + master->dev.of_node = pdev->dev.of_node;
>> + platform_set_drvdata(pdev, master);
>> +
>> + res = platform_get_resource(pdev, IORESOURCE_MEM, 0);
>> + xspi->regs = devm_ioremap_resource(&pdev->dev, res);
>> + if (IS_ERR(xspi->regs)) {
>> + ret = PTR_ERR(xspi->regs);
>> + goto remove_master;
>> + }
>> +
>> + xspi->pclk = devm_clk_get(&pdev->dev, "pclk");
>> + if (IS_ERR(xspi->pclk)) {
>> + dev_err(&pdev->dev, "pclk clock not found.\n");
>> + ret = PTR_ERR(xspi->pclk);
>> + goto remove_master;
>> + }
>> +
>> + xspi->ref_clk = devm_clk_get(&pdev->dev, "ref_clk");
>> + if (IS_ERR(xspi->ref_clk)) {
>> + dev_err(&pdev->dev, "ref_clk clock not found.\n");
>> + ret = PTR_ERR(xspi->ref_clk);
>> + goto remove_master;
>> + }
>> +
>> + ret = clk_prepare_enable(xspi->pclk);
>> + if (ret) {
>> + dev_err(&pdev->dev, "Unable to enable APB clock.\n");
>> + goto remove_master;
>> + }
>> +
>> + ret = clk_prepare_enable(xspi->ref_clk);
>> + if (ret) {
>> + dev_err(&pdev->dev, "Unable to enable device clock.\n");
>> + goto clk_dis_apb;
>> + }
>> +
>> + /* SPI controller initializations */
>> + cdns_spi_init_hw(xspi);
>> +
>> + irq = platform_get_irq(pdev, 0);
>> + if (irq<= 0) {
>> + ret = -ENXIO;
>> + dev_err(&pdev->dev, "irq number is invalid\n");
>> + goto remove_master;
>> + }
>> +
>> + ret = devm_request_irq(&pdev->dev, irq, cdns_spi_irq,
>> + 0, pdev->name, master);
>> + if (ret != 0) {
>> + ret = -ENXIO;
>> + dev_err(&pdev->dev, "request_irq failed\n");
>> + goto remove_master;
>> + }
>> +
>> + ret = of_property_read_u16(pdev->dev.of_node, "num-cs",
>> + &master->num_chipselect);
>> + if (ret< 0)
>> + master->num_chipselect = CDNS_SPI_DEFAULT_NUM_CS;
>> +
>> + master->setup = cdns_spi_setup;
>> + master->prepare_transfer_hardware = cdns_prepare_transfer_hardware;
>> + master->transfer_one = cdns_transfer_one;
>> + master->unprepare_transfer_hardware =
>> cdns_unprepare_transfer_hardware;
>> + master->set_cs = cdns_spi_chipselect;
>> + master->mode_bits = SPI_CPOL | SPI_CPHA;
>> +
>> + /* Set to default valid value */
>> + master->max_speed_hz = clk_get_rate(xspi->ref_clk) / 4;
>> + xspi->speed_hz = master->max_speed_hz;
>> +
>> + master->bits_per_word_mask = SPI_BPW_MASK(8);
>> +
>> + xspi->driver_state = CDNS_SPI_DRIVER_STATE_READY;
>> +
>> + ret = spi_register_master(master);
>> + if (ret) {
>> + dev_err(&pdev->dev, "spi_register_master failed\n");
>> + goto clk_dis_all;
>> + }
>> +
>> + return ret;
>> +
>> +clk_dis_all:
>> + clk_disable_unprepare(xspi->ref_clk);
>> +clk_dis_apb:
>> + clk_disable_unprepare(xspi->pclk);
>> +remove_master:
>> + spi_master_put(master);
>> + return ret;
>> +}
>> +
>> +/**
>> + * cdns_spi_remove - Remove method for the SPI driver
>> + * @pdev: Pointer to the platform_device structure
>> + *
>> + * This function is called if a device is physically removed from
>> the system or
>> + * if the driver module is being unloaded. It frees all resources
>> allocated to
>> + * the device.
>> + *
>> + * Return: 0 on success and error value on error
>> + */
>> +static int cdns_spi_remove(struct platform_device *pdev)
>> +{
>> + struct spi_master *master = platform_get_drvdata(pdev);
>> + struct cdns_spi *xspi = spi_master_get_devdata(master);
>> +
>> + cdns_spi_write(xspi, CDNS_SPI_ER_OFFSET,
>> + CDNS_SPI_ER_DISABLE_MASK);
>> +
>> + clk_disable_unprepare(xspi->ref_clk);
>> + clk_disable_unprepare(xspi->pclk);
>> +
>> + spi_unregister_master(master);
>> +
>> + return 0;
>> +}
>> +
>> +/**
>> + * cdns_spi_suspend - Suspend method for the SPI driver
>> + * @dev: Address of the platform_device structure
>> + *
>> + * This function disables the SPI controller and
>> + * changes the driver state to "suspend"
>> + *
>> + * Return: Always 0
>> + */
>> +static int __maybe_unused cdns_spi_suspend(struct device *dev)
>> +{
>> + struct platform_device *pdev = container_of(dev,
>> + struct platform_device, dev);
>> + struct spi_master *master = platform_get_drvdata(pdev);
>> +
>> + spi_master_suspend(master);
>> +
>> + cdns_unprepare_transfer_hardware(master);
>> +
>> + return 0;
>> +}
>> +
>> +/**
>> + * cdns_spi_resume - Resume method for the SPI driver
>> + * @dev: Address of the platform_device structure
>> + *
>> + * This function changes the driver state to "ready"
>> + *
>> + * Return: 0 on success and error value on error
>> + */
>> +static int __maybe_unused cdns_spi_resume(struct device *dev)
>> +{
>> + struct platform_device *pdev = container_of(dev,
>> + struct platform_device, dev);
>> + struct spi_master *master = platform_get_drvdata(pdev);
>> + struct cdns_spi *xspi = spi_master_get_devdata(master);
>> + int ret = 0;
>> +
>> + ret = clk_enable(xspi->pclk);
>> + if (ret) {
>> + dev_err(dev, "Cannot enable APB clock.\n");
>> + return ret;
>> + }
>> +
>> + ret = clk_enable(xspi->ref_clk);
>> + if (ret) {
>> + dev_err(dev, "Cannot enable device clock.\n");
>> + clk_disable(xspi->pclk);
>> + return ret;
>> + }
>> + spi_master_resume(master);
>> +
>> + return 0;
>> +}
>> +
>> +static SIMPLE_DEV_PM_OPS(cdns_spi_dev_pm_ops, cdns_spi_suspend,
>> + cdns_spi_resume);
>> +
>> +static struct of_device_id cdns_spi_of_match[] = {
>> + { .compatible = "xlnx,zynq-spi-r1p6" },
>> + { .compatible = "cdns,spi-r1p6" },
>> + { /* end of table */ }
>> +};
>> +MODULE_DEVICE_TABLE(of, cdns_spi_of_match);
>> +
>> +/* cdns_spi_driver - This structure defines the SPI subsystem
>> platform driver */
>> +static struct platform_driver cdns_spi_driver = {
>> + .probe = cdns_spi_probe,
>> + .remove = cdns_spi_remove,
>> + .driver = {
>> + .name = CDNS_SPI_NAME,
>> + .owner = THIS_MODULE,
>> + .of_match_table = cdns_spi_of_match,
>> + .pm =&cdns_spi_dev_pm_ops,
>> + },
>> +};
>> +
>> +module_platform_driver(cdns_spi_driver);
>> +
>> +MODULE_AUTHOR("Xilinx, Inc.");
>> +MODULE_DESCRIPTION("Cadence SPI driver");
>> +MODULE_LICENSE("GPL");
>
> --
> To unsubscribe from this list: send the line "unsubscribe linux-spi" in
> the body of a message to [email protected]
> More majordomo info at http://vger.kernel.org/majordomo-info.html

2014-04-04 10:02:22

by Michal Simek

[permalink] [raw]
Subject: Re: [PATCH v2 1/2] SPI: Add driver for Cadence SPI controller

Hi Sourav

On 04/04/2014 11:24 AM, sourav wrote:
> HI,
> On Friday 04 April 2014 02:34 PM, sourav wrote:
>> Hi Harini,
>> On Thursday 03 April 2014 04:40 PM, Harini Katakam wrote:
>>> Add driver for Cadence SPI controller. This is used in Xilinx Zynq.
>>>
>>> Signed-off-by: Harini Katakam<[email protected]>
>>> ---
>> I had looked at cadence qspi controller. What I can see is that your
>> patch implements "normal spi ode of operation" ? and the patch looks fine.
>> But, to avail the maximum throughput, I see cadence qspi supports
>> direct/indirect mode of operations, as well as read data capture logic.
>>
>> So, do you intent to add any of the above in your driver?
>>
> Looks like, I got a bit confused. This is not cadence QSPI controller but only SPI controller.
> Sorry for the noise.

Look at this one
http://www.spinics.net/lists/kernel/msg1716894.html

Thanks,
Michal

--
Michal Simek, Ing. (M.Eng), OpenPGP -> KeyID: FE3D1F91
w: http://www.monstr.eu p: +42-0-721842854
Maintainer of Linux kernel - Microblaze cpu - http://www.monstr.eu/fdt/
Maintainer of Linux kernel - Xilinx Zynq ARM architecture
Microblaze U-BOOT custodian and responsible for u-boot arm zynq platform



Attachments:
signature.asc (263.00 B)
OpenPGP digital signature

2014-04-04 10:09:58

by Mark Brown

[permalink] [raw]
Subject: Re: [PATCH v2 2/2] devicetree: Add devicetree bindings documentation for Cadence SPI

On Fri, Apr 04, 2014 at 08:30:38AM +0530, Harini Katakam wrote:
> On Fri, Apr 4, 2014 at 3:04 AM, Mark Brown <[email protected]> wrote:
> > On Thu, Apr 03, 2014 at 04:40:31PM +0530, Harini Katakam wrote:

> >> +Optional properties:
> >> +- num-cs : Number of chip selects used.

> > How does this translate to the hardware?

> This IP can drive 4 slaves.
> The CS line to be driven is selected in spi device structure and
> that is driven by the software.

So why specify this in the binding at all? If the device always has the
same number of chip selects it's redundant.

> >> + num-cs = /bits/ 16 <4>;

> > What's going on with the /bits/ - is this something that's required for
> > the property?

> The master->num-chipselect property is 16 bit but writing <4> here directly
> leads to 0 being read in of_property_read (because it's big endian).
> Instead using of property read u32 and then copying, we decided to do this.
> This was discussed on v2 between Michal and Rob:

No, don't do that. You're contorting the binding to serve Linux's
implementation needs and you've not documented this requirement either.
If there *was* a need to have the number be 16 bits you'd need to
document that reqirement in the binding, though like I say I don't think
the number needs to be there at all.


Attachments:
(No filename) (1.29 kB)
signature.asc (836.00 B)
Digital signature
Download all attachments

2014-04-04 11:17:09

by Michal Simek

[permalink] [raw]
Subject: Re: [PATCH v2 2/2] devicetree: Add devicetree bindings documentation for Cadence SPI

On 04/04/2014 10:09 AM, Geert Uytterhoeven wrote:
> Hi Harini,
>
> On Fri, Apr 4, 2014 at 5:00 AM, Harini Katakam
> <[email protected]> wrote:
>>>> + num-cs = /bits/ 16 <4>;
>>>
>>> What's going on with the /bits/ - is this something that's required for
>>> the property?
>>
>> The master->num-chipselect property is 16 bit but writing <4> here directly
>> leads to 0 being read in of_property_read (because it's big endian).
>> Instead using of property read u32 and then copying, we decided to do this.
>> This was discussed on v2 between Michal and Rob:
>>>>>> + num-chip-select = /bits/ 16 <4>;
>>>>
>>>> I was expecting you will comment this a little bit. :-)
>>>> Because all just reading this num-cs as 32bit and then
>>>> assigning this value to master->num_chipselect which is 16bit.
>>>
>>> Well, everyone else has that problem then. Obviously it takes a bit
>>> more care than just reading into a u32, but that is a kernel problem
>>> and not a problem of the binding.
>> They are not reading it directly with read_u32 but they are using
>> intermediate u32 value which is assigned to u16 which is fine.
>> This pattern is in most drivers(maybe all).
>> The point is if binding should or can't simplify driver code.
>> And from your reaction above I expect that it is up to driver
>> owner and binding doc how you want to do it.
>
> IMHO this "/bits/ 16" doesn't simplify the binding.
>
> As "num-cs" is a generic spi subsystem binding, it should not be
> restricted to 16 bits for the sake of a driver. As your hardware can drive 4
> chip selects, you could represent it in 3 bits (don't!).
>
> Simple integers are 32 bit in DT, so use a temporary.

No problem to keep it there to 32bit range. I really appreciate
that discussion we have about it.

Just a note: If "num-cs" is the part of generic spi subsystem binding
maybe it should be moved directly to spi core as is done for
example for timeout-sec in watchdog.
Also this should be listed in any Documentation/devicetree/bindings/spi/spi.txt
file that this is generic spi binding.

Thanks,
Michal

--
Michal Simek, Ing. (M.Eng), OpenPGP -> KeyID: FE3D1F91
w: http://www.monstr.eu p: +42-0-721842854
Maintainer of Linux kernel - Microblaze cpu - http://www.monstr.eu/fdt/
Maintainer of Linux kernel - Xilinx Zynq ARM architecture
Microblaze U-BOOT custodian and responsible for u-boot arm zynq platform



Attachments:
signature.asc (263.00 B)
OpenPGP digital signature

2014-04-04 12:14:27

by Harini Katakam

[permalink] [raw]
Subject: Re: [PATCH v2 2/2] devicetree: Add devicetree bindings documentation for Cadence SPI

Hi Mark,

On Fri, Apr 4, 2014 at 3:39 PM, Mark Brown <[email protected]> wrote:
> On Fri, Apr 04, 2014 at 08:30:38AM +0530, Harini Katakam wrote:
>> On Fri, Apr 4, 2014 at 3:04 AM, Mark Brown <[email protected]> wrote:
>> > On Thu, Apr 03, 2014 at 04:40:31PM +0530, Harini Katakam wrote:
>
>> >> +Optional properties:
>> >> +- num-cs : Number of chip selects used.
>
>> > How does this translate to the hardware?
>
>> This IP can drive 4 slaves.
>> The CS line to be driven is selected in spi device structure and
>> that is driven by the software.
>
> So why specify this in the binding at all? If the device always has the
> same number of chip selects it's redundant.

I'm sorry, I should have explained that better.
The IP can support upto 4 chip selects.
The num-cs value here is the number of chip selects actually used on the board.

>
>> >> + num-cs = /bits/ 16 <4>;
>
>> > What's going on with the /bits/ - is this something that's required for
>> > the property?
>
>> The master->num-chipselect property is 16 bit but writing <4> here directly
>> leads to 0 being read in of_property_read (because it's big endian).
>> Instead using of property read u32 and then copying, we decided to do this.
>> This was discussed on v2 between Michal and Rob:
>
> No, don't do that. You're contorting the binding to serve Linux's
> implementation needs and you've not documented this requirement either.
> If there *was* a need to have the number be 16 bits you'd need to
> document that reqirement in the binding, though like I say I don't think
> the number needs to be there at all.

OK. I'll remove the /bits/ 16 and handle it in the driver.

Regards,
Harini

2014-04-04 12:24:34

by Peter Crosthwaite

[permalink] [raw]
Subject: Re: [PATCH v2 2/2] devicetree: Add devicetree bindings documentation for Cadence SPI

On Fri, Apr 4, 2014 at 10:14 PM, Harini Katakam
<[email protected]> wrote:
> Hi Mark,
>
> On Fri, Apr 4, 2014 at 3:39 PM, Mark Brown <[email protected]> wrote:
>> On Fri, Apr 04, 2014 at 08:30:38AM +0530, Harini Katakam wrote:
>>> On Fri, Apr 4, 2014 at 3:04 AM, Mark Brown <[email protected]> wrote:
>>> > On Thu, Apr 03, 2014 at 04:40:31PM +0530, Harini Katakam wrote:
>>
>>> >> +Optional properties:
>>> >> +- num-cs : Number of chip selects used.
>>
>>> > How does this translate to the hardware?
>>
>>> This IP can drive 4 slaves.
>>> The CS line to be driven is selected in spi device structure and
>>> that is driven by the software.
>>
>> So why specify this in the binding at all? If the device always has the
>> same number of chip selects it's redundant.
>
> I'm sorry, I should have explained that better.
> The IP can support upto 4 chip selects.
> The num-cs value here is the number of chip selects actually used on the board.
>

Just to clarify - do you mean SoC or board level?

Regards,
Peter

>>
>>> >> + num-cs = /bits/ 16 <4>;
>>
>>> > What's going on with the /bits/ - is this something that's required for
>>> > the property?
>>
>>> The master->num-chipselect property is 16 bit but writing <4> here directly
>>> leads to 0 being read in of_property_read (because it's big endian).
>>> Instead using of property read u32 and then copying, we decided to do this.
>>> This was discussed on v2 between Michal and Rob:
>>
>> No, don't do that. You're contorting the binding to serve Linux's
>> implementation needs and you've not documented this requirement either.
>> If there *was* a need to have the number be 16 bits you'd need to
>> document that reqirement in the binding, though like I say I don't think
>> the number needs to be there at all.
>
> OK. I'll remove the /bits/ 16 and handle it in the driver.
>
> Regards,
> Harini
> --
> To unsubscribe from this list: send the line "unsubscribe linux-kernel" in
> the body of a message to [email protected]
> More majordomo info at http://vger.kernel.org/majordomo-info.html
> Please read the FAQ at http://www.tux.org/lkml/

2014-04-04 12:39:40

by Harini Katakam

[permalink] [raw]
Subject: Re: [PATCH v2 2/2] devicetree: Add devicetree bindings documentation for Cadence SPI

Hi,

On Fri, Apr 4, 2014 at 5:54 PM, Peter Crosthwaite
<[email protected]> wrote:
> On Fri, Apr 4, 2014 at 10:14 PM, Harini Katakam
> <[email protected]> wrote:
>> Hi Mark,
>>
>> On Fri, Apr 4, 2014 at 3:39 PM, Mark Brown <[email protected]> wrote:
>>> On Fri, Apr 04, 2014 at 08:30:38AM +0530, Harini Katakam wrote:
>>>> On Fri, Apr 4, 2014 at 3:04 AM, Mark Brown <[email protected]> wrote:
>>>> > On Thu, Apr 03, 2014 at 04:40:31PM +0530, Harini Katakam wrote:
>>>
>>>> >> +Optional properties:
>>>> >> +- num-cs : Number of chip selects used.
>>>
>>>> > How does this translate to the hardware?
>>>
>>>> This IP can drive 4 slaves.
>>>> The CS line to be driven is selected in spi device structure and
>>>> that is driven by the software.
>>>
>>> So why specify this in the binding at all? If the device always has the
>>> same number of chip selects it's redundant.
>>
>> I'm sorry, I should have explained that better.
>> The IP can support upto 4 chip selects.
>> The num-cs value here is the number of chip selects actually used on the board.
>>
>
> Just to clarify - do you mean SoC or board level?
>

I mean board level.
One more reason it will be useful to keep this property is because
there is support for adding a decoder where extended slaves can be selected
through the IP's control register.
(This is not currently implemented in the driver but will be in the future.)

Regards,
Harini

2014-04-04 12:47:18

by Mark Brown

[permalink] [raw]
Subject: Re: [PATCH v2 2/2] devicetree: Add devicetree bindings documentation for Cadence SPI

On Fri, Apr 04, 2014 at 05:44:23PM +0530, Harini Katakam wrote:
> On Fri, Apr 4, 2014 at 3:39 PM, Mark Brown <[email protected]> wrote:
> > On Fri, Apr 04, 2014 at 08:30:38AM +0530, Harini Katakam wrote:

> >> This IP can drive 4 slaves.
> >> The CS line to be driven is selected in spi device structure and
> >> that is driven by the software.

> > So why specify this in the binding at all? If the device always has the
> > same number of chip selects it's redundant.

> I'm sorry, I should have explained that better.
> The IP can support upto 4 chip selects.
> The num-cs value here is the number of chip selects actually used on the board.

Why does that need to be configured? Surely the presence of slaves is
enough information.


Attachments:
(No filename) (739.00 B)
signature.asc (836.00 B)
Digital signature
Download all attachments

2014-04-04 14:08:20

by Harini Katakam

[permalink] [raw]
Subject: Re: [PATCH v2 2/2] devicetree: Add devicetree bindings documentation for Cadence SPI

Hi Mark,

On Fri, Apr 4, 2014 at 6:16 PM, Mark Brown <[email protected]> wrote:
> On Fri, Apr 04, 2014 at 05:44:23PM +0530, Harini Katakam wrote:
>> On Fri, Apr 4, 2014 at 3:39 PM, Mark Brown <[email protected]> wrote:
>> > On Fri, Apr 04, 2014 at 08:30:38AM +0530, Harini Katakam wrote:
>
>> >> This IP can drive 4 slaves.
>> >> The CS line to be driven is selected in spi device structure and
>> >> that is driven by the software.
>
>> > So why specify this in the binding at all? If the device always has the
>> > same number of chip selects it's redundant.
>
>> I'm sorry, I should have explained that better.
>> The IP can support upto 4 chip selects.
>> The num-cs value here is the number of chip selects actually used on the board.
>
> Why does that need to be configured? Surely the presence of slaves is
> enough information.

OK. I understand.
Can you comment on the case where a decoder is used?

There is support for adding a decoder where extended slaves can be selected
through the IP's control register.
(This is not currently implemented in the driver but will be in the future.)

How should the driver know whether it is 4 or 16 select lines for example?
This has to be written to master->num_chipselect.

Regards,
Harini

2014-04-04 14:30:23

by Harini Katakam

[permalink] [raw]
Subject: Re: [PATCH v2 2/2] devicetree: Add devicetree bindings documentation for Cadence SPI

Hi,

On Fri, Apr 4, 2014 at 7:38 PM, Harini Katakam
<[email protected]> wrote:
> Hi Mark,
>
> On Fri, Apr 4, 2014 at 6:16 PM, Mark Brown <[email protected]> wrote:
>> On Fri, Apr 04, 2014 at 05:44:23PM +0530, Harini Katakam wrote:
>>> On Fri, Apr 4, 2014 at 3:39 PM, Mark Brown <[email protected]> wrote:
>>> > On Fri, Apr 04, 2014 at 08:30:38AM +0530, Harini Katakam wrote:
>>
>>> >> This IP can drive 4 slaves.
>>> >> The CS line to be driven is selected in spi device structure and
>>> >> that is driven by the software.
>>
>>> > So why specify this in the binding at all? If the device always has the
>>> > same number of chip selects it's redundant.
>>
>>> I'm sorry, I should have explained that better.
>>> The IP can support upto 4 chip selects.
>>> The num-cs value here is the number of chip selects actually used on the board.
>>
>> Why does that need to be configured? Surely the presence of slaves is
>> enough information.
>
> OK. I understand.
> Can you comment on the case where a decoder is used?
>
> There is support for adding a decoder where extended slaves can be selected
> through the IP's control register.
> (This is not currently implemented in the driver but will be in the future.)
>
> How should the driver know whether it is 4 or 16 select lines for example?
> This has to be written to master->num_chipselect.
>
> Regards,
> Harini

Just adding to my above comment.
Alternately, I could not use the "num-cs" property and add another
optional property to be used only when required.
The driver sets a default value already.

Regards,
Harini

2014-04-04 14:45:16

by Mark Brown

[permalink] [raw]
Subject: Re: [PATCH v2 2/2] devicetree: Add devicetree bindings documentation for Cadence SPI

On Fri, Apr 04, 2014 at 07:38:14PM +0530, Harini Katakam wrote:

> OK. I understand.
> Can you comment on the case where a decoder is used?

> There is support for adding a decoder where extended slaves can be selected
> through the IP's control register.
> (This is not currently implemented in the driver but will be in the future.)

> How should the driver know whether it is 4 or 16 select lines for example?
> This has to be written to master->num_chipselect.

That's the sort of case where it's useful yes - depending on how the
implementation is done it may be sensible to just have a property
specifying if a decoder is there (if it just changes the encoding in the
register for example).


Attachments:
(No filename) (697.00 B)
signature.asc (836.00 B)
Digital signature
Download all attachments

2014-04-04 14:49:40

by Harini Katakam

[permalink] [raw]
Subject: Re: [PATCH v2 2/2] devicetree: Add devicetree bindings documentation for Cadence SPI

Hi Mark,

On Fri, Apr 4, 2014 at 8:12 PM, Mark Brown <[email protected]> wrote:
> On Fri, Apr 04, 2014 at 07:38:14PM +0530, Harini Katakam wrote:
>
>> OK. I understand.
>> Can you comment on the case where a decoder is used?
>
>> There is support for adding a decoder where extended slaves can be selected
>> through the IP's control register.
>> (This is not currently implemented in the driver but will be in the future.)
>
>> How should the driver know whether it is 4 or 16 select lines for example?
>> This has to be written to master->num_chipselect.
>
> That's the sort of case where it's useful yes - depending on how the
> implementation is done it may be sensible to just have a property
> specifying if a decoder is there (if it just changes the encoding in the
> register for example).

OK, great. That approach will work.

Regards,
Harini

2014-04-04 22:58:07

by Peter Crosthwaite

[permalink] [raw]
Subject: Re: [PATCH v2 1/2] SPI: Add driver for Cadence SPI controller

On Thu, Apr 3, 2014 at 9:10 PM, Harini Katakam <[email protected]> wrote:
> Add driver for Cadence SPI controller. This is used in Xilinx Zynq.
>
> Signed-off-by: Harini Katakam <[email protected]>
> ---
>
> v2 changes:
> - Use xilinx compatible string too.
> - Changes read register and write register functions to static inline.
> - Removed unecessary dev_info and dev_dbg prints.
> - Return IRQ_HANDLED only when interrupt is handled.
> - Use a default num-cs value.
> - Do init_hardware before requesting irq.
> - Remove unecessary master_put()
> - Set master->max_speed_hz
> - Check for busy in cdns_setup().
> Retained this function with this check as opposed to removing.
> The reason for this is clock configuration needs to be done for
> the first time before enable is done in prepare_hardware;
> prepare_hardware however, doesn't receive spi_device structure.
> - Implememnt transfer_one instead of transfer_one_message.
> Remove wait_for_completion as this is done by core.
> - Implement set_cs.
> - Clock enable/disable in prepare/unprepare respectively.
> - In suspend, remove reset of hardware; simply call unprepare_hardware.
> - In suspend/resume call master_suspend/resume respectively.
> - Check for irq<=0 in probe.
> - Remove MODULE_ALIAS.
>
> ---
> drivers/spi/Kconfig | 7 +
> drivers/spi/Makefile | 1 +
> drivers/spi/spi-cadence.c | 677 +++++++++++++++++++++++++++++++++++++++++++++
> 3 files changed, 685 insertions(+)
> create mode 100644 drivers/spi/spi-cadence.c
>
> diff --git a/drivers/spi/Kconfig b/drivers/spi/Kconfig
> index 581ee2a..aeae44a 100644
> --- a/drivers/spi/Kconfig
> +++ b/drivers/spi/Kconfig
> @@ -148,6 +148,13 @@ config SPI_BUTTERFLY
> inexpensive battery powered microcontroller evaluation board.
> This same cable can be used to flash new firmware.
>
> +config SPI_CADENCE
> + tristate "Cadence SPI controller"
> + depends on SPI_MASTER
> + help
> + This selects the Cadence SPI controller master driver
> + used by Xilinx Zynq.
> +
> config SPI_CLPS711X
> tristate "CLPS711X host SPI controller"
> depends on ARCH_CLPS711X
> diff --git a/drivers/spi/Makefile b/drivers/spi/Makefile
> index 95af48d..1be2ed7 100644
> --- a/drivers/spi/Makefile
> +++ b/drivers/spi/Makefile
> @@ -22,6 +22,7 @@ obj-$(CONFIG_SPI_BFIN_V3) += spi-bfin-v3.o
> obj-$(CONFIG_SPI_BFIN_SPORT) += spi-bfin-sport.o
> obj-$(CONFIG_SPI_BITBANG) += spi-bitbang.o
> obj-$(CONFIG_SPI_BUTTERFLY) += spi-butterfly.o
> +obj-$(CONFIG_SPI_CADENCE) += spi-cadence.o
> obj-$(CONFIG_SPI_CLPS711X) += spi-clps711x.o
> obj-$(CONFIG_SPI_COLDFIRE_QSPI) += spi-coldfire-qspi.o
> obj-$(CONFIG_SPI_DAVINCI) += spi-davinci.o
> diff --git a/drivers/spi/spi-cadence.c b/drivers/spi/spi-cadence.c
> new file mode 100644
> index 0000000..071642d
> --- /dev/null
> +++ b/drivers/spi/spi-cadence.c
> @@ -0,0 +1,677 @@
> +/*
> + * Cadence SPI controller driver (master mode only)
> + *
> + * Copyright (C) 2008 - 2014 Xilinx, Inc.
> + *
> + * based on Blackfin On-Chip SPI Driver (spi_bfin5xx.c)
> + *
> + * This program is free software; you can redistribute it and/or modify it under
> + * the terms of the GNU General Public License version 2 as published by the
> + * Free Software Foundation; either version 2 of the License, or (at your
> + * option) any later version.
> + */
> +
> +#include <linux/clk.h>
> +#include <linux/delay.h>
> +#include <linux/interrupt.h>
> +#include <linux/io.h>
> +#include <linux/module.h>
> +#include <linux/of_irq.h>
> +#include <linux/of_address.h>
> +#include <linux/platform_device.h>
> +#include <linux/spi/spi.h>
> +
> +/* Name of this driver */
> +#define CDNS_SPI_NAME "cdns-spi"
> +
> +/* Register offset definitions */
> +#define CDNS_SPI_CR_OFFSET 0x00 /* Configuration Register, RW */
> +#define CDNS_SPI_ISR_OFFSET 0x04 /* Interrupt Status Register, RO */
> +#define CDNS_SPI_IER_OFFSET 0x08 /* Interrupt Enable Register, WO */
> +#define CDNS_SPI_IDR_OFFSET 0x0c /* Interrupt Disable Register, WO */
> +#define CDNS_SPI_IMR_OFFSET 0x10 /* Interrupt Enabled Mask Register, RO */
> +#define CDNS_SPI_ER_OFFSET 0x14 /* Enable/Disable Register, RW */
> +#define CDNS_SPI_DR_OFFSET 0x18 /* Delay Register, RW */
> +#define CDNS_SPI_TXD_OFFSET 0x1C /* Data Transmit Register, WO */
> +#define CDNS_SPI_RXD_OFFSET 0x20 /* Data Receive Register, RO */
> +#define CDNS_SPI_SICR_OFFSET 0x24 /* Slave Idle Count Register, RW */
> +#define CDNS_SPI_THLD_OFFSET 0x28 /* Transmit FIFO Watermark Register,RW */
> +
> +/*
> + * SPI Configuration Register bit Masks
> + *
> + * This register contains various control bits that affect the operation
> + * of the SPI controller
> + */
> +#define CDNS_SPI_CR_MANSTRT_MASK 0x00010000 /* Manual TX Start */
> +#define CDNS_SPI_CR_CPHA_MASK 0x00000004 /* Clock Phase Control */
> +#define CDNS_SPI_CR_CPOL_MASK 0x00000002 /* Clock Polarity Control */
> +#define CDNS_SPI_CR_SSCTRL_MASK 0x00003C00 /* Slave Select Mask */
> +#define CDNS_SPI_CR_BAUD_DIV_MASK 0x00000038 /* Baud Rate Divisor Mask */
> +#define CDNS_SPI_CR_MSTREN_MASK 0x00000001 /* Master Enable Mask */
> +#define CDNS_SPI_CR_MANSTRTEN_MASK 0x00008000 /* Manual TX Enable Mask */
> +#define CDNS_SPI_CR_SSFORCE_MASK 0x00004000 /* Manual SS Enable Mask */
> +#define CDNS_SPI_CR_BAUD_DIV_4_MASK 0x00000008 /* Default Baud Div Mask */
> +#define CDNS_SPI_CR_DEFAULT_MASK (CDNS_SPI_CR_MSTREN_MASK | \
> + CDNS_SPI_CR_SSCTRL_MASK | \
> + CDNS_SPI_CR_SSFORCE_MASK | \
> + CDNS_SPI_CR_BAUD_DIV_4_MASK)
> +
> +/*
> + * SPI Configuration Register - Baud rate and slave select
> + *
> + * These are the values used in the calculation of baud rate divisor and
> + * setting the slave select.
> + */
> +
> +#define CDNS_SPI_BAUD_DIV_MAX 7 /* Baud rate divisor maximum */
> +#define CDNS_SPI_BAUD_DIV_MIN 1 /* Baud rate divisor minimum */
> +#define CDNS_SPI_BAUD_DIV_SHIFT 3 /* Baud rate divisor shift in CR */
> +#define CDNS_SPI_SS_SHIFT 10 /* Slave Select field shift in CR */
> +#define CDNS_SPI_SS0 0x1 /* Slave Select zero */
> +
> +/*
> + * SPI Interrupt Registers bit Masks
> + *
> + * All the four interrupt registers (Status/Mask/Enable/Disable) have the same
> + * bit definitions.
> + */
> +#define CDNS_SPI_IXR_TXOW_MASK 0x00000004 /* SPI TX FIFO Overwater */
> +#define CDNS_SPI_IXR_MODF_MASK 0x00000002 /* SPI Mode Fault */
> +#define CDNS_SPI_IXR_RXNEMTY_MASK 0x00000010 /* SPI RX FIFO Not Empty */
> +#define CDNS_SPI_IXR_DEFAULT_MASK (CDNS_SPI_IXR_TXOW_MASK | \
> + CDNS_SPI_IXR_MODF_MASK)
> +#define CDNS_SPI_IXR_TXFULL_MASK 0x00000008 /* SPI TX Full */
> +#define CDNS_SPI_IXR_ALL_MASK 0x0000007F /* SPI all interrupts */
> +
> +/*
> + * SPI Enable Register bit Masks
> + *
> + * This register is used to enable or disable the SPI controller
> + */
> +#define CDNS_SPI_ER_ENABLE_MASK 0x00000001 /* SPI Enable Bit Mask */
> +#define CDNS_SPI_ER_DISABLE_MASK 0x0 /* SPI Disable Bit Mask */
> +
> +/* SPI timeout value */
> +#define CDNS_SPI_TIMEOUT (5 * HZ)
> +
> +/* SPI FIFO depth in bytes */
> +#define CDNS_SPI_FIFO_DEPTH 128
> +
> +/* Default number of chip select lines */
> +#define CDNS_SPI_DEFAULT_NUM_CS 4
> +
> +/* Driver state - suspend/ready */
> +enum driver_state_val {
> + CDNS_SPI_DRIVER_STATE_READY = 0,
> + CDNS_SPI_DRIVER_STATE_SUSPEND
> +};
> +
> +/**
> + * struct cdns_spi - This definition defines spi driver instance
> + * @regs: Virtual address of the SPI controller registers
> + * @ref_clk: Pointer to the peripheral clock
> + * @pclk: Pointer to the APB clock
> + * @speed_hz: Current SPI bus clock speed in Hz
> + * @txbuf: Pointer to the TX buffer
> + * @rxbuf: Pointer to the RX buffer
> + * @remaining_bytes: Number of bytes left to transfer
> + * @requested_bytes: Number of bytes requested
> + * @dev_busy: Device busy flag
> + * @done: Transfer complete status
> + * @driver_state: Describes driver state - ready/suspended
> + */
> +struct cdns_spi {
> + void __iomem *regs;
> + struct clk *ref_clk;
> + struct clk *pclk;
> + u32 speed_hz;
> + const u8 *txbuf;
> + u8 *rxbuf;
> + int remaining_bytes;
> + int requested_bytes;
> + u8 dev_busy;
> + enum driver_state_val driver_state;
> +};
> +
> +/* Macros for the SPI controller read/write */
> +static inline u32 cdns_spi_read(struct cdns_spi *xspi, u32 offset)
> +{
> + return readl_relaxed(xspi->regs + offset);
> +}
> +
> +static inline void cdns_spi_write(struct cdns_spi *xspi, u32 offset, u32 val)
> +{
> + writel_relaxed(val, xspi->regs + offset);
> +}
> +
> +/**
> + * cdns_spi_init_hw - Initialize the hardware and configure the SPI controller
> + * @xspi: Pointer to the cdns_spi structure
> + *
> + * On reset the SPI controller is configured to be in master mode, baud rate
> + * divisor is set to 4, threshold value for TX FIFO not full interrupt is set
> + * to 1 and size of the word to be transferred as 8 bit.
> + * This function initializes the SPI controller to disable and clear all the
> + * interrupts, enable manual slave select and manual start, deselect all the
> + * chip select lines, and enable the SPI controller.
> + */
> +static void cdns_spi_init_hw(struct cdns_spi *xspi)
> +{
> + cdns_spi_write(xspi, CDNS_SPI_ER_OFFSET,
> + CDNS_SPI_ER_DISABLE_MASK);
> + cdns_spi_write(xspi, CDNS_SPI_IDR_OFFSET,
> + CDNS_SPI_IXR_ALL_MASK);
> +
> + /* Clear the RX FIFO */
> + while (cdns_spi_read(xspi, CDNS_SPI_ISR_OFFSET) &
> + CDNS_SPI_IXR_RXNEMTY_MASK)
> + cdns_spi_read(xspi, CDNS_SPI_RXD_OFFSET);
> +
> + cdns_spi_write(xspi, CDNS_SPI_ISR_OFFSET,
> + CDNS_SPI_IXR_ALL_MASK);
> + cdns_spi_write(xspi, CDNS_SPI_CR_OFFSET,
> + CDNS_SPI_CR_DEFAULT_MASK);
> + cdns_spi_write(xspi, CDNS_SPI_ER_OFFSET,
> + CDNS_SPI_ER_ENABLE_MASK);
> +}
> +
> +/**
> + * cdns_spi_chipselect - Select or deselect the chip select line
> + * @spi: Pointer to the spi_device structure
> + * @is_on: Select(0) or deselect (1) the chip select line
> + */
> +static void cdns_spi_chipselect(struct spi_device *spi, bool is_high)
> +{
> + struct cdns_spi *xspi = spi_master_get_devdata(spi->master);
> + u32 ctrl_reg;
> +
> + ctrl_reg = cdns_spi_read(xspi, CDNS_SPI_CR_OFFSET);
> +
> + if (is_high) {
> + /* Deselect the slave */
> + ctrl_reg |= CDNS_SPI_CR_SSCTRL_MASK;
> + } else {
> + /* Select the slave */
> + ctrl_reg &= ~CDNS_SPI_CR_SSCTRL_MASK;
> + ctrl_reg |= ((~(CDNS_SPI_SS0 << spi->chip_select)) <<
> + CDNS_SPI_SS_SHIFT) & CDNS_SPI_CR_SSCTRL_MASK;
> + }
> +

This looks more complicated than it needs to be. The logic is:

if (high) {
deselect all; /* |= */
} else {
select all; /* &= ~ */
deselect all except the selected one; /* |= ~ */
}

Can you cut it down to:

deselect all; /* |= */
if (!high) {
select the selected one; /* &= ~(1 << ...) */
}

> + cdns_spi_write(xspi, CDNS_SPI_CR_OFFSET, ctrl_reg);
> +}
> +
> +/**
> + * cdns_spi_config_clock - Sets clock polarity, phase and frequency
> + * @spi: Pointer to the spi_device structure
> + * @transfer: Pointer to the spi_transfer structure which provides
> + * information about next transfer setup parameters
> + *
> + * Sets the requested clock polarity, phase and frequency.
> + * Note: If the requested frequency is not an exact match with what can be
> + * obtained using the prescalar value the driver sets the clock frequency which
> + * is lower than the requested frequency (maximum lower) for the transfer. If
> + * the requested frequency is higher or lower than that is supported by the SPI
> + * controller the driver will set the highest or lowest frequency supported by
> + * controller.
> + */
> +static void cdns_spi_config_clock(struct spi_device *spi,
> + struct spi_transfer *transfer)
> +{
> + struct cdns_spi *xspi = spi_master_get_devdata(spi->master);
> + u32 ctrl_reg, req_hz, baud_rate_val;
> + unsigned long frequency;
> +
> + if (transfer)
> + req_hz = transfer->speed_hz;
> + else
> + req_hz = spi->max_speed_hz;
> +
> + frequency = clk_get_rate(xspi->ref_clk);
> +
> + ctrl_reg = cdns_spi_read(xspi, CDNS_SPI_CR_OFFSET);
> +
> + /* Set the SPI clock phase and clock polarity */
> + ctrl_reg &= ~(CDNS_SPI_CR_CPHA_MASK | CDNS_SPI_CR_CPOL_MASK);
> + if (spi->mode & SPI_CPHA)
> + ctrl_reg |= CDNS_SPI_CR_CPHA_MASK;
> + if (spi->mode & SPI_CPOL)
> + ctrl_reg |= CDNS_SPI_CR_CPOL_MASK;
> +
> + /* Set the clock frequency */
> + if (xspi->speed_hz != req_hz) {
> + /* first valid value is 1 */
> + baud_rate_val = CDNS_SPI_BAUD_DIV_MIN;
> + while ((baud_rate_val < CDNS_SPI_BAUD_DIV_MAX) &&
> + (frequency / (2 << baud_rate_val)) > req_hz)
> + baud_rate_val++;
> +
> + ctrl_reg &= ~CDNS_SPI_CR_BAUD_DIV_MASK;
> + ctrl_reg |= baud_rate_val << CDNS_SPI_BAUD_DIV_SHIFT;
> +
> + xspi->speed_hz = frequency / (2 << baud_rate_val);
> + }
> + cdns_spi_write(xspi, CDNS_SPI_CR_OFFSET, ctrl_reg);
> +}
> +
> +/**
> + * cdns_spi_setup_transfer - Configure SPI controller for specified transfer
> + * @spi: Pointer to the spi_device structure
> + * @transfer: Pointer to the spi_transfer structure which provides
> + * information about next transfer setup parameters
> + *
> + * Sets the operational mode of SPI controller for the next SPI transfer and
> + * sets the requested clock frequency.
> + *
> + * Return: Always 0
> + */
> +static int cdns_spi_setup_transfer(struct spi_device *spi,
> + struct spi_transfer *transfer)
> +{
> + struct cdns_spi *xspi = spi_master_get_devdata(spi->master);
> +
> + cdns_spi_config_clock(spi, transfer);
> +
> + dev_dbg(&spi->dev, "%s, mode %d, %u bits/w, %u clock speed\n",
> + __func__, spi->mode, spi->bits_per_word,
> + xspi->speed_hz);
> +
> + return 0;
> +}
> +
> +/**
> + * cdns_spi_setup - Configure the SPI controller
> + * @spi: Pointer to the spi_device structure
> + *
> + * Sets the operational mode of SPI controller for the next SPI transfer, sets
> + * the baud rate and divisor value to setup the requested spi clock.
> + *
> + * Return: 0 on success and error value on error
> + */
> +static int cdns_spi_setup(struct spi_device *spi)
> +{
> + if (spi->master->busy)
> + return -EBUSY;
> +
> + return cdns_spi_setup_transfer(spi, NULL);
> +}
> +
> +/**
> + * cdns_spi_fill_tx_fifo - Fills the TX FIFO with as many bytes as possible
> + * @xspi: Pointer to the cdns_spi structure
> + */
> +static void cdns_spi_fill_tx_fifo(struct cdns_spi *xspi)
> +{
> + unsigned long trans_cnt = 0;
> +
> + while ((trans_cnt < CDNS_SPI_FIFO_DEPTH) &&
> + (xspi->remaining_bytes > 0)) {
> + if (xspi->txbuf)
> + cdns_spi_write(xspi, CDNS_SPI_TXD_OFFSET,
> + *xspi->txbuf++);
> + else
> + cdns_spi_write(xspi, CDNS_SPI_TXD_OFFSET, 0);
> +
> + xspi->remaining_bytes--;
> + trans_cnt++;
> + }
> +}
> +
> +/**
> + * cdns_spi_irq - Interrupt service routine of the SPI controller
> + * @irq: IRQ number
> + * @dev_id: Pointer to the xspi structure
> + *
> + * This function handles TX empty and Mode Fault interrupts only.
> + * On TX empty interrupt this function reads the received data from RX FIFO and
> + * fills the TX FIFO if there is any data remaining to be transferred.
> + * On Mode Fault interrupt this function indicates that transfer is completed,
> + * the SPI subsystem will identify the error as the remaining bytes to be
> + * transferred is non-zero.
> + *
> + * Return: IRQ_HANDLED when handled; IRQ_NONE otherwise.
> + */
> +static irqreturn_t cdns_spi_irq(int irq, void *dev_id)
> +{
> + struct spi_master *master = dev_id;
> + struct cdns_spi *xspi = spi_master_get_devdata(master);
> + u32 intr_status, status;
> +
> + status = IRQ_NONE;
> + intr_status = cdns_spi_read(xspi, CDNS_SPI_ISR_OFFSET);
> + cdns_spi_write(xspi, CDNS_SPI_ISR_OFFSET, intr_status);
> +
> + if (intr_status & CDNS_SPI_IXR_MODF_MASK) {
> + /* Indicate that transfer is completed, the SPI subsystem will
> + * identify the error as the remaining bytes to be
> + * transferred is non-zero
> + */
> + cdns_spi_write(xspi, CDNS_SPI_IDR_OFFSET,
> + CDNS_SPI_IXR_DEFAULT_MASK);
> + spi_finalize_current_transfer(master);
> + status = IRQ_HANDLED;
> + } else if (intr_status & CDNS_SPI_IXR_TXOW_MASK) {
> + unsigned long trans_cnt;
> +
> + trans_cnt = xspi->requested_bytes - xspi->remaining_bytes;
> +
> + /* Read out the data from the RX FIFO */
> + while (trans_cnt) {
> + u8 data;
> +
> + data = cdns_spi_read(xspi, CDNS_SPI_RXD_OFFSET);
> + if (xspi->rxbuf)
> + *xspi->rxbuf++ = data;
> +
> + xspi->requested_bytes--;

Its clear that requested_bytes directly corresponds to the rx work queue ...

> + trans_cnt--;
> + }
> +
> + if (xspi->remaining_bytes) {

... while remaining_bytes is the tx work queue. Can you rename to
include "tx" and "rx" for clarity?

Regards,
Peter

> + /* There is more data to send */
> + cdns_spi_fill_tx_fifo(xspi);
> + } else {
> + /* Transfer is completed */
> + cdns_spi_write(xspi, CDNS_SPI_IDR_OFFSET,
> + CDNS_SPI_IXR_DEFAULT_MASK);
> + spi_finalize_current_transfer(master);
> + }
> + status = IRQ_HANDLED;
> + }
> +
> + return status;
> +}
> +
> +/**
> + * cdns_transfer_one - Initiates the SPI transfer
> + * @master: Pointer to spi_master structure
> + * @spi: Pointer to the spi_device structure
> + * @transfer: Pointer to the spi_transfer structure which provides
> + * information about next transfer parameters
> + *
> + * This function fills the TX FIFO, starts the SPI transfer and
> + * returns a positive transfer count so that core will wait for completion.
> + *
> + * Return: Number of bytes transferred in the last transfer
> + */
> +static int cdns_transfer_one(struct spi_master *master,
> + struct spi_device *spi,
> + struct spi_transfer *transfer)
> +{
> + struct cdns_spi *xspi = spi_master_get_devdata(master);
> +
> + xspi->txbuf = transfer->tx_buf;
> + xspi->rxbuf = transfer->rx_buf;
> + xspi->remaining_bytes = transfer->len;
> + xspi->requested_bytes = transfer->len;
> +
> + cdns_spi_setup_transfer(spi, transfer);
> +
> + cdns_spi_fill_tx_fifo(xspi);
> +
> + cdns_spi_write(xspi, CDNS_SPI_IER_OFFSET,
> + CDNS_SPI_IXR_DEFAULT_MASK);
> + return transfer->len;
> +}
> +
> +/**
> + * cdns_prepare_transfer_hardware - Prepares hardware for transfer.
> + * @master: Pointer to the spi_master structure which provides
> + * information about the controller.
> + *
> + * This function enables SPI master controller.
> + *
> + * Return: 0 always
> + */
> +static int cdns_prepare_transfer_hardware(struct spi_master *master)
> +{
> + struct cdns_spi *xspi = spi_master_get_devdata(master);
> +
> + clk_enable(xspi->ref_clk);
> + clk_enable(xspi->pclk);
> + cdns_spi_write(xspi, CDNS_SPI_ER_OFFSET,
> + CDNS_SPI_ER_ENABLE_MASK);
> +
> + return 0;
> +}
> +
> +/**
> + * cdns_unprepare_transfer_hardware - Relaxes hardware after transfer
> + * @master: Pointer to the spi_master structure which provides
> + * information about the controller.
> + *
> + * This function disables the SPI master controller.
> + *
> + * Return: 0 always
> + */
> +static int cdns_unprepare_transfer_hardware(struct spi_master *master)
> +{
> + struct cdns_spi *xspi = spi_master_get_devdata(master);
> +
> + cdns_spi_write(xspi, CDNS_SPI_ER_OFFSET,
> + CDNS_SPI_ER_DISABLE_MASK);
> + clk_disable(xspi->ref_clk);
> + clk_disable(xspi->pclk);
> +
> + return 0;
> +}
> +
> +/**
> + * cdns_spi_probe - Probe method for the SPI driver
> + * @pdev: Pointer to the platform_device structure
> + *
> + * This function initializes the driver data structures and the hardware.
> + *
> + * Return: 0 on success and error value on error
> + */
> +static int cdns_spi_probe(struct platform_device *pdev)
> +{
> + int ret = 0, irq;
> + struct spi_master *master;
> + struct cdns_spi *xspi;
> + struct resource *res;
> +
> + master = spi_alloc_master(&pdev->dev, sizeof(*xspi));
> + if (master == NULL)
> + return -ENOMEM;
> +
> + xspi = spi_master_get_devdata(master);
> + master->dev.of_node = pdev->dev.of_node;
> + platform_set_drvdata(pdev, master);
> +
> + res = platform_get_resource(pdev, IORESOURCE_MEM, 0);
> + xspi->regs = devm_ioremap_resource(&pdev->dev, res);
> + if (IS_ERR(xspi->regs)) {
> + ret = PTR_ERR(xspi->regs);
> + goto remove_master;
> + }
> +
> + xspi->pclk = devm_clk_get(&pdev->dev, "pclk");
> + if (IS_ERR(xspi->pclk)) {
> + dev_err(&pdev->dev, "pclk clock not found.\n");
> + ret = PTR_ERR(xspi->pclk);
> + goto remove_master;
> + }
> +
> + xspi->ref_clk = devm_clk_get(&pdev->dev, "ref_clk");
> + if (IS_ERR(xspi->ref_clk)) {
> + dev_err(&pdev->dev, "ref_clk clock not found.\n");
> + ret = PTR_ERR(xspi->ref_clk);
> + goto remove_master;
> + }
> +
> + ret = clk_prepare_enable(xspi->pclk);
> + if (ret) {
> + dev_err(&pdev->dev, "Unable to enable APB clock.\n");
> + goto remove_master;
> + }
> +
> + ret = clk_prepare_enable(xspi->ref_clk);
> + if (ret) {
> + dev_err(&pdev->dev, "Unable to enable device clock.\n");
> + goto clk_dis_apb;
> + }
> +
> + /* SPI controller initializations */
> + cdns_spi_init_hw(xspi);
> +
> + irq = platform_get_irq(pdev, 0);
> + if (irq <= 0) {
> + ret = -ENXIO;
> + dev_err(&pdev->dev, "irq number is invalid\n");
> + goto remove_master;
> + }
> +
> + ret = devm_request_irq(&pdev->dev, irq, cdns_spi_irq,
> + 0, pdev->name, master);
> + if (ret != 0) {
> + ret = -ENXIO;
> + dev_err(&pdev->dev, "request_irq failed\n");
> + goto remove_master;
> + }
> +
> + ret = of_property_read_u16(pdev->dev.of_node, "num-cs",
> + &master->num_chipselect);
> + if (ret < 0)
> + master->num_chipselect = CDNS_SPI_DEFAULT_NUM_CS;
> +
> + master->setup = cdns_spi_setup;
> + master->prepare_transfer_hardware = cdns_prepare_transfer_hardware;
> + master->transfer_one = cdns_transfer_one;
> + master->unprepare_transfer_hardware = cdns_unprepare_transfer_hardware;
> + master->set_cs = cdns_spi_chipselect;
> + master->mode_bits = SPI_CPOL | SPI_CPHA;
> +
> + /* Set to default valid value */
> + master->max_speed_hz = clk_get_rate(xspi->ref_clk) / 4;
> + xspi->speed_hz = master->max_speed_hz;
> +
> + master->bits_per_word_mask = SPI_BPW_MASK(8);
> +
> + xspi->driver_state = CDNS_SPI_DRIVER_STATE_READY;
> +
> + ret = spi_register_master(master);
> + if (ret) {
> + dev_err(&pdev->dev, "spi_register_master failed\n");
> + goto clk_dis_all;
> + }
> +
> + return ret;
> +
> +clk_dis_all:
> + clk_disable_unprepare(xspi->ref_clk);
> +clk_dis_apb:
> + clk_disable_unprepare(xspi->pclk);
> +remove_master:
> + spi_master_put(master);
> + return ret;
> +}
> +
> +/**
> + * cdns_spi_remove - Remove method for the SPI driver
> + * @pdev: Pointer to the platform_device structure
> + *
> + * This function is called if a device is physically removed from the system or
> + * if the driver module is being unloaded. It frees all resources allocated to
> + * the device.
> + *
> + * Return: 0 on success and error value on error
> + */
> +static int cdns_spi_remove(struct platform_device *pdev)
> +{
> + struct spi_master *master = platform_get_drvdata(pdev);
> + struct cdns_spi *xspi = spi_master_get_devdata(master);
> +
> + cdns_spi_write(xspi, CDNS_SPI_ER_OFFSET,
> + CDNS_SPI_ER_DISABLE_MASK);
> +
> + clk_disable_unprepare(xspi->ref_clk);
> + clk_disable_unprepare(xspi->pclk);
> +
> + spi_unregister_master(master);
> +
> + return 0;
> +}
> +
> +/**
> + * cdns_spi_suspend - Suspend method for the SPI driver
> + * @dev: Address of the platform_device structure
> + *
> + * This function disables the SPI controller and
> + * changes the driver state to "suspend"
> + *
> + * Return: Always 0
> + */
> +static int __maybe_unused cdns_spi_suspend(struct device *dev)
> +{
> + struct platform_device *pdev = container_of(dev,
> + struct platform_device, dev);
> + struct spi_master *master = platform_get_drvdata(pdev);
> +
> + spi_master_suspend(master);
> +
> + cdns_unprepare_transfer_hardware(master);
> +
> + return 0;
> +}
> +
> +/**
> + * cdns_spi_resume - Resume method for the SPI driver
> + * @dev: Address of the platform_device structure
> + *
> + * This function changes the driver state to "ready"
> + *
> + * Return: 0 on success and error value on error
> + */
> +static int __maybe_unused cdns_spi_resume(struct device *dev)
> +{
> + struct platform_device *pdev = container_of(dev,
> + struct platform_device, dev);
> + struct spi_master *master = platform_get_drvdata(pdev);
> + struct cdns_spi *xspi = spi_master_get_devdata(master);
> + int ret = 0;
> +
> + ret = clk_enable(xspi->pclk);
> + if (ret) {
> + dev_err(dev, "Cannot enable APB clock.\n");
> + return ret;
> + }
> +
> + ret = clk_enable(xspi->ref_clk);
> + if (ret) {
> + dev_err(dev, "Cannot enable device clock.\n");
> + clk_disable(xspi->pclk);
> + return ret;
> + }
> + spi_master_resume(master);
> +
> + return 0;
> +}
> +
> +static SIMPLE_DEV_PM_OPS(cdns_spi_dev_pm_ops, cdns_spi_suspend,
> + cdns_spi_resume);
> +
> +static struct of_device_id cdns_spi_of_match[] = {
> + { .compatible = "xlnx,zynq-spi-r1p6" },
> + { .compatible = "cdns,spi-r1p6" },
> + { /* end of table */ }
> +};
> +MODULE_DEVICE_TABLE(of, cdns_spi_of_match);
> +
> +/* cdns_spi_driver - This structure defines the SPI subsystem platform driver */
> +static struct platform_driver cdns_spi_driver = {
> + .probe = cdns_spi_probe,
> + .remove = cdns_spi_remove,
> + .driver = {
> + .name = CDNS_SPI_NAME,
> + .owner = THIS_MODULE,
> + .of_match_table = cdns_spi_of_match,
> + .pm = &cdns_spi_dev_pm_ops,
> + },
> +};
> +
> +module_platform_driver(cdns_spi_driver);
> +
> +MODULE_AUTHOR("Xilinx, Inc.");
> +MODULE_DESCRIPTION("Cadence SPI driver");
> +MODULE_LICENSE("GPL");
> --
> 1.7.9.5
>
> --
> To unsubscribe from this list: send the line "unsubscribe linux-kernel" in
> the body of a message to [email protected]
> More majordomo info at http://vger.kernel.org/majordomo-info.html
> Please read the FAQ at http://www.tux.org/lkml/

2014-04-04 23:14:59

by Peter Crosthwaite

[permalink] [raw]
Subject: Re: [PATCH v2 2/2] devicetree: Add devicetree bindings documentation for Cadence SPI

On Sat, Apr 5, 2014 at 12:30 AM, Harini Katakam
<[email protected]> wrote:
> Hi,
>
> On Fri, Apr 4, 2014 at 7:38 PM, Harini Katakam
> <[email protected]> wrote:
>> Hi Mark,
>>
>> On Fri, Apr 4, 2014 at 6:16 PM, Mark Brown <[email protected]> wrote:
>>> On Fri, Apr 04, 2014 at 05:44:23PM +0530, Harini Katakam wrote:
>>>> On Fri, Apr 4, 2014 at 3:39 PM, Mark Brown <[email protected]> wrote:
>>>> > On Fri, Apr 04, 2014 at 08:30:38AM +0530, Harini Katakam wrote:
>>>
>>>> >> This IP can drive 4 slaves.
>>>> >> The CS line to be driven is selected in spi device structure and
>>>> >> that is driven by the software.
>>>
>>>> > So why specify this in the binding at all? If the device always has the
>>>> > same number of chip selects it's redundant.
>>>
>>>> I'm sorry, I should have explained that better.
>>>> The IP can support upto 4 chip selects.
>>>> The num-cs value here is the number of chip selects actually used on the board.

Shouldnt it be a property of the controller not the board? How for
example do we differentiate between different implementations of
cadence SPI controller that only supports up to two CS lines? My
thinking is that this property should always be present and = 4 in the
Zynq case as the controller always has 4 physical CS lines coming out
(before any decoders, pin muxes or slaves etc.).

>>>
>>> Why does that need to be configured? Surely the presence of slaves is
>>> enough information.

And presence of slaves / board info is inferable from subnodes.

>>
>> OK. I understand.
>> Can you comment on the case where a decoder is used?
>>
>> There is support for adding a decoder where extended slaves can be selected
>> through the IP's control register.
>> (This is not currently implemented in the driver but will be in the future.)
>>

I think thats seperate information. is-decoded-cs property of something.

>> How should the driver know whether it is 4 or 16 select lines for example?
>> This has to be written to master->num_chipselect.
>>

If you only have one property (== 4) how do you tell the difference
between 4 un-decoded CS lines vs 2 decoded CS lines?

>> Regards,
>> Harini
>
> Just adding to my above comment.
> Alternately, I could not use the "num-cs" property and add another
> optional property to be used only when required.

I think num-cs has validity as the number of CS lines implemented in
the controller. For any given SoC, it's constant but could differ
between SoCs.

Regards,
Peter

> The driver sets a default value already.
>
> Regards,
> Harini
> --
> To unsubscribe from this list: send the line "unsubscribe linux-kernel" in
> the body of a message to [email protected]
> More majordomo info at http://vger.kernel.org/majordomo-info.html
> Please read the FAQ at http://www.tux.org/lkml/

2014-04-05 06:05:09

by Harini Katakam

[permalink] [raw]
Subject: Re: [PATCH v2 2/2] devicetree: Add devicetree bindings documentation for Cadence SPI

Hi Peter,

On Sat, Apr 5, 2014 at 4:44 AM, Peter Crosthwaite
<[email protected]> wrote:
> On Sat, Apr 5, 2014 at 12:30 AM, Harini Katakam
> <[email protected]> wrote:
>> Hi,
>>
>> On Fri, Apr 4, 2014 at 7:38 PM, Harini Katakam
>> <[email protected]> wrote:
>>> Hi Mark,
>>>
>>> On Fri, Apr 4, 2014 at 6:16 PM, Mark Brown <[email protected]> wrote:
>>>> On Fri, Apr 04, 2014 at 05:44:23PM +0530, Harini Katakam wrote:
>>>>> On Fri, Apr 4, 2014 at 3:39 PM, Mark Brown <[email protected]> wrote:
>>>>> > On Fri, Apr 04, 2014 at 08:30:38AM +0530, Harini Katakam wrote:
>>>>
>>>>> >> This IP can drive 4 slaves.
>>>>> >> The sCS line to be driven is selected in spi device structure and
>>>>> >> that is driven by the software.
>>>>
>>>>> > So why specify this in the binding at all? If the device always has the
>>>>> > same number of chip selects it's redundant.
>>>>
>>>>> I'm sorry, I should have explained that better.
>>>>> The IP can support upto 4 chip selects.
>>>>> The num-cs value here is the number of chip selects actually used on the board.
>
> Shouldnt it be a property of the controller not the board? How for
> example do we differentiate between different implementations of
> cadence SPI controller that only supports up to two CS lines? My
> thinking is that this property should always be present and = 4 in the
> Zynq case as the controller always has 4 physical CS lines coming out
> (before any decoders, pin muxes or slaves etc.).
>
>>>>
>>>> Why does that need to be configured? Surely the presence of slaves is
>>>> enough information.
>
> And presence of slaves / board info is inferable from subnodes.
>
>>>
>>> OK. I understand.
>>> Can you comment on the case where a decoder is used?
>>>
>>> There is support for adding a decoder where extended slaves can be selected
>>> through the IP's control register.
>>> (This is not currently implemented in the driver but will be in the future.)
>>>
>
> I think thats seperate information. is-decoded-cs property of something.
>
>>> How should the driver know whether it is 4 or 16 select lines for example?
>>> This has to be written to master->num_chipselect.
>>>
>
> If you only have one property (== 4) how do you tell the difference
> between 4 un-decoded CS lines vs 2 decoded CS lines?
>

If an SoC implements 2 CS and sets "decoder" property,
then we'd configure the register with "select decode" bit and write
0b0011 to the slave select field to select 4th slave.

If decoder property is not set, then we'd write 0b1000 to select 4th slave.

But yes, if the SoC only implements 2 CS, doesn't use decoder but
if there is an erroneous input to set_cs for 4th slave, it would be a problem.

>
> I think num-cs has validity as the number of CS lines implemented in
> the controller. For any given SoC, it's constant but could differ
> between SoCs.
>

I dint consider that this property will be useful to SoC's implementing <4 CS;
master->num_chipselect (when set to this property's value)
will be used to check error conditions.

Regards,
Harini

2014-04-05 23:43:35

by Peter Crosthwaite

[permalink] [raw]
Subject: Re: [PATCH v2 2/2] devicetree: Add devicetree bindings documentation for Cadence SPI

On Sat, Apr 5, 2014 at 4:05 PM, Harini Katakam
<[email protected]> wrote:
> Hi Peter,
>
> On Sat, Apr 5, 2014 at 4:44 AM, Peter Crosthwaite
> <[email protected]> wrote:
>> On Sat, Apr 5, 2014 at 12:30 AM, Harini Katakam
>> <[email protected]> wrote:
>>> Hi,
>>>
>>> On Fri, Apr 4, 2014 at 7:38 PM, Harini Katakam
>>> <[email protected]> wrote:
>>>> Hi Mark,
>>>>
>>>> On Fri, Apr 4, 2014 at 6:16 PM, Mark Brown <[email protected]> wrote:
>>>>> On Fri, Apr 04, 2014 at 05:44:23PM +0530, Harini Katakam wrote:
>>>>>> On Fri, Apr 4, 2014 at 3:39 PM, Mark Brown <[email protected]> wrote:
>>>>>> > On Fri, Apr 04, 2014 at 08:30:38AM +0530, Harini Katakam wrote:
>>>>>
>>>>>> >> This IP can drive 4 slaves.
>>>>>> >> The sCS line to be driven is selected in spi device structure and
>>>>>> >> that is driven by the software.
>>>>>
>>>>>> > So why specify this in the binding at all? If the device always has the
>>>>>> > same number of chip selects it's redundant.
>>>>>
>>>>>> I'm sorry, I should have explained that better.
>>>>>> The IP can support upto 4 chip selects.
>>>>>> The num-cs value here is the number of chip selects actually used on the board.
>>
>> Shouldnt it be a property of the controller not the board? How for
>> example do we differentiate between different implementations of
>> cadence SPI controller that only supports up to two CS lines? My
>> thinking is that this property should always be present and = 4 in the
>> Zynq case as the controller always has 4 physical CS lines coming out
>> (before any decoders, pin muxes or slaves etc.).
>>
>>>>>
>>>>> Why does that need to be configured? Surely the presence of slaves is
>>>>> enough information.
>>
>> And presence of slaves / board info is inferable from subnodes.
>>
>>>>
>>>> OK. I understand.
>>>> Can you comment on the case where a decoder is used?
>>>>
>>>> There is support for adding a decoder where extended slaves can be selected
>>>> through the IP's control register.
>>>> (This is not currently implemented in the driver but will be in the future.)
>>>>
>>
>> I think thats seperate information. is-decoded-cs property of something.
>>
>>>> How should the driver know whether it is 4 or 16 select lines for example?
>>>> This has to be written to master->num_chipselect.
>>>>
>>
>> If you only have one property (== 4) how do you tell the difference
>> between 4 un-decoded CS lines vs 2 decoded CS lines?
>>
>
> If an SoC implements 2 CS and sets "decoder" property,
> then we'd configure the register with "select decode" bit and write
> 0b0011 to the slave select field to select 4th slave.
>
> If decoder property is not set, then we'd write 0b1000 to select 4th slave.
>

What are your proposed dt bindings for these differing options - what
is num-cs in each case?

> But yes, if the SoC only implements 2 CS, doesn't use decoder but
> if there is an erroneous input to set_cs for 4th slave, it would be a problem.
>

Sure, that's an error condition though that should be caught by SPI
because master->num_chipselect would only be 2 right?

Regards,
Peter

>>
>> I think num-cs has validity as the number of CS lines implemented in
>> the controller. For any given SoC, it's constant but could differ
>> between SoCs.
>>
>
> I dint consider that this property will be useful to SoC's implementing <4 CS;
> master->num_chipselect (when set to this property's value)
> will be used to check error conditions.
>
> Regards,
> Harini

2014-04-07 07:46:50

by Harini Katakam

[permalink] [raw]
Subject: Re: [PATCH v2 2/2] devicetree: Add devicetree bindings documentation for Cadence SPI

Hi Peter,

On Sun, Apr 6, 2014 at 5:13 AM, Peter Crosthwaite
<[email protected]> wrote:
> On Sat, Apr 5, 2014 at 4:05 PM, Harini Katakam
> <[email protected]> wrote:
>> Hi Peter,
>>
>> On Sat, Apr 5, 2014 at 4:44 AM, Peter Crosthwaite
>> <[email protected]> wrote:
>>> On Sat, Apr 5, 2014 at 12:30 AM, Harini Katakam
>>> <[email protected]> wrote:
>>>> Hi,
>>>>
>>>> On Fri, Apr 4, 2014 at 7:38 PM, Harini Katakam
>>>> <[email protected]> wrote:
>>>>> Hi Mark,
>>>>>
>>>>> On Fri, Apr 4, 2014 at 6:16 PM, Mark Brown <[email protected]> wrote:
>>>>>> On Fri, Apr 04, 2014 at 05:44:23PM +0530, Harini Katakam wrote:
>>>>>>> On Fri, Apr 4, 2014 at 3:39 PM, Mark Brown <[email protected]> wrote:
>>>>>>> > On Fri, Apr 04, 2014 at 08:30:38AM +0530, Harini Katakam wrote:
>>>>>>
>>>>>>> >> This IP can drive 4 slaves.
>>>>>>> >> The sCS line to be driven is selected in spi device structure and
>>>>>>> >> that is driven by the software.
>>>>>>
>>>>>>> > So why specify this in the binding at all? If the device always has the
>>>>>>> > same number of chip selects it's redundant.
>>>>>>
>>>>>>> I'm sorry, I should have explained that better.
>>>>>>> The IP can support upto 4 chip selects.
>>>>>>> The num-cs value here is the number of chip selects actually used on the board.
>>>
>>> Shouldnt it be a property of the controller not the board? How for
>>> example do we differentiate between different implementations of
>>> cadence SPI controller that only supports up to two CS lines? My
>>> thinking is that this property should always be present and = 4 in the
>>> Zynq case as the controller always has 4 physical CS lines coming out
>>> (before any decoders, pin muxes or slaves etc.).
>>>
>>>>>>
>>>>>> Why does that need to be configured? Surely the presence of slaves is
>>>>>> enough information.
>>>
>>> And presence of slaves / board info is inferable from subnodes.
>>>
>>>>>
>>>>> OK. I understand.
>>>>> Can you comment on the case where a decoder is used?
>>>>>
>>>>> There is support for adding a decoder where extended slaves can be selected
>>>>> through the IP's control register.
>>>>> (This is not currently implemented in the driver but will be in the future.)
>>>>>
>>>
>>> I think thats seperate information. is-decoded-cs property of something.
>>>
>>>>> How should the driver know whether it is 4 or 16 select lines for example?
>>>>> This has to be written to master->num_chipselect.
>>>>>
>>>
>>> If you only have one property (== 4) how do you tell the difference
>>> between 4 un-decoded CS lines vs 2 decoded CS lines?
>>>
>>
>> If an SoC implements 2 CS and sets "decoder" property,
>> then we'd configure the register with "select decode" bit and write
>> 0b0011 to the slave select field to select 4th slave.
>>
>> If decoder property is not set, then we'd write 0b1000 to select 4th slave.
>>
>
> What are your proposed dt bindings for these differing options - what
> is num-cs in each case?

I think it will be better to have num-cs equal to the max slaves allowed and
the property to indicate if decoder is present helps driver configure the
register accordingly. (master->num_chipselect is written with "num-cs" value)

For ex.,
1. 4 slaves without decoder
num-cs = <4>
is-decoded-cs = <false>

2. 4 slaves driven through 2 to 4 decoder:
num-cs = <4>
is-decoded-cs = <true>

The other option is have num-cs reflect number of CS before decoder
but the above option makes more sense as num-cs directly reflects
the max valid slaves.

>
>> But yes, if the SoC only implements 2 CS, doesn't use decoder but
>> if there is an erroneous input to set_cs for 4th slave, it would be a problem.
>>
>
> Sure, that's an error condition though that should be caught by SPI
> because master->num_chipselect would only be 2 right?
>

Yes.

Regards,
Harini

> Regards,
> Peter
>
>>>
>>> I think num-cs has validity as the number of CS lines implemented in
>>> the controller. For any given SoC, it's constant but could differ
>>> between SoCs.
>>>
>>
>> I dint consider that this property will be useful to SoC's implementing <4 CS;
>> master->num_chipselect (when set to this property's value)
>> will be used to check error conditions.
>>
>> Regards,
>> Harini