2013-07-08 13:43:20

by Sourav Poddar

[permalink] [raw]
Subject: [PATCH 0/3] spi changes and ti quad spi controller.

Add support for calculating message length in spi framework.

Add support for quad spi controller.

Patch 2 of this series had been posted before. Sending along
with the series along with ather propsed change.

Sourav Poddar (3):
driver: spi: Modify core to compute the message length
drivers: spi: Add qspi flash controller
driver: spi: Add quad spi read support

Documentation/devicetree/bindings/spi/ti_qspi.txt | 22 +
drivers/spi/Kconfig | 8 +
drivers/spi/Makefile | 1 +
drivers/spi/spi-ti-qspi.c | 489 +++++++++++++++++++++
drivers/spi/spi.c | 1 +
include/linux/spi/spi.h | 1 +
6 files changed, 522 insertions(+), 0 deletions(-)
create mode 100644 Documentation/devicetree/bindings/spi/ti_qspi.txt
create mode 100644 drivers/spi/spi-ti-qspi.c


2013-07-08 13:43:48

by Sourav Poddar

[permalink] [raw]
Subject: [RFC/PATCH 1/3] driver: spi: Modify core to compute the message length

Make spi core calculate the message length while
populating the other transfer parameters. This will
be useful in cases where controller driver need to configure its
framelength field without iterating through the linklist again in the
driver controller.

Signed-off-by: Sourav Poddar <[email protected]>
---
drivers/spi/spi.c | 1 +
include/linux/spi/spi.h | 1 +
2 files changed, 2 insertions(+), 0 deletions(-)

diff --git a/drivers/spi/spi.c b/drivers/spi/spi.c
index 32b7bb1..6a05b3c 100644
--- a/drivers/spi/spi.c
+++ b/drivers/spi/spi.c
@@ -1375,6 +1375,7 @@ static int __spi_async(struct spi_device *spi, struct spi_message *message)
* it is not set for this transfer.
*/
list_for_each_entry(xfer, &message->transfers, transfer_list) {
+ message->frame_length += xfer->len;
if (!xfer->bits_per_word)
xfer->bits_per_word = spi->bits_per_word;
if (!xfer->speed_hz)
diff --git a/include/linux/spi/spi.h b/include/linux/spi/spi.h
index 6ff26c8..d83841e 100644
--- a/include/linux/spi/spi.h
+++ b/include/linux/spi/spi.h
@@ -575,6 +575,7 @@ struct spi_message {
/* completion is reported through a callback */
void (*complete)(void *context);
void *context;
+ unsigned frame_length;
unsigned actual_length;
int status;

--
1.7.1

2013-07-08 13:43:59

by Sourav Poddar

[permalink] [raw]
Subject: [PATCHv3 2/3] drivers: spi: Add qspi flash controller

The patch add basic support for the quad spi controller.

QSPI is a kind of spi module that allows single,
dual and quad read access to external spi devices. The module
has a memory mapped interface which provide direct interface
for accessing data form external spi devices.

The patch will configure controller clocks, device control
register and for defining low level transfer apis which
will be used by the spi framework to transfer data to
the slave spi device(flash in this case).

Signed-off-by: Sourav Poddar <[email protected]>
---
v2->v3
1. Add threaded irq support
2. made the driver more generic in terms of chip select, bits_per_word etc.
3. Made it more modular by sepoerating tx/rx function.
Documentation/devicetree/bindings/spi/ti_qspi.txt | 22 +
drivers/spi/Kconfig | 8 +
drivers/spi/Makefile | 1 +
drivers/spi/spi-ti-qspi.c | 485 +++++++++++++++++++++
4 files changed, 516 insertions(+), 0 deletions(-)
create mode 100644 Documentation/devicetree/bindings/spi/ti_qspi.txt
create mode 100644 drivers/spi/spi-ti-qspi.c

diff --git a/Documentation/devicetree/bindings/spi/ti_qspi.txt b/Documentation/devicetree/bindings/spi/ti_qspi.txt
new file mode 100644
index 0000000..398ef59
--- /dev/null
+++ b/Documentation/devicetree/bindings/spi/ti_qspi.txt
@@ -0,0 +1,22 @@
+TI QSPI controller.
+
+Required properties:
+- compatible : should be "ti,dra7xxx-qspi".
+- reg: Should contain QSPI registers location and length.
+- #address-cells, #size-cells : Must be present if the device has sub-nodes
+- ti,hwmods: Name of the hwmod associated to the QSPI
+
+Recommended properties:
+- spi-max-frequency: Definition as per
+ Documentation/devicetree/bindings/spi/spi-bus.txt
+
+Example:
+
+qspi: qspi@4b300000 {
+ compatible = "ti,dra7xxx-qspi";
+ reg = <0x4b300000 0x100>;
+ #address-cells = <1>;
+ #size-cells = <0>;
+ spi-max-frequency = <25000000>;
+ ti,hwmods = "qspi";
+};
diff --git a/drivers/spi/Kconfig b/drivers/spi/Kconfig
index 92a9345..e594fdb 100644
--- a/drivers/spi/Kconfig
+++ b/drivers/spi/Kconfig
@@ -285,6 +285,14 @@ config SPI_OMAP24XX
SPI master controller for OMAP24XX and later Multichannel SPI
(McSPI) modules.

+config QSPI_DRA7xxx
+ tristate "DRA7xxx QSPI controller support"
+ depends on ARCH_OMAP2PLUS || COMPILE_TEST
+ help
+ QSPI master controller for DRA7xxx used for flash devices.
+ This device supports single, dual and quad read support, while
+ it only supports single write mode.
+
config SPI_OMAP_100K
tristate "OMAP SPI 100K"
depends on ARCH_OMAP850 || ARCH_OMAP730
diff --git a/drivers/spi/Makefile b/drivers/spi/Makefile
index 33f9c09..b3b4857 100644
--- a/drivers/spi/Makefile
+++ b/drivers/spi/Makefile
@@ -46,6 +46,7 @@ obj-$(CONFIG_SPI_OCTEON) += spi-octeon.o
obj-$(CONFIG_SPI_OMAP_UWIRE) += spi-omap-uwire.o
obj-$(CONFIG_SPI_OMAP_100K) += spi-omap-100k.o
obj-$(CONFIG_SPI_OMAP24XX) += spi-omap2-mcspi.o
+obj-$(CONFIG_QSPI_DRA7xxx) += spi-ti-qspi.o
obj-$(CONFIG_SPI_ORION) += spi-orion.o
obj-$(CONFIG_SPI_PL022) += spi-pl022.o
obj-$(CONFIG_SPI_PPC4xx) += spi-ppc4xx.o
diff --git a/drivers/spi/spi-ti-qspi.c b/drivers/spi/spi-ti-qspi.c
new file mode 100644
index 0000000..430de9c
--- /dev/null
+++ b/drivers/spi/spi-ti-qspi.c
@@ -0,0 +1,485 @@
+/*
+ * TI QSPI driver
+ *
+ * Copyright (C) 2013 Texas Instruments Incorporated - http://www.ti.com
+ * Author: Sourav Poddar <[email protected]>
+ *
+ * This program is free software; you can redistribute it and/or
+ * modify it under the terms of the GPLv2.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR /PURPOSE. See the
+ * GNU General Public License for more details.
+ */
+
+#include <linux/kernel.h>
+#include <linux/init.h>
+#include <linux/interrupt.h>
+#include <linux/module.h>
+#include <linux/device.h>
+#include <linux/delay.h>
+#include <linux/dma-mapping.h>
+#include <linux/dmaengine.h>
+#include <linux/omap-dma.h>
+#include <linux/platform_device.h>
+#include <linux/err.h>
+#include <linux/clk.h>
+#include <linux/io.h>
+#include <linux/slab.h>
+#include <linux/pm_runtime.h>
+#include <linux/of.h>
+#include <linux/of_device.h>
+#include <linux/pinctrl/consumer.h>
+
+#include <linux/spi/spi.h>
+
+struct dra7xxx_qspi {
+ spinlock_t lock; /* IRQ synchronization */
+ struct spi_master *master;
+ void __iomem *base;
+ struct device *dev;
+ struct completion word_complete;
+ struct clk *fclk;
+ int device_type;
+ u32 spi_max_frequency;
+ u32 cmd;
+ u32 dc;
+};
+
+#define QSPI_PID (0x0)
+#define QSPI_SYSCONFIG (0x10)
+#define QSPI_INTR_STATUS_RAW_SET (0x20)
+#define QSPI_INTR_STATUS_ENABLED_CLEAR (0x24)
+#define QSPI_INTR_ENABLE_SET_REG (0x28)
+#define QSPI_INTR_ENABLE_CLEAR_REG (0x2c)
+#define QSPI_SPI_CLOCK_CNTRL_REG (0x40)
+#define QSPI_SPI_DC_REG (0x44)
+#define QSPI_SPI_CMD_REG (0x48)
+#define QSPI_SPI_STATUS_REG (0x4c)
+#define QSPI_SPI_DATA_REG (0x50)
+#define QSPI_SPI_SETUP0_REG (0x54)
+#define QSPI_SPI_SWITCH_REG (0x64)
+#define QSPI_SPI_SETUP1_REG (0x58)
+#define QSPI_SPI_SETUP2_REG (0x5c)
+#define QSPI_SPI_SETUP3_REG (0x60)
+#define QSPI_SPI_DATA_REG_1 (0x68)
+#define QSPI_SPI_DATA_REG_2 (0x6c)
+#define QSPI_SPI_DATA_REG_3 (0x70)
+
+#define QSPI_TIMEOUT 2000000
+
+#define QSPI_FCLK 192000000
+
+/* Clock Control */
+#define QSPI_CLK_EN (1 << 31)
+#define QSPI_CLK_DIV_MAX 0xffff
+
+/* Command */
+#define QSPI_EN_CS(n) (n << 28)
+#define QSPI_WLEN(n) ((n-1) << 19)
+#define QSPI_3_PIN (1 << 18)
+#define QSPI_RD_SNGL (1 << 16)
+#define QSPI_WR_SNGL (2 << 16)
+#define QSPI_RD_QUAD (7 << 16)
+#define QSPI_INVAL (4 << 16)
+#define QSPI_WC_CMD_INT_EN (1 << 14)
+#define QSPI_FLEN(n) ((n-1) << 0)
+
+/* INTERRUPT REGISTER */
+#define QSPI_WC_INT_EN (1 << 1)
+#define QSPI_WC_INT_DISABLE (1 << 1)
+
+/* Device Control */
+#define QSPI_DD(m, n) (m << (3 + n*8))
+#define QSPI_CKPHA(n) (1 << (2 + n*8))
+#define QSPI_CSPOL(n) (1 << (1 + n*8))
+#define QSPI_CKPOL(n) (1 << (n*8))
+
+/* Status */
+#define QSPI_WC (1 << 1)
+#define QSPI_BUSY (1 << 0)
+#define QSPI_WC_BUSY (QSPI_WC | QSPI_BUSY)
+#define QSPI_XFER_DONE QSPI_WC
+
+#define QSPI_FRAME_MAX 0xfff
+
+#define SPI_AUTOSUSPEND_TIMEOUT 2000
+
+static inline unsigned long dra7xxx_readl(struct dra7xxx_qspi *qspi,
+ unsigned long reg)
+{
+ return readl(qspi->base + reg);
+}
+
+static inline void dra7xxx_writel(struct dra7xxx_qspi *qspi,
+ unsigned long val, unsigned long reg)
+{
+ writel(val, qspi->base + reg);
+}
+
+static inline unsigned long dra7xxx_readl_data(struct dra7xxx_qspi *qspi,
+ unsigned long reg, int wlen)
+{
+ switch (wlen) {
+ case 8:
+ return readw(qspi->base + reg);
+ break;
+ case 16:
+ return readb(qspi->base + reg);
+ break;
+ case 32:
+ return readl(qspi->base + reg);
+ break;
+ default:
+ return -1;
+ }
+}
+
+static inline void dra7xxx_writel_data(struct dra7xxx_qspi *qspi,
+ unsigned long val, unsigned long reg, int wlen)
+{
+ switch (wlen) {
+ case 8:
+ writew(val, qspi->base + reg);
+ break;
+ case 16:
+ writeb(val, qspi->base + reg);
+ break;
+ case 32:
+ writeb(val, qspi->base + reg);
+ break;
+ default:
+ dev_dbg(qspi->dev, "word lenght out of range");
+ break;
+ }
+}
+
+static int dra7xxx_qspi_setup(struct spi_device *spi)
+{
+ struct dra7xxx_qspi *qspi = spi_master_get_devdata(spi->master);
+ int clk_div = 0;
+ u32 clk_ctrl_reg, clk_rate;
+
+ clk_rate = clk_get_rate(qspi->fclk);
+
+ if (!qspi->spi_max_frequency) {
+ dev_err(qspi->dev, "spi max frequency not defined\n");
+ return -1;
+ } else
+ clk_div = (clk_rate / qspi->spi_max_frequency) - 1;
+
+ dev_dbg(qspi->dev, "%s: hz: %d, clock divider %d\n", __func__,
+ qspi->spi_max_frequency, clk_div);
+
+ pm_runtime_get_sync(qspi->dev);
+
+ clk_ctrl_reg = dra7xxx_readl(qspi, QSPI_SPI_CLOCK_CNTRL_REG);
+
+ clk_ctrl_reg &= ~QSPI_CLK_EN;
+
+ /* disable SCLK */
+ dra7xxx_writel(qspi, clk_ctrl_reg, QSPI_SPI_CLOCK_CNTRL_REG);
+
+ if (clk_div < 0) {
+ dev_dbg(qspi->dev, "%s: clock divider < 0, using /1 divider\n",
+ __func__);
+ clk_div = 1;
+ }
+
+ if (clk_div > QSPI_CLK_DIV_MAX) {
+ dev_dbg(qspi->dev, "%s: clock divider >%d , using /%d divider\n",
+ __func__, QSPI_CLK_DIV_MAX, QSPI_CLK_DIV_MAX + 1);
+ clk_div = QSPI_CLK_DIV_MAX;
+ }
+
+ /* enable SCLK */
+ dra7xxx_writel(qspi, QSPI_CLK_EN | clk_div, QSPI_SPI_CLOCK_CNTRL_REG);
+
+ pm_runtime_mark_last_busy(qspi->dev);
+ pm_runtime_put_autosuspend(qspi->dev);
+
+ return 0;
+}
+
+static int dra7xxx_qspi_prepare_xfer(struct spi_master *master)
+{
+ struct dra7xxx_qspi *qspi = spi_master_get_devdata(master);
+
+ pm_runtime_get_sync(qspi->dev);
+
+ return 0;
+}
+
+static int dra7xxx_qspi_unprepare_xfer(struct spi_master *master)
+{
+ struct dra7xxx_qspi *qspi = spi_master_get_devdata(master);
+
+ pm_runtime_mark_last_busy(qspi->dev);
+ pm_runtime_put_autosuspend(qspi->dev);
+
+ return 0;
+}
+
+static int qspi_write_msg(struct dra7xxx_qspi *qspi, struct spi_transfer *t)
+{
+ const u8 *txbuf;
+ int wlen, count;
+
+ count = t->len;
+ txbuf = t->tx_buf;
+ wlen = t->bits_per_word;
+
+ while (count--) {
+ dev_dbg(qspi->dev, "tx cmd %08x dc %08x data %02x\n",
+ qspi->cmd | QSPI_WR_SNGL, qspi->dc, *txbuf);
+ dra7xxx_writel(qspi, QSPI_WC_INT_EN, QSPI_INTR_ENABLE_SET_REG);
+ dra7xxx_writel_data(qspi, *txbuf++, QSPI_SPI_DATA_REG, wlen);
+ dra7xxx_writel(qspi, qspi->dc, QSPI_SPI_DC_REG);
+ dra7xxx_writel(qspi, qspi->cmd | QSPI_WR_SNGL,
+ QSPI_SPI_CMD_REG);
+ wait_for_completion(&qspi->word_complete);
+ }
+
+ return 0;
+}
+
+static int qspi_read_msg(struct dra7xxx_qspi *qspi, struct spi_transfer *t)
+{
+ u8 *rxbuf;
+ int wlen, count;
+
+ count = t->len;
+ rxbuf = t->rx_buf;
+ wlen = t->bits_per_word;
+
+ while (count--) {
+ dev_dbg(qspi->dev, "rx cmd %08x dc %08x\n",
+ qspi->cmd | QSPI_RD_SNGL, qspi->dc);
+ dra7xxx_writel(qspi, QSPI_WC_INT_EN, QSPI_INTR_ENABLE_SET_REG);
+ dra7xxx_writel(qspi, qspi->dc, QSPI_SPI_DC_REG);
+ dra7xxx_writel(qspi, qspi->cmd | QSPI_RD_SNGL,
+ QSPI_SPI_CMD_REG);
+ wait_for_completion(&qspi->word_complete);
+ *rxbuf++ = dra7xxx_readl_data(qspi, QSPI_SPI_DATA_REG, wlen);
+ dev_dbg(qspi->dev, "rx done, read %02x\n", *(rxbuf-1));
+ }
+
+ return 0;
+}
+
+static int qspi_transfer_msg(struct dra7xxx_qspi *qspi, struct spi_transfer *t)
+{
+ if (t->tx_buf)
+ qspi_write_msg(qspi, t);
+ if (t->rx_buf)
+ qspi_read_msg(qspi, t);
+
+ return 0;
+}
+
+static int dra7xxx_qspi_start_transfer_one(struct spi_master *master,
+ struct spi_message *m)
+{
+ struct dra7xxx_qspi *qspi = spi_master_get_devdata(master);
+ struct spi_device *spi = m->spi;
+ struct spi_transfer *t;
+ int status = 0;
+ int frame_length;
+
+ /* setup device control reg */
+ qspi->dc = 0;
+
+ if (spi->mode & SPI_CPHA)
+ qspi->dc |= QSPI_CKPHA(spi->chip_select);
+ if (spi->mode & SPI_CPOL)
+ qspi->dc |= QSPI_CKPOL(spi->chip_select);
+ if (spi->mode & SPI_CS_HIGH)
+ qspi->dc |= QSPI_CSPOL(spi->chip_select);
+
+ frame_length = DIV_ROUND_UP(m->frame_length * spi->bits_per_word,
+ spi->bits_per_word);
+
+ frame_length = clamp(frame_length, 0, QSPI_FRAME_MAX);
+
+ /* setup command reg */
+ qspi->cmd = 0;
+ qspi->cmd |= QSPI_EN_CS(spi->chip_select);
+ qspi->cmd |= QSPI_FLEN(frame_length);
+
+ list_for_each_entry(t, &m->transfers, transfer_list) {
+ qspi->cmd |= QSPI_WLEN(t->bits_per_word);
+ qspi->cmd |= QSPI_WC_CMD_INT_EN;
+
+ qspi_transfer_msg(qspi, t);
+
+ m->actual_length += t->len;
+
+ if (list_is_last(&t->transfer_list, &m->transfers))
+ goto out;
+ }
+
+out:
+ m->status = status;
+ spi_finalize_current_message(master);
+
+ dra7xxx_writel(qspi, qspi->cmd | QSPI_INVAL, QSPI_SPI_CMD_REG);
+
+ return status;
+}
+
+static irqreturn_t dra7xxx_qspi_isr(int irq, void *dev_id)
+{
+ struct dra7xxx_qspi *qspi = dev_id;
+ u16 mask, stat;
+
+ irqreturn_t ret = IRQ_HANDLED;
+
+ spin_lock(&qspi->lock);
+
+ stat = dra7xxx_readl(qspi, QSPI_SPI_STATUS_REG);
+ mask = dra7xxx_readl(qspi, QSPI_SPI_CMD_REG);
+
+ if ((stat & QSPI_WC) && (mask & QSPI_WC_CMD_INT_EN))
+ ret = IRQ_WAKE_THREAD;
+
+ spin_unlock(&qspi->lock);
+
+ return ret;
+}
+
+static irqreturn_t dra7xxx_qspi_threaded_isr(int this_irq, void *dev_id)
+{
+ struct dra7xxx_qspi *qspi = dev_id;
+ unsigned long flags;
+
+ spin_lock_irqsave(&qspi->lock, flags);
+
+ dra7xxx_writel(qspi, QSPI_WC_INT_DISABLE, QSPI_INTR_ENABLE_CLEAR_REG);
+ dra7xxx_writel(qspi, QSPI_WC_INT_DISABLE,
+ QSPI_INTR_STATUS_ENABLED_CLEAR);
+
+ complete(&qspi->word_complete);
+
+ spin_unlock_irqrestore(&qspi->lock, flags);
+
+ return IRQ_HANDLED;
+}
+
+static const struct of_device_id dra7xxx_qspi_match[] = {
+ {.compatible = "ti,dra7xxx-qspi" },
+ {},
+};
+MODULE_DEVICE_TABLE(of, dra7xxx_qspi_match);
+
+static int dra7xxx_qspi_probe(struct platform_device *pdev)
+{
+ struct dra7xxx_qspi *qspi;
+ struct spi_master *master;
+ struct resource *r;
+ struct device_node *np = pdev->dev.of_node;
+ u32 max_freq;
+ int ret = 0, num_cs, irq;
+
+ master = spi_alloc_master(&pdev->dev, sizeof(*qspi));
+ if (!master)
+ return -ENOMEM;
+
+ master->mode_bits = SPI_CPOL | SPI_CPHA;
+
+ master->num_chipselect = 1;
+ master->bus_num = -1;
+ master->setup = dra7xxx_qspi_setup;
+ master->prepare_transfer_hardware = dra7xxx_qspi_prepare_xfer;
+ master->transfer_one_message = dra7xxx_qspi_start_transfer_one;
+ master->unprepare_transfer_hardware = dra7xxx_qspi_unprepare_xfer;
+ master->dev.of_node = pdev->dev.of_node;
+ master->bits_per_word_mask = BIT(32 - 1) | BIT(16 - 1) | BIT(8 - 1);
+
+ if (!of_property_read_u32(np, "ti,spi-num-cs", &num_cs))
+ master->num_chipselect = num_cs;
+
+ platform_set_drvdata(pdev, master);
+
+ qspi = spi_master_get_devdata(master);
+ qspi->master = master;
+ qspi->dev = &pdev->dev;
+
+ r = platform_get_resource(pdev, IORESOURCE_MEM, 0);
+ if (r == NULL) {
+ ret = -ENODEV;
+ goto free_master;
+ }
+
+ irq = platform_get_irq(pdev, 0);
+ if (irq < 0) {
+ dev_err(&pdev->dev, "no irq resource?\n");
+ return irq;
+ }
+
+ spin_lock_init(&qspi->lock);
+
+ qspi->base = devm_ioremap_resource(&pdev->dev, r);
+ if (IS_ERR(qspi->base)) {
+ ret = -ENOMEM;
+ goto free_master;
+ }
+
+ ret = devm_request_threaded_irq(&pdev->dev, irq, dra7xxx_qspi_isr,
+ dra7xxx_qspi_threaded_isr, IRQF_NO_SUSPEND | IRQF_ONESHOT,
+ dev_name(&pdev->dev), qspi);
+ if (ret < 0) {
+ dev_err(&pdev->dev, "Failed to register ISR for IRQ %d\n",
+ irq);
+ goto free_master;
+ }
+
+ qspi->fclk = devm_clk_get(&pdev->dev, "fck");
+ if (IS_ERR(qspi->fclk)) {
+ ret = PTR_ERR(qspi->fclk);
+ dev_err(&pdev->dev, "could not get clk: %d\n", ret);
+ }
+
+ init_completion(&qspi->word_complete);
+
+ pm_runtime_use_autosuspend(&pdev->dev);
+ pm_runtime_set_autosuspend_delay(&pdev->dev, SPI_AUTOSUSPEND_TIMEOUT);
+ pm_runtime_enable(&pdev->dev);
+
+ if (!of_property_read_u32(np, "spi-max-frequency", &max_freq))
+ qspi->spi_max_frequency = max_freq;
+
+ ret = spi_register_master(master);
+ if (ret)
+ goto free_master;
+
+ return ret;
+
+free_master:
+ spi_master_put(master);
+ return ret;
+}
+
+static int dra7xxx_qspi_remove(struct platform_device *pdev)
+{
+ struct dra7xxx_qspi *qspi = platform_get_drvdata(pdev);
+
+ spi_unregister_master(qspi->master);
+
+ return 0;
+}
+
+static struct platform_driver dra7xxx_qspi_driver = {
+ .probe = dra7xxx_qspi_probe,
+ .remove = dra7xxx_qspi_remove,
+ .driver = {
+ .name = "ti,dra7xxx-qspi",
+ .owner = THIS_MODULE,
+ .of_match_table = dra7xxx_qspi_match,
+ }
+};
+
+module_platform_driver(dra7xxx_qspi_driver);
+
+MODULE_LICENSE("GPL");
+MODULE_DESCRIPTION("TI QSPI controller driver");
--
1.7.1

2013-07-08 13:43:57

by Sourav Poddar

[permalink] [raw]
Subject: [RFC/PATCH 3/3] driver: spi: Add quad spi read support

Since, qspi controller uses quad read.

Configuring the command register, if the transfer of data needs
quad lines.

This patch has been done on top of the following patch[1], which is still
under review/comments.
This patch will also go changes, as the parent patch[1] does.

[1]: http://comments.gmane.org/gmane.linux.kernel.spi.devel/14047

Signed-off-by: Sourav Poddar <[email protected]>
---
drivers/spi/spi-ti-qspi.c | 8 ++++++--
1 files changed, 6 insertions(+), 2 deletions(-)

diff --git a/drivers/spi/spi-ti-qspi.c b/drivers/spi/spi-ti-qspi.c
index 430de9c..307cbed 100644
--- a/drivers/spi/spi-ti-qspi.c
+++ b/drivers/spi/spi-ti-qspi.c
@@ -258,8 +258,12 @@ static int qspi_read_msg(struct dra7xxx_qspi *qspi, struct spi_transfer *t)
qspi->cmd | QSPI_RD_SNGL, qspi->dc);
dra7xxx_writel(qspi, QSPI_WC_INT_EN, QSPI_INTR_ENABLE_SET_REG);
dra7xxx_writel(qspi, qspi->dc, QSPI_SPI_DC_REG);
- dra7xxx_writel(qspi, qspi->cmd | QSPI_RD_SNGL,
- QSPI_SPI_CMD_REG);
+ if (t->bitwidth == SPI_BITWIDTH_QUAD)
+ dra7xxx_writel(qspi, qspi->cmd | QSPI_RD_QUAD,
+ QSPI_SPI_CMD_REG);
+ else
+ dra7xxx_writel(qspi, qspi->cmd | QSPI_RD_SNGL,
+ QSPI_SPI_CMD_REG);
wait_for_completion(&qspi->word_complete);
*rxbuf++ = dra7xxx_readl_data(qspi, QSPI_SPI_DATA_REG, wlen);
dev_dbg(qspi->dev, "rx done, read %02x\n", *(rxbuf-1));
--
1.7.1

2013-07-08 14:33:17

by Felipe Balbi

[permalink] [raw]
Subject: Re: [PATCHv3 2/3] drivers: spi: Add qspi flash controller

Hi,

On Mon, Jul 08, 2013 at 07:12:59PM +0530, Sourav Poddar wrote:
> +static inline unsigned long dra7xxx_readl(struct dra7xxx_qspi *qspi,
> + unsigned long reg)
> +{
> + return readl(qspi->base + reg);
> +}
> +
> +static inline void dra7xxx_writel(struct dra7xxx_qspi *qspi,
> + unsigned long val, unsigned long reg)
> +{
> + writel(val, qspi->base + reg);
> +}
> +
> +static inline unsigned long dra7xxx_readl_data(struct dra7xxx_qspi *qspi,
> + unsigned long reg, int wlen)
> +{
> + switch (wlen) {
> + case 8:
> + return readw(qspi->base + reg);
> + break;
> + case 16:
> + return readb(qspi->base + reg);
> + break;
> + case 32:
> + return readl(qspi->base + reg);
> + break;
> + default:
> + return -1;

return -EINVAL ? or some other error code ?

> + }
> +}
> +
> +static inline void dra7xxx_writel_data(struct dra7xxx_qspi *qspi,
> + unsigned long val, unsigned long reg, int wlen)
> +{
> + switch (wlen) {
> + case 8:
> + writew(val, qspi->base + reg);
> + break;
> + case 16:
> + writeb(val, qspi->base + reg);
> + break;
> + case 32:
> + writeb(val, qspi->base + reg);
> + break;
> + default:
> + dev_dbg(qspi->dev, "word lenght out of range");
> + break;
> + }
> +}
> +
> +static int dra7xxx_qspi_setup(struct spi_device *spi)
> +{
> + struct dra7xxx_qspi *qspi = spi_master_get_devdata(spi->master);
> + int clk_div = 0;
> + u32 clk_ctrl_reg, clk_rate;
> +
> + clk_rate = clk_get_rate(qspi->fclk);
> +
> + if (!qspi->spi_max_frequency) {
> + dev_err(qspi->dev, "spi max frequency not defined\n");
> + return -1;

same here

> + } else

this needs to have curly braces too, per CodingStyle

> + clk_div = (clk_rate / qspi->spi_max_frequency) - 1;
> +
> + dev_dbg(qspi->dev, "%s: hz: %d, clock divider %d\n", __func__,
> + qspi->spi_max_frequency, clk_div);
> +
> + pm_runtime_get_sync(qspi->dev);
> +
> + clk_ctrl_reg = dra7xxx_readl(qspi, QSPI_SPI_CLOCK_CNTRL_REG);
> +
> + clk_ctrl_reg &= ~QSPI_CLK_EN;
> +
> + /* disable SCLK */
> + dra7xxx_writel(qspi, clk_ctrl_reg, QSPI_SPI_CLOCK_CNTRL_REG);
> +
> + if (clk_div < 0) {
> + dev_dbg(qspi->dev, "%s: clock divider < 0, using /1 divider\n",
> + __func__);
> + clk_div = 1;
> + }
> +
> + if (clk_div > QSPI_CLK_DIV_MAX) {
> + dev_dbg(qspi->dev, "%s: clock divider >%d , using /%d divider\n",
> + __func__, QSPI_CLK_DIV_MAX, QSPI_CLK_DIV_MAX + 1);
> + clk_div = QSPI_CLK_DIV_MAX;
> + }
> +
> + /* enable SCLK */
> + dra7xxx_writel(qspi, QSPI_CLK_EN | clk_div, QSPI_SPI_CLOCK_CNTRL_REG);
> +
> + pm_runtime_mark_last_busy(qspi->dev);
> + pm_runtime_put_autosuspend(qspi->dev);
> +
> + return 0;
> +}
> +
> +static int dra7xxx_qspi_prepare_xfer(struct spi_master *master)
> +{
> + struct dra7xxx_qspi *qspi = spi_master_get_devdata(master);
> +
> + pm_runtime_get_sync(qspi->dev);

not going to check return value ?

> + return 0;
> +}
> +
> +static int dra7xxx_qspi_unprepare_xfer(struct spi_master *master)
> +{
> + struct dra7xxx_qspi *qspi = spi_master_get_devdata(master);
> +
> + pm_runtime_mark_last_busy(qspi->dev);
> + pm_runtime_put_autosuspend(qspi->dev);

what about on these two ?

> + return 0;
> +}
> +
> +static int qspi_write_msg(struct dra7xxx_qspi *qspi, struct spi_transfer *t)
> +{
> + const u8 *txbuf;
> + int wlen, count;
> +
> + count = t->len;
> + txbuf = t->tx_buf;
> + wlen = t->bits_per_word;
> +
> + while (count--) {
> + dev_dbg(qspi->dev, "tx cmd %08x dc %08x data %02x\n",
> + qspi->cmd | QSPI_WR_SNGL, qspi->dc, *txbuf);
> + dra7xxx_writel(qspi, QSPI_WC_INT_EN, QSPI_INTR_ENABLE_SET_REG);

you should enable the interrupt as the last step. Also, why aren't you
using frame interrupt ?

> + dra7xxx_writel_data(qspi, *txbuf++, QSPI_SPI_DATA_REG, wlen);
> + dra7xxx_writel(qspi, qspi->dc, QSPI_SPI_DC_REG);
> + dra7xxx_writel(qspi, qspi->cmd | QSPI_WR_SNGL,
> + QSPI_SPI_CMD_REG);
> + wait_for_completion(&qspi->word_complete);
> + }
> +
> + return 0;
> +}
> +
> +static int qspi_read_msg(struct dra7xxx_qspi *qspi, struct spi_transfer *t)
> +{
> + u8 *rxbuf;
> + int wlen, count;
> +
> + count = t->len;
> + rxbuf = t->rx_buf;
> + wlen = t->bits_per_word;
> +
> + while (count--) {
> + dev_dbg(qspi->dev, "rx cmd %08x dc %08x\n",
> + qspi->cmd | QSPI_RD_SNGL, qspi->dc);
> + dra7xxx_writel(qspi, QSPI_WC_INT_EN, QSPI_INTR_ENABLE_SET_REG);

ditto

> + dra7xxx_writel(qspi, qspi->dc, QSPI_SPI_DC_REG);
> + dra7xxx_writel(qspi, qspi->cmd | QSPI_RD_SNGL,
> + QSPI_SPI_CMD_REG);
> + wait_for_completion(&qspi->word_complete);
> + *rxbuf++ = dra7xxx_readl_data(qspi, QSPI_SPI_DATA_REG, wlen);
> + dev_dbg(qspi->dev, "rx done, read %02x\n", *(rxbuf-1));
> + }
> +
> + return 0;
> +}
> +
> +static int qspi_transfer_msg(struct dra7xxx_qspi *qspi, struct spi_transfer *t)
> +{
> + if (t->tx_buf)
> + qspi_write_msg(qspi, t);
> + if (t->rx_buf)
> + qspi_read_msg(qspi, t);
> +
> + return 0;
> +}
> +
> +static int dra7xxx_qspi_start_transfer_one(struct spi_master *master,
> + struct spi_message *m)
> +{
> + struct dra7xxx_qspi *qspi = spi_master_get_devdata(master);
> + struct spi_device *spi = m->spi;
> + struct spi_transfer *t;
> + int status = 0;
> + int frame_length;
> +
> + /* setup device control reg */
> + qspi->dc = 0;
> +
> + if (spi->mode & SPI_CPHA)
> + qspi->dc |= QSPI_CKPHA(spi->chip_select);
> + if (spi->mode & SPI_CPOL)
> + qspi->dc |= QSPI_CKPOL(spi->chip_select);
> + if (spi->mode & SPI_CS_HIGH)
> + qspi->dc |= QSPI_CSPOL(spi->chip_select);
> +
> + frame_length = DIV_ROUND_UP(m->frame_length * spi->bits_per_word,

why this multiplication ? Frame is not counted in bits but in number of
words. Which means that m->framelength / spi->bits_per_word should be
enough.

Also, this actually brings up a mistake I made, if I read the TRM
correclty this time, frame length is nothing but the t->len which
renders patch 1 in this series unnecessary, my mistake.

> + spi->bits_per_word);
> +
> + frame_length = clamp(frame_length, 0, QSPI_FRAME_MAX);
> +
> + /* setup command reg */
> + qspi->cmd = 0;
> + qspi->cmd |= QSPI_EN_CS(spi->chip_select);
> + qspi->cmd |= QSPI_FLEN(frame_length);

right, right, so far so good...

> + list_for_each_entry(t, &m->transfers, transfer_list) {
> + qspi->cmd |= QSPI_WLEN(t->bits_per_word);

sure about this ? according to TRM a write of 0 means 1 bit, 1, means 2
bits, 2 means 3 bits, etc... So this should be t->bits_per_word - 1.

> + qspi->cmd |= QSPI_WC_CMD_INT_EN;

... but why are you still interrupting on every word ????

as I said before, we want to interrupt on every frame. one spi_transfer
is one frame, if that frame has a length of 1MiB, I want to be
interrupted after 1MiB.

> + qspi_transfer_msg(qspi, t);
> + m->actual_length += t->len;
> +
> + if (list_is_last(&t->transfer_list, &m->transfers))
> + goto out;
> + }
> +
> +out:
> + m->status = status;
> + spi_finalize_current_message(master);
> +
> + dra7xxx_writel(qspi, qspi->cmd | QSPI_INVAL, QSPI_SPI_CMD_REG);
> +
> + return status;
> +}
> +
> +static irqreturn_t dra7xxx_qspi_isr(int irq, void *dev_id)
> +{
> + struct dra7xxx_qspi *qspi = dev_id;
> + u16 mask, stat;
> +
> + irqreturn_t ret = IRQ_HANDLED;
> +
> + spin_lock(&qspi->lock);
> +
> + stat = dra7xxx_readl(qspi, QSPI_SPI_STATUS_REG);
> + mask = dra7xxx_readl(qspi, QSPI_SPI_CMD_REG);
> +
> + if ((stat & QSPI_WC) && (mask & QSPI_WC_CMD_INT_EN))

this is wrong, everytime you want to handle another IRQ bit, you will
have to update this line.

if (stat & mask)

sounds like it's enough

--
balbi


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

2013-07-08 14:37:18

by Felipe Balbi

[permalink] [raw]
Subject: Re: [RFC/PATCH 3/3] driver: spi: Add quad spi read support

On Mon, Jul 08, 2013 at 07:13:00PM +0530, Sourav Poddar wrote:
> Since, qspi controller uses quad read.
>
> Configuring the command register, if the transfer of data needs
> quad lines.
>
> This patch has been done on top of the following patch[1], which is still
> under review/comments.
> This patch will also go changes, as the parent patch[1] does.
>
> [1]: http://comments.gmane.org/gmane.linux.kernel.spi.devel/14047
>
> Signed-off-by: Sourav Poddar <[email protected]>
> ---
> drivers/spi/spi-ti-qspi.c | 8 ++++++--
> 1 files changed, 6 insertions(+), 2 deletions(-)
>
> diff --git a/drivers/spi/spi-ti-qspi.c b/drivers/spi/spi-ti-qspi.c
> index 430de9c..307cbed 100644
> --- a/drivers/spi/spi-ti-qspi.c
> +++ b/drivers/spi/spi-ti-qspi.c
> @@ -258,8 +258,12 @@ static int qspi_read_msg(struct dra7xxx_qspi *qspi, struct spi_transfer *t)
> qspi->cmd | QSPI_RD_SNGL, qspi->dc);
> dra7xxx_writel(qspi, QSPI_WC_INT_EN, QSPI_INTR_ENABLE_SET_REG);
> dra7xxx_writel(qspi, qspi->dc, QSPI_SPI_DC_REG);
> - dra7xxx_writel(qspi, qspi->cmd | QSPI_RD_SNGL,
> - QSPI_SPI_CMD_REG);
> + if (t->bitwidth == SPI_BITWIDTH_QUAD)
> + dra7xxx_writel(qspi, qspi->cmd | QSPI_RD_QUAD,
> + QSPI_SPI_CMD_REG);
> + else
> + dra7xxx_writel(qspi, qspi->cmd | QSPI_RD_SNGL,
> + QSPI_SPI_CMD_REG);

we also have read dual, in order to make this code a little better you
could:

unsigned cmd = qspi->cmd;

switch (t->bitwidth)
case SPI_BITWIDTH_QUAD:
cmd |= QSPI_RD_QUAD;
break;
case SPI_BITWIDTH_DUAL:
cmd |= QSPI_RD_DUAL;
break;
case SPI_BITWIDTH_SINGLE:
default:
cmd |= QSPI_RD_SNGL;
}

dra7xx_writel(qspi, cmd, QSPI_SPI_CMD_REG);

--
balbi


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

2013-07-08 16:28:22

by Mark Brown

[permalink] [raw]
Subject: Re: [RFC/PATCH 1/3] driver: spi: Modify core to compute the message length

On Mon, Jul 08, 2013 at 07:12:58PM +0530, Sourav Poddar wrote:
> Make spi core calculate the message length while
> populating the other transfer parameters. This will
> be useful in cases where controller driver need to configure its
> framelength field without iterating through the linklist again in the
> driver controller.

This seems fine but I'm going to hold off on applying it until it's
reqired since it'll bloat the structure a little and it's a bit unusual
to need it. We should do an audit in case some drivers do need this
though...


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

2013-07-08 20:33:45

by Nishanth Menon

[permalink] [raw]
Subject: Re: [PATCHv3 2/3] drivers: spi: Add qspi flash controller

On 19:12-20130708, Sourav Poddar wrote:
[..]
generic comment, given our historical mistakes of making drivers
specific to a SoC family, it never is.

Now, ti-qspi in file name is a step in the right direction, but, rest
of the code(function names etc) is just married to DRA7 family of
processor, when it should not be.

> diff --git a/drivers/spi/spi-ti-qspi.c b/drivers/spi/spi-ti-qspi.c
> new file mode 100644
> index 0000000..430de9c
> --- /dev/null
> +++ b/drivers/spi/spi-ti-qspi.c
[...]
> +static inline unsigned long dra7xxx_readl(struct dra7xxx_qspi *qspi,
> + unsigned long reg)
> +{
> + return readl(qspi->base + reg);
> +}
> +
> +static inline void dra7xxx_writel(struct dra7xxx_qspi *qspi,
> + unsigned long val, unsigned long reg)
> +{
> + writel(val, qspi->base + reg);
> +}
> +
> +static inline unsigned long dra7xxx_readl_data(struct dra7xxx_qspi *qspi,
> + unsigned long reg, int wlen)
> +{
> + switch (wlen) {
> + case 8:
> + return readw(qspi->base + reg);
> + break;
> + case 16:
> + return readb(qspi->base + reg);
> + break;
> + case 32:
> + return readl(qspi->base + reg);
> + break;
> + default:
> + return -1;
> + }
> +}
> +
> +static inline void dra7xxx_writel_data(struct dra7xxx_qspi *qspi,
> + unsigned long val, unsigned long reg, int wlen)
> +{
> + switch (wlen) {
> + case 8:
> + writew(val, qspi->base + reg);
> + break;
> + case 16:
> + writeb(val, qspi->base + reg);
> + break;
> + case 32:
> + writeb(val, qspi->base + reg);
> + break;
> + default:
> + dev_dbg(qspi->dev, "word lenght out of range");
> + break;
> + }
> +}
Looks like a case to use regmap?
Dumb q: why cant we use regmap_spi? worst case, you should be able to
use mmio if regmap_spi cant be used. The commit message was not clear
about this.

> +
> +static int dra7xxx_qspi_setup(struct spi_device *spi)
> +{
> + struct dra7xxx_qspi *qspi = spi_master_get_devdata(spi->master);
> + int clk_div = 0;
> + u32 clk_ctrl_reg, clk_rate;
> +
> + clk_rate = clk_get_rate(qspi->fclk);
> +
> + if (!qspi->spi_max_frequency) {
> + dev_err(qspi->dev, "spi max frequency not defined\n");
> + return -1;
> + } else
> + clk_div = (clk_rate / qspi->spi_max_frequency) - 1;

did you run checkpatch --strict here?
Also, would you prefer to use DIV_ROUND_UP?

> +
> + dev_dbg(qspi->dev, "%s: hz: %d, clock divider %d\n", __func__,
> + qspi->spi_max_frequency, clk_div);
> +
> + pm_runtime_get_sync(qspi->dev);
error check?
> +
> + clk_ctrl_reg = dra7xxx_readl(qspi, QSPI_SPI_CLOCK_CNTRL_REG);
> +
> + clk_ctrl_reg &= ~QSPI_CLK_EN;
> +
> + /* disable SCLK */
> + dra7xxx_writel(qspi, clk_ctrl_reg, QSPI_SPI_CLOCK_CNTRL_REG);
> +
> + if (clk_div < 0) {
> + dev_dbg(qspi->dev, "%s: clock divider < 0, using /1 divider\n",
> + __func__);
> + clk_div = 1;
should you not fail here?
> + }
> +
> + if (clk_div > QSPI_CLK_DIV_MAX) {
> + dev_dbg(qspi->dev, "%s: clock divider >%d , using /%d divider\n",
> + __func__, QSPI_CLK_DIV_MAX, QSPI_CLK_DIV_MAX + 1);
> + clk_div = QSPI_CLK_DIV_MAX;
should you not fail here?
> + }
> +
> + /* enable SCLK */
> + dra7xxx_writel(qspi, QSPI_CLK_EN | clk_div, QSPI_SPI_CLOCK_CNTRL_REG);
> +
> + pm_runtime_mark_last_busy(qspi->dev);
> + pm_runtime_put_autosuspend(qspi->dev);
error check?
> +
> + return 0;
> +}
> +
> +static int dra7xxx_qspi_prepare_xfer(struct spi_master *master)
> +{
> + struct dra7xxx_qspi *qspi = spi_master_get_devdata(master);
> +
> + pm_runtime_get_sync(qspi->dev);
error check?
> +
> + return 0;
> +}
> +
> +static int dra7xxx_qspi_unprepare_xfer(struct spi_master *master)
> +{
> + struct dra7xxx_qspi *qspi = spi_master_get_devdata(master);
> +
> + pm_runtime_mark_last_busy(qspi->dev);
> + pm_runtime_put_autosuspend(qspi->dev);
error check?
> +
> + return 0;
> +}
> +
> +static int qspi_write_msg(struct dra7xxx_qspi *qspi, struct spi_transfer *t)
> +{
> + const u8 *txbuf;
> + int wlen, count;
> +
> + count = t->len;
> + txbuf = t->tx_buf;
> + wlen = t->bits_per_word;
> +
> + while (count--) {
> + dev_dbg(qspi->dev, "tx cmd %08x dc %08x data %02x\n",
> + qspi->cmd | QSPI_WR_SNGL, qspi->dc, *txbuf);
> + dra7xxx_writel(qspi, QSPI_WC_INT_EN, QSPI_INTR_ENABLE_SET_REG);
> + dra7xxx_writel_data(qspi, *txbuf++, QSPI_SPI_DATA_REG, wlen);
> + dra7xxx_writel(qspi, qspi->dc, QSPI_SPI_DC_REG);
> + dra7xxx_writel(qspi, qspi->cmd | QSPI_WR_SNGL,
> + QSPI_SPI_CMD_REG);
> + wait_for_completion(&qspi->word_complete);
> + }
> +
> + return 0;
> +}
> +
> +static int qspi_read_msg(struct dra7xxx_qspi *qspi, struct spi_transfer *t)
> +{
> + u8 *rxbuf;
> + int wlen, count;
> +
> + count = t->len;
> + rxbuf = t->rx_buf;
> + wlen = t->bits_per_word;
> +
> + while (count--) {
> + dev_dbg(qspi->dev, "rx cmd %08x dc %08x\n",
> + qspi->cmd | QSPI_RD_SNGL, qspi->dc);
> + dra7xxx_writel(qspi, QSPI_WC_INT_EN, QSPI_INTR_ENABLE_SET_REG);
> + dra7xxx_writel(qspi, qspi->dc, QSPI_SPI_DC_REG);
> + dra7xxx_writel(qspi, qspi->cmd | QSPI_RD_SNGL,
> + QSPI_SPI_CMD_REG);
> + wait_for_completion(&qspi->word_complete);
> + *rxbuf++ = dra7xxx_readl_data(qspi, QSPI_SPI_DATA_REG, wlen);
*rxbuf =
> + dev_dbg(qspi->dev, "rx done, read %02x\n", *(rxbuf-1));
rxbuf++ after dev_dbg?
> + }
> +
> + return 0;
> +}
> +
> +static int qspi_transfer_msg(struct dra7xxx_qspi *qspi, struct spi_transfer *t)
> +{
> + if (t->tx_buf)
> + qspi_write_msg(qspi, t);
what is the point of the function returning error when we dont use it?
> + if (t->rx_buf)
> + qspi_read_msg(qspi, t);
what is the point of the function returning error when we dont use it?
> +
> + return 0;
> +}
> +
> +static int dra7xxx_qspi_start_transfer_one(struct spi_master *master,
> + struct spi_message *m)
> +{
> + struct dra7xxx_qspi *qspi = spi_master_get_devdata(master);
> + struct spi_device *spi = m->spi;
> + struct spi_transfer *t;
> + int status = 0;
> + int frame_length;
> +
> + /* setup device control reg */
> + qspi->dc = 0;
> +
> + if (spi->mode & SPI_CPHA)
> + qspi->dc |= QSPI_CKPHA(spi->chip_select);
> + if (spi->mode & SPI_CPOL)
> + qspi->dc |= QSPI_CKPOL(spi->chip_select);
> + if (spi->mode & SPI_CS_HIGH)
> + qspi->dc |= QSPI_CSPOL(spi->chip_select);
> +
> + frame_length = DIV_ROUND_UP(m->frame_length * spi->bits_per_word,
> + spi->bits_per_word);
> +
> + frame_length = clamp(frame_length, 0, QSPI_FRAME_MAX);
> +
> + /* setup command reg */
> + qspi->cmd = 0;
> + qspi->cmd |= QSPI_EN_CS(spi->chip_select);
> + qspi->cmd |= QSPI_FLEN(frame_length);
> +
how does one ensure pm runtime has not disabled clocks in
background? e.g. long latency between transfers.
> + list_for_each_entry(t, &m->transfers, transfer_list) {
> + qspi->cmd |= QSPI_WLEN(t->bits_per_word);
> + qspi->cmd |= QSPI_WC_CMD_INT_EN;
> +
> + qspi_transfer_msg(qspi, t);
error handling?
> +
> + m->actual_length += t->len;
> +
> + if (list_is_last(&t->transfer_list, &m->transfers))
> + goto out;
> + }
> +
> +out:
> + m->status = status;
> + spi_finalize_current_message(master);
> +
> + dra7xxx_writel(qspi, qspi->cmd | QSPI_INVAL, QSPI_SPI_CMD_REG);
> +
> + return status;
> +}
> +
> +static irqreturn_t dra7xxx_qspi_isr(int irq, void *dev_id)
> +{
> + struct dra7xxx_qspi *qspi = dev_id;
> + u16 mask, stat;
> +
> + irqreturn_t ret = IRQ_HANDLED;
> +
> + spin_lock(&qspi->lock);
> +
what if autosuspend has triggered here? before ISR was scheduled?
> + stat = dra7xxx_readl(qspi, QSPI_SPI_STATUS_REG);
> + mask = dra7xxx_readl(qspi, QSPI_SPI_CMD_REG);
> +
> + if ((stat & QSPI_WC) && (mask & QSPI_WC_CMD_INT_EN))
> + ret = IRQ_WAKE_THREAD;
> +
> + spin_unlock(&qspi->lock);
> +
> + return ret;
> +}
> +
> +static irqreturn_t dra7xxx_qspi_threaded_isr(int this_irq, void *dev_id)
> +{
> + struct dra7xxx_qspi *qspi = dev_id;
> + unsigned long flags;
> +
> + spin_lock_irqsave(&qspi->lock, flags);
> +
what if autosuspend has triggered here? before ISR was scheduled?
> + dra7xxx_writel(qspi, QSPI_WC_INT_DISABLE, QSPI_INTR_ENABLE_CLEAR_REG);
> + dra7xxx_writel(qspi, QSPI_WC_INT_DISABLE,
> + QSPI_INTR_STATUS_ENABLED_CLEAR);
> +
> + complete(&qspi->word_complete);
> +
> + spin_unlock_irqrestore(&qspi->lock, flags);
> +
> + return IRQ_HANDLED;
> +}
> +
> +static const struct of_device_id dra7xxx_qspi_match[] = {
> + {.compatible = "ti,dra7xxx-qspi" },
> + {},
> +};
> +MODULE_DEVICE_TABLE(of, dra7xxx_qspi_match);
> +
> +static int dra7xxx_qspi_probe(struct platform_device *pdev)
> +{
> + struct dra7xxx_qspi *qspi;
> + struct spi_master *master;
> + struct resource *r;
> + struct device_node *np = pdev->dev.of_node;
> + u32 max_freq;
> + int ret = 0, num_cs, irq;
> +
> + master = spi_alloc_master(&pdev->dev, sizeof(*qspi));
> + if (!master)
> + return -ENOMEM;
> +
> + master->mode_bits = SPI_CPOL | SPI_CPHA;
> +
> + master->num_chipselect = 1;
> + master->bus_num = -1;
> + master->setup = dra7xxx_qspi_setup;
> + master->prepare_transfer_hardware = dra7xxx_qspi_prepare_xfer;
> + master->transfer_one_message = dra7xxx_qspi_start_transfer_one;
> + master->unprepare_transfer_hardware = dra7xxx_qspi_unprepare_xfer;
> + master->dev.of_node = pdev->dev.of_node;
> + master->bits_per_word_mask = BIT(32 - 1) | BIT(16 - 1) | BIT(8 - 1);
> +
> + if (!of_property_read_u32(np, "ti,spi-num-cs", &num_cs))
> + master->num_chipselect = num_cs;
> +
> + platform_set_drvdata(pdev, master);
> +
> + qspi = spi_master_get_devdata(master);
> + qspi->master = master;
> + qspi->dev = &pdev->dev;
> +
> + r = platform_get_resource(pdev, IORESOURCE_MEM, 0);
> + if (r == NULL) {
> + ret = -ENODEV;
> + goto free_master;
> + }
> +
> + irq = platform_get_irq(pdev, 0);
> + if (irq < 0) {
> + dev_err(&pdev->dev, "no irq resource?\n");
> + return irq;
> + }
> +
> + spin_lock_init(&qspi->lock);
> +
> + qspi->base = devm_ioremap_resource(&pdev->dev, r);
> + if (IS_ERR(qspi->base)) {
> + ret = -ENOMEM;
> + goto free_master;
> + }
why not use devm_request_and_ioremap? Lock that region down so that no
two drivers can manage the same region?
> +
> + ret = devm_request_threaded_irq(&pdev->dev, irq, dra7xxx_qspi_isr,
> + dra7xxx_qspi_threaded_isr, IRQF_NO_SUSPEND | IRQF_ONESHOT,
> + dev_name(&pdev->dev), qspi);
> + if (ret < 0) {
> + dev_err(&pdev->dev, "Failed to register ISR for IRQ %d\n",
> + irq);
> + goto free_master;
> + }
> +
> + qspi->fclk = devm_clk_get(&pdev->dev, "fck");
> + if (IS_ERR(qspi->fclk)) {
> + ret = PTR_ERR(qspi->fclk);
> + dev_err(&pdev->dev, "could not get clk: %d\n", ret);
> + }
> +
> + init_completion(&qspi->word_complete);
> +
> + pm_runtime_use_autosuspend(&pdev->dev);
> + pm_runtime_set_autosuspend_delay(&pdev->dev, SPI_AUTOSUSPEND_TIMEOUT);
> + pm_runtime_enable(&pdev->dev);
> +
> + if (!of_property_read_u32(np, "spi-max-frequency", &max_freq))
> + qspi->spi_max_frequency = max_freq;
> +
> + ret = spi_register_master(master);
> + if (ret)
> + goto free_master;
> +
> + return ret;
> +
> +free_master:
> + spi_master_put(master);
> + return ret;
> +}
> +
> +static int dra7xxx_qspi_remove(struct platform_device *pdev)
> +{
> + struct dra7xxx_qspi *qspi = platform_get_drvdata(pdev);
> +
> + spi_unregister_master(qspi->master);
> +
> + return 0;
> +}
> +
> +static struct platform_driver dra7xxx_qspi_driver = {
> + .probe = dra7xxx_qspi_probe,
> + .remove = dra7xxx_qspi_remove,
> + .driver = {
> + .name = "ti,dra7xxx-qspi",
> + .owner = THIS_MODULE,
> + .of_match_table = dra7xxx_qspi_match,
> + }
no need for pm_ops?
> +};
> +
> +module_platform_driver(dra7xxx_qspi_driver);
> +
> +MODULE_LICENSE("GPL");
GPL V2?
> +MODULE_DESCRIPTION("TI QSPI controller driver");
MODULE_AUTHOR?
> --
> 1.7.1
>
> --
> To unsubscribe from this list: send the line "unsubscribe linux-omap" in
> the body of a message to [email protected]
> More majordomo info at http://vger.kernel.org/majordomo-info.html

--
Regards,
Nishanth Menon

2013-07-09 06:52:09

by Felipe Balbi

[permalink] [raw]
Subject: Re: [PATCHv3 2/3] drivers: spi: Add qspi flash controller

Hi,

On Mon, Jul 08, 2013 at 03:33:30PM -0500, Nishanth Menon wrote:
> > +static inline unsigned long dra7xxx_readl_data(struct dra7xxx_qspi *qspi,
> > + unsigned long reg, int wlen)
> > +{
> > + switch (wlen) {
> > + case 8:
> > + return readw(qspi->base + reg);
> > + break;
> > + case 16:
> > + return readb(qspi->base + reg);
> > + break;
> > + case 32:
> > + return readl(qspi->base + reg);
> > + break;
> > + default:
> > + return -1;
> > + }
> > +}
> > +
> > +static inline void dra7xxx_writel_data(struct dra7xxx_qspi *qspi,
> > + unsigned long val, unsigned long reg, int wlen)
> > +{
> > + switch (wlen) {
> > + case 8:
> > + writew(val, qspi->base + reg);
> > + break;
> > + case 16:
> > + writeb(val, qspi->base + reg);
> > + break;
> > + case 32:
> > + writeb(val, qspi->base + reg);
> > + break;
> > + default:
> > + dev_dbg(qspi->dev, "word lenght out of range");
> > + break;
> > + }
> > +}
> Looks like a case to use regmap?
> Dumb q: why cant we use regmap_spi? worst case, you should be able to

read regmap-spi and you'll see why it can't be used in this case.

regmap-spi is for SPI clients who want to read their register map
through SPI commands. This is a driver for the SPI master which has its
registers memory mapped.

> > +static int dra7xxx_qspi_start_transfer_one(struct spi_master *master,
> > + struct spi_message *m)
> > +{
> > + struct dra7xxx_qspi *qspi = spi_master_get_devdata(master);
> > + struct spi_device *spi = m->spi;
> > + struct spi_transfer *t;
> > + int status = 0;
> > + int frame_length;
> > +
> > + /* setup device control reg */
> > + qspi->dc = 0;
> > +
> > + if (spi->mode & SPI_CPHA)
> > + qspi->dc |= QSPI_CKPHA(spi->chip_select);
> > + if (spi->mode & SPI_CPOL)
> > + qspi->dc |= QSPI_CKPOL(spi->chip_select);
> > + if (spi->mode & SPI_CS_HIGH)
> > + qspi->dc |= QSPI_CSPOL(spi->chip_select);
> > +
> > + frame_length = DIV_ROUND_UP(m->frame_length * spi->bits_per_word,
> > + spi->bits_per_word);
> > +
> > + frame_length = clamp(frame_length, 0, QSPI_FRAME_MAX);
> > +
> > + /* setup command reg */
> > + qspi->cmd = 0;
> > + qspi->cmd |= QSPI_EN_CS(spi->chip_select);
> > + qspi->cmd |= QSPI_FLEN(frame_length);
> > +
> how does one ensure pm runtime has not disabled clocks in
> background? e.g. long latency between transfers.

because pm_runtime_put*() has not been called ?

There's no way clocks will be gated until we kick the pm autosuspend
timer, which is only done when the transfer is finished.

> > +static irqreturn_t dra7xxx_qspi_isr(int irq, void *dev_id)
> > +{
> > + struct dra7xxx_qspi *qspi = dev_id;
> > + u16 mask, stat;
> > +
> > + irqreturn_t ret = IRQ_HANDLED;
> > +
> > + spin_lock(&qspi->lock);
> > +
> what if autosuspend has triggered here? before ISR was scheduled?

how ?

the pm timer hasn't been kicked yet

> > + stat = dra7xxx_readl(qspi, QSPI_SPI_STATUS_REG);
> > + mask = dra7xxx_readl(qspi, QSPI_SPI_CMD_REG);
> > +
> > + if ((stat & QSPI_WC) && (mask & QSPI_WC_CMD_INT_EN))
> > + ret = IRQ_WAKE_THREAD;
> > +
> > + spin_unlock(&qspi->lock);
> > +
> > + return ret;
> > +}
> > +
> > +static irqreturn_t dra7xxx_qspi_threaded_isr(int this_irq, void *dev_id)
> > +{
> > + struct dra7xxx_qspi *qspi = dev_id;
> > + unsigned long flags;
> > +
> > + spin_lock_irqsave(&qspi->lock, flags);
> > +
> what if autosuspend has triggered here? before ISR was scheduled?

how ?

pm timer hasn't been kicked yet

> > + qspi->base = devm_ioremap_resource(&pdev->dev, r);
> > + if (IS_ERR(qspi->base)) {
> > + ret = -ENOMEM;
> > + goto free_master;
> > + }
> why not use devm_request_and_ioremap? Lock that region down so that no
> two drivers can manage the same region?

read devm_ioremap_resource() and look at the git log for all the
numerous drivers which were converted to devm_ioremap_resource() to find
the reason.

> > +static struct platform_driver dra7xxx_qspi_driver = {
> > + .probe = dra7xxx_qspi_probe,
> > + .remove = dra7xxx_qspi_remove,
> > + .driver = {
> > + .name = "ti,dra7xxx-qspi",
> > + .owner = THIS_MODULE,
> > + .of_match_table = dra7xxx_qspi_match,
> > + }
> no need for pm_ops?

+1

> > +};
> > +
> > +module_platform_driver(dra7xxx_qspi_driver);
> > +
> > +MODULE_LICENSE("GPL");
> GPL V2?

+1

> > +MODULE_DESCRIPTION("TI QSPI controller driver");
> MODULE_AUTHOR?

+1

--
balbi


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

2013-07-09 07:21:09

by Sourav Poddar

[permalink] [raw]
Subject: Re: [PATCHv3 2/3] drivers: spi: Add qspi flash controller

On Tuesday 09 July 2013 02:03 AM, Nishanth Menon wrote:
> On 19:12-20130708, Sourav Poddar wrote:
> [..]
> generic comment, given our historical mistakes of making drivers
> specific to a SoC family, it never is.
>
> Now, ti-qspi in file name is a step in the right direction, but, rest
> of the code(function names etc) is just married to DRA7 family of
> processor, when it should not be.
>
Make sense. Will change apis accordingly.
>> diff --git a/drivers/spi/spi-ti-qspi.c b/drivers/spi/spi-ti-qspi.c
>> new file mode 100644
>> index 0000000..430de9c
>> --- /dev/null
>> +++ b/drivers/spi/spi-ti-qspi.c
> [...]
>> +static inline unsigned long dra7xxx_readl(struct dra7xxx_qspi *qspi,
>> + unsigned long reg)
>> +{
>> + return readl(qspi->base + reg);
>> +}
>> +
>> +static inline void dra7xxx_writel(struct dra7xxx_qspi *qspi,
>> + unsigned long val, unsigned long reg)
>> +{
>> + writel(val, qspi->base + reg);
>> +}
>> +
>> +static inline unsigned long dra7xxx_readl_data(struct dra7xxx_qspi *qspi,
>> + unsigned long reg, int wlen)
>> +{
>> + switch (wlen) {
>> + case 8:
>> + return readw(qspi->base + reg);
>> + break;
>> + case 16:
>> + return readb(qspi->base + reg);
>> + break;
>> + case 32:
>> + return readl(qspi->base + reg);
>> + break;
>> + default:
>> + return -1;
>> + }
>> +}
>> +
>> +static inline void dra7xxx_writel_data(struct dra7xxx_qspi *qspi,
>> + unsigned long val, unsigned long reg, int wlen)
>> +{
>> + switch (wlen) {
>> + case 8:
>> + writew(val, qspi->base + reg);
>> + break;
>> + case 16:
>> + writeb(val, qspi->base + reg);
>> + break;
>> + case 32:
>> + writeb(val, qspi->base + reg);
>> + break;
>> + default:
>> + dev_dbg(qspi->dev, "word lenght out of range");
>> + break;
>> + }
>> +}
> Looks like a case to use regmap?
> Dumb q: why cant we use regmap_spi? worst case, you should be able to
> use mmio if regmap_spi cant be used. The commit message was not clear
> about this.
>
MMIO can be used as this controller supports memory mapped port, but that
will be addition/enhancement on top of this.
This driver is adding qspi controller read/write support in SPI mode.
>> +
>> +static int dra7xxx_qspi_setup(struct spi_device *spi)
>> +{
>> + struct dra7xxx_qspi *qspi = spi_master_get_devdata(spi->master);
>> + int clk_div = 0;
>> + u32 clk_ctrl_reg, clk_rate;
>> +
>> + clk_rate = clk_get_rate(qspi->fclk);
>> +
>> + if (!qspi->spi_max_frequency) {
>> + dev_err(qspi->dev, "spi max frequency not defined\n");
>> + return -1;
>> + } else
>> + clk_div = (clk_rate / qspi->spi_max_frequency) - 1;
> did you run checkpatch --strict here?
Didn,t do the strict, yes will add braces.
> Also, would you prefer to use DIV_ROUND_UP?
>
Ok.
>> +
>> + dev_dbg(qspi->dev, "%s: hz: %d, clock divider %d\n", __func__,
>> + qspi->spi_max_frequency, clk_div);
>> +
>> + pm_runtime_get_sync(qspi->dev);
> error check?
Will add.
>> +
>> + clk_ctrl_reg = dra7xxx_readl(qspi, QSPI_SPI_CLOCK_CNTRL_REG);
>> +
>> + clk_ctrl_reg&= ~QSPI_CLK_EN;
>> +
>> + /* disable SCLK */
>> + dra7xxx_writel(qspi, clk_ctrl_reg, QSPI_SPI_CLOCK_CNTRL_REG);
>> +
>> + if (clk_div< 0) {
>> + dev_dbg(qspi->dev, "%s: clock divider< 0, using /1 divider\n",
>> + __func__);
>> + clk_div = 1;
> should you not fail here?
May be yes.
>> + }
>> +
>> + if (clk_div> QSPI_CLK_DIV_MAX) {
>> + dev_dbg(qspi->dev, "%s: clock divider>%d , using /%d divider\n",
>> + __func__, QSPI_CLK_DIV_MAX, QSPI_CLK_DIV_MAX + 1);
>> + clk_div = QSPI_CLK_DIV_MAX;
> should you not fail here?
Yup.
>> + }
>> +
>> + /* enable SCLK */
>> + dra7xxx_writel(qspi, QSPI_CLK_EN | clk_div, QSPI_SPI_CLOCK_CNTRL_REG);
>> +
>> + pm_runtime_mark_last_busy(qspi->dev);
>> + pm_runtime_put_autosuspend(qspi->dev);
> error check?
Will add.
>> +
>> + return 0;
>> +}
>> +
>> +static int dra7xxx_qspi_prepare_xfer(struct spi_master *master)
>> +{
>> + struct dra7xxx_qspi *qspi = spi_master_get_devdata(master);
>> +
>> + pm_runtime_get_sync(qspi->dev);
> error check?
Will add.
>> +
>> + return 0;
>> +}
>> +
>> +static int dra7xxx_qspi_unprepare_xfer(struct spi_master *master)
>> +{
>> + struct dra7xxx_qspi *qspi = spi_master_get_devdata(master);
>> +
>> + pm_runtime_mark_last_busy(qspi->dev);
>> + pm_runtime_put_autosuspend(qspi->dev);
> error check?
Will add.
>> +
>> + return 0;
>> +}
>> +
>> +static int qspi_write_msg(struct dra7xxx_qspi *qspi, struct spi_transfer *t)
>> +{
>> + const u8 *txbuf;
>> + int wlen, count;
>> +
>> + count = t->len;
>> + txbuf = t->tx_buf;
>> + wlen = t->bits_per_word;
>> +
>> + while (count--) {
>> + dev_dbg(qspi->dev, "tx cmd %08x dc %08x data %02x\n",
>> + qspi->cmd | QSPI_WR_SNGL, qspi->dc, *txbuf);
>> + dra7xxx_writel(qspi, QSPI_WC_INT_EN, QSPI_INTR_ENABLE_SET_REG);
>> + dra7xxx_writel_data(qspi, *txbuf++, QSPI_SPI_DATA_REG, wlen);
>> + dra7xxx_writel(qspi, qspi->dc, QSPI_SPI_DC_REG);
>> + dra7xxx_writel(qspi, qspi->cmd | QSPI_WR_SNGL,
>> + QSPI_SPI_CMD_REG);
>> + wait_for_completion(&qspi->word_complete);
>> + }
>> +
>> + return 0;
>> +}
>> +
>> +static int qspi_read_msg(struct dra7xxx_qspi *qspi, struct spi_transfer *t)
>> +{
>> + u8 *rxbuf;
>> + int wlen, count;
>> +
>> + count = t->len;
>> + rxbuf = t->rx_buf;
>> + wlen = t->bits_per_word;
>> +
>> + while (count--) {
>> + dev_dbg(qspi->dev, "rx cmd %08x dc %08x\n",
>> + qspi->cmd | QSPI_RD_SNGL, qspi->dc);
>> + dra7xxx_writel(qspi, QSPI_WC_INT_EN, QSPI_INTR_ENABLE_SET_REG);
>> + dra7xxx_writel(qspi, qspi->dc, QSPI_SPI_DC_REG);
>> + dra7xxx_writel(qspi, qspi->cmd | QSPI_RD_SNGL,
>> + QSPI_SPI_CMD_REG);
>> + wait_for_completion(&qspi->word_complete);
>> + *rxbuf++ = dra7xxx_readl_data(qspi, QSPI_SPI_DATA_REG, wlen);
> *rxbuf =
>> + dev_dbg(qspi->dev, "rx done, read %02x\n", *(rxbuf-1));
> rxbuf++ after dev_dbg?
I am not sure, anywyas we are decrementing pointer during dev_dbg..
>> + }
>> +
>> + return 0;
>> +}
>> +
>> +static int qspi_transfer_msg(struct dra7xxx_qspi *qspi, struct spi_transfer *t)
>> +{
>> + if (t->tx_buf)
>> + qspi_write_msg(qspi, t);
> what is the point of the function returning error when we dont use it?
hmm..yes, will check for errors.
>> + if (t->rx_buf)
>> + qspi_read_msg(qspi, t);
> what is the point of the function returning error when we dont use it?
Same as above.
>> +
>> + return 0;
>> +}
>> +
>> +static int dra7xxx_qspi_start_transfer_one(struct spi_master *master,
>> + struct spi_message *m)
>> +{
>> + struct dra7xxx_qspi *qspi = spi_master_get_devdata(master);
>> + struct spi_device *spi = m->spi;
>> + struct spi_transfer *t;
>> + int status = 0;
>> + int frame_length;
>> +
>> + /* setup device control reg */
>> + qspi->dc = 0;
>> +
>> + if (spi->mode& SPI_CPHA)
>> + qspi->dc |= QSPI_CKPHA(spi->chip_select);
>> + if (spi->mode& SPI_CPOL)
>> + qspi->dc |= QSPI_CKPOL(spi->chip_select);
>> + if (spi->mode& SPI_CS_HIGH)
>> + qspi->dc |= QSPI_CSPOL(spi->chip_select);
>> +
>> + frame_length = DIV_ROUND_UP(m->frame_length * spi->bits_per_word,
>> + spi->bits_per_word);
>> +
>> + frame_length = clamp(frame_length, 0, QSPI_FRAME_MAX);
>> +
>> + /* setup command reg */
>> + qspi->cmd = 0;
>> + qspi->cmd |= QSPI_EN_CS(spi->chip_select);
>> + qspi->cmd |= QSPI_FLEN(frame_length);
>> +
> how does one ensure pm runtime has not disabled clocks in
> background? e.g. long latency between transfers.
As felipe also pointed out, in prepare transfer I will enable clocks which
will get get disabled only during unprepare transfer. I dont know if we
hit the above scenario.
+ list_for_each_entry(t, &m->transfers, transfer_list) {
>> + qspi->cmd |= QSPI_WLEN(t->bits_per_word);
>> + qspi->cmd |= QSPI_WC_CMD_INT_EN;
>> +
>> + qspi_transfer_msg(qspi, t);
> error handling?
Will add.
>> +
>> + m->actual_length += t->len;
>> +
>> + if (list_is_last(&t->transfer_list,&m->transfers))
>> + goto out;
>> + }
>> +
>> +out:
>> + m->status = status;
>> + spi_finalize_current_message(master);
>> +
>> + dra7xxx_writel(qspi, qspi->cmd | QSPI_INVAL, QSPI_SPI_CMD_REG);
>> +
>> + return status;
>> +}
>> +
>> +static irqreturn_t dra7xxx_qspi_isr(int irq, void *dev_id)
>> +{
>> + struct dra7xxx_qspi *qspi = dev_id;
>> + u16 mask, stat;
>> +
>> + irqreturn_t ret = IRQ_HANDLED;
>> +
>> + spin_lock(&qspi->lock);
>> +
> what if autosuspend has triggered here? before ISR was scheduled?
Similar understanding as above, autosuspend should get triggered only
during unprepare.
>> + stat = dra7xxx_readl(qspi, QSPI_SPI_STATUS_REG);
>> + mask = dra7xxx_readl(qspi, QSPI_SPI_CMD_REG);
>> +
>> + if ((stat& QSPI_WC)&& (mask& QSPI_WC_CMD_INT_EN))
>> + ret = IRQ_WAKE_THREAD;
>> +
>> + spin_unlock(&qspi->lock);
>> +
>> + return ret;
>> +}
>> +
>> +static irqreturn_t dra7xxx_qspi_threaded_isr(int this_irq, void *dev_id)
>> +{
>> + struct dra7xxx_qspi *qspi = dev_id;
>> + unsigned long flags;
>> +
>> + spin_lock_irqsave(&qspi->lock, flags);
>> +
> what if autosuspend has triggered here? before ISR was scheduled?
>> + dra7xxx_writel(qspi, QSPI_WC_INT_DISABLE, QSPI_INTR_ENABLE_CLEAR_REG);
>> + dra7xxx_writel(qspi, QSPI_WC_INT_DISABLE,
>> + QSPI_INTR_STATUS_ENABLED_CLEAR);
>> +
>> + complete(&qspi->word_complete);
>> +
>> + spin_unlock_irqrestore(&qspi->lock, flags);
>> +
>> + return IRQ_HANDLED;
>> +}
>> +
>> +static const struct of_device_id dra7xxx_qspi_match[] = {
>> + {.compatible = "ti,dra7xxx-qspi" },
>> + {},
>> +};
>> +MODULE_DEVICE_TABLE(of, dra7xxx_qspi_match);
>> +
>> +static int dra7xxx_qspi_probe(struct platform_device *pdev)
>> +{
>> + struct dra7xxx_qspi *qspi;
>> + struct spi_master *master;
>> + struct resource *r;
>> + struct device_node *np = pdev->dev.of_node;
>> + u32 max_freq;
>> + int ret = 0, num_cs, irq;
>> +
>> + master = spi_alloc_master(&pdev->dev, sizeof(*qspi));
>> + if (!master)
>> + return -ENOMEM;
>> +
>> + master->mode_bits = SPI_CPOL | SPI_CPHA;
>> +
>> + master->num_chipselect = 1;
>> + master->bus_num = -1;
>> + master->setup = dra7xxx_qspi_setup;
>> + master->prepare_transfer_hardware = dra7xxx_qspi_prepare_xfer;
>> + master->transfer_one_message = dra7xxx_qspi_start_transfer_one;
>> + master->unprepare_transfer_hardware = dra7xxx_qspi_unprepare_xfer;
>> + master->dev.of_node = pdev->dev.of_node;
>> + master->bits_per_word_mask = BIT(32 - 1) | BIT(16 - 1) | BIT(8 - 1);
>> +
>> + if (!of_property_read_u32(np, "ti,spi-num-cs",&num_cs))
>> + master->num_chipselect = num_cs;
>> +
>> + platform_set_drvdata(pdev, master);
>> +
>> + qspi = spi_master_get_devdata(master);
>> + qspi->master = master;
>> + qspi->dev =&pdev->dev;
>> +
>> + r = platform_get_resource(pdev, IORESOURCE_MEM, 0);
>> + if (r == NULL) {
>> + ret = -ENODEV;
>> + goto free_master;
>> + }
>> +
>> + irq = platform_get_irq(pdev, 0);
>> + if (irq< 0) {
>> + dev_err(&pdev->dev, "no irq resource?\n");
>> + return irq;
>> + }
>> +
>> + spin_lock_init(&qspi->lock);
>> +
>> + qspi->base = devm_ioremap_resource(&pdev->dev, r);
>> + if (IS_ERR(qspi->base)) {
>> + ret = -ENOMEM;
>> + goto free_master;
>> + }
> why not use devm_request_and_ioremap? Lock that region down so that no
> two drivers can manage the same region?
>> +
>> + ret = devm_request_threaded_irq(&pdev->dev, irq, dra7xxx_qspi_isr,
>> + dra7xxx_qspi_threaded_isr, IRQF_NO_SUSPEND | IRQF_ONESHOT,
>> + dev_name(&pdev->dev), qspi);
>> + if (ret< 0) {
>> + dev_err(&pdev->dev, "Failed to register ISR for IRQ %d\n",
>> + irq);
>> + goto free_master;
>> + }
>> +
>> + qspi->fclk = devm_clk_get(&pdev->dev, "fck");
>> + if (IS_ERR(qspi->fclk)) {
>> + ret = PTR_ERR(qspi->fclk);
>> + dev_err(&pdev->dev, "could not get clk: %d\n", ret);
>> + }
>> +
>> + init_completion(&qspi->word_complete);
>> +
>> + pm_runtime_use_autosuspend(&pdev->dev);
>> + pm_runtime_set_autosuspend_delay(&pdev->dev, SPI_AUTOSUSPEND_TIMEOUT);
>> + pm_runtime_enable(&pdev->dev);
>> +
>> + if (!of_property_read_u32(np, "spi-max-frequency",&max_freq))
>> + qspi->spi_max_frequency = max_freq;
>> +
>> + ret = spi_register_master(master);
>> + if (ret)
>> + goto free_master;
>> +
>> + return ret;
>> +
>> +free_master:
>> + spi_master_put(master);
>> + return ret;
>> +}
>> +
>> +static int dra7xxx_qspi_remove(struct platform_device *pdev)
>> +{
>> + struct dra7xxx_qspi *qspi = platform_get_drvdata(pdev);
>> +
>> + spi_unregister_master(qspi->master);
>> +
>> + return 0;
>> +}
>> +
>> +static struct platform_driver dra7xxx_qspi_driver = {
>> + .probe = dra7xxx_qspi_probe,
>> + .remove = dra7xxx_qspi_remove,
>> + .driver = {
>> + .name = "ti,dra7xxx-qspi",
>> + .owner = THIS_MODULE,
>> + .of_match_table = dra7xxx_qspi_match,
>> + }
> no need for pm_ops?
Yes, we need to, I thought of sending that as a seperate patch after this
this one gets fixed.
Would you prefer that I add it here?
>> +};
>> +
>> +module_platform_driver(dra7xxx_qspi_driver);
>> +
>> +MODULE_LICENSE("GPL");
> GPL V2?
Yes, will change.
>> +MODULE_DESCRIPTION("TI QSPI controller driver");
> MODULE_AUTHOR?
Will add.
>> --
>> 1.7.1
>>
>> --
>> To unsubscribe from this list: send the line "unsubscribe linux-omap" in
>> the body of a message to [email protected]
>> More majordomo info at http://vger.kernel.org/majordomo-info.html

2013-07-09 07:29:44

by Sourav Poddar

[permalink] [raw]
Subject: Re: [PATCHv3 2/3] drivers: spi: Add qspi flash controller

On Monday 08 July 2013 08:02 PM, Felipe Balbi wrote:
> Hi,
>
> On Mon, Jul 08, 2013 at 07:12:59PM +0530, Sourav Poddar wrote:
>> +static inline unsigned long dra7xxx_readl(struct dra7xxx_qspi *qspi,
>> + unsigned long reg)
>> +{
>> + return readl(qspi->base + reg);
>> +}
>> +
>> +static inline void dra7xxx_writel(struct dra7xxx_qspi *qspi,
>> + unsigned long val, unsigned long reg)
>> +{
>> + writel(val, qspi->base + reg);
>> +}
>> +
>> +static inline unsigned long dra7xxx_readl_data(struct dra7xxx_qspi *qspi,
>> + unsigned long reg, int wlen)
>> +{
>> + switch (wlen) {
>> + case 8:
>> + return readw(qspi->base + reg);
>> + break;
>> + case 16:
>> + return readb(qspi->base + reg);
>> + break;
>> + case 32:
>> + return readl(qspi->base + reg);
>> + break;
>> + default:
>> + return -1;
> return -EINVAL ? or some other error code ?
>
Ok.will change.
>> + }
>> +}
>> +
>> +static inline void dra7xxx_writel_data(struct dra7xxx_qspi *qspi,
>> + unsigned long val, unsigned long reg, int wlen)
>> +{
>> + switch (wlen) {
>> + case 8:
>> + writew(val, qspi->base + reg);
>> + break;
>> + case 16:
>> + writeb(val, qspi->base + reg);
>> + break;
>> + case 32:
>> + writeb(val, qspi->base + reg);
>> + break;
>> + default:
>> + dev_dbg(qspi->dev, "word lenght out of range");
>> + break;
>> + }
>> +}
>> +
>> +static int dra7xxx_qspi_setup(struct spi_device *spi)
>> +{
>> + struct dra7xxx_qspi *qspi = spi_master_get_devdata(spi->master);
>> + int clk_div = 0;
>> + u32 clk_ctrl_reg, clk_rate;
>> +
>> + clk_rate = clk_get_rate(qspi->fclk);
>> +
>> + if (!qspi->spi_max_frequency) {
>> + dev_err(qspi->dev, "spi max frequency not defined\n");
>> + return -1;
> same here
>
Ok.
>> + } else
> this needs to have curly braces too, per CodingStyle
>
hmm..will change.
>> + clk_div = (clk_rate / qspi->spi_max_frequency) - 1;
>> +
>> + dev_dbg(qspi->dev, "%s: hz: %d, clock divider %d\n", __func__,
>> + qspi->spi_max_frequency, clk_div);
>> +
>> + pm_runtime_get_sync(qspi->dev);
>> +
>> + clk_ctrl_reg = dra7xxx_readl(qspi, QSPI_SPI_CLOCK_CNTRL_REG);
>> +
>> + clk_ctrl_reg&= ~QSPI_CLK_EN;
>> +
>> + /* disable SCLK */
>> + dra7xxx_writel(qspi, clk_ctrl_reg, QSPI_SPI_CLOCK_CNTRL_REG);
>> +
>> + if (clk_div< 0) {
>> + dev_dbg(qspi->dev, "%s: clock divider< 0, using /1 divider\n",
>> + __func__);
>> + clk_div = 1;
>> + }
>> +
>> + if (clk_div> QSPI_CLK_DIV_MAX) {
>> + dev_dbg(qspi->dev, "%s: clock divider>%d , using /%d divider\n",
>> + __func__, QSPI_CLK_DIV_MAX, QSPI_CLK_DIV_MAX + 1);
>> + clk_div = QSPI_CLK_DIV_MAX;
>> + }
>> +
>> + /* enable SCLK */
>> + dra7xxx_writel(qspi, QSPI_CLK_EN | clk_div, QSPI_SPI_CLOCK_CNTRL_REG);
>> +
>> + pm_runtime_mark_last_busy(qspi->dev);
>> + pm_runtime_put_autosuspend(qspi->dev);
>> +
>> + return 0;
>> +}
>> +
>> +static int dra7xxx_qspi_prepare_xfer(struct spi_master *master)
>> +{
>> + struct dra7xxx_qspi *qspi = spi_master_get_devdata(master);
>> +
>> + pm_runtime_get_sync(qspi->dev);
> not going to check return value ?
>
Will add.
>> + return 0;
>> +}
>> +
>> +static int dra7xxx_qspi_unprepare_xfer(struct spi_master *master)
>> +{
>> + struct dra7xxx_qspi *qspi = spi_master_get_devdata(master);
>> +
>> + pm_runtime_mark_last_busy(qspi->dev);
>> + pm_runtime_put_autosuspend(qspi->dev);
> what about on these two ?
>
Yes, will add error checking.
>> + return 0;
>> +}
>> +
>> +static int qspi_write_msg(struct dra7xxx_qspi *qspi, struct spi_transfer *t)
>> +{
>> + const u8 *txbuf;
>> + int wlen, count;
>> +
>> + count = t->len;
>> + txbuf = t->tx_buf;
>> + wlen = t->bits_per_word;
>> +
>> + while (count--) {
>> + dev_dbg(qspi->dev, "tx cmd %08x dc %08x data %02x\n",
>> + qspi->cmd | QSPI_WR_SNGL, qspi->dc, *txbuf);
>> + dra7xxx_writel(qspi, QSPI_WC_INT_EN, QSPI_INTR_ENABLE_SET_REG);
> you should enable the interrupt as the last step. Also, why aren't you
> using frame interrupt ?
>
>> + dra7xxx_writel_data(qspi, *txbuf++, QSPI_SPI_DATA_REG, wlen);
>> + dra7xxx_writel(qspi, qspi->dc, QSPI_SPI_DC_REG);
>> + dra7xxx_writel(qspi, qspi->cmd | QSPI_WR_SNGL,
>> + QSPI_SPI_CMD_REG);
>> + wait_for_completion(&qspi->word_complete);
>> + }
>> +
>> + return 0;
>> +}
>> +
>> +static int qspi_read_msg(struct dra7xxx_qspi *qspi, struct spi_transfer *t)
>> +{
>> + u8 *rxbuf;
>> + int wlen, count;
>> +
>> + count = t->len;
>> + rxbuf = t->rx_buf;
>> + wlen = t->bits_per_word;
>> +
>> + while (count--) {
>> + dev_dbg(qspi->dev, "rx cmd %08x dc %08x\n",
>> + qspi->cmd | QSPI_RD_SNGL, qspi->dc);
>> + dra7xxx_writel(qspi, QSPI_WC_INT_EN, QSPI_INTR_ENABLE_SET_REG);
> ditto
>
hmm. will move this down.
>> + dra7xxx_writel(qspi, qspi->dc, QSPI_SPI_DC_REG);
>> + dra7xxx_writel(qspi, qspi->cmd | QSPI_RD_SNGL,
>> + QSPI_SPI_CMD_REG);
>> + wait_for_completion(&qspi->word_complete);
>> + *rxbuf++ = dra7xxx_readl_data(qspi, QSPI_SPI_DATA_REG, wlen);
>> + dev_dbg(qspi->dev, "rx done, read %02x\n", *(rxbuf-1));
>> + }
>> +
>> + return 0;
>> +}
>> +
>> +static int qspi_transfer_msg(struct dra7xxx_qspi *qspi, struct spi_transfer *t)
>> +{
>> + if (t->tx_buf)
>> + qspi_write_msg(qspi, t);
>> + if (t->rx_buf)
>> + qspi_read_msg(qspi, t);
>> +
>> + return 0;
>> +}
>> +
>> +static int dra7xxx_qspi_start_transfer_one(struct spi_master *master,
>> + struct spi_message *m)
>> +{
>> + struct dra7xxx_qspi *qspi = spi_master_get_devdata(master);
>> + struct spi_device *spi = m->spi;
>> + struct spi_transfer *t;
>> + int status = 0;
>> + int frame_length;
>> +
>> + /* setup device control reg */
>> + qspi->dc = 0;
>> +
>> + if (spi->mode& SPI_CPHA)
>> + qspi->dc |= QSPI_CKPHA(spi->chip_select);
>> + if (spi->mode& SPI_CPOL)
>> + qspi->dc |= QSPI_CKPOL(spi->chip_select);
>> + if (spi->mode& SPI_CS_HIGH)
>> + qspi->dc |= QSPI_CSPOL(spi->chip_select);
>> +
>> + frame_length = DIV_ROUND_UP(m->frame_length * spi->bits_per_word,
> why this multiplication ? Frame is not counted in bits but in number of
> words. Which means that m->framelength / spi->bits_per_word should be
> enough.
Yes, got confused here. Will change.
> Also, this actually brings up a mistake I made, if I read the TRM
> correclty this time, frame length is nothing but the t->len which
> renders patch 1 in this series unnecessary, my mistake.
>
If flen is t->len, then
1.) yes patch 1 is useles.
2.) frame interrupt will make more sense then.
Till now, we were using flen as sum of all transfers, because of
which
I was forced to check for word complete.

I will check on "flen" and will get back on frame interrupt with
experimental results.
>> + spi->bits_per_word);
>> +
>> + frame_length = clamp(frame_length, 0, QSPI_FRAME_MAX);
>> +
>> + /* setup command reg */
>> + qspi->cmd = 0;
>> + qspi->cmd |= QSPI_EN_CS(spi->chip_select);
>> + qspi->cmd |= QSPI_FLEN(frame_length);
> right, right, so far so good...
>
>> + list_for_each_entry(t,&m->transfers, transfer_list) {
>> + qspi->cmd |= QSPI_WLEN(t->bits_per_word);
> sure about this ? according to TRM a write of 0 means 1 bit, 1, means 2
> bits, 2 means 3 bits, etc... So this should be t->bits_per_word - 1.
>
QSPI_WLEN is taking care of subtrating it by -1.
>> + qspi->cmd |= QSPI_WC_CMD_INT_EN;
> ... but why are you still interrupting on every word ????
>
> as I said before, we want to interrupt on every frame. one spi_transfer
> is one frame, if that frame has a length of 1MiB, I want to be
> interrupted after 1MiB.

>> + qspi_transfer_msg(qspi, t);
>> + m->actual_length += t->len;
>> +
>> + if (list_is_last(&t->transfer_list,&m->transfers))
>> + goto out;
>> + }
>> +
>> +out:
>> + m->status = status;
>> + spi_finalize_current_message(master);
>> +
>> + dra7xxx_writel(qspi, qspi->cmd | QSPI_INVAL, QSPI_SPI_CMD_REG);
>> +
>> + return status;
>> +}
>> +
>> +static irqreturn_t dra7xxx_qspi_isr(int irq, void *dev_id)
>> +{
>> + struct dra7xxx_qspi *qspi = dev_id;
>> + u16 mask, stat;
>> +
>> + irqreturn_t ret = IRQ_HANDLED;
>> +
>> + spin_lock(&qspi->lock);
>> +
>> + stat = dra7xxx_readl(qspi, QSPI_SPI_STATUS_REG);
>> + mask = dra7xxx_readl(qspi, QSPI_SPI_CMD_REG);
>> +
>> + if ((stat& QSPI_WC)&& (mask& QSPI_WC_CMD_INT_EN))
> this is wrong, everytime you want to handle another IRQ bit, you will
> have to update this line.
>
> if (stat& mask)
>
> sounds like it's enough
>
Yes, correct will change.

2013-07-09 10:06:14

by Mark Brown

[permalink] [raw]
Subject: Re: [PATCHv3 2/3] drivers: spi: Add qspi flash controller

On Tue, Jul 09, 2013 at 09:51:43AM +0300, Felipe Balbi wrote:

> > Looks like a case to use regmap?
> > Dumb q: why cant we use regmap_spi? worst case, you should be able to

> read regmap-spi and you'll see why it can't be used in this case.

> regmap-spi is for SPI clients who want to read their register map
> through SPI commands. This is a driver for the SPI master which has its
> registers memory mapped.

Indeed, regmap-spi would be a client of this driver. Though there is
regmap-mmio which may be helpful, on the other hand it's relatively
heavyweight and SPI can be a bit performance sensitive so perhaps it's
not awesome here. Russell did mention the idea of some helpers along a
similar style though, they may be a good idea but nobody wrote them yet.


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

2013-07-09 12:32:59

by Nishanth Menon

[permalink] [raw]
Subject: Re: [PATCHv3 2/3] drivers: spi: Add qspi flash controller

On 07/09/2013 05:05 AM, Mark Brown wrote:
> On Tue, Jul 09, 2013 at 09:51:43AM +0300, Felipe Balbi wrote:
>
>>> Looks like a case to use regmap?
>>> Dumb q: why cant we use regmap_spi? worst case, you should be able to
>
>> read regmap-spi and you'll see why it can't be used in this case.
>
>> regmap-spi is for SPI clients who want to read their register map
>> through SPI commands. This is a driver for the SPI master which has its
>> registers memory mapped.
>
> Indeed, regmap-spi would be a client of this driver. Though there is
> regmap-mmio which may be helpful, on the other hand it's relatively
> heavyweight and SPI can be a bit performance sensitive so perhaps it's
> not awesome here. Russell did mention the idea of some helpers along a
> similar style though, they may be a good idea but nobody wrote them yet.
>
Fair enough. I am starting to see at least a second driver (internally
for DRA7 IRQ/DMA crossbar) doing the same handling for different bit
sized registers. maybe now is the time for us to create a lighter
version of mmio. mmio at least the last I looked uses spinlocks and is
fairly fast. But, I agree, when the client of regmap uses locks to
protect operations of their own, regmap might be a bit of an overhead.
that said, replicating regmap logic in the driver looks a bit weird and
might allow the basis for other drivers to do the same as well as some
users of mmio would consider themselves performance sensitive :(.

--
Regards,
Nishanth Menon

2013-07-09 12:51:09

by Nishanth Menon

[permalink] [raw]
Subject: Re: [PATCHv3 2/3] drivers: spi: Add qspi flash controller

On 07/09/2013 01:51 AM, Felipe Balbi wrote:
> On Mon, Jul 08, 2013 at 03:33:30PM -0500, Nishanth Menon wrote:

>>> +static int dra7xxx_qspi_start_transfer_one(struct spi_master *master,
>>> + struct spi_message *m)
>>> +{
>>> + struct dra7xxx_qspi *qspi = spi_master_get_devdata(master);
>>> + struct spi_device *spi = m->spi;
>>> + struct spi_transfer *t;
>>> + int status = 0;
>>> + int frame_length;
>>> +
>>> + /* setup device control reg */
>>> + qspi->dc = 0;
>>> +
>>> + if (spi->mode & SPI_CPHA)
>>> + qspi->dc |= QSPI_CKPHA(spi->chip_select);
>>> + if (spi->mode & SPI_CPOL)
>>> + qspi->dc |= QSPI_CKPOL(spi->chip_select);
>>> + if (spi->mode & SPI_CS_HIGH)
>>> + qspi->dc |= QSPI_CSPOL(spi->chip_select);
>>> +
>>> + frame_length = DIV_ROUND_UP(m->frame_length * spi->bits_per_word,
>>> + spi->bits_per_word);
>>> +
>>> + frame_length = clamp(frame_length, 0, QSPI_FRAME_MAX);
>>> +
>>> + /* setup command reg */
>>> + qspi->cmd = 0;
>>> + qspi->cmd |= QSPI_EN_CS(spi->chip_select);
>>> + qspi->cmd |= QSPI_FLEN(frame_length);
>>> +
>> how does one ensure pm runtime has not disabled clocks in
>> background? e.g. long latency between transfers.
>
> because pm_runtime_put*() has not been called ?
>
> There's no way clocks will be gated until we kick the pm autosuspend
> timer, which is only done when the transfer is finished.

with this input and looking closer, I think I see what you are saying now:
dra7xxx_qspi_prepare_xfer -> does a pm_runtime_get_sync
dra7xxx_qspi_unprepare_xfer -> does a pm_runtime_mark_last_busy,
pm_runtime_put_autosuspend

In between these calls, you have the remaining xfer calls going on.
we are assuming here that autosuspend timeout should be greater than the
time to complete the worst case transfer.

Is that a valid assumption? would it not be better to mark_busy at other
points? my thought is that considering a threaded isr, if by any chance
you have a latency > autosuspend due to premption or some un-forseen
event, this could crash badly, no? mark_busy will atleast ensure that
runtime timer is reset. yep, we can also argue to converse, with a
autosuspend delay set to appropriate value, we should not see this
issue. pm_runtime_mark_last_busy() may be executed from interrupt
context as well. At least going with "marks the last time of the
device's busy state" we dont seem to mark them at all potential points?

ofcourse we can debate about how granular the marking should be, IMHO,
though, I like autosuspend, however, I like autosuspend as a way to
reduce transfer-to-transfer latency to re-enable the clocks. I however
am a bit gittery about autosuspend kicking inside required time
boundaries (especially considering the delay is upto user of the system).

Just my 2 cents.

[...]

>>> + qspi->base = devm_ioremap_resource(&pdev->dev, r);
>>> + if (IS_ERR(qspi->base)) {
>>> + ret = -ENOMEM;
>>> + goto free_master;
>>> + }
>> why not use devm_request_and_ioremap? Lock that region down so that no
>> two drivers can manage the same region?
>
> read devm_ioremap_resource() and look at the git log for all the
> numerous drivers which were converted to devm_ioremap_resource() to find
> the reason.

my bad. fair enough.

--
Regards,
Nishanth Menon

2013-07-09 14:40:52

by Mark Brown

[permalink] [raw]
Subject: Re: [PATCHv3 2/3] drivers: spi: Add qspi flash controller

On Tue, Jul 09, 2013 at 07:50:55AM -0500, Nishanth Menon wrote:

> with this input and looking closer, I think I see what you are saying now:
> dra7xxx_qspi_prepare_xfer -> does a pm_runtime_get_sync
> dra7xxx_qspi_unprepare_xfer -> does a pm_runtime_mark_last_busy,
> pm_runtime_put_autosuspend

> In between these calls, you have the remaining xfer calls going on.
> we are assuming here that autosuspend timeout should be greater than
> the time to complete the worst case transfer.

No, autosuspend will do nothing so long as there are references to the
device held. The effect of autosuspend is to delay power down after the
last reference has been dropped, otherwise things run normally.


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

2013-07-09 14:53:35

by Nishanth Menon

[permalink] [raw]
Subject: Re: [PATCHv3 2/3] drivers: spi: Add qspi flash controller

On 15:40-20130709, Mark Brown wrote:
> On Tue, Jul 09, 2013 at 07:50:55AM -0500, Nishanth Menon wrote:
>
> > with this input and looking closer, I think I see what you are saying now:
> > dra7xxx_qspi_prepare_xfer -> does a pm_runtime_get_sync
> > dra7xxx_qspi_unprepare_xfer -> does a pm_runtime_mark_last_busy,
> > pm_runtime_put_autosuspend
>
> > In between these calls, you have the remaining xfer calls going on.
> > we are assuming here that autosuspend timeout should be greater than
> > the time to complete the worst case transfer.
>
> No, autosuspend will do nothing so long as there are references to the
> device held. The effect of autosuspend is to delay power down after the
> last reference has been dropped, otherwise things run normally.

Thanks on the clarification. That concludes my confusion on the topic
:).

--
Regards,
Nishanth Menon

2013-07-11 09:12:45

by Sourav Poddar

[permalink] [raw]
Subject: Re: [PATCHv3 2/3] drivers: spi: Add qspi flash controller

On Monday 08 July 2013 08:02 PM, Felipe Balbi wrote:
> Hi,
>
> On Mon, Jul 08, 2013 at 07:12:59PM +0530, Sourav Poddar wrote:
>> +static inline unsigned long dra7xxx_readl(struct dra7xxx_qspi *qspi,
>> + unsigned long reg)
>> +{
>> + return readl(qspi->base + reg);
>> +}
>> +
>> +static inline void dra7xxx_writel(struct dra7xxx_qspi *qspi,
>> + unsigned long val, unsigned long reg)
>> +{
>> + writel(val, qspi->base + reg);
>> +}
>> +
>> +static inline unsigned long dra7xxx_readl_data(struct dra7xxx_qspi *qspi,
>> + unsigned long reg, int wlen)
>> +{
>> + switch (wlen) {
>> + case 8:
>> + return readw(qspi->base + reg);
>> + break;
>> + case 16:
>> + return readb(qspi->base + reg);
>> + break;
>> + case 32:
>> + return readl(qspi->base + reg);
>> + break;
>> + default:
>> + return -1;
> return -EINVAL ? or some other error code ?
>
>> + }
>> +}
>> +
>> +static inline void dra7xxx_writel_data(struct dra7xxx_qspi *qspi,
>> + unsigned long val, unsigned long reg, int wlen)
>> +{
>> + switch (wlen) {
>> + case 8:
>> + writew(val, qspi->base + reg);
>> + break;
>> + case 16:
>> + writeb(val, qspi->base + reg);
>> + break;
>> + case 32:
>> + writeb(val, qspi->base + reg);
>> + break;
>> + default:
>> + dev_dbg(qspi->dev, "word lenght out of range");
>> + break;
>> + }
>> +}
>> +
>> +static int dra7xxx_qspi_setup(struct spi_device *spi)
>> +{
>> + struct dra7xxx_qspi *qspi = spi_master_get_devdata(spi->master);
>> + int clk_div = 0;
>> + u32 clk_ctrl_reg, clk_rate;
>> +
>> + clk_rate = clk_get_rate(qspi->fclk);
>> +
>> + if (!qspi->spi_max_frequency) {
>> + dev_err(qspi->dev, "spi max frequency not defined\n");
>> + return -1;
> same here
>
>> + } else
> this needs to have curly braces too, per CodingStyle
>
>> + clk_div = (clk_rate / qspi->spi_max_frequency) - 1;
>> +
>> + dev_dbg(qspi->dev, "%s: hz: %d, clock divider %d\n", __func__,
>> + qspi->spi_max_frequency, clk_div);
>> +
>> + pm_runtime_get_sync(qspi->dev);
>> +
>> + clk_ctrl_reg = dra7xxx_readl(qspi, QSPI_SPI_CLOCK_CNTRL_REG);
>> +
>> + clk_ctrl_reg&= ~QSPI_CLK_EN;
>> +
>> + /* disable SCLK */
>> + dra7xxx_writel(qspi, clk_ctrl_reg, QSPI_SPI_CLOCK_CNTRL_REG);
>> +
>> + if (clk_div< 0) {
>> + dev_dbg(qspi->dev, "%s: clock divider< 0, using /1 divider\n",
>> + __func__);
>> + clk_div = 1;
>> + }
>> +
>> + if (clk_div> QSPI_CLK_DIV_MAX) {
>> + dev_dbg(qspi->dev, "%s: clock divider>%d , using /%d divider\n",
>> + __func__, QSPI_CLK_DIV_MAX, QSPI_CLK_DIV_MAX + 1);
>> + clk_div = QSPI_CLK_DIV_MAX;
>> + }
>> +
>> + /* enable SCLK */
>> + dra7xxx_writel(qspi, QSPI_CLK_EN | clk_div, QSPI_SPI_CLOCK_CNTRL_REG);
>> +
>> + pm_runtime_mark_last_busy(qspi->dev);
>> + pm_runtime_put_autosuspend(qspi->dev);
>> +
>> + return 0;
>> +}
>> +
>> +static int dra7xxx_qspi_prepare_xfer(struct spi_master *master)
>> +{
>> + struct dra7xxx_qspi *qspi = spi_master_get_devdata(master);
>> +
>> + pm_runtime_get_sync(qspi->dev);
> not going to check return value ?
>
>> + return 0;
>> +}
>> +
>> +static int dra7xxx_qspi_unprepare_xfer(struct spi_master *master)
>> +{
>> + struct dra7xxx_qspi *qspi = spi_master_get_devdata(master);
>> +
>> + pm_runtime_mark_last_busy(qspi->dev);
>> + pm_runtime_put_autosuspend(qspi->dev);
> what about on these two ?
>
Just realised this, pm_runtime_mark_last_busy does not need a check, it
returns nothing.
>> + return 0;
>> +}
>> +
>> +static int qspi_write_msg(struct dra7xxx_qspi *qspi, struct spi_transfer *t)
>> +{
>> + const u8 *txbuf;
>> + int wlen, count;
>> +
>> + count = t->len;
>> + txbuf = t->tx_buf;
>> + wlen = t->bits_per_word;
>> +
>> + while (count--) {
>> + dev_dbg(qspi->dev, "tx cmd %08x dc %08x data %02x\n",
>> + qspi->cmd | QSPI_WR_SNGL, qspi->dc, *txbuf);
>> + dra7xxx_writel(qspi, QSPI_WC_INT_EN, QSPI_INTR_ENABLE_SET_REG);
> you should enable the interrupt as the last step. Also, why aren't you
> using frame interrupt ?
>
>> + dra7xxx_writel_data(qspi, *txbuf++, QSPI_SPI_DATA_REG, wlen);
>> + dra7xxx_writel(qspi, qspi->dc, QSPI_SPI_DC_REG);
>> + dra7xxx_writel(qspi, qspi->cmd | QSPI_WR_SNGL,
>> + QSPI_SPI_CMD_REG);
>> + wait_for_completion(&qspi->word_complete);
>> + }
>> +
>> + return 0;
>> +}
>> +
>> +static int qspi_read_msg(struct dra7xxx_qspi *qspi, struct spi_transfer *t)
>> +{
>> + u8 *rxbuf;
>> + int wlen, count;
>> +
>> + count = t->len;
>> + rxbuf = t->rx_buf;
>> + wlen = t->bits_per_word;
>> +
>> + while (count--) {
>> + dev_dbg(qspi->dev, "rx cmd %08x dc %08x\n",
>> + qspi->cmd | QSPI_RD_SNGL, qspi->dc);
>> + dra7xxx_writel(qspi, QSPI_WC_INT_EN, QSPI_INTR_ENABLE_SET_REG);
> ditto
>
>> + dra7xxx_writel(qspi, qspi->dc, QSPI_SPI_DC_REG);
>> + dra7xxx_writel(qspi, qspi->cmd | QSPI_RD_SNGL,
>> + QSPI_SPI_CMD_REG);
>> + wait_for_completion(&qspi->word_complete);
>> + *rxbuf++ = dra7xxx_readl_data(qspi, QSPI_SPI_DATA_REG, wlen);
>> + dev_dbg(qspi->dev, "rx done, read %02x\n", *(rxbuf-1));
>> + }
>> +
>> + return 0;
>> +}
>> +
>> +static int qspi_transfer_msg(struct dra7xxx_qspi *qspi, struct spi_transfer *t)
>> +{
>> + if (t->tx_buf)
>> + qspi_write_msg(qspi, t);
>> + if (t->rx_buf)
>> + qspi_read_msg(qspi, t);
>> +
>> + return 0;
>> +}
>> +
>> +static int dra7xxx_qspi_start_transfer_one(struct spi_master *master,
>> + struct spi_message *m)
>> +{
>> + struct dra7xxx_qspi *qspi = spi_master_get_devdata(master);
>> + struct spi_device *spi = m->spi;
>> + struct spi_transfer *t;
>> + int status = 0;
>> + int frame_length;
>> +
>> + /* setup device control reg */
>> + qspi->dc = 0;
>> +
>> + if (spi->mode& SPI_CPHA)
>> + qspi->dc |= QSPI_CKPHA(spi->chip_select);
>> + if (spi->mode& SPI_CPOL)
>> + qspi->dc |= QSPI_CKPOL(spi->chip_select);
>> + if (spi->mode& SPI_CS_HIGH)
>> + qspi->dc |= QSPI_CSPOL(spi->chip_select);
>> +
>> + frame_length = DIV_ROUND_UP(m->frame_length * spi->bits_per_word,
> why this multiplication ? Frame is not counted in bits but in number of
> words. Which means that m->framelength / spi->bits_per_word should be
> enough.
>
> Also, this actually brings up a mistake I made, if I read the TRM
> correclty this time, frame length is nothing but the t->len which
> renders patch 1 in this series unnecessary, my mistake.
>
>> + spi->bits_per_word);
>> +
>> + frame_length = clamp(frame_length, 0, QSPI_FRAME_MAX);
>> +
>> + /* setup command reg */
>> + qspi->cmd = 0;
>> + qspi->cmd |= QSPI_EN_CS(spi->chip_select);
>> + qspi->cmd |= QSPI_FLEN(frame_length);
> right, right, so far so good...
>
>> + list_for_each_entry(t,&m->transfers, transfer_list) {
>> + qspi->cmd |= QSPI_WLEN(t->bits_per_word);
> sure about this ? according to TRM a write of 0 means 1 bit, 1, means 2
> bits, 2 means 3 bits, etc... So this should be t->bits_per_word - 1.
>
>> + qspi->cmd |= QSPI_WC_CMD_INT_EN;
> ... but why are you still interrupting on every word ????
>
> as I said before, we want to interrupt on every frame. one spi_transfer
> is one frame, if that frame has a length of 1MiB, I want to be
> interrupted after 1MiB.
>
>> + qspi_transfer_msg(qspi, t);
>> + m->actual_length += t->len;
>> +
>> + if (list_is_last(&t->transfer_list,&m->transfers))
>> + goto out;
>> + }
>> +
>> +out:
>> + m->status = status;
>> + spi_finalize_current_message(master);
>> +
>> + dra7xxx_writel(qspi, qspi->cmd | QSPI_INVAL, QSPI_SPI_CMD_REG);
>> +
>> + return status;
>> +}
>> +
>> +static irqreturn_t dra7xxx_qspi_isr(int irq, void *dev_id)
>> +{
>> + struct dra7xxx_qspi *qspi = dev_id;
>> + u16 mask, stat;
>> +
>> + irqreturn_t ret = IRQ_HANDLED;
>> +
>> + spin_lock(&qspi->lock);
>> +
>> + stat = dra7xxx_readl(qspi, QSPI_SPI_STATUS_REG);
>> + mask = dra7xxx_readl(qspi, QSPI_SPI_CMD_REG);
>> +
>> + if ((stat& QSPI_WC)&& (mask& QSPI_WC_CMD_INT_EN))
> this is wrong, everytime you want to handle another IRQ bit, you will
> have to update this line.
>
> if (stat& mask)
>
> sounds like it's enough
>