blob: bb8e527d1baa26a8667fbf3c19d3201f7932084e [file] [log] [blame]
From 99e292bf8f472ce9475a68b37eb89ef201ff8acb Mon Sep 17 00:00:00 2001
From: Soren Brinkmann <soren.brinkmann@xilinx.com>
Date: Tue, 24 Dec 2013 09:10:07 +0900
Subject: spi: xilinx: merge qspi support from xilinx repository
This merges support for Xilinx QSPI from the Xilinx repository
(based on commit efc27505715e64526653f35274717c0fc56491e3 in master
branch). This has been tested to read the QSPI flash in the
Zynq 702 board.
Signed-off-by: Daniel Sangorrin <daniel.sangorrin@toshiba.co.jp>
Signed-off-by: Yoshitake Kobayashi <yoshitake.kobayashi@toshiba.co.jp>
---
drivers/spi/Kconfig | 24
drivers/spi/Makefile | 2
drivers/spi/spi-xilinx-ps.c | 927 ++++++++++++++++++++++++++++++++
drivers/spi/spi-xilinx-qps.c | 1220 +++++++++++++++++++++++++++++++++++++++++++
drivers/spi/spi-xilinx.c | 27
include/linux/spi/spi.h | 2
6 files changed, 2196 insertions(+), 6 deletions(-)
create mode 100644 drivers/spi/spi-xilinx-ps.c
create mode 100644 drivers/spi/spi-xilinx-qps.c
--- a/drivers/spi/Kconfig
+++ b/drivers/spi/Kconfig
@@ -474,12 +474,32 @@ config SPI_XILINX
select SPI_BITBANG
help
This exposes the SPI controller IP from the Xilinx EDK.
-
See the "OPB Serial Peripheral Interface (SPI) (v1.00e)"
Product Specification document (DS464) for hardware details.
-
Or for the DS570, see "XPS Serial Peripheral Interface (SPI) (v2.00b)"
+config SPI_XILINX_PS_QSPI
+ tristate "Xilinx PS QSPI controller"
+ depends on ARCH_ZYNQ
+ depends on SPI_MASTER
+ help
+ This selects the PS Quad SPI controller master driver from the Xilinx.
+
+config SPI_XILINX_PS_QSPI_DUAL_STACKED
+ bool "Xilinx PS QSPI Dual stacked configuration"
+ depends on SPI_XILINX_PS_QSPI
+ help
+ This selects the PS Quad SPI controller in dual stacked mode.
+ Enable this option if your hw design is using dual stacked
+ configuration.
+
+config SPI_XILINX_PS_SPI
+ tristate "Xilinx PS SPI controller"
+ depends on ARCH_ZYNQ
+ depends on SPI_MASTER
+ help
+ This selects the PS SPI controller master driver from the Xilinx.
+
config SPI_NUC900
tristate "Nuvoton NUC900 series SPI"
depends on ARCH_W90X900
--- a/drivers/spi/Makefile
+++ b/drivers/spi/Makefile
@@ -74,3 +74,5 @@ obj-$(CONFIG_SPI_TOPCLIFF_PCH) += spi-t
obj-$(CONFIG_SPI_TXX9) += spi-txx9.o
obj-$(CONFIG_SPI_XCOMM) += spi-xcomm.o
obj-$(CONFIG_SPI_XILINX) += spi-xilinx.o
+obj-$(CONFIG_SPI_XILINX_PS_SPI) += spi-xilinx-ps.o
+obj-$(CONFIG_SPI_XILINX_PS_QSPI) += spi-xilinx-qps.o
--- /dev/null
+++ b/drivers/spi/spi-xilinx-ps.c
@@ -0,0 +1,927 @@
+/*
+ *
+ * Xilinx PS SPI controller driver (master mode only)
+ *
+ * (c) 2008-2011 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.
+ *
+ * You should have received a copy of the GNU General Public License along with
+ * this program; if not, write to the Free Software Foundation, Inc., 59 Temple
+ * Place, Suite 330, Boston, MA 02111-1307 USA
+ */
+
+
+#include <linux/clk.h>
+#include <linux/delay.h>
+#include <linux/init.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>
+#include <linux/spinlock.h>
+#include <linux/workqueue.h>
+
+/*
+ * Name of this driver
+ */
+#define XSPIPS_NAME "xspips"
+
+/*
+ * Register offset definitions
+ */
+#define XSPIPS_CR_OFFSET 0x00 /* Configuration Register, RW */
+#define XSPIPS_ISR_OFFSET 0x04 /* Interrupt Status Register, RO */
+#define XSPIPS_IER_OFFSET 0x08 /* Interrupt Enable Register, WO */
+#define XSPIPS_IDR_OFFSET 0x0c /* Interrupt Disable Register, WO */
+#define XSPIPS_IMR_OFFSET 0x10 /* Interrupt Enabled Mask Register, RO */
+#define XSPIPS_ER_OFFSET 0x14 /* Enable/Disable Register, RW */
+#define XSPIPS_DR_OFFSET 0x18 /* Delay Register, RW */
+#define XSPIPS_TXD_OFFSET 0x1C /* Data Transmit Register, WO */
+#define XSPIPS_RXD_OFFSET 0x20 /* Data Receive Register, RO */
+#define XSPIPS_SICR_OFFSET 0x24 /* Slave Idle Count Register, RW */
+#define XSPIPS_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 XSPIPS_CR_MANSTRT_MASK 0x00010000 /* Manual TX Start */
+#define XSPIPS_CR_CPHA_MASK 0x00000004 /* Clock Phase Control */
+#define XSPIPS_CR_CPOL_MASK 0x00000002 /* Clock Polarity Control */
+#define XSPIPS_CR_SSCTRL_MASK 0x00003C00 /* Slave Select Mask */
+
+/*
+ * SPI Interrupt Registers bit Masks
+ *
+ * All the four interrupt registers (Status/Mask/Enable/Disable) have the same
+ * bit definitions.
+ */
+#define XSPIPS_IXR_TXOW_MASK 0x00000004 /* SPI TX FIFO Overwater */
+#define XSPIPS_IXR_MODF_MASK 0x00000002 /* SPI Mode Fault */
+#define XSPIPS_IXR_RXNEMTY_MASK 0x00000010 /* SPI RX FIFO Not Empty */
+#define XSPIPS_IXR_ALL_MASK (XSPIPS_IXR_TXOW_MASK | XSPIPS_IXR_MODF_MASK)
+
+/*
+ * SPI Enable Register bit Masks
+ *
+ * This register is used to enable or disable the SPI controller
+ */
+#define XSPIPS_ER_ENABLE_MASK 0x00000001 /* SPI Enable Bit Mask */
+
+/*
+ * Definitions for the status of queue
+ */
+#define XSPIPS_QUEUE_STOPPED 0
+#define XSPIPS_QUEUE_RUNNING 1
+
+/*
+ * Macros for the SPI controller read/write
+ */
+#define xspips_read(addr) __raw_readl(addr)
+#define xspips_write(addr, val) __raw_writel((val), (addr))
+
+
+/**
+ * struct xspips - This definition defines spi driver instance
+ * @workqueue: Queue of all the transfers
+ * @work: Information about current transfer
+ * @queue: Head of the queue
+ * @queue_state: Queue status
+ * @regs: Virtual address of the SPI controller registers
+ * @devclk: Pointer to the peripheral clock
+ * @aperclk: Pointer to the APER clock
+ * @clk_rate_change_nb: Notifier block for clock frequency change callback
+ * @irq: IRQ number
+ * @speed_hz: Current SPI bus clock speed in Hz
+ * @trans_queue_lock: Lock used for accessing transfer queue
+ * @ctrl_reg_lock: Lock used for accessing configuration register
+ * @txbuf: Pointer to the TX buffer
+ * @rxbuf: Pointer to the RX buffer
+ * @remaining_bytes: Number of bytes left to transfer
+ * @dev_busy: Device busy flag
+ * @done: Transfer complete status
+ */
+struct xspips {
+ struct workqueue_struct *workqueue;
+ struct work_struct work;
+ struct list_head queue;
+ int queue_state;
+ void __iomem *regs;
+ struct clk *devclk;
+ struct clk *aperclk;
+ struct notifier_block clk_rate_change_nb;
+ int irq;
+ u32 speed_hz;
+ spinlock_t trans_queue_lock;
+ spinlock_t ctrl_reg_lock;
+ const u8 *txbuf;
+ u8 *rxbuf;
+ int remaining_bytes;
+ u8 dev_busy;
+ struct completion done;
+};
+
+
+/**
+ * xspips_init_hw - Initialize the hardware and configure the SPI controller
+ * @regs_base: Base address of SPI controller
+ *
+ * On reset the SPI controller is configured to be in master mode, baud rate
+ * divisor is set to 2, 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 xspips_init_hw(void __iomem *regs_base)
+{
+ xspips_write(regs_base + XSPIPS_ER_OFFSET, ~XSPIPS_ER_ENABLE_MASK);
+ xspips_write(regs_base + XSPIPS_IDR_OFFSET, 0x7F);
+
+ /* Clear the RX FIFO */
+ while (xspips_read(regs_base + XSPIPS_ISR_OFFSET) &
+ XSPIPS_IXR_RXNEMTY_MASK)
+ xspips_read(regs_base + XSPIPS_RXD_OFFSET);
+
+ xspips_write(regs_base + XSPIPS_ISR_OFFSET, 0x7F);
+ xspips_write(regs_base + XSPIPS_CR_OFFSET, 0x0000FC01);
+ xspips_write(regs_base + XSPIPS_ER_OFFSET, XSPIPS_ER_ENABLE_MASK);
+}
+
+/**
+ * xspips_chipselect - Select or deselect the chip select line
+ * @spi: Pointer to the spi_device structure
+ * @is_on: Select(1) or deselect (0) the chip select line
+ */
+static void xspips_chipselect(struct spi_device *spi, int is_on)
+{
+ struct xspips *xspi = spi_master_get_devdata(spi->master);
+ u32 ctrl_reg;
+ unsigned long flags;
+
+ spin_lock_irqsave(&xspi->ctrl_reg_lock, flags);
+
+ ctrl_reg = xspips_read(xspi->regs + XSPIPS_CR_OFFSET);
+
+ if (is_on) {
+ /* Select the slave */
+ ctrl_reg &= ~XSPIPS_CR_SSCTRL_MASK;
+ ctrl_reg |= (((~(0x0001 << spi->chip_select)) << 10) &
+ XSPIPS_CR_SSCTRL_MASK);
+ } else {
+ /* Deselect the slave */
+ ctrl_reg |= XSPIPS_CR_SSCTRL_MASK;
+ }
+
+ xspips_write(xspi->regs + XSPIPS_CR_OFFSET, ctrl_reg);
+
+ spin_unlock_irqrestore(&xspi->ctrl_reg_lock, flags);
+}
+
+/**
+ * xspips_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.
+ *
+ * returns: 0 on success and error value on error
+ *
+ * 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 int xspips_setup_transfer(struct spi_device *spi,
+ struct spi_transfer *transfer)
+{
+ struct xspips *xspi = spi_master_get_devdata(spi->master);
+ u8 bits_per_word;
+ u32 ctrl_reg;
+ u32 req_hz;
+ u32 baud_rate_val;
+ unsigned long flags, frequency;
+
+ bits_per_word = (transfer) ?
+ transfer->bits_per_word : spi->bits_per_word;
+ req_hz = (transfer) ? transfer->speed_hz : spi->max_speed_hz;
+
+ if (bits_per_word != 8) {
+ dev_err(&spi->dev, "%s, unsupported bits per word %x\n",
+ __func__, spi->bits_per_word);
+ return -EINVAL;
+ }
+
+ frequency = clk_get_rate(xspi->devclk);
+
+ spin_lock_irqsave(&xspi->ctrl_reg_lock, flags);
+
+ xspips_write(xspi->regs + XSPIPS_ER_OFFSET, ~XSPIPS_ER_ENABLE_MASK);
+ ctrl_reg = xspips_read(xspi->regs + XSPIPS_CR_OFFSET);
+
+ /* Set the SPI clock phase and clock polarity */
+ ctrl_reg &= (~XSPIPS_CR_CPHA_MASK) & (~XSPIPS_CR_CPOL_MASK);
+ if (spi->mode & SPI_CPHA)
+ ctrl_reg |= XSPIPS_CR_CPHA_MASK;
+ if (spi->mode & SPI_CPOL)
+ ctrl_reg |= XSPIPS_CR_CPOL_MASK;
+
+ /* Set the clock frequency */
+ if (xspi->speed_hz != req_hz) {
+ baud_rate_val = 0;
+ while ((baud_rate_val < 8) && (frequency /
+ (2 << baud_rate_val)) > req_hz)
+ baud_rate_val++;
+
+ ctrl_reg &= 0xFFFFFFC7;
+ ctrl_reg |= (baud_rate_val << 3);
+
+ xspi->speed_hz = (frequency / (2 << baud_rate_val));
+ }
+
+ xspips_write(xspi->regs + XSPIPS_CR_OFFSET, ctrl_reg);
+ xspips_write(xspi->regs + XSPIPS_ER_OFFSET, XSPIPS_ER_ENABLE_MASK);
+
+ spin_unlock_irqrestore(&xspi->ctrl_reg_lock, flags);
+
+ 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;
+}
+
+/**
+ * xspips_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.
+ *
+ * returns: 0 on success and error value on error
+ */
+static int xspips_setup(struct spi_device *spi)
+{
+ if (!spi->max_speed_hz)
+ return -EINVAL;
+
+ if (!spi->bits_per_word)
+ spi->bits_per_word = 8;
+
+ return xspips_setup_transfer(spi, NULL);
+}
+
+/**
+ * xspips_fill_tx_fifo - Fills the TX FIFO with as many bytes as possible
+ * @xspi: Pointer to the xspips structure
+ */
+static void xspips_fill_tx_fifo(struct xspips *xspi)
+{
+ while ((xspips_read(xspi->regs + XSPIPS_ISR_OFFSET) & 0x00000008) == 0
+ && (xspi->remaining_bytes > 0)) {
+ if (xspi->txbuf)
+ xspips_write(xspi->regs + XSPIPS_TXD_OFFSET,
+ *xspi->txbuf++);
+ else
+ xspips_write(xspi->regs + XSPIPS_TXD_OFFSET, 0);
+
+ xspi->remaining_bytes--;
+ }
+}
+
+/**
+ * xspips_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.
+ *
+ * returns: IRQ_HANDLED always
+ */
+static irqreturn_t xspips_irq(int irq, void *dev_id)
+{
+ struct xspips *xspi = dev_id;
+ u32 intr_status;
+
+ intr_status = xspips_read(xspi->regs + XSPIPS_ISR_OFFSET);
+ xspips_write(xspi->regs + XSPIPS_ISR_OFFSET, intr_status);
+ xspips_write(xspi->regs + XSPIPS_IDR_OFFSET, XSPIPS_IXR_ALL_MASK);
+
+ if (intr_status & XSPIPS_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 */
+ complete(&xspi->done);
+ } else if (intr_status & XSPIPS_IXR_TXOW_MASK) {
+ u32 ctrl_reg;
+
+ /* Read out the data from the RX FIFO */
+ while (xspips_read(xspi->regs + XSPIPS_ISR_OFFSET) &
+ XSPIPS_IXR_RXNEMTY_MASK) {
+ u8 data;
+
+ data = xspips_read(xspi->regs + XSPIPS_RXD_OFFSET);
+ if (xspi->rxbuf)
+ *xspi->rxbuf++ = data;
+
+ /* Data memory barrier is placed here to ensure that
+ * data read operation is completed before the status
+ * read is initiated. Without dmb, there are chances
+ * that data and status reads will appear at the SPI
+ * peripheral back-to-back which results in an
+ * incorrect status read.
+ */
+ dmb();
+ }
+
+ if (xspi->remaining_bytes) {
+ /* There is more data to send */
+ xspips_fill_tx_fifo(xspi);
+
+ xspips_write(xspi->regs + XSPIPS_IER_OFFSET,
+ XSPIPS_IXR_ALL_MASK);
+
+ spin_lock(&xspi->ctrl_reg_lock);
+
+ ctrl_reg = xspips_read(xspi->regs + XSPIPS_CR_OFFSET);
+ ctrl_reg |= XSPIPS_CR_MANSTRT_MASK;
+ xspips_write(xspi->regs + XSPIPS_CR_OFFSET, ctrl_reg);
+
+ spin_unlock(&xspi->ctrl_reg_lock);
+ } else {
+ /* Transfer is completed */
+ complete(&xspi->done);
+ }
+ }
+
+ return IRQ_HANDLED;
+}
+
+/**
+ * xspips_start_transfer - Initiates the SPI transfer
+ * @spi: Pointer to the spi_device structure
+ * @transfer: Pointer to the spi_transfer structure which provide information
+ * about next transfer parameters
+ *
+ * This function fills the TX FIFO, starts the SPI transfer, and waits for the
+ * transfer to be completed.
+ *
+ * returns: Number of bytes transferred in the last transfer
+ */
+static int xspips_start_transfer(struct spi_device *spi,
+ struct spi_transfer *transfer)
+{
+ struct xspips *xspi = spi_master_get_devdata(spi->master);
+ u32 ctrl_reg;
+ unsigned long flags;
+
+ xspi->txbuf = transfer->tx_buf;
+ xspi->rxbuf = transfer->rx_buf;
+ xspi->remaining_bytes = transfer->len;
+ INIT_COMPLETION(xspi->done);
+
+ xspips_fill_tx_fifo(xspi);
+
+ xspips_write(xspi->regs + XSPIPS_IER_OFFSET, XSPIPS_IXR_ALL_MASK);
+
+ spin_lock_irqsave(&xspi->ctrl_reg_lock, flags);
+
+ /* Start the transfer by enabling manual start bit */
+ ctrl_reg = xspips_read(xspi->regs + XSPIPS_CR_OFFSET);
+ ctrl_reg |= XSPIPS_CR_MANSTRT_MASK;
+ xspips_write(xspi->regs + XSPIPS_CR_OFFSET, ctrl_reg);
+
+ spin_unlock_irqrestore(&xspi->ctrl_reg_lock, flags);
+
+ wait_for_completion(&xspi->done);
+
+ return (transfer->len) - (xspi->remaining_bytes);
+}
+
+/**
+ * xspips_work_queue - Get the transfer request from queue to perform transfers
+ * @work: Pointer to the work_struct structure
+ */
+static void xspips_work_queue(struct work_struct *work)
+{
+ struct xspips *xspi = container_of(work, struct xspips, work);
+ unsigned long flags;
+
+ spin_lock_irqsave(&xspi->trans_queue_lock, flags);
+ xspi->dev_busy = 1;
+
+ if (list_empty(&xspi->queue) ||
+ xspi->queue_state == XSPIPS_QUEUE_STOPPED) {
+ xspi->dev_busy = 0;
+ spin_unlock_irqrestore(&xspi->trans_queue_lock, flags);
+ return;
+ }
+
+ while (!list_empty(&xspi->queue)) {
+ struct spi_message *msg;
+ struct spi_device *spi;
+ struct spi_transfer *transfer = NULL;
+ unsigned cs_change = 1;
+ int status = 0;
+
+ msg = container_of(xspi->queue.next, struct spi_message, queue);
+ list_del_init(&msg->queue);
+ spin_unlock_irqrestore(&xspi->trans_queue_lock, flags);
+ spi = msg->spi;
+
+ list_for_each_entry(transfer, &msg->transfers, transfer_list) {
+ if ((transfer->bits_per_word || transfer->speed_hz) &&
+ cs_change) {
+ status = xspips_setup_transfer(spi, transfer);
+ if (status < 0)
+ break;
+ }
+
+ if (cs_change)
+ xspips_chipselect(spi, 1);
+
+ cs_change = transfer->cs_change;
+
+ if (!transfer->tx_buf && !transfer->rx_buf &&
+ transfer->len) {
+ status = -EINVAL;
+ break;
+ }
+
+ if (transfer->len)
+ status = xspips_start_transfer(spi, transfer);
+
+ if (status != transfer->len) {
+ if (status > 0)
+ status = -EMSGSIZE;
+ break;
+ }
+ msg->actual_length += status;
+ status = 0;
+
+ if (transfer->delay_usecs)
+ udelay(transfer->delay_usecs);
+
+ if (!cs_change)
+ continue;
+ if (transfer->transfer_list.next == &msg->transfers)
+ break;
+
+ xspips_chipselect(spi, 0);
+ }
+
+ msg->status = status;
+ msg->complete(msg->context);
+
+ if (!(status == 0 && cs_change))
+ xspips_chipselect(spi, 0);
+
+ spin_lock_irqsave(&xspi->trans_queue_lock, flags);
+ }
+ xspi->dev_busy = 0;
+ spin_unlock_irqrestore(&xspi->trans_queue_lock, flags);
+}
+
+/**
+ * xspips_transfer - Add a new transfer request at the tail of work queue
+ * @spi: Pointer to the spi_device structure
+ * @message: Pointer to the spi_transfer structure which provide information
+ * about next transfer parameters
+ *
+ * returns: 0 on success and error value on error
+ */
+static int xspips_transfer(struct spi_device *spi, struct spi_message *message)
+{
+ struct xspips *xspi = spi_master_get_devdata(spi->master);
+ struct spi_transfer *transfer;
+ unsigned long flags;
+
+ if (xspi->queue_state == XSPIPS_QUEUE_STOPPED)
+ return -ESHUTDOWN;
+
+ message->actual_length = 0;
+ message->status = -EINPROGRESS;
+
+ /* Check each transfer's parameters */
+ list_for_each_entry(transfer, &message->transfers, transfer_list) {
+ u8 bits_per_word =
+ transfer->bits_per_word ? : spi->bits_per_word;
+
+ bits_per_word = bits_per_word ? : 8;
+ if (!transfer->tx_buf && !transfer->rx_buf && transfer->len)
+ return -EINVAL;
+ if (bits_per_word != 8)
+ return -EINVAL;
+ }
+
+ spin_lock_irqsave(&xspi->trans_queue_lock, flags);
+ list_add_tail(&message->queue, &xspi->queue);
+ if (!xspi->dev_busy)
+ queue_work(xspi->workqueue, &xspi->work);
+ spin_unlock_irqrestore(&xspi->trans_queue_lock, flags);
+
+ return 0;
+}
+
+/**
+ * xspips_start_queue - Starts the queue of the SPI driver
+ * @xspi: Pointer to the xspips structure
+ *
+ * returns: 0 on success and error value on error
+ */
+static inline int xspips_start_queue(struct xspips *xspi)
+{
+ unsigned long flags;
+
+ spin_lock_irqsave(&xspi->trans_queue_lock, flags);
+
+ if (xspi->queue_state == XSPIPS_QUEUE_RUNNING || xspi->dev_busy) {
+ spin_unlock_irqrestore(&xspi->trans_queue_lock, flags);
+ return -EBUSY;
+ }
+
+ xspi->queue_state = XSPIPS_QUEUE_RUNNING;
+ spin_unlock_irqrestore(&xspi->trans_queue_lock, flags);
+
+ return 0;
+}
+
+/**
+ * xspips_stop_queue - Stops the queue of the SPI driver
+ * @xspi: Pointer to the xspips structure
+ *
+ * This function waits till queue is empty and then stops the queue.
+ * Maximum time out is set to 5 seconds.
+ *
+ * returns: 0 on success and error value on error
+ */
+static inline int xspips_stop_queue(struct xspips *xspi)
+{
+ unsigned long flags;
+ unsigned limit = 500;
+ int ret = 0;
+
+ if (xspi->queue_state != XSPIPS_QUEUE_RUNNING)
+ return ret;
+
+ spin_lock_irqsave(&xspi->trans_queue_lock, flags);
+
+ while ((!list_empty(&xspi->queue) || xspi->dev_busy) && limit--) {
+ spin_unlock_irqrestore(&xspi->trans_queue_lock, flags);
+ msleep(10);
+ spin_lock_irqsave(&xspi->trans_queue_lock, flags);
+ }
+
+ if (!list_empty(&xspi->queue) || xspi->dev_busy)
+ ret = -EBUSY;
+
+ if (ret == 0)
+ xspi->queue_state = XSPIPS_QUEUE_STOPPED;
+
+ spin_unlock_irqrestore(&xspi->trans_queue_lock, flags);
+
+ return ret;
+}
+
+/**
+ * xspips_destroy_queue - Destroys the queue of the SPI driver
+ * @xspi: Pointer to the xspips structure
+ *
+ * returns: 0 on success and error value on error
+ */
+static inline int xspips_destroy_queue(struct xspips *xspi)
+{
+ int ret;
+
+ ret = xspips_stop_queue(xspi);
+ if (ret != 0)
+ return ret;
+
+ destroy_workqueue(xspi->workqueue);
+
+ return 0;
+}
+
+static int xspips_clk_notifier_cb(struct notifier_block *nb,
+ unsigned long event, void *data)
+{
+ switch (event) {
+ case PRE_RATE_CHANGE:
+ /* if a rate change is announced we need to check whether we can
+ * maintain the current frequency by changing the clock
+ * dividers. And we may have to suspend operation and return
+ * after the rate change or its abort
+ */
+ return NOTIFY_OK;
+ case POST_RATE_CHANGE:
+ return NOTIFY_OK;
+ case ABORT_RATE_CHANGE:
+ default:
+ return NOTIFY_DONE;
+ }
+}
+
+/**
+ * xspips_probe - Probe method for the SPI driver
+ * @pdev: Pointer to the platform_device structure
+ *
+ * This function initializes the driver data structures and the hardware.
+ *
+ * returns: 0 on success and error value on error
+ */
+static int xspips_probe(struct platform_device *pdev)
+{
+ int ret = 0;
+ struct spi_master *master;
+ struct xspips *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);
+ dev_err(&pdev->dev, "ioremap failed\n");
+ goto remove_master;
+ }
+
+ xspi->irq = platform_get_irq(pdev, 0);
+ if (xspi->irq < 0) {
+ ret = -ENXIO;
+ dev_err(&pdev->dev, "irq number is negative\n");
+ goto remove_master;
+ }
+
+ ret = devm_request_irq(&pdev->dev, xspi->irq, xspips_irq,
+ 0, pdev->name, xspi);
+ if (ret != 0) {
+ ret = -ENXIO;
+ dev_err(&pdev->dev, "request_irq failed\n");
+ goto remove_master;
+ }
+
+ xspi->aperclk = clk_get(&pdev->dev, "aper_clk");
+ if (IS_ERR(xspi->aperclk)) {
+ dev_err(&pdev->dev, "aper_clk clock not found.\n");
+ ret = PTR_ERR(xspi->aperclk);
+ goto remove_master;
+ }
+
+ xspi->devclk = clk_get(&pdev->dev, "ref_clk");
+ if (IS_ERR(xspi->devclk)) {
+ dev_err(&pdev->dev, "ref_clk clock not found.\n");
+ ret = PTR_ERR(xspi->devclk);
+ goto clk_put_aper;
+ }
+
+ ret = clk_prepare_enable(xspi->aperclk);
+ if (ret) {
+ dev_err(&pdev->dev, "Unable to enable APER clock.\n");
+ goto clk_put;
+ }
+
+ ret = clk_prepare_enable(xspi->devclk);
+ if (ret) {
+ dev_err(&pdev->dev, "Unable to enable device clock.\n");
+ goto clk_dis_aper;
+ }
+
+ xspi->clk_rate_change_nb.notifier_call = xspips_clk_notifier_cb;
+ xspi->clk_rate_change_nb.next = NULL;
+ if (clk_notifier_register(xspi->devclk, &xspi->clk_rate_change_nb))
+ dev_warn(&pdev->dev, "Unable to register clock notifier.\n");
+
+ /* SPI controller initializations */
+ xspips_init_hw(xspi->regs);
+
+ init_completion(&xspi->done);
+
+ ret = of_property_read_u32(pdev->dev.of_node, "num-chip-select",
+ (u32 *)&master->num_chipselect);
+ if (ret < 0) {
+ dev_err(&pdev->dev, "couldn't determine num-chip-select\n");
+ goto clk_notif_unreg;
+ }
+ master->setup = xspips_setup;
+ master->transfer = xspips_transfer;
+ master->mode_bits = SPI_CPOL | SPI_CPHA;
+
+ xspi->speed_hz = clk_get_rate(xspi->devclk) / 2;
+
+ xspi->dev_busy = 0;
+
+ INIT_LIST_HEAD(&xspi->queue);
+ spin_lock_init(&xspi->trans_queue_lock);
+ spin_lock_init(&xspi->ctrl_reg_lock);
+
+ xspi->queue_state = XSPIPS_QUEUE_STOPPED;
+ xspi->dev_busy = 0;
+
+ INIT_WORK(&xspi->work, xspips_work_queue);
+ xspi->workqueue =
+ create_singlethread_workqueue(dev_name(&pdev->dev));
+ if (!xspi->workqueue) {
+ ret = -ENOMEM;
+ dev_err(&pdev->dev, "problem initializing queue\n");
+ goto clk_notif_unreg;
+ }
+
+ ret = xspips_start_queue(xspi);
+ if (ret != 0) {
+ dev_err(&pdev->dev, "problem starting queue\n");
+ goto remove_queue;
+ }
+
+ ret = spi_register_master(master);
+ if (ret) {
+ dev_err(&pdev->dev, "spi_register_master failed\n");
+ goto remove_queue;
+ }
+
+ dev_info(&pdev->dev, "at 0x%08X mapped to 0x%08X, irq=%d\n", res->start,
+ (u32 __force)xspi->regs, xspi->irq);
+
+ return ret;
+
+remove_queue:
+ (void)xspips_destroy_queue(xspi);
+clk_notif_unreg:
+ clk_notifier_unregister(xspi->devclk, &xspi->clk_rate_change_nb);
+ clk_disable_unprepare(xspi->devclk);
+clk_dis_aper:
+ clk_disable_unprepare(xspi->aperclk);
+clk_put:
+ clk_put(xspi->devclk);
+clk_put_aper:
+ clk_put(xspi->aperclk);
+remove_master:
+ spi_master_put(master);
+ return ret;
+}
+
+/**
+ * xspips_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.
+ *
+ * returns: 0 on success and error value on error
+ */
+static int xspips_remove(struct platform_device *pdev)
+{
+ struct spi_master *master = platform_get_drvdata(pdev);
+ struct xspips *xspi = spi_master_get_devdata(master);
+ int ret = 0;
+
+ ret = xspips_destroy_queue(xspi);
+ if (ret != 0)
+ return ret;
+
+ xspips_write(xspi->regs + XSPIPS_ER_OFFSET, ~XSPIPS_ER_ENABLE_MASK);
+
+ clk_notifier_unregister(xspi->devclk, &xspi->clk_rate_change_nb);
+ clk_disable_unprepare(xspi->devclk);
+ clk_disable_unprepare(xspi->aperclk);
+ clk_put(xspi->devclk);
+ clk_put(xspi->aperclk);
+
+ spi_unregister_master(master);
+ spi_master_put(master);
+
+ dev_dbg(&pdev->dev, "remove succeeded\n");
+ return 0;
+
+}
+
+#ifdef CONFIG_PM_SLEEP
+/**
+ * xspips_suspend - Suspend method for the SPI driver
+ * @dev: Address of the platform_device structure
+ *
+ * This function stops the SPI driver queue and disables the SPI controller
+ *
+ * returns: 0 on success and error value on error
+ */
+static int xspips_suspend(struct device *dev)
+{
+ struct platform_device *pdev = container_of(dev,
+ struct platform_device, dev);
+ struct spi_master *master = platform_get_drvdata(pdev);
+ struct xspips *xspi = spi_master_get_devdata(master);
+ int ret = 0;
+
+ ret = xspips_stop_queue(xspi);
+ if (ret != 0)
+ return ret;
+
+ xspips_write(xspi->regs + XSPIPS_ER_OFFSET, ~XSPIPS_ER_ENABLE_MASK);
+
+ clk_disable(xspi->devclk);
+ clk_disable(xspi->aperclk);
+
+ dev_dbg(&pdev->dev, "suspend succeeded\n");
+ return 0;
+}
+
+/**
+ * xspips_resume - Resume method for the SPI driver
+ * @dev: Address of the platform_device structure
+ *
+ * This function starts the SPI driver queue and initializes the SPI controller
+ *
+ * returns: 0 on success and error value on error
+ */
+static int xspips_resume(struct device *dev)
+{
+ struct platform_device *pdev = container_of(dev,
+ struct platform_device, dev);
+ struct spi_master *master = platform_get_drvdata(pdev);
+ struct xspips *xspi = spi_master_get_devdata(master);
+ int ret = 0;
+
+ ret = clk_enable(xspi->aperclk);
+ if (ret) {
+ dev_err(dev, "Cannot enable APER clock.\n");
+ return ret;
+ }
+
+ ret = clk_enable(xspi->devclk);
+ if (ret) {
+ dev_err(dev, "Cannot enable device clock.\n");
+ clk_disable(xspi->aperclk);
+ return ret;
+ }
+
+ xspips_init_hw(xspi->regs);
+
+ ret = xspips_start_queue(xspi);
+ if (ret != 0) {
+ dev_err(&pdev->dev, "problem starting queue (%d)\n", ret);
+ return ret;
+ }
+
+ dev_dbg(&pdev->dev, "resume succeeded\n");
+ return 0;
+}
+#endif /* ! CONFIG_PM_SLEEP */
+
+static SIMPLE_DEV_PM_OPS(xspips_dev_pm_ops, xspips_suspend, xspips_resume);
+
+/* Work with hotplug and coldplug */
+MODULE_ALIAS("platform:" XSPIPS_NAME);
+
+static struct of_device_id xspips_of_match[] = {
+ { .compatible = "xlnx,ps7-spi-1.00.a", },
+ { /* end of table */}
+};
+MODULE_DEVICE_TABLE(of, xspips_of_match);
+
+/*
+ * xspips_driver - This structure defines the SPI subsystem platform driver
+ */
+static struct platform_driver xspips_driver = {
+ .probe = xspips_probe,
+ .remove = xspips_remove,
+ .driver = {
+ .name = XSPIPS_NAME,
+ .owner = THIS_MODULE,
+ .of_match_table = xspips_of_match,
+ .pm = &xspips_dev_pm_ops,
+ },
+};
+
+module_platform_driver(xspips_driver);
+
+MODULE_AUTHOR("Xilinx, Inc.");
+MODULE_DESCRIPTION("Xilinx PS SPI driver");
+MODULE_LICENSE("GPL");
+
--- /dev/null
+++ b/drivers/spi/spi-xilinx-qps.c
@@ -0,0 +1,1220 @@
+/*
+ *
+ * Xilinx PS Quad-SPI (QSPI) controller driver (master mode only)
+ *
+ * (c) 2009-2011 Xilinx, Inc.
+ *
+ * based on Xilinx PS SPI Driver (xspips.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.
+ *
+ * You should have received a copy of the GNU General Public License along with
+ * this program; if not, write to the Free Software Foundation, Inc., 59 Temple
+ * Place, Suite 330, Boston, MA 02111-1307 USA
+ */
+
+
+#include <linux/clk.h>
+#include <linux/delay.h>
+#include <linux/init.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>
+#include <linux/spinlock.h>
+#include <linux/workqueue.h>
+
+/*
+ * Name of this driver
+ */
+#define DRIVER_NAME "xqspips"
+
+/*
+ * Register offset definitions
+ */
+#define XQSPIPS_CONFIG_OFFSET 0x00 /* Configuration Register, RW */
+#define XQSPIPS_STATUS_OFFSET 0x04 /* Interrupt Status Register, RO */
+#define XQSPIPS_IEN_OFFSET 0x08 /* Interrupt Enable Register, WO */
+#define XQSPIPS_IDIS_OFFSET 0x0C /* Interrupt Disable Reg, WO */
+#define XQSPIPS_IMASK_OFFSET 0x10 /* Interrupt Enabled Mask Reg,RO */
+#define XQSPIPS_ENABLE_OFFSET 0x14 /* Enable/Disable Register, RW */
+#define XQSPIPS_DELAY_OFFSET 0x18 /* Delay Register, RW */
+#define XQSPIPS_TXD_00_00_OFFSET 0x1C /* Transmit 4-byte inst, WO */
+#define XQSPIPS_TXD_00_01_OFFSET 0x80 /* Transmit 1-byte inst, WO */
+#define XQSPIPS_TXD_00_10_OFFSET 0x84 /* Transmit 2-byte inst, WO */
+#define XQSPIPS_TXD_00_11_OFFSET 0x88 /* Transmit 3-byte inst, WO */
+#define XQSPIPS_RXD_OFFSET 0x20 /* Data Receive Register, RO */
+#define XQSPIPS_SIC_OFFSET 0x24 /* Slave Idle Count Register, RW */
+#define XQSPIPS_TX_THRESH_OFFSET 0x28 /* TX FIFO Watermark Reg, RW */
+#define XQSPIPS_RX_THRESH_OFFSET 0x2C /* RX FIFO Watermark Reg, RW */
+#define XQSPIPS_GPIO_OFFSET 0x30 /* GPIO Register, RW */
+#define XQSPIPS_LINEAR_CFG_OFFSET 0xA0 /* Linear Adapter Config Ref, RW */
+#define XQSPIPS_MOD_ID_OFFSET 0xFC /* Module ID Register, RO */
+
+/*
+ * QSPI Configuration Register bit Masks
+ *
+ * This register contains various control bits that effect the operation
+ * of the QSPI controller
+ */
+#define XQSPIPS_CONFIG_MANSRT_MASK 0x00010000 /* Manual TX Start */
+#define XQSPIPS_CONFIG_CPHA_MASK 0x00000004 /* Clock Phase Control */
+#define XQSPIPS_CONFIG_CPOL_MASK 0x00000002 /* Clock Polarity Control */
+#define XQSPIPS_CONFIG_SSCTRL_MASK 0x00003C00 /* Slave Select Mask */
+
+/*
+ * QSPI Interrupt Registers bit Masks
+ *
+ * All the four interrupt registers (Status/Mask/Enable/Disable) have the same
+ * bit definitions.
+ */
+#define XQSPIPS_IXR_TXNFULL_MASK 0x00000004 /* QSPI TX FIFO Overflow */
+#define XQSPIPS_IXR_TXFULL_MASK 0x00000008 /* QSPI TX FIFO is full */
+#define XQSPIPS_IXR_RXNEMTY_MASK 0x00000010 /* QSPI RX FIFO Not Empty */
+#define XQSPIPS_IXR_ALL_MASK (XQSPIPS_IXR_TXNFULL_MASK)
+
+/*
+ * QSPI Enable Register bit Masks
+ *
+ * This register is used to enable or disable the QSPI controller
+ */
+#define XQSPIPS_ENABLE_ENABLE_MASK 0x00000001 /* QSPI Enable Bit Mask */
+
+/*
+ * QSPI Linear Configuration Register
+ *
+ * It is named Linear Configuration but it controls other modes when not in
+ * linear mode also.
+ */
+#define XQSPIPS_LCFG_TWO_MEM_MASK 0x40000000 /* LQSPI Two memories Mask */
+#define XQSPIPS_LCFG_SEP_BUS_MASK 0x20000000 /* LQSPI Separate bus Mask */
+#define XQSPIPS_LCFG_U_PAGE_MASK 0x10000000 /* LQSPI Upper Page Mask */
+
+#define XQSPIPS_LCFG_DUMMY_SHIFT 8
+
+#define XQSPIPS_FAST_READ_QOUT_CODE 0x6B /* read instruction code */
+
+/*
+ * The modebits configurable by the driver to make the SPI support different
+ * data formats
+ */
+#define MODEBITS (SPI_CPOL | SPI_CPHA)
+
+/*
+ * Definitions for the status of queue
+ */
+#define XQSPIPS_QUEUE_STOPPED 0
+#define XQSPIPS_QUEUE_RUNNING 1
+
+/*
+ * Definitions of the flash commands
+ */
+/* Flash opcodes in ascending order */
+#define XQSPIPS_FLASH_OPCODE_WRSR 0x01 /* Write status register */
+#define XQSPIPS_FLASH_OPCODE_PP 0x02 /* Page program */
+#define XQSPIPS_FLASH_OPCODE_NORM_READ 0x03 /* Normal read data bytes */
+#define XQSPIPS_FLASH_OPCODE_WRDS 0x04 /* Write disable */
+#define XQSPIPS_FLASH_OPCODE_RDSR1 0x05 /* Read status register 1 */
+#define XQSPIPS_FLASH_OPCODE_WREN 0x06 /* Write enable */
+#define XQSPIPS_FLASH_OPCODE_BRRD 0x16 /* Bank Register Read */
+#define XQSPIPS_FLASH_OPCODE_BRWR 0x17 /* Bank Register Write */
+#define XQSPIPS_FLASH_OPCODE_EXTADRD 0xC8 /* Micron - Bank Reg Read */
+#define XQSPIPS_FLASH_OPCODE_EXTADWR 0xC5 /* Micron - Bank Reg Write */
+#define XQSPIPS_FLASH_OPCODE_FAST_READ 0x0B /* Fast read data bytes */
+#define XQSPIPS_FLASH_OPCODE_BE_4K 0x20 /* Erase 4KiB block */
+#define XQSPIPS_FLASH_OPCODE_RDSR2 0x35 /* Read status register 2 */
+#define XQSPIPS_FLASH_OPCODE_RDFSR 0x70 /* Read flag status register */
+#define XQSPIPS_FLASH_OPCODE_DUAL_READ 0x3B /* Dual read data bytes */
+#define XQSPIPS_FLASH_OPCODE_BE_32K 0x52 /* Erase 32KiB block */
+#define XQSPIPS_FLASH_OPCODE_QUAD_READ 0x6B /* Quad read data bytes */
+#define XQSPIPS_FLASH_OPCODE_ERASE_SUS 0x75 /* Erase suspend */
+#define XQSPIPS_FLASH_OPCODE_ERASE_RES 0x7A /* Erase resume */
+#define XQSPIPS_FLASH_OPCODE_RDID 0x9F /* Read JEDEC ID */
+#define XQSPIPS_FLASH_OPCODE_BE 0xC7 /* Erase whole flash block */
+#define XQSPIPS_FLASH_OPCODE_SE 0xD8 /* Sector erase (usually 64KB)*/
+#define XQSPIPS_FLASH_OPCODE_QPP 0x32 /* Quad page program */
+
+/*
+ * Macros for the QSPI controller read/write
+ */
+#define xqspips_read(addr) readl(addr)
+#define xqspips_write(addr, val) writel((val), (addr))
+
+/**
+ * struct xqspips - Defines qspi driver instance
+ * @workqueue: Queue of all the transfers
+ * @work: Information about current transfer
+ * @queue: Head of the queue
+ * @queue_state: Queue status
+ * @regs: Virtual address of the QSPI controller registers
+ * @devclk: Pointer to the peripheral clock
+ * @aperclk: Pointer to the APER clock
+ * @clk_rate_change_nb: Notifier block for clock frequency change callback
+ * @irq: IRQ number
+ * @speed_hz: Current QSPI bus clock speed in Hz
+ * @trans_queue_lock: Lock used for accessing transfer queue
+ * @config_reg_lock: Lock used for accessing configuration register
+ * @txbuf: Pointer to the TX buffer
+ * @rxbuf: Pointer to the RX buffer
+ * @bytes_to_transfer: Number of bytes left to transfer
+ * @bytes_to_receive: Number of bytes left to receive
+ * @dev_busy: Device busy flag
+ * @done: Transfer complete status
+ * @is_inst: Flag to indicate the first message in a Transfer request
+ * @is_dual: Flag to indicate whether dual flash memories are used
+ */
+struct xqspips {
+ struct workqueue_struct *workqueue;
+ struct work_struct work;
+ struct list_head queue;
+ u8 queue_state;
+ void __iomem *regs;
+ struct clk *devclk;
+ struct clk *aperclk;
+ struct notifier_block clk_rate_change_nb;
+ int irq;
+ u32 speed_hz;
+ spinlock_t trans_queue_lock;
+ spinlock_t config_reg_lock;
+ const void *txbuf;
+ void *rxbuf;
+ int bytes_to_transfer;
+ int bytes_to_receive;
+ u8 dev_busy;
+ struct completion done;
+ bool is_inst;
+ u32 is_dual;
+};
+
+/**
+ * struct xqspips_inst_format - Defines qspi flash instruction format
+ * @opcode: Operational code of instruction
+ * @inst_size: Size of the instruction including address bytes
+ * @offset: Register address where instruction has to be written
+ */
+struct xqspips_inst_format {
+ u8 opcode;
+ u8 inst_size;
+ u8 offset;
+};
+
+/*
+ * List of all the QSPI instructions and its format
+ */
+static struct xqspips_inst_format flash_inst[] = {
+ { XQSPIPS_FLASH_OPCODE_WREN, 1, XQSPIPS_TXD_00_01_OFFSET },
+ { XQSPIPS_FLASH_OPCODE_WRDS, 1, XQSPIPS_TXD_00_01_OFFSET },
+ { XQSPIPS_FLASH_OPCODE_RDSR1, 1, XQSPIPS_TXD_00_01_OFFSET },
+ { XQSPIPS_FLASH_OPCODE_RDSR2, 1, XQSPIPS_TXD_00_01_OFFSET },
+ { XQSPIPS_FLASH_OPCODE_WRSR, 1, XQSPIPS_TXD_00_01_OFFSET },
+ { XQSPIPS_FLASH_OPCODE_RDFSR, 1, XQSPIPS_TXD_00_01_OFFSET },
+ { XQSPIPS_FLASH_OPCODE_PP, 4, XQSPIPS_TXD_00_00_OFFSET },
+ { XQSPIPS_FLASH_OPCODE_SE, 4, XQSPIPS_TXD_00_00_OFFSET },
+ { XQSPIPS_FLASH_OPCODE_BE_32K, 4, XQSPIPS_TXD_00_00_OFFSET },
+ { XQSPIPS_FLASH_OPCODE_BE_4K, 4, XQSPIPS_TXD_00_00_OFFSET },
+ { XQSPIPS_FLASH_OPCODE_BE, 1, XQSPIPS_TXD_00_01_OFFSET },
+ { XQSPIPS_FLASH_OPCODE_ERASE_SUS, 1, XQSPIPS_TXD_00_01_OFFSET },
+ { XQSPIPS_FLASH_OPCODE_ERASE_RES, 1, XQSPIPS_TXD_00_01_OFFSET },
+ { XQSPIPS_FLASH_OPCODE_RDID, 1, XQSPIPS_TXD_00_01_OFFSET },
+ { XQSPIPS_FLASH_OPCODE_NORM_READ, 4, XQSPIPS_TXD_00_00_OFFSET },
+ { XQSPIPS_FLASH_OPCODE_FAST_READ, 1, XQSPIPS_TXD_00_01_OFFSET },
+ { XQSPIPS_FLASH_OPCODE_DUAL_READ, 1, XQSPIPS_TXD_00_01_OFFSET },
+ { XQSPIPS_FLASH_OPCODE_QUAD_READ, 1, XQSPIPS_TXD_00_01_OFFSET },
+ { XQSPIPS_FLASH_OPCODE_BRRD, 1, XQSPIPS_TXD_00_01_OFFSET },
+ { XQSPIPS_FLASH_OPCODE_BRWR, 2, XQSPIPS_TXD_00_10_OFFSET },
+ { XQSPIPS_FLASH_OPCODE_EXTADRD, 1, XQSPIPS_TXD_00_01_OFFSET },
+ { XQSPIPS_FLASH_OPCODE_EXTADWR, 2, XQSPIPS_TXD_00_10_OFFSET },
+ { XQSPIPS_FLASH_OPCODE_QPP, 4, XQSPIPS_TXD_00_00_OFFSET },
+ /* Add all the instructions supported by the flash device */
+};
+
+/**
+ * xqspips_init_hw - Initialize the hardware
+ * @regs_base: Base address of QSPI controller
+ * @is_dual: Indicates whether dual memories are used
+ *
+ * The default settings of the QSPI controller's configurable parameters on
+ * reset are
+ * - Master mode
+ * - Baud rate divisor is set to 2
+ * - Threshold value for TX FIFO not full interrupt is set to 1
+ * - Flash memory interface mode enabled
+ * - Size of the word to be transferred as 8 bit
+ * This function performs the following actions
+ * - Disable and clear all the interrupts
+ * - Enable manual slave select
+ * - Enable manual start
+ * - Deselect all the chip select lines
+ * - Set the size of the word to be transferred as 32 bit
+ * - Set the little endian mode of TX FIFO and
+ * - Enable the QSPI controller
+ */
+static void xqspips_init_hw(void __iomem *regs_base, int is_dual)
+{
+ u32 config_reg;
+
+ xqspips_write(regs_base + XQSPIPS_ENABLE_OFFSET,
+ ~XQSPIPS_ENABLE_ENABLE_MASK);
+ xqspips_write(regs_base + XQSPIPS_IDIS_OFFSET, 0x7F);
+
+ /* Disable linear mode as the boot loader may have used it */
+ xqspips_write(regs_base + XQSPIPS_LINEAR_CFG_OFFSET, 0);
+
+ /* Clear the RX FIFO */
+ while (xqspips_read(regs_base + XQSPIPS_STATUS_OFFSET) &
+ XQSPIPS_IXR_RXNEMTY_MASK)
+ xqspips_read(regs_base + XQSPIPS_RXD_OFFSET);
+
+ xqspips_write(regs_base + XQSPIPS_STATUS_OFFSET , 0x7F);
+ config_reg = xqspips_read(regs_base + XQSPIPS_CONFIG_OFFSET);
+ config_reg &= 0xFBFFFFFF; /* Set little endian mode of TX FIFO */
+ config_reg |= 0x8000FCC1;
+ xqspips_write(regs_base + XQSPIPS_CONFIG_OFFSET, config_reg);
+
+ if (is_dual == 1)
+ /* Enable two memories on seperate buses */
+ xqspips_write(regs_base + XQSPIPS_LINEAR_CFG_OFFSET,
+ (XQSPIPS_LCFG_TWO_MEM_MASK |
+ XQSPIPS_LCFG_SEP_BUS_MASK |
+ (1 << XQSPIPS_LCFG_DUMMY_SHIFT) |
+ XQSPIPS_FAST_READ_QOUT_CODE));
+#ifdef CONFIG_SPI_XILINX_PS_QSPI_DUAL_STACKED
+ /* Enable two memories on shared bus */
+ xqspips_write(regs_base + XQSPIPS_LINEAR_CFG_OFFSET,
+ (XQSPIPS_LCFG_TWO_MEM_MASK |
+ (1 << XQSPIPS_LCFG_DUMMY_SHIFT) |
+ XQSPIPS_FAST_READ_QOUT_CODE));
+#endif
+ xqspips_write(regs_base + XQSPIPS_ENABLE_OFFSET,
+ XQSPIPS_ENABLE_ENABLE_MASK);
+}
+
+/**
+ * xqspips_copy_read_data - Copy data to RX buffer
+ * @xqspi: Pointer to the xqspips structure
+ * @data: The 32 bit variable where data is stored
+ * @size: Number of bytes to be copied from data to RX buffer
+ */
+static void xqspips_copy_read_data(struct xqspips *xqspi, u32 data, u8 size)
+{
+ if (xqspi->rxbuf) {
+ data >>= (4 - size) * 8;
+ data = le32_to_cpu(data);
+ memcpy((u8 *)xqspi->rxbuf, &data, size);
+ xqspi->rxbuf += size;
+ }
+ xqspi->bytes_to_receive -= size;
+ if (xqspi->bytes_to_receive < 0)
+ xqspi->bytes_to_receive = 0;
+}
+
+/**
+ * xqspips_copy_write_data - Copy data from TX buffer
+ * @xqspi: Pointer to the xqspips structure
+ * @data: Pointer to the 32 bit variable where data is to be copied
+ * @size: Number of bytes to be copied from TX buffer to data
+ */
+static void xqspips_copy_write_data(struct xqspips *xqspi, u32 *data, u8 size)
+{
+
+ if (xqspi->txbuf) {
+ switch (size) {
+ case 1:
+ *data = *((u8 *)xqspi->txbuf);
+ xqspi->txbuf += 1;
+ *data |= 0xFFFFFF00;
+ break;
+ case 2:
+ *data = *((u16 *)xqspi->txbuf);
+ xqspi->txbuf += 2;
+ *data |= 0xFFFF0000;
+ break;
+ case 3:
+ *data = *((u16 *)xqspi->txbuf);
+ xqspi->txbuf += 2;
+ *data |= (*((u8 *)xqspi->txbuf) << 16);
+ xqspi->txbuf += 1;
+ *data |= 0xFF000000;
+ break;
+ case 4:
+ *data = *((u32 *)xqspi->txbuf);
+ xqspi->txbuf += 4;
+ break;
+ default:
+ /* This will never execute */
+ break;
+ }
+ } else {
+ *data = 0;
+ }
+
+ xqspi->bytes_to_transfer -= size;
+ if (xqspi->bytes_to_transfer < 0)
+ xqspi->bytes_to_transfer = 0;
+}
+
+/**
+ * xqspips_chipselect - Select or deselect the chip select line
+ * @qspi: Pointer to the spi_device structure
+ * @is_on: Select(1) or deselect (0) the chip select line
+ */
+static void xqspips_chipselect(struct spi_device *qspi, int is_on)
+{
+ struct xqspips *xqspi = spi_master_get_devdata(qspi->master);
+ u32 config_reg;
+ unsigned long flags;
+
+ spin_lock_irqsave(&xqspi->config_reg_lock, flags);
+
+ config_reg = xqspips_read(xqspi->regs + XQSPIPS_CONFIG_OFFSET);
+
+ if (is_on) {
+ /* Select the slave */
+ config_reg &= ~XQSPIPS_CONFIG_SSCTRL_MASK;
+ config_reg |= (((~(0x0001 << qspi->chip_select)) << 10) &
+ XQSPIPS_CONFIG_SSCTRL_MASK);
+ } else {
+ /* Deselect the slave */
+ config_reg |= XQSPIPS_CONFIG_SSCTRL_MASK;
+ }
+
+ xqspips_write(xqspi->regs + XQSPIPS_CONFIG_OFFSET, config_reg);
+
+ spin_unlock_irqrestore(&xqspi->config_reg_lock, flags);
+}
+
+/**
+ * xqspips_setup_transfer - Configure QSPI controller for specified transfer
+ * @qspi: 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 QSPI controller for the next QSPI transfer and
+ * sets the requested clock frequency.
+ *
+ * returns: 0 on success and -EINVAL on invalid input parameter
+ *
+ * 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 QSPI
+ * controller the driver will set the highest or lowest frequency supported by
+ * controller.
+ */
+static int xqspips_setup_transfer(struct spi_device *qspi,
+ struct spi_transfer *transfer)
+{
+ struct xqspips *xqspi = spi_master_get_devdata(qspi->master);
+ u32 config_reg;
+ u32 req_hz;
+ u32 baud_rate_val = 0;
+ unsigned long flags;
+ int update_baud = 0;
+
+ req_hz = (transfer) ? transfer->speed_hz : qspi->max_speed_hz;
+
+ if (qspi->mode & ~MODEBITS) {
+ dev_err(&qspi->dev, "%s, unsupported mode bits %x\n",
+ __func__, qspi->mode & ~MODEBITS);
+ return -EINVAL;
+ }
+
+ if (transfer && (transfer->speed_hz == 0))
+ req_hz = qspi->max_speed_hz;
+
+ /* Set the clock frequency */
+ if (xqspi->speed_hz != req_hz) {
+ while ((baud_rate_val < 8) &&
+ (clk_get_rate(xqspi->devclk) / (2 << baud_rate_val)) >
+ req_hz)
+ baud_rate_val++;
+ xqspi->speed_hz = req_hz;
+ update_baud = 1;
+ }
+
+ spin_lock_irqsave(&xqspi->config_reg_lock, flags);
+
+ config_reg = xqspips_read(xqspi->regs + XQSPIPS_CONFIG_OFFSET);
+
+ /* Set the QSPI clock phase and clock polarity */
+ config_reg &= (~XQSPIPS_CONFIG_CPHA_MASK) &
+ (~XQSPIPS_CONFIG_CPOL_MASK);
+ if (qspi->mode & SPI_CPHA)
+ config_reg |= XQSPIPS_CONFIG_CPHA_MASK;
+ if (qspi->mode & SPI_CPOL)
+ config_reg |= XQSPIPS_CONFIG_CPOL_MASK;
+
+ if (update_baud) {
+ config_reg &= 0xFFFFFFC7;
+ config_reg |= (baud_rate_val << 3);
+ }
+
+ xqspips_write(xqspi->regs + XQSPIPS_CONFIG_OFFSET, config_reg);
+
+ spin_unlock_irqrestore(&xqspi->config_reg_lock, flags);
+
+ dev_dbg(&qspi->dev, "%s, mode %d, %u bits/w, %u clock speed\n",
+ __func__, qspi->mode & MODEBITS, qspi->bits_per_word,
+ xqspi->speed_hz);
+
+ return 0;
+}
+
+/**
+ * xqspips_setup - Configure the QSPI controller
+ * @qspi: Pointer to the spi_device structure
+ *
+ * Sets the operational mode of QSPI controller for the next QSPI transfer, baud
+ * rate and divisor value to setup the requested qspi clock.
+ *
+ * returns: 0 on success and error value on failure
+ */
+static int xqspips_setup(struct spi_device *qspi)
+{
+
+ if (qspi->mode & SPI_LSB_FIRST)
+ return -EINVAL;
+
+ if (!qspi->max_speed_hz)
+ return -EINVAL;
+
+ if (!qspi->bits_per_word)
+ qspi->bits_per_word = 32;
+
+ return xqspips_setup_transfer(qspi, NULL);
+}
+
+/**
+ * xqspips_fill_tx_fifo - Fills the TX FIFO with as many bytes as possible
+ * @xqspi: Pointer to the xqspips structure
+ */
+static void xqspips_fill_tx_fifo(struct xqspips *xqspi)
+{
+ u32 data = 0;
+
+ while ((!(xqspips_read(xqspi->regs + XQSPIPS_STATUS_OFFSET) &
+ XQSPIPS_IXR_TXFULL_MASK)) && (xqspi->bytes_to_transfer >= 4)) {
+ xqspips_copy_write_data(xqspi, &data, 4);
+ xqspips_write(xqspi->regs + XQSPIPS_TXD_00_00_OFFSET, data);
+ }
+}
+
+/**
+ * xqspips_irq - Interrupt service routine of the QSPI controller
+ * @irq: IRQ number
+ * @dev_id: Pointer to the xqspi structure
+ *
+ * This function handles TX empty 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.
+ *
+ * returns: IRQ_HANDLED always
+ */
+static irqreturn_t xqspips_irq(int irq, void *dev_id)
+{
+ struct xqspips *xqspi = dev_id;
+ u32 intr_status;
+ u8 offset[3] = {XQSPIPS_TXD_00_01_OFFSET, XQSPIPS_TXD_00_10_OFFSET,
+ XQSPIPS_TXD_00_11_OFFSET};
+
+ intr_status = xqspips_read(xqspi->regs + XQSPIPS_STATUS_OFFSET);
+ xqspips_write(xqspi->regs + XQSPIPS_STATUS_OFFSET , intr_status);
+ xqspips_write(xqspi->regs + XQSPIPS_IDIS_OFFSET,
+ XQSPIPS_IXR_ALL_MASK);
+
+ if ((intr_status & XQSPIPS_IXR_TXNFULL_MASK) ||
+ (intr_status & XQSPIPS_IXR_RXNEMTY_MASK)) {
+ /* This bit is set when Tx FIFO has < THRESHOLD entries. We have
+ the THRESHOLD value set to 1, so this bit indicates Tx FIFO
+ is empty */
+ u32 config_reg;
+ u32 data;
+
+ /* Read out the data from the RX FIFO */
+ while (xqspips_read(xqspi->regs + XQSPIPS_STATUS_OFFSET) &
+ XQSPIPS_IXR_RXNEMTY_MASK) {
+
+ data = xqspips_read(xqspi->regs + XQSPIPS_RXD_OFFSET);
+
+ if (xqspi->bytes_to_receive < 4 && !xqspi->is_dual)
+ xqspips_copy_read_data(xqspi, data,
+ xqspi->bytes_to_receive);
+ else
+ xqspips_copy_read_data(xqspi, data, 4);
+ }
+
+ if (xqspi->bytes_to_transfer) {
+ if (xqspi->bytes_to_transfer >= 4) {
+ /* There is more data to send */
+ xqspips_fill_tx_fifo(xqspi);
+ } else {
+ int tmp;
+ tmp = xqspi->bytes_to_transfer;
+ xqspips_copy_write_data(xqspi, &data,
+ xqspi->bytes_to_transfer);
+ if (xqspi->is_dual)
+ xqspips_write(xqspi->regs +
+ XQSPIPS_TXD_00_00_OFFSET, data);
+ else
+ xqspips_write(xqspi->regs +
+ offset[tmp - 1], data);
+ }
+ xqspips_write(xqspi->regs + XQSPIPS_IEN_OFFSET,
+ XQSPIPS_IXR_ALL_MASK);
+
+ spin_lock(&xqspi->config_reg_lock);
+ config_reg = xqspips_read(xqspi->regs +
+ XQSPIPS_CONFIG_OFFSET);
+
+ config_reg |= XQSPIPS_CONFIG_MANSRT_MASK;
+ xqspips_write(xqspi->regs + XQSPIPS_CONFIG_OFFSET,
+ config_reg);
+ spin_unlock(&xqspi->config_reg_lock);
+ } else {
+ /* If transfer and receive is completed then only send
+ * complete signal */
+ if (xqspi->bytes_to_receive) {
+ /* There is still some data to be received.
+ Enable Rx not empty interrupt */
+ xqspips_write(xqspi->regs + XQSPIPS_IEN_OFFSET,
+ XQSPIPS_IXR_RXNEMTY_MASK);
+ } else {
+ xqspips_write(xqspi->regs + XQSPIPS_IDIS_OFFSET,
+ XQSPIPS_IXR_RXNEMTY_MASK);
+ complete(&xqspi->done);
+ }
+ }
+ }
+
+ return IRQ_HANDLED;
+}
+
+/**
+ * xqspips_start_transfer - Initiates the QSPI transfer
+ * @qspi: Pointer to the spi_device structure
+ * @transfer: Pointer to the spi_transfer structure which provide information
+ * about next transfer parameters
+ *
+ * This function fills the TX FIFO, starts the QSPI transfer, and waits for the
+ * transfer to be completed.
+ *
+ * returns: Number of bytes transferred in the last transfer
+ */
+static int xqspips_start_transfer(struct spi_device *qspi,
+ struct spi_transfer *transfer)
+{
+ struct xqspips *xqspi = spi_master_get_devdata(qspi->master);
+ u32 config_reg;
+ unsigned long flags;
+ u32 data = 0;
+ u8 instruction = 0;
+ u8 index;
+ struct xqspips_inst_format *curr_inst;
+
+ xqspi->txbuf = transfer->tx_buf;
+ xqspi->rxbuf = transfer->rx_buf;
+ xqspi->bytes_to_transfer = transfer->len;
+ xqspi->bytes_to_receive = transfer->len;
+
+ if (xqspi->txbuf)
+ instruction = *(u8 *)xqspi->txbuf;
+
+ INIT_COMPLETION(xqspi->done);
+ if (instruction && xqspi->is_inst) {
+ for (index = 0; index < ARRAY_SIZE(flash_inst); index++)
+ if (instruction == flash_inst[index].opcode)
+ break;
+
+ /* Instruction might have already been transmitted. This is a
+ * 'data only' transfer */
+ if (index == ARRAY_SIZE(flash_inst))
+ goto xfer_data;
+
+ curr_inst = &flash_inst[index];
+
+ /* Get the instruction */
+ data = 0;
+ xqspips_copy_write_data(xqspi, &data,
+ curr_inst->inst_size);
+
+ /* Write the instruction to LSB of the FIFO. The core is
+ * designed such that it is not necessary to check whether the
+ * write FIFO is full before writing. However, write would be
+ * delayed if the user tries to write when write FIFO is full
+ */
+ xqspips_write(xqspi->regs + curr_inst->offset, data);
+ goto xfer_start;
+ }
+
+xfer_data:
+ /* In case of Fast, Dual and Quad reads, transmit the instruction first.
+ * Address and dummy byte will be transmitted in interrupt handler,
+ * after instruction is transmitted */
+ if (((xqspi->is_inst == 0) && (xqspi->bytes_to_transfer >= 4)) ||
+ ((xqspi->bytes_to_transfer >= 4) &&
+ (instruction != XQSPIPS_FLASH_OPCODE_FAST_READ) &&
+ (instruction != XQSPIPS_FLASH_OPCODE_DUAL_READ) &&
+ (instruction != XQSPIPS_FLASH_OPCODE_QUAD_READ)))
+ xqspips_fill_tx_fifo(xqspi);
+
+xfer_start:
+ xqspips_write(xqspi->regs + XQSPIPS_IEN_OFFSET,
+ XQSPIPS_IXR_ALL_MASK);
+ /* Start the transfer by enabling manual start bit */
+ spin_lock_irqsave(&xqspi->config_reg_lock, flags);
+ config_reg = xqspips_read(xqspi->regs +
+ XQSPIPS_CONFIG_OFFSET) | XQSPIPS_CONFIG_MANSRT_MASK;
+ xqspips_write(xqspi->regs + XQSPIPS_CONFIG_OFFSET, config_reg);
+ spin_unlock_irqrestore(&xqspi->config_reg_lock, flags);
+
+ wait_for_completion(&xqspi->done);
+
+ return (transfer->len) - (xqspi->bytes_to_transfer);
+}
+
+/**
+ * xqspips_work_queue - Get the request from queue to perform transfers
+ * @work: Pointer to the work_struct structure
+ */
+static void xqspips_work_queue(struct work_struct *work)
+{
+ struct xqspips *xqspi = container_of(work, struct xqspips, work);
+ unsigned long flags;
+#ifdef CONFIG_SPI_XILINX_PS_QSPI_DUAL_STACKED
+ u32 lqspi_cfg_reg;
+#endif
+
+ spin_lock_irqsave(&xqspi->trans_queue_lock, flags);
+ xqspi->dev_busy = 1;
+
+ /* Check if list is empty or queue is stoped */
+ if (list_empty(&xqspi->queue) ||
+ xqspi->queue_state == XQSPIPS_QUEUE_STOPPED) {
+ xqspi->dev_busy = 0;
+ spin_unlock_irqrestore(&xqspi->trans_queue_lock, flags);
+ return;
+ }
+
+ /* Keep requesting transfer till list is empty */
+ while (!list_empty(&xqspi->queue)) {
+ struct spi_message *msg;
+ struct spi_device *qspi;
+ struct spi_transfer *transfer = NULL;
+ unsigned cs_change = 1;
+ int status = 0;
+
+ msg = container_of(xqspi->queue.next, struct spi_message,
+ queue);
+ list_del_init(&msg->queue);
+ spin_unlock_irqrestore(&xqspi->trans_queue_lock, flags);
+ qspi = msg->spi;
+
+#ifdef CONFIG_SPI_XILINX_PS_QSPI_DUAL_STACKED
+ lqspi_cfg_reg = xqspips_read(xqspi->regs +
+ XQSPIPS_LINEAR_CFG_OFFSET);
+ if (qspi->master->flags & SPI_MASTER_U_PAGE)
+ lqspi_cfg_reg |= XQSPIPS_LCFG_U_PAGE_MASK;
+ else
+ lqspi_cfg_reg &= ~XQSPIPS_LCFG_U_PAGE_MASK;
+ xqspips_write(xqspi->regs + XQSPIPS_LINEAR_CFG_OFFSET,
+ lqspi_cfg_reg);
+#endif
+
+ list_for_each_entry(transfer, &msg->transfers, transfer_list) {
+ if (transfer->bits_per_word || transfer->speed_hz) {
+ status = xqspips_setup_transfer(qspi, transfer);
+ if (status < 0)
+ break;
+ }
+
+ /* Select the chip if required */
+ if (cs_change) {
+ xqspips_chipselect(qspi, 1);
+ xqspi->is_inst = 1;
+ }
+
+ cs_change = transfer->cs_change;
+
+ if (!transfer->tx_buf && !transfer->rx_buf &&
+ transfer->len) {
+ status = -EINVAL;
+ break;
+ }
+
+ /* Request the transfer */
+ if (transfer->len) {
+ status = xqspips_start_transfer(qspi, transfer);
+ xqspi->is_inst = 0;
+ }
+
+ if (status != transfer->len) {
+ if (status > 0)
+ status = -EMSGSIZE;
+ break;
+ }
+ msg->actual_length += status;
+ status = 0;
+
+ if (transfer->delay_usecs)
+ udelay(transfer->delay_usecs);
+
+ if (cs_change)
+ /* Deselect the chip */
+ xqspips_chipselect(qspi, 0);
+
+ if (transfer->transfer_list.next == &msg->transfers)
+ break;
+ }
+
+ msg->status = status;
+ msg->complete(msg->context);
+
+ xqspips_setup_transfer(qspi, NULL);
+
+ if (!(status == 0 && cs_change))
+ xqspips_chipselect(qspi, 0);
+
+ spin_lock_irqsave(&xqspi->trans_queue_lock, flags);
+ }
+ xqspi->dev_busy = 0;
+ spin_unlock_irqrestore(&xqspi->trans_queue_lock, flags);
+}
+
+/**
+ * xqspips_transfer - Add a new transfer request at the tail of work queue
+ * @qspi: Pointer to the spi_device structure
+ * @message: Pointer to the spi_transfer structure which provides information
+ * about next transfer parameters
+ *
+ * returns: 0 on success, -EINVAL on invalid input parameter and
+ * -ESHUTDOWN if queue is stopped by module unload function
+ */
+static int xqspips_transfer(struct spi_device *qspi,
+ struct spi_message *message)
+{
+ struct xqspips *xqspi = spi_master_get_devdata(qspi->master);
+ struct spi_transfer *transfer;
+ unsigned long flags;
+
+ if (xqspi->queue_state == XQSPIPS_QUEUE_STOPPED)
+ return -ESHUTDOWN;
+
+ message->actual_length = 0;
+ message->status = -EINPROGRESS;
+
+ /* Check each transfer's parameters */
+ list_for_each_entry(transfer, &message->transfers, transfer_list) {
+ if (!transfer->tx_buf && !transfer->rx_buf && transfer->len)
+ return -EINVAL;
+ /* QSPI controller supports only 32 bit transfers whereas higher
+ * layer drivers request 8 bit transfers. Re-visit at a later
+ * time */
+ /* if (bits_per_word != 32)
+ return -EINVAL; */
+ }
+
+ spin_lock_irqsave(&xqspi->trans_queue_lock, flags);
+ list_add_tail(&message->queue, &xqspi->queue);
+ if (!xqspi->dev_busy)
+ queue_work(xqspi->workqueue, &xqspi->work);
+ spin_unlock_irqrestore(&xqspi->trans_queue_lock, flags);
+
+ return 0;
+}
+
+/**
+ * xqspips_start_queue - Starts the queue of the QSPI driver
+ * @xqspi: Pointer to the xqspips structure
+ *
+ * returns: 0 on success and -EBUSY if queue is already running or device is
+ * busy
+ */
+static inline int xqspips_start_queue(struct xqspips *xqspi)
+{
+ unsigned long flags;
+
+ spin_lock_irqsave(&xqspi->trans_queue_lock, flags);
+
+ if (xqspi->queue_state == XQSPIPS_QUEUE_RUNNING || xqspi->dev_busy) {
+ spin_unlock_irqrestore(&xqspi->trans_queue_lock, flags);
+ return -EBUSY;
+ }
+
+ xqspi->queue_state = XQSPIPS_QUEUE_RUNNING;
+ spin_unlock_irqrestore(&xqspi->trans_queue_lock, flags);
+
+ return 0;
+}
+
+/**
+ * xqspips_stop_queue - Stops the queue of the QSPI driver
+ * @xqspi: Pointer to the xqspips structure
+ *
+ * This function waits till queue is empty and then stops the queue.
+ * Maximum time out is set to 5 seconds.
+ *
+ * returns: 0 on success and -EBUSY if queue is not empty or device is busy
+ */
+static inline int xqspips_stop_queue(struct xqspips *xqspi)
+{
+ unsigned long flags;
+ unsigned limit = 500;
+ int ret = 0;
+
+ if (xqspi->queue_state != XQSPIPS_QUEUE_RUNNING)
+ return ret;
+
+ spin_lock_irqsave(&xqspi->trans_queue_lock, flags);
+
+ while ((!list_empty(&xqspi->queue) || xqspi->dev_busy) && limit--) {
+ spin_unlock_irqrestore(&xqspi->trans_queue_lock, flags);
+ msleep(10);
+ spin_lock_irqsave(&xqspi->trans_queue_lock, flags);
+ }
+
+ if (!list_empty(&xqspi->queue) || xqspi->dev_busy)
+ ret = -EBUSY;
+
+ if (ret == 0)
+ xqspi->queue_state = XQSPIPS_QUEUE_STOPPED;
+
+ spin_unlock_irqrestore(&xqspi->trans_queue_lock, flags);
+
+ return ret;
+}
+
+/**
+ * xqspips_destroy_queue - Destroys the queue of the QSPI driver
+ * @xqspi: Pointer to the xqspips structure
+ *
+ * returns: 0 on success and error value on failure
+ */
+static inline int xqspips_destroy_queue(struct xqspips *xqspi)
+{
+ int ret;
+
+ ret = xqspips_stop_queue(xqspi);
+ if (ret != 0)
+ return ret;
+
+ destroy_workqueue(xqspi->workqueue);
+
+ return 0;
+}
+
+static int xqspips_clk_notifier_cb(struct notifier_block *nb,
+ unsigned long event, void *data)
+{
+ switch (event) {
+ case PRE_RATE_CHANGE:
+ /* if a rate change is announced we need to check whether we can
+ * maintain the current frequency by changing the clock
+ * dividers. And we may have to suspend operation and return
+ * after the rate change or its abort
+ */
+ return NOTIFY_OK;
+ case POST_RATE_CHANGE:
+ return NOTIFY_OK;
+ case ABORT_RATE_CHANGE:
+ default:
+ return NOTIFY_DONE;
+ }
+}
+
+#ifdef CONFIG_PM_SLEEP
+/**
+ * xqspips_suspend - Suspend method for the QSPI driver
+ * @_dev: Address of the platform_device structure
+ *
+ * This function stops the QSPI driver queue and disables the QSPI controller
+ *
+ * returns: 0 on success and error value on error
+ */
+static int xqspips_suspend(struct device *_dev)
+{
+ struct platform_device *pdev = container_of(_dev,
+ struct platform_device, dev);
+ struct spi_master *master = platform_get_drvdata(pdev);
+ struct xqspips *xqspi = spi_master_get_devdata(master);
+ int ret = 0;
+
+ ret = xqspips_stop_queue(xqspi);
+ if (ret != 0)
+ return ret;
+
+ xqspips_write(xqspi->regs + XQSPIPS_ENABLE_OFFSET,
+ ~XQSPIPS_ENABLE_ENABLE_MASK);
+
+ clk_disable(xqspi->devclk);
+ clk_disable(xqspi->aperclk);
+
+ dev_dbg(&pdev->dev, "suspend succeeded\n");
+ return 0;
+}
+
+/**
+ * xqspips_resume - Resume method for the QSPI driver
+ * @dev: Address of the platform_device structure
+ *
+ * The function starts the QSPI driver queue and initializes the QSPI controller
+ *
+ * returns: 0 on success and error value on error
+ */
+static int xqspips_resume(struct device *dev)
+{
+ struct platform_device *pdev = container_of(dev,
+ struct platform_device, dev);
+ struct spi_master *master = platform_get_drvdata(pdev);
+ struct xqspips *xqspi = spi_master_get_devdata(master);
+ int ret = 0;
+
+ ret = clk_enable(xqspi->aperclk);
+ if (ret) {
+ dev_err(dev, "Cannot enable APER clock.\n");
+ return ret;
+ }
+
+ ret = clk_enable(xqspi->devclk);
+ if (ret) {
+ dev_err(dev, "Cannot enable device clock.\n");
+ clk_disable(xqspi->aperclk);
+ return ret;
+ }
+
+ xqspips_init_hw(xqspi->regs, xqspi->is_dual);
+
+ ret = xqspips_start_queue(xqspi);
+ if (ret != 0) {
+ dev_err(&pdev->dev, "problem starting queue (%d)\n", ret);
+ return ret;
+ }
+
+ dev_dbg(&pdev->dev, "resume succeeded\n");
+ return 0;
+}
+#endif /* ! CONFIG_PM_SLEEP */
+
+static SIMPLE_DEV_PM_OPS(xqspips_dev_pm_ops, xqspips_suspend, xqspips_resume);
+
+/**
+ * xqspips_probe - Probe method for the QSPI driver
+ * @pdev: Pointer to the platform_device structure
+ *
+ * This function initializes the driver data structures and the hardware.
+ *
+ * returns: 0 on success and error value on failure
+ */
+static int xqspips_probe(struct platform_device *pdev)
+{
+ int ret = 0;
+ struct spi_master *master;
+ struct xqspips *xqspi;
+ struct resource *res;
+
+ master = spi_alloc_master(&pdev->dev, sizeof(*xqspi));
+ if (master == NULL)
+ return -ENOMEM;
+
+ xqspi = 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);
+ xqspi->regs = devm_ioremap_resource(&pdev->dev, res);
+ if (IS_ERR(xqspi->regs)) {
+ ret = PTR_ERR(xqspi->regs);
+ dev_err(&pdev->dev, "ioremap failed\n");
+ goto remove_master;
+ }
+
+ xqspi->irq = platform_get_irq(pdev, 0);
+ if (xqspi->irq < 0) {
+ ret = -ENXIO;
+ dev_err(&pdev->dev, "irq resource not found\n");
+ goto remove_master;
+ }
+ ret = devm_request_irq(&pdev->dev, xqspi->irq, xqspips_irq,
+ 0, pdev->name, xqspi);
+ if (ret != 0) {
+ ret = -ENXIO;
+ dev_err(&pdev->dev, "request_irq failed\n");
+ goto remove_master;
+ }
+
+ if (of_property_read_u32(pdev->dev.of_node, "is-dual", &xqspi->is_dual))
+ dev_warn(&pdev->dev, "couldn't determine configuration info "
+ "about dual memories. defaulting to single memory\n");
+
+ xqspi->aperclk = clk_get(&pdev->dev, "aper_clk");
+ if (IS_ERR(xqspi->aperclk)) {
+ dev_err(&pdev->dev, "aper_clk clock not found.\n");
+ ret = PTR_ERR(xqspi->aperclk);
+ goto remove_master;
+ }
+
+ xqspi->devclk = clk_get(&pdev->dev, "ref_clk");
+ if (IS_ERR(xqspi->devclk)) {
+ dev_err(&pdev->dev, "ref_clk clock not found.\n");
+ ret = PTR_ERR(xqspi->devclk);
+ goto clk_put_aper;
+ }
+
+ ret = clk_prepare_enable(xqspi->aperclk);
+ if (ret) {
+ dev_err(&pdev->dev, "Unable to enable APER clock.\n");
+ goto clk_put;
+ }
+
+ ret = clk_prepare_enable(xqspi->devclk);
+ if (ret) {
+ dev_err(&pdev->dev, "Unable to enable device clock.\n");
+ goto clk_dis_aper;
+ }
+
+ xqspi->clk_rate_change_nb.notifier_call = xqspips_clk_notifier_cb;
+ xqspi->clk_rate_change_nb.next = NULL;
+ if (clk_notifier_register(xqspi->devclk, &xqspi->clk_rate_change_nb))
+ dev_warn(&pdev->dev, "Unable to register clock notifier.\n");
+
+
+ /* QSPI controller initializations */
+ xqspips_init_hw(xqspi->regs, xqspi->is_dual);
+
+ init_completion(&xqspi->done);
+
+ ret = of_property_read_u32(pdev->dev.of_node, "num-chip-select",
+ (u32 *)&master->num_chipselect);
+ if (ret < 0) {
+ dev_err(&pdev->dev, "couldn't determine num-chip-select\n");
+ goto clk_unreg_notif;
+ }
+
+ master->setup = xqspips_setup;
+ master->transfer = xqspips_transfer;
+ master->flags = SPI_MASTER_QUAD_MODE;
+
+ xqspi->speed_hz = clk_get_rate(xqspi->devclk) / 2;
+
+ xqspi->dev_busy = 0;
+
+ INIT_LIST_HEAD(&xqspi->queue);
+ spin_lock_init(&xqspi->trans_queue_lock);
+ spin_lock_init(&xqspi->config_reg_lock);
+
+ xqspi->queue_state = XQSPIPS_QUEUE_STOPPED;
+ xqspi->dev_busy = 0;
+
+ INIT_WORK(&xqspi->work, xqspips_work_queue);
+ xqspi->workqueue =
+ create_singlethread_workqueue(dev_name(&pdev->dev));
+ if (!xqspi->workqueue) {
+ ret = -ENOMEM;
+ dev_err(&pdev->dev, "problem initializing queue\n");
+ goto clk_unreg_notif;
+ }
+
+ ret = xqspips_start_queue(xqspi);
+ if (ret != 0) {
+ dev_err(&pdev->dev, "problem starting queue\n");
+ goto remove_queue;
+ }
+
+ ret = spi_register_master(master);
+ if (ret) {
+ dev_err(&pdev->dev, "spi_register_master failed\n");
+ goto remove_queue;
+ }
+
+ dev_info(&pdev->dev, "at 0x%08X mapped to 0x%08X, irq=%d\n", res->start,
+ (u32 __force)xqspi->regs, xqspi->irq);
+
+ return ret;
+
+remove_queue:
+ (void)xqspips_destroy_queue(xqspi);
+clk_unreg_notif:
+ clk_notifier_unregister(xqspi->devclk, &xqspi->clk_rate_change_nb);
+ clk_disable_unprepare(xqspi->devclk);
+clk_dis_aper:
+ clk_disable_unprepare(xqspi->aperclk);
+clk_put:
+ clk_put(xqspi->devclk);
+clk_put_aper:
+ clk_put(xqspi->aperclk);
+remove_master:
+ spi_master_put(master);
+ return ret;
+}
+
+/**
+ * xqspips_remove - Remove method for the QSPI 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.
+ *
+ * returns: 0 on success and error value on failure
+ */
+static int xqspips_remove(struct platform_device *pdev)
+{
+ struct spi_master *master = platform_get_drvdata(pdev);
+ struct xqspips *xqspi = spi_master_get_devdata(master);
+ int ret = 0;
+
+ ret = xqspips_destroy_queue(xqspi);
+ if (ret != 0)
+ return ret;
+
+ xqspips_write(xqspi->regs + XQSPIPS_ENABLE_OFFSET,
+ ~XQSPIPS_ENABLE_ENABLE_MASK);
+
+ clk_notifier_unregister(xqspi->devclk, &xqspi->clk_rate_change_nb);
+ clk_disable_unprepare(xqspi->devclk);
+ clk_disable_unprepare(xqspi->aperclk);
+ clk_put(xqspi->devclk);
+ clk_put(xqspi->aperclk);
+
+
+ spi_unregister_master(master);
+ spi_master_put(master);
+
+
+ dev_dbg(&pdev->dev, "remove succeeded\n");
+ return 0;
+}
+
+/* Work with hotplug and coldplug */
+MODULE_ALIAS("platform:" DRIVER_NAME);
+
+static struct of_device_id xqspips_of_match[] = {
+ { .compatible = "xlnx,ps7-qspi-1.00.a", },
+ { /* end of table */}
+};
+MODULE_DEVICE_TABLE(of, xqspips_of_match);
+
+/*
+ * xqspips_driver - This structure defines the QSPI platform driver
+ */
+static struct platform_driver xqspips_driver = {
+ .probe = xqspips_probe,
+ .remove = xqspips_remove,
+ .driver = {
+ .name = DRIVER_NAME,
+ .owner = THIS_MODULE,
+ .of_match_table = xqspips_of_match,
+ .pm = &xqspips_dev_pm_ops,
+ },
+};
+
+module_platform_driver(xqspips_driver);
+
+MODULE_AUTHOR("Xilinx, Inc.");
+MODULE_DESCRIPTION("Xilinx PS QSPI driver");
+MODULE_LICENSE("GPL");
--- a/drivers/spi/spi-xilinx.c
+++ b/drivers/spi/spi-xilinx.c
@@ -82,7 +82,7 @@ struct xilinx_spi {
struct completion done;
void __iomem *regs; /* virt. address of the control registers */
- int irq;
+ int irq;
u8 *rx_ptr; /* pointer in the Tx buffer */
const u8 *tx_ptr; /* pointer in the Rx buffer */
@@ -232,6 +232,21 @@ static int xilinx_spi_setup_transfer(str
return 0;
}
+static int xilinx_spi_setup(struct spi_device *spi)
+{
+ /* always return 0, we can not check the number of bits.
+ * There are cases when SPI setup is called before any driver is
+ * there, in that case the SPI core defaults to 8 bits, which we
+ * do not support in some cases. But if we return an error, the
+ * SPI device would not be registered and no driver can get hold of it
+ * When the driver is there, it will call SPI setup again with the
+ * correct number of bits per transfer.
+ * If a driver setups with the wrong bit number, it will fail when
+ * it tries to do a transfer
+ */
+ return 0;
+}
+
static void xilinx_spi_fill_tx_fifo(struct xilinx_spi *xspi)
{
u8 sr;
@@ -300,7 +315,7 @@ static int xilinx_spi_txrx_bufs(struct s
}
/* See if there is more data to send */
- if (xspi->remaining_bytes <= 0)
+ if (!xspi->remaining_bytes > 0)
break;
}
@@ -349,7 +364,7 @@ static int xilinx_spi_probe(struct platf
u32 tmp;
u8 i;
- pdata = dev_get_platdata(&pdev->dev);
+ pdata = pdev->dev.platform_data;
if (pdata) {
num_cs = pdata->num_chipselect;
bits_per_word = pdata->bits_per_word;
@@ -368,14 +383,18 @@ static int xilinx_spi_probe(struct platf
if (!master)
return -ENODEV;
+ /* clear the dma_mask, to try to disable use of dma */
+ master->dev.dma_mask = 0;
+
/* the spi->mode bits understood by this driver: */
master->mode_bits = SPI_CPOL | SPI_CPHA;
xspi = spi_master_get_devdata(master);
- xspi->bitbang.master = master;
+ xspi->bitbang.master = spi_master_get(master);
xspi->bitbang.chipselect = xilinx_spi_chipselect;
xspi->bitbang.setup_transfer = xilinx_spi_setup_transfer;
xspi->bitbang.txrx_bufs = xilinx_spi_txrx_bufs;
+ xspi->bitbang.master->setup = xilinx_spi_setup;
init_completion(&xspi->done);
res = platform_get_resource(pdev, IORESOURCE_MEM, 0);
--- a/include/linux/spi/spi.h
+++ b/include/linux/spi/spi.h
@@ -314,6 +314,8 @@ struct spi_master {
#define SPI_MASTER_HALF_DUPLEX BIT(0) /* can't do full duplex */
#define SPI_MASTER_NO_RX BIT(1) /* can't do buffer read */
#define SPI_MASTER_NO_TX BIT(2) /* can't do buffer write */
+#define SPI_MASTER_U_PAGE BIT(3) /* select upper flash */
+#define SPI_MASTER_QUAD_MODE BIT(4) /* support quad mode */
/* lock and mutex for SPI bus locking */
spinlock_t bus_lock_spinlock;