2018-03-30 12:53:54

by Sergey Suloev

[permalink] [raw]
Subject: [PATCH v2 0/6] spi: Add support for DMA transfers in sun6i SPI driver

The following patchset provides corrections for PIO-mode
and support for DMA transfers in sun6i SPI driver.

Changes in v2:
1) Fixed issue with misplacing a piece of code that requires access
to the transfer structure into sun6i_spi_prepare_message() function
where the transfer structure is not available.

2) Fixed issue with passing an invalid argument into devm_request_irq()
function.

Sergey Suloev (6):
spi: sun6i: coding style/readability improvements
spi: sun6i: handle chip select polarity flag
spi: sun6i: restrict transfer length in PIO-mode
spi: sun6i: use completion provided by SPI core
spi: sun6i: introduce register set/unset helpers
spi: sun6i: add DMA transfers support

drivers/spi/spi-sun6i.c | 507 ++++++++++++++++++++++++++++++++++++------------
1 file changed, 381 insertions(+), 126 deletions(-)

--
2.16.2



2018-03-30 12:52:29

by Sergey Suloev

[permalink] [raw]
Subject: [PATCH v2 2/6] spi: sun6i: handle chip select polarity flag

The chip select polarity flag is declared as supported
but is not handled in the code.

Signed-off-by: Sergey Suloev <[email protected]>

---
drivers/spi/spi-sun6i.c | 6 ++++++
1 file changed, 6 insertions(+)

diff --git a/drivers/spi/spi-sun6i.c b/drivers/spi/spi-sun6i.c
index 88ad45e..78acc1f 100644
--- a/drivers/spi/spi-sun6i.c
+++ b/drivers/spi/spi-sun6i.c
@@ -193,6 +193,12 @@ static void sun6i_spi_set_cs(struct spi_device *spi, bool enable)
else
reg &= ~SUN6I_TFR_CTL_CS_LEVEL;

+ /* Handle chip select "reverse" polarity */
+ if (spi->mode & SPI_CS_HIGH)
+ reg &= ~SUN6I_TFR_CTL_SPOL;
+ else
+ reg |= SUN6I_TFR_CTL_SPOL;
+
/* We want to control the chip select manually */
reg |= SUN6I_TFR_CTL_CS_MANUAL;

--
2.16.2


2018-03-30 12:52:42

by Sergey Suloev

[permalink] [raw]
Subject: [PATCH v2 6/6] spi: sun6i: add DMA transfers support

DMA transfers are now available for sun6i and sun8i SoCs.
The DMA mode is used automatically as soon as requested
transfer length is more than FIFO length.

Signed-off-by: Sergey Suloev <[email protected]>

---
drivers/spi/spi-sun6i.c | 296 ++++++++++++++++++++++++++++++++++++++++++++----
1 file changed, 275 insertions(+), 21 deletions(-)

diff --git a/drivers/spi/spi-sun6i.c b/drivers/spi/spi-sun6i.c
index 18f9344..5665c84 100644
--- a/drivers/spi/spi-sun6i.c
+++ b/drivers/spi/spi-sun6i.c
@@ -14,6 +14,8 @@
#include <linux/clk.h>
#include <linux/delay.h>
#include <linux/device.h>
+#include <linux/dmaengine.h>
+#include <linux/dma-mapping.h>
#include <linux/interrupt.h>
#include <linux/io.h>
#include <linux/module.h>
@@ -55,11 +57,14 @@

#define SUN6I_FIFO_CTL_REG 0x18
#define SUN6I_FIFO_CTL_RF_RDY_TRIG_LEVEL_MASK 0xff
-#define SUN6I_FIFO_CTL_RF_RDY_TRIG_LEVEL_BITS 0
+#define SUN6I_FIFO_CTL_RF_RDY_TRIG_LEVEL_POS 0
+#define SUN6I_FIFO_CTL_RF_DRQ_EN BIT(8)
#define SUN6I_FIFO_CTL_RF_RST BIT(15)
#define SUN6I_FIFO_CTL_TF_ERQ_TRIG_LEVEL_MASK 0xff
-#define SUN6I_FIFO_CTL_TF_ERQ_TRIG_LEVEL_BITS 16
+#define SUN6I_FIFO_CTL_TF_ERQ_TRIG_LEVEL_POS 16
+#define SUN6I_FIFO_CTL_TF_DRQ_EN BIT(24)
#define SUN6I_FIFO_CTL_TF_RST BIT(31)
+#define SUN6I_FIFO_CTL_DMA_DEDICATE BIT(9)|BIT(25)

#define SUN6I_FIFO_STA_REG 0x1c
#define SUN6I_FIFO_STA_RF_CNT_MASK 0x7f
@@ -177,6 +182,15 @@ static inline void sun6i_spi_fill_fifo(struct sun6i_spi *sspi, int len)
}
}

+static bool sun6i_spi_can_dma(struct spi_master *master,
+ struct spi_device *spi,
+ struct spi_transfer *tfr)
+{
+ struct sun6i_spi *sspi = spi_master_get_devdata(master);
+
+ return tfr->len > sspi->fifo_depth;
+}
+
static void sun6i_spi_set_cs(struct spi_device *spi, bool enable)
{
struct sun6i_spi *sspi = spi_master_get_devdata(spi->master);
@@ -208,6 +222,9 @@ static size_t sun6i_spi_max_transfer_size(struct spi_device *spi)
struct spi_master *master = spi->master;
struct sun6i_spi *sspi = spi_master_get_devdata(master);

+ if (master->can_dma)
+ return SUN6I_MAX_XFER_SIZE;
+
return sspi->fifo_depth;
}

@@ -268,15 +285,174 @@ static int sun6i_spi_wait_for_transfer(struct spi_device *spi,
return 0;
}

+static void sun6i_spi_dma_callback(void *param)
+{
+ struct spi_master *master = param;
+
+ dev_dbg(&master->dev, "DMA transfer complete\n");
+ spi_finalize_current_transfer(master);
+}
+
+static int sun6i_spi_dmap_prep_tx(struct spi_master *master,
+ struct spi_transfer *tfr,
+ dma_cookie_t *cookie)
+{
+ struct dma_async_tx_descriptor *chan_desc = NULL;
+
+ chan_desc = dmaengine_prep_slave_sg(master->dma_tx,
+ tfr->tx_sg.sgl, tfr->tx_sg.nents,
+ DMA_TO_DEVICE,
+ DMA_PREP_INTERRUPT | DMA_CTRL_ACK);
+ if (!chan_desc) {
+ dev_err(&master->dev,
+ "Couldn't prepare TX DMA slave\n");
+ return -EIO;
+ }
+
+ chan_desc->callback = sun6i_spi_dma_callback;
+ chan_desc->callback_param = master;
+
+ *cookie = dmaengine_submit(chan_desc);
+ dma_async_issue_pending(master->dma_tx);
+
+ return 0;
+}
+
+static int sun6i_spi_dmap_prep_rx(struct spi_master *master,
+ struct spi_transfer *tfr,
+ dma_cookie_t *cookie)
+{
+ struct dma_async_tx_descriptor *chan_desc = NULL;
+
+ chan_desc = dmaengine_prep_slave_sg(master->dma_rx,
+ tfr->rx_sg.sgl, tfr->rx_sg.nents,
+ DMA_FROM_DEVICE,
+ DMA_PREP_INTERRUPT | DMA_CTRL_ACK);
+ if (!chan_desc) {
+ dev_err(&master->dev,
+ "Couldn't prepare RX DMA slave\n");
+ return -EIO;
+ }
+
+ chan_desc->callback = sun6i_spi_dma_callback;
+ chan_desc->callback_param = master;
+
+ *cookie = dmaengine_submit(chan_desc);
+ dma_async_issue_pending(master->dma_rx);
+
+ return 0;
+}
+
+static int sun6i_spi_transfer_one_dma(struct spi_device *spi,
+ struct spi_transfer *tfr)
+{
+ struct spi_master *master = spi->master;
+ struct sun6i_spi *sspi = spi_master_get_devdata(master);
+ dma_cookie_t tx_cookie = 0,rx_cookie = 0;
+ enum dma_status status;
+ int ret;
+ u32 reg, trig_level = 0;
+
+ dev_dbg(&master->dev, "Using DMA mode for transfer\n");
+
+ reg = sun6i_spi_read(sspi, SUN6I_FIFO_CTL_REG);
+
+ if (sspi->tx_buf) {
+ ret = sun6i_spi_dmap_prep_tx(master, tfr, &tx_cookie);
+ if (ret)
+ goto out;
+
+ reg |= SUN6I_FIFO_CTL_TF_DRQ_EN;
+
+ trig_level = sspi->fifo_depth;
+ reg &= ~SUN6I_FIFO_CTL_TF_ERQ_TRIG_LEVEL_MASK;
+ reg |= (trig_level << SUN6I_FIFO_CTL_TF_ERQ_TRIG_LEVEL_POS);
+ }
+
+ if (sspi->rx_buf) {
+ ret = sun6i_spi_dmap_prep_rx(master, tfr, &rx_cookie);
+ if (ret)
+ goto out;
+
+ reg |= SUN6I_FIFO_CTL_RF_DRQ_EN;
+
+ trig_level = 1;
+ reg &= ~SUN6I_FIFO_CTL_RF_RDY_TRIG_LEVEL_MASK;
+ reg |= (trig_level << SUN6I_FIFO_CTL_RF_RDY_TRIG_LEVEL_POS);
+ }
+
+ /* Enable Dedicated DMA requests */
+ sun6i_spi_write(sspi, SUN6I_FIFO_CTL_REG,
+ reg | SUN6I_FIFO_CTL_DMA_DEDICATE);
+
+ /* Start transfer */
+ sun6i_spi_set(sspi, SUN6I_TFR_CTL_REG, SUN6I_TFR_CTL_XCH);
+
+ ret = sun6i_spi_wait_for_transfer(spi, tfr);
+ if (ret)
+ goto out;
+
+ if (sspi->tx_buf && (status = dma_async_is_tx_complete(master->dma_tx,
+ tx_cookie, NULL, NULL))) {
+ dev_warn(&master->dev,
+ "DMA returned completion status of: %s\n",
+ status == DMA_ERROR ? "error" : "in progress");
+ }
+ if (sspi->rx_buf && (status = dma_async_is_tx_complete(master->dma_rx,
+ rx_cookie, NULL, NULL))) {
+ dev_warn(&master->dev,
+ "DMA returned completion status of: %s\n",
+ status == DMA_ERROR ? "error" : "in progress");
+ }
+
+out:
+ if (ret) {
+ dev_dbg(&master->dev, "DMA channel teardown\n");
+ if (sspi->tx_buf)
+ dmaengine_terminate_sync(master->dma_tx);
+ if (sspi->rx_buf)
+ dmaengine_terminate_sync(master->dma_rx);
+ }
+
+ sun6i_spi_drain_fifo(sspi, sspi->fifo_depth);
+
+ sun6i_spi_write(sspi, SUN6I_INT_CTL_REG, 0);
+
+ return ret;
+}
+
+static int sun6i_spi_transfer_one_pio(struct spi_device *spi,
+ struct spi_transfer *tfr)
+{
+ struct spi_master *master = spi->master;
+ struct sun6i_spi *sspi = spi_master_get_devdata(master);
+ int ret;
+
+ /* Disable DMA requests */
+ sun6i_spi_write(sspi, SUN6I_FIFO_CTL_REG, 0);
+
+ sun6i_spi_fill_fifo(sspi, sspi->fifo_depth);
+
+ /* Enable transfer complete IRQ */
+ sun6i_spi_set(sspi, SUN6I_INT_CTL_REG, SUN6I_INT_CTL_TC);
+
+ /* Start transfer */
+ sun6i_spi_set(sspi, SUN6I_TFR_CTL_REG, SUN6I_TFR_CTL_XCH);
+
+ ret = sun6i_spi_wait_for_transfer(spi, tfr);
+
+ sun6i_spi_write(sspi, SUN6I_INT_CTL_REG, 0);
+
+ return ret;
+}
+
static int sun6i_spi_transfer_one(struct spi_master *master,
struct spi_device *spi,
struct spi_transfer *tfr)
{
struct sun6i_spi *sspi = spi_master_get_devdata(master);
- unsigned int mclk_rate, div, timeout;
- unsigned int start, end, tx_time;
+ unsigned int mclk_rate, div;
unsigned int tx_len = 0;
- int ret = 0;
u32 reg;

/* A zero length transfer never finishes if programmed
@@ -284,10 +460,15 @@ static int sun6i_spi_transfer_one(struct spi_master *master,
if (!tfr->len)
return 0;

- /* Don't support transfer larger than the FIFO */
- if (tfr->len > sspi->fifo_depth)
+ if (tfr->len > SUN6I_MAX_XFER_SIZE)
return -EMSGSIZE;

+ if (!master->can_dma) {
+ /* Don't support transfer larger than the FIFO */
+ if (tfr->len > sspi->fifo_depth)
+ return -EMSGSIZE;
+ }
+
sspi->tx_buf = tfr->tx_buf;
sspi->rx_buf = tfr->rx_buf;
sspi->len = tfr->len;
@@ -353,21 +534,10 @@ static int sun6i_spi_transfer_one(struct spi_master *master,
sun6i_spi_write(sspi, SUN6I_BURST_CTL_CNT_REG,
SUN6I_BURST_CTL_CNT_STC(tx_len));

- /* Fill the TX FIFO */
- sun6i_spi_fill_fifo(sspi, sspi->fifo_depth);
-
- /* Enable transfer complete interrupt */
- sun6i_spi_set(sspi, SUN6I_INT_CTL_REG, SUN6I_INT_CTL_TC);
-
- /* Start the transfer */
- sun6i_spi_set(sspi, SUN6I_TFR_CTL_REG, SUN6I_TFR_CTL_XCH);
-
- /* Wait for completion */
- ret = sun6i_spi_wait_for_transfer(spi, tfr);
-
- sun6i_spi_write(sspi, SUN6I_INT_CTL_REG, 0);
+ if (sun6i_spi_can_dma(master, spi, tfr))
+ return sun6i_spi_transfer_one_dma(spi, tfr);

- return ret;
+ return sun6i_spi_transfer_one_pio(spi, tfr);
}

static irqreturn_t sun6i_spi_handler(int irq, void *dev_id)
@@ -389,6 +559,76 @@ static irqreturn_t sun6i_spi_handler(int irq, void *dev_id)
return IRQ_NONE;
}

+static int sun6i_spi_dma_setup(struct platform_device *pdev,
+ struct resource *res)
+{
+ struct spi_master *master = platform_get_drvdata(pdev);
+ struct dma_slave_config dma_sconf;
+ int ret;
+
+ master->dma_tx = dma_request_slave_channel_reason(&pdev->dev, "tx");
+ if (IS_ERR(master->dma_tx)) {
+ dev_err(&pdev->dev, "Unable to acquire DMA TX channel\n");
+ ret = PTR_ERR(master->dma_tx);
+ goto out;
+ }
+
+ dma_sconf.direction = DMA_MEM_TO_DEV;
+ dma_sconf.src_addr_width = DMA_SLAVE_BUSWIDTH_1_BYTE;
+ dma_sconf.dst_addr_width = DMA_SLAVE_BUSWIDTH_1_BYTE;
+ dma_sconf.dst_addr = res->start + SUN6I_TXDATA_REG;
+ dma_sconf.src_maxburst = 1;
+ dma_sconf.dst_maxburst = 1;
+
+ ret = dmaengine_slave_config(master->dma_tx, &dma_sconf);
+ if (ret) {
+ dev_err(&pdev->dev, "Unable to configure DMA TX slave\n");
+ goto err_rel_tx;
+ }
+
+ master->dma_rx = dma_request_slave_channel_reason(&pdev->dev, "rx");
+ if (IS_ERR(master->dma_rx)) {
+ dev_err(&pdev->dev, "Unable to acquire DMA RX channel\n");
+ ret = PTR_ERR(master->dma_rx);
+ goto err_rel_tx;
+ }
+
+ dma_sconf.direction = DMA_DEV_TO_MEM;
+ dma_sconf.src_addr_width = DMA_SLAVE_BUSWIDTH_1_BYTE;
+ dma_sconf.dst_addr_width = DMA_SLAVE_BUSWIDTH_1_BYTE;
+ dma_sconf.src_addr = res->start + SUN6I_RXDATA_REG;
+ dma_sconf.src_maxburst = 1;
+ dma_sconf.dst_maxburst = 1;
+
+ ret = dmaengine_slave_config(master->dma_rx, &dma_sconf);
+ if (ret) {
+ dev_err(&pdev->dev, "Unable to configure DMA RX slave\n");
+ goto err_rel_rx;
+ }
+
+ /* don't set can_dma unless both channels are valid*/
+ master->can_dma = sun6i_spi_can_dma;
+
+ return 0;
+
+err_rel_rx:
+ dma_release_channel(master->dma_rx);
+err_rel_tx:
+ dma_release_channel(master->dma_tx);
+out:
+ master->dma_tx = NULL;
+ master->dma_rx = NULL;
+ return ret;
+}
+
+static void sun6i_spi_dma_release(struct spi_master *master)
+{
+ if (master->can_dma) {
+ dma_release_channel(master->dma_rx);
+ dma_release_channel(master->dma_tx);
+ }
+}
+
static int sun6i_spi_runtime_resume(struct device *dev)
{
struct spi_master *master = dev_get_drvdata(dev);
@@ -510,6 +750,15 @@ static int sun6i_spi_probe(struct platform_device *pdev)
goto err_free_master;
}

+ ret = sun6i_spi_dma_setup(pdev, res);
+ if (ret) {
+ if (ret == -EPROBE_DEFER) {
+ /* wait for the dma driver to load */
+ goto err_free_master;
+ }
+ dev_warn(&pdev->dev, "DMA transfer not supported\n");
+ }
+
/*
* This wake-up/shutdown pattern is to be able to have the
* device woken up, even if runtime_pm is disabled
@@ -536,14 +785,19 @@ err_pm_disable:
pm_runtime_disable(&pdev->dev);
sun6i_spi_runtime_suspend(&pdev->dev);
err_free_master:
+ sun6i_spi_dma_release(master);
spi_master_put(master);
return ret;
}

static int sun6i_spi_remove(struct platform_device *pdev)
{
+ struct spi_master *master = platform_get_drvdata(pdev);
+
pm_runtime_force_suspend(&pdev->dev);

+ sun6i_spi_dma_release(master);
+
return 0;
}

--
2.16.2


2018-03-30 12:53:24

by Sergey Suloev

[permalink] [raw]
Subject: [PATCH v2 3/6] spi: sun6i: restrict transfer length in PIO-mode

There is no need to handle 3/4 empty/full interrupts as
the maximum supported transfer length in PIO mode is
128 bytes for sun6i- and 64 bytes for sun8i-family SoCs.

Signed-off-by: Sergey Suloev <[email protected]>

---
drivers/spi/spi-sun6i.c | 61 ++++++++++++++-----------------------------------
1 file changed, 17 insertions(+), 44 deletions(-)

diff --git a/drivers/spi/spi-sun6i.c b/drivers/spi/spi-sun6i.c
index 78acc1f..4db1f20 100644
--- a/drivers/spi/spi-sun6i.c
+++ b/drivers/spi/spi-sun6i.c
@@ -207,7 +207,10 @@ static void sun6i_spi_set_cs(struct spi_device *spi, bool enable)

static size_t sun6i_spi_max_transfer_size(struct spi_device *spi)
{
- return SUN6I_MAX_XFER_SIZE - 1;
+ struct spi_master *master = spi->master;
+ struct sun6i_spi *sspi = spi_master_get_devdata(master);
+
+ return sspi->fifo_depth;
}

static int sun6i_spi_prepare_message(struct spi_master *master,
@@ -250,13 +253,18 @@ static int sun6i_spi_transfer_one(struct spi_master *master,
struct sun6i_spi *sspi = spi_master_get_devdata(master);
unsigned int mclk_rate, div, timeout;
unsigned int start, end, tx_time;
- unsigned int trig_level;
unsigned int tx_len = 0;
int ret = 0;
u32 reg;

- if (tfr->len > SUN6I_MAX_XFER_SIZE)
- return -EINVAL;
+ /* A zero length transfer never finishes if programmed
+ in the hardware */
+ if (!tfr->len)
+ return 0;
+
+ /* Don't support transfer larger than the FIFO */
+ if (tfr->len > sspi->fifo_depth)
+ return -EMSGSIZE;

reinit_completion(&sspi->done);
sspi->tx_buf = tfr->tx_buf;
@@ -270,17 +278,6 @@ static int sun6i_spi_transfer_one(struct spi_master *master,
sun6i_spi_write(sspi, SUN6I_FIFO_CTL_REG,
SUN6I_FIFO_CTL_RF_RST | SUN6I_FIFO_CTL_TF_RST);

- /*
- * Setup FIFO interrupt trigger level
- * Here we choose 3/4 of the full fifo depth, as it's the hardcoded
- * value used in old generation of Allwinner SPI controller.
- * (See spi-sun4i.c)
- */
- trig_level = sspi->fifo_depth / 4 * 3;
- sun6i_spi_write(sspi, SUN6I_FIFO_CTL_REG,
- (trig_level << SUN6I_FIFO_CTL_RF_RDY_TRIG_LEVEL_BITS) |
- (trig_level << SUN6I_FIFO_CTL_TF_ERQ_TRIG_LEVEL_BITS));
-

reg = sun6i_spi_read(sspi, SUN6I_TFR_CTL_REG);
/*
@@ -342,12 +339,8 @@ static int sun6i_spi_transfer_one(struct spi_master *master,
/* Fill the TX FIFO */
sun6i_spi_fill_fifo(sspi, sspi->fifo_depth);

- /* Enable the interrupts */
- sun6i_spi_write(sspi, SUN6I_INT_CTL_REG, SUN6I_INT_CTL_TC);
- sun6i_spi_enable_interrupt(sspi, SUN6I_INT_CTL_TC |
- SUN6I_INT_CTL_RF_RDY);
- if (tx_len > sspi->fifo_depth)
- sun6i_spi_enable_interrupt(sspi, SUN6I_INT_CTL_TF_ERQ);
+ /* Enable transfer complete interrupt */
+ sun6i_spi_enable_interrupt(sspi, SUN6I_INT_CTL_TC);

/* Start the transfer */
reg = sun6i_spi_read(sspi, SUN6I_TFR_CTL_REG);
@@ -376,7 +369,9 @@ out:
static irqreturn_t sun6i_spi_handler(int irq, void *dev_id)
{
struct sun6i_spi *sspi = dev_id;
- u32 status = sun6i_spi_read(sspi, SUN6I_INT_STA_REG);
+ u32 status;
+
+ status = sun6i_spi_read(sspi, SUN6I_INT_STA_REG);

/* Transfer complete */
if (status & SUN6I_INT_CTL_TC) {
@@ -386,28 +381,6 @@ static irqreturn_t sun6i_spi_handler(int irq, void *dev_id)
return IRQ_HANDLED;
}

- /* Receive FIFO 3/4 full */
- if (status & SUN6I_INT_CTL_RF_RDY) {
- sun6i_spi_drain_fifo(sspi, SUN6I_FIFO_DEPTH);
- /* Only clear the interrupt _after_ draining the FIFO */
- sun6i_spi_write(sspi, SUN6I_INT_STA_REG, SUN6I_INT_CTL_RF_RDY);
- return IRQ_HANDLED;
- }
-
- /* Transmit FIFO 3/4 empty */
- if (status & SUN6I_INT_CTL_TF_ERQ) {
- sun6i_spi_fill_fifo(sspi, SUN6I_FIFO_DEPTH);
-
- if (!sspi->len)
- /* nothing left to transmit */
- sun6i_spi_disable_interrupt(sspi, SUN6I_INT_CTL_TF_ERQ);
-
- /* Only clear the interrupt _after_ re-seeding the FIFO */
- sun6i_spi_write(sspi, SUN6I_INT_STA_REG, SUN6I_INT_CTL_TF_ERQ);
-
- return IRQ_HANDLED;
- }
-
return IRQ_NONE;
}

--
2.16.2


2018-03-30 12:53:29

by Sergey Suloev

[permalink] [raw]
Subject: [PATCH v2 5/6] spi: sun6i: introduce register set/unset helpers

Two helper functions were added in order to update registers
easily.

Signed-off-by: Sergey Suloev <[email protected]>

---
drivers/spi/spi-sun6i.c | 39 +++++++++++++++++----------------------
1 file changed, 17 insertions(+), 22 deletions(-)

diff --git a/drivers/spi/spi-sun6i.c b/drivers/spi/spi-sun6i.c
index 210cef9..18f9344 100644
--- a/drivers/spi/spi-sun6i.c
+++ b/drivers/spi/spi-sun6i.c
@@ -115,29 +115,29 @@ static inline void sun6i_spi_write(struct sun6i_spi *sspi, u32 reg, u32 value)
writel(value, sspi->base_addr + reg);
}

-static inline u32 sun6i_spi_get_tx_fifo_count(struct sun6i_spi *sspi)
+static inline void sun6i_spi_set(struct sun6i_spi *sspi, u32 addr, u32 val)
{
- u32 reg = sun6i_spi_read(sspi, SUN6I_FIFO_STA_REG);
-
- reg >>= SUN6I_FIFO_STA_TF_CNT_BITS;
+ u32 reg = sun6i_spi_read(sspi, addr);

- return reg & SUN6I_FIFO_STA_TF_CNT_MASK;
+ reg |= val;
+ sun6i_spi_write(sspi, addr, reg);
}

-static inline void sun6i_spi_enable_interrupt(struct sun6i_spi *sspi, u32 mask)
+static inline void sun6i_spi_unset(struct sun6i_spi *sspi, u32 addr, u32 val)
{
- u32 reg = sun6i_spi_read(sspi, SUN6I_INT_CTL_REG);
+ u32 reg = sun6i_spi_read(sspi, addr);

- reg |= mask;
- sun6i_spi_write(sspi, SUN6I_INT_CTL_REG, reg);
+ reg &= ~val;
+ sun6i_spi_write(sspi, addr, reg);
}

-static inline void sun6i_spi_disable_interrupt(struct sun6i_spi *sspi, u32 mask)
+static inline u32 sun6i_spi_get_tx_fifo_count(struct sun6i_spi *sspi)
{
- u32 reg = sun6i_spi_read(sspi, SUN6I_INT_CTL_REG);
+ u32 reg = sun6i_spi_read(sspi, SUN6I_FIFO_STA_REG);

- reg &= ~mask;
- sun6i_spi_write(sspi, SUN6I_INT_CTL_REG, reg);
+ reg >>= SUN6I_FIFO_STA_TF_CNT_BITS;
+
+ return reg & SUN6I_FIFO_STA_TF_CNT_MASK;
}

static inline void sun6i_spi_drain_fifo(struct sun6i_spi *sspi, int len)
@@ -299,18 +299,14 @@ static int sun6i_spi_transfer_one(struct spi_master *master,
sun6i_spi_write(sspi, SUN6I_FIFO_CTL_REG,
SUN6I_FIFO_CTL_RF_RST | SUN6I_FIFO_CTL_TF_RST);

-
- reg = sun6i_spi_read(sspi, SUN6I_TFR_CTL_REG);
/*
* If it's a TX only transfer, we don't want to fill the RX
* FIFO with bogus data
*/
if (sspi->rx_buf)
- reg &= ~SUN6I_TFR_CTL_DHB;
+ sun6i_spi_unset(sspi, SUN6I_TFR_CTL_REG, SUN6I_TFR_CTL_DHB);
else
- reg |= SUN6I_TFR_CTL_DHB;
-
- sun6i_spi_write(sspi, SUN6I_TFR_CTL_REG, reg);
+ sun6i_spi_set(sspi, SUN6I_TFR_CTL_REG, SUN6I_TFR_CTL_DHB);


/* Ensure that we have a parent clock fast enough */
@@ -361,11 +357,10 @@ static int sun6i_spi_transfer_one(struct spi_master *master,
sun6i_spi_fill_fifo(sspi, sspi->fifo_depth);

/* Enable transfer complete interrupt */
- sun6i_spi_enable_interrupt(sspi, SUN6I_INT_CTL_TC);
+ sun6i_spi_set(sspi, SUN6I_INT_CTL_REG, SUN6I_INT_CTL_TC);

/* Start the transfer */
- reg = sun6i_spi_read(sspi, SUN6I_TFR_CTL_REG);
- sun6i_spi_write(sspi, SUN6I_TFR_CTL_REG, reg | SUN6I_TFR_CTL_XCH);
+ sun6i_spi_set(sspi, SUN6I_TFR_CTL_REG, SUN6I_TFR_CTL_XCH);

/* Wait for completion */
ret = sun6i_spi_wait_for_transfer(spi, tfr);
--
2.16.2


2018-03-30 12:53:55

by Sergey Suloev

[permalink] [raw]
Subject: [PATCH v2 1/6] spi: sun6i: coding style/readability improvements

Minor changes to fulfill the coding style and improve
the readability of the code.

Changes in v2:
1) Fixed issue with misplacing a piece of code that requires access
to the transfer structure into sun6i_spi_prepare_message() function
where the transfer structure is not available.

Signed-off-by: Sergey Suloev <[email protected]>

---
drivers/spi/spi-sun6i.c | 97 +++++++++++++++++++++++++++++--------------------
1 file changed, 58 insertions(+), 39 deletions(-)

diff --git a/drivers/spi/spi-sun6i.c b/drivers/spi/spi-sun6i.c
index 8533f4e..88ad45e 100644
--- a/drivers/spi/spi-sun6i.c
+++ b/drivers/spi/spi-sun6i.c
@@ -88,8 +88,12 @@
#define SUN6I_TXDATA_REG 0x200
#define SUN6I_RXDATA_REG 0x300

+#define SUN6I_SPI_MODE_BITS (SPI_CPOL | SPI_CPHA | SPI_CS_HIGH | SPI_LSB_FIRST)
+
+#define SUN6I_SPI_MAX_SPEED_HZ 100000000
+#define SUN6I_SPI_MIN_SPEED_HZ 3000
+
struct sun6i_spi {
- struct spi_master *master;
void __iomem *base_addr;
struct clk *hclk;
struct clk *mclk;
@@ -189,6 +193,9 @@ static void sun6i_spi_set_cs(struct spi_device *spi, bool enable)
else
reg &= ~SUN6I_TFR_CTL_CS_LEVEL;

+ /* We want to control the chip select manually */
+ reg |= SUN6I_TFR_CTL_CS_MANUAL;
+
sun6i_spi_write(sspi, SUN6I_TFR_CTL_REG, reg);
}

@@ -197,6 +204,39 @@ static size_t sun6i_spi_max_transfer_size(struct spi_device *spi)
return SUN6I_MAX_XFER_SIZE - 1;
}

+static int sun6i_spi_prepare_message(struct spi_master *master,
+ struct spi_message *msg)
+{
+ struct spi_device *spi = msg->spi;
+ struct sun6i_spi *sspi = spi_master_get_devdata(master);
+ u32 reg;
+
+ /*
+ * Setup the transfer control register: Chip Select,
+ * polarities, etc.
+ */
+ reg = sun6i_spi_read(sspi, SUN6I_TFR_CTL_REG);
+
+ if (spi->mode & SPI_CPOL)
+ reg |= SUN6I_TFR_CTL_CPOL;
+ else
+ reg &= ~SUN6I_TFR_CTL_CPOL;
+
+ if (spi->mode & SPI_CPHA)
+ reg |= SUN6I_TFR_CTL_CPHA;
+ else
+ reg &= ~SUN6I_TFR_CTL_CPHA;
+
+ if (spi->mode & SPI_LSB_FIRST)
+ reg |= SUN6I_TFR_CTL_FBS;
+ else
+ reg &= ~SUN6I_TFR_CTL_FBS;
+
+ sun6i_spi_write(sspi, SUN6I_TFR_CTL_REG, reg);
+
+ return 0;
+}
+
static int sun6i_spi_transfer_one(struct spi_master *master,
struct spi_device *spi,
struct spi_transfer *tfr)
@@ -235,27 +275,8 @@ static int sun6i_spi_transfer_one(struct spi_master *master,
(trig_level << SUN6I_FIFO_CTL_RF_RDY_TRIG_LEVEL_BITS) |
(trig_level << SUN6I_FIFO_CTL_TF_ERQ_TRIG_LEVEL_BITS));

- /*
- * Setup the transfer control register: Chip Select,
- * polarities, etc.
- */
- reg = sun6i_spi_read(sspi, SUN6I_TFR_CTL_REG);
-
- if (spi->mode & SPI_CPOL)
- reg |= SUN6I_TFR_CTL_CPOL;
- else
- reg &= ~SUN6I_TFR_CTL_CPOL;
-
- if (spi->mode & SPI_CPHA)
- reg |= SUN6I_TFR_CTL_CPHA;
- else
- reg &= ~SUN6I_TFR_CTL_CPHA;
-
- if (spi->mode & SPI_LSB_FIRST)
- reg |= SUN6I_TFR_CTL_FBS;
- else
- reg &= ~SUN6I_TFR_CTL_FBS;

+ reg = sun6i_spi_read(sspi, SUN6I_TFR_CTL_REG);
/*
* If it's a TX only transfer, we don't want to fill the RX
* FIFO with bogus data
@@ -265,11 +286,9 @@ static int sun6i_spi_transfer_one(struct spi_master *master,
else
reg |= SUN6I_TFR_CTL_DHB;

- /* We want to control the chip select manually */
- reg |= SUN6I_TFR_CTL_CS_MANUAL;
-
sun6i_spi_write(sspi, SUN6I_TFR_CTL_REG, reg);

+
/* Ensure that we have a parent clock fast enough */
mclk_rate = clk_get_rate(sspi->mclk);
if (mclk_rate < (2 * tfr->speed_hz)) {
@@ -442,12 +461,24 @@ static int sun6i_spi_probe(struct platform_device *pdev)
struct resource *res;
int ret = 0, irq;

- master = spi_alloc_master(&pdev->dev, sizeof(struct sun6i_spi));
+ master = spi_alloc_master(&pdev->dev, sizeof(*sspi));
if (!master) {
dev_err(&pdev->dev, "Unable to allocate SPI Master\n");
return -ENOMEM;
}

+ master->max_speed_hz = SUN6I_SPI_MAX_SPEED_HZ;
+ master->min_speed_hz = SUN6I_SPI_MIN_SPEED_HZ;
+ master->num_chipselect = 4;
+ master->mode_bits = SUN6I_SPI_MODE_BITS;
+ master->bits_per_word_mask = SPI_BPW_MASK(8);
+ master->set_cs = sun6i_spi_set_cs;
+ master->prepare_message = sun6i_spi_prepare_message;
+ master->transfer_one = sun6i_spi_transfer_one;
+ master->max_transfer_size = sun6i_spi_max_transfer_size;
+ master->dev.of_node = pdev->dev.of_node;
+ master->auto_runtime_pm = true;
+
platform_set_drvdata(pdev, master);
sspi = spi_master_get_devdata(master);

@@ -466,26 +497,14 @@ static int sun6i_spi_probe(struct platform_device *pdev)
}

ret = devm_request_irq(&pdev->dev, irq, sun6i_spi_handler,
- 0, "sun6i-spi", sspi);
+ 0, dev_name(&pdev->dev), sspi);
if (ret) {
dev_err(&pdev->dev, "Cannot request IRQ\n");
goto err_free_master;
}

- sspi->master = master;
sspi->fifo_depth = (unsigned long)of_device_get_match_data(&pdev->dev);

- master->max_speed_hz = 100 * 1000 * 1000;
- master->min_speed_hz = 3 * 1000;
- master->set_cs = sun6i_spi_set_cs;
- master->transfer_one = sun6i_spi_transfer_one;
- master->num_chipselect = 4;
- master->mode_bits = SPI_CPOL | SPI_CPHA | SPI_CS_HIGH | SPI_LSB_FIRST;
- master->bits_per_word_mask = SPI_BPW_MASK(8);
- master->dev.of_node = pdev->dev.of_node;
- master->auto_runtime_pm = true;
- master->max_transfer_size = sun6i_spi_max_transfer_size;
-
sspi->hclk = devm_clk_get(&pdev->dev, "ahb");
if (IS_ERR(sspi->hclk)) {
dev_err(&pdev->dev, "Unable to acquire AHB clock\n");
@@ -525,7 +544,7 @@ static int sun6i_spi_probe(struct platform_device *pdev)

ret = devm_spi_register_master(&pdev->dev, master);
if (ret) {
- dev_err(&pdev->dev, "cannot register SPI master\n");
+ dev_err(&pdev->dev, "Couldn't register SPI master\n");
goto err_pm_disable;
}

--
2.16.2


2018-03-30 12:53:57

by Sergey Suloev

[permalink] [raw]
Subject: [PATCH v2 4/6] spi: sun6i: use completion provided by SPI core

As long as the completion is already provided by the SPI core
then there is no need to waste extra-memory on this.
Also a waiting function was added to avoid code duplication.

Changes in v2:
1) Fixed issue with passing an invalid argument into devm_request_irq()
function.

Signed-off-by: Sergey Suloev <[email protected]>

---
drivers/spi/spi-sun6i.c | 52 ++++++++++++++++++++++++++++---------------------
1 file changed, 30 insertions(+), 22 deletions(-)

diff --git a/drivers/spi/spi-sun6i.c b/drivers/spi/spi-sun6i.c
index 4db1f20..210cef9 100644
--- a/drivers/spi/spi-sun6i.c
+++ b/drivers/spi/spi-sun6i.c
@@ -99,8 +99,6 @@ struct sun6i_spi {
struct clk *mclk;
struct reset_control *rstc;

- struct completion done;
-
const u8 *tx_buf;
u8 *rx_buf;
int len;
@@ -246,6 +244,30 @@ static int sun6i_spi_prepare_message(struct spi_master *master,
return 0;
}

+static int sun6i_spi_wait_for_transfer(struct spi_device *spi,
+ struct spi_transfer *tfr)
+{
+ struct spi_master *master = spi->master;
+ unsigned int start, end, tx_time;
+ unsigned int timeout;
+
+ /* smart wait for completion */
+ tx_time = max(tfr->len * 8 * 2 / (tfr->speed_hz / 1000), 100U);
+ start = jiffies;
+ timeout = wait_for_completion_timeout(&master->xfer_completion,
+ msecs_to_jiffies(tx_time));
+ end = jiffies;
+ if (!timeout) {
+ dev_warn(&master->dev,
+ "%s: timeout transferring %u bytes@%iHz for %i(%i)ms",
+ dev_name(&spi->dev), tfr->len, tfr->speed_hz,
+ jiffies_to_msecs(end - start), tx_time);
+ return -ETIMEDOUT;
+ }
+
+ return 0;
+}
+
static int sun6i_spi_transfer_one(struct spi_master *master,
struct spi_device *spi,
struct spi_transfer *tfr)
@@ -266,7 +288,6 @@ static int sun6i_spi_transfer_one(struct spi_master *master,
if (tfr->len > sspi->fifo_depth)
return -EMSGSIZE;

- reinit_completion(&sspi->done);
sspi->tx_buf = tfr->tx_buf;
sspi->rx_buf = tfr->rx_buf;
sspi->len = tfr->len;
@@ -346,21 +367,9 @@ static int sun6i_spi_transfer_one(struct spi_master *master,
reg = sun6i_spi_read(sspi, SUN6I_TFR_CTL_REG);
sun6i_spi_write(sspi, SUN6I_TFR_CTL_REG, reg | SUN6I_TFR_CTL_XCH);

- tx_time = max(tfr->len * 8 * 2 / (tfr->speed_hz / 1000), 100U);
- start = jiffies;
- timeout = wait_for_completion_timeout(&sspi->done,
- msecs_to_jiffies(tx_time));
- end = jiffies;
- if (!timeout) {
- dev_warn(&master->dev,
- "%s: timeout transferring %u bytes@%iHz for %i(%i)ms",
- dev_name(&spi->dev), tfr->len, tfr->speed_hz,
- jiffies_to_msecs(end - start), tx_time);
- ret = -ETIMEDOUT;
- goto out;
- }
+ /* Wait for completion */
+ ret = sun6i_spi_wait_for_transfer(spi, tfr);

-out:
sun6i_spi_write(sspi, SUN6I_INT_CTL_REG, 0);

return ret;
@@ -368,7 +377,8 @@ out:

static irqreturn_t sun6i_spi_handler(int irq, void *dev_id)
{
- struct sun6i_spi *sspi = dev_id;
+ struct spi_master *master = dev_id;
+ struct sun6i_spi *sspi = spi_master_get_devdata(master);
u32 status;

status = sun6i_spi_read(sspi, SUN6I_INT_STA_REG);
@@ -377,7 +387,7 @@ static irqreturn_t sun6i_spi_handler(int irq, void *dev_id)
if (status & SUN6I_INT_CTL_TC) {
sun6i_spi_write(sspi, SUN6I_INT_STA_REG, SUN6I_INT_CTL_TC);
sun6i_spi_drain_fifo(sspi, sspi->fifo_depth);
- complete(&sspi->done);
+ spi_finalize_current_transfer(master);
return IRQ_HANDLED;
}

@@ -476,7 +486,7 @@ static int sun6i_spi_probe(struct platform_device *pdev)
}

ret = devm_request_irq(&pdev->dev, irq, sun6i_spi_handler,
- 0, dev_name(&pdev->dev), sspi);
+ 0, dev_name(&pdev->dev), master);
if (ret) {
dev_err(&pdev->dev, "Cannot request IRQ\n");
goto err_free_master;
@@ -498,8 +508,6 @@ static int sun6i_spi_probe(struct platform_device *pdev)
goto err_free_master;
}

- init_completion(&sspi->done);
-
sspi->rstc = devm_reset_control_get_exclusive(&pdev->dev, NULL);
if (IS_ERR(sspi->rstc)) {
dev_err(&pdev->dev, "Couldn't get reset controller\n");
--
2.16.2


2018-05-17 16:38:22

by Mark Brown

[permalink] [raw]
Subject: Re: [PATCH v2 3/6] spi: sun6i: restrict transfer length in PIO-mode

On Fri, Mar 30, 2018 at 03:50:44PM +0300, Sergey Suloev wrote:

> There is no need to handle 3/4 empty/full interrupts as
> the maximum supported transfer length in PIO mode is
> 128 bytes for sun6i- and 64 bytes for sun8i-family SoCs.

Surely the whole point of the 3/4 full interrupts is to allow the FIFO
to be refilled and enable longer transfers?


Attachments:
(No filename) (360.00 B)
signature.asc (499.00 B)
Download all attachments

2018-05-17 16:46:47

by Mark Brown

[permalink] [raw]
Subject: Re: [PATCH v2 1/6] spi: sun6i: coding style/readability improvements

On Fri, Mar 30, 2018 at 03:50:42PM +0300, Sergey Suloev wrote:
> Minor changes to fulfill the coding style and improve
> the readability of the code.
>
> Changes in v2:
> 1) Fixed issue with misplacing a piece of code that requires access
> to the transfer structure into sun6i_spi_prepare_message() function
> where the transfer structure is not available.

Place inter-version changelogs after the --- as covered in
SubmittingPatches.

>
> Signed-off-by: Sergey Suloev <[email protected]>
>
> ---
> drivers/spi/spi-sun6i.c | 97 +++++++++++++++++++++++++++++--------------------

This is a *very* large change doing a whole bunch of different things,
including some fairly substantial changes like moving things into
different functions but the changelog doesn't provide any details at all
on what the changes are supposed to be. This makes it difficult to
review, it should be split into separate patches each doing one clerly
described thing (I'm guessing this might be part of why the AllWinner
maintainers haven't reviewed the series).


Attachments:
(No filename) (1.05 kB)
signature.asc (499.00 B)
Download all attachments

2018-05-17 16:49:26

by Mark Brown

[permalink] [raw]
Subject: Re: [PATCH v2 2/6] spi: sun6i: handle chip select polarity flag

On Fri, Mar 30, 2018 at 03:50:43PM +0300, Sergey Suloev wrote:
> The chip select polarity flag is declared as supported
> but is not handled in the code.

This is more of a fix and should really have come before the cosmetic
changes in patch 1. In general it's best to put fixes fist in a series
unless there's a strong reason to do something else, that makes it
easier to get the fixes in without them getting caught by review issues
with other code.


Attachments:
(No filename) (462.00 B)
signature.asc (499.00 B)
Download all attachments

2018-05-18 14:30:33

by Maxime Ripard

[permalink] [raw]
Subject: Re: [PATCH v2 1/6] spi: sun6i: coding style/readability improvements

Hi,

On Thu, May 17, 2018 at 04:03:07PM +0900, Mark Brown wrote:
> On Fri, Mar 30, 2018 at 03:50:42PM +0300, Sergey Suloev wrote:
> > Minor changes to fulfill the coding style and improve
> > the readability of the code.
> >
> > Changes in v2:
> > 1) Fixed issue with misplacing a piece of code that requires access
> > to the transfer structure into sun6i_spi_prepare_message() function
> > where the transfer structure is not available.
>
> Place inter-version changelogs after the --- as covered in
> SubmittingPatches.
>
> >
> > Signed-off-by: Sergey Suloev <[email protected]>
> >
> > ---
> > drivers/spi/spi-sun6i.c | 97 +++++++++++++++++++++++++++++--------------------
>
> This is a *very* large change doing a whole bunch of different things,
> including some fairly substantial changes like moving things into
> different functions but the changelog doesn't provide any details at all
> on what the changes are supposed to be. This makes it difficult to
> review, it should be split into separate patches each doing one clerly
> described thing (I'm guessing this might be part of why the AllWinner
> maintainers haven't reviewed the series).

We didn't really review them because most of the changes done here
were also applicable to the sun4i series that was sent pretty much at
the same time:
http://lists.infradead.org/pipermail/linux-arm-kernel/2018-April/570056.html

We should have made that clearer, sorry.

Maxime

--
Maxime Ripard, Bootlin (formerly Free Electrons)
Embedded Linux and Kernel engineering
https://bootlin.com


Attachments:
(No filename) (1.56 kB)
signature.asc (849.00 B)
Download all attachments