linux-i2c.vger.kernel.org archive mirror
 help / color / mirror / Atom feed
* [PATCH V12 1/5] i2c: tegra: sort all the include headers alphabetically
@ 2019-02-05 22:46 Sowjanya Komatineni
  2019-02-05 22:46 ` [PATCH V12 2/5] i2c: tegra: add bus clear Master Support Sowjanya Komatineni
                   ` (3 more replies)
  0 siblings, 4 replies; 35+ messages in thread
From: Sowjanya Komatineni @ 2019-02-05 22:46 UTC (permalink / raw)
  To: thierry.reding, jonathanh, mkarthik, smohammed, talho
  Cc: digetx, linux-tegra, linux-kernel, linux-i2c, Sowjanya Komatineni

This patch sorts all the include headers alphabetically for the
I2C Tegra driver.

Acked-by: Thierry Reding <treding@nvidia.com>
Reviewed-by: Dmitry Osipenko <digetx@gmail.com>
Signed-off-by: Sowjanya Komatineni <skomatineni@nvidia.com>
---
 [V9/V10/V11/V12] : Rebased to 5.0-rc4
 [V3/V4/V5/V7/V8] : Removed unsued headers in tegra I2C
 [V2] 		  : Added this in V2 to sort the headers in tegra I2C

 drivers/i2c/busses/i2c-tegra.c | 19 ++++++++-----------
 1 file changed, 8 insertions(+), 11 deletions(-)

diff --git a/drivers/i2c/busses/i2c-tegra.c b/drivers/i2c/busses/i2c-tegra.c
index c77adbbea0c7..79c6aa87499b 100644
--- a/drivers/i2c/busses/i2c-tegra.c
+++ b/drivers/i2c/busses/i2c-tegra.c
@@ -6,24 +6,21 @@
  * Author: Colin Cross <ccross@android.com>
  */
 
-#include <linux/kernel.h>
-#include <linux/init.h>
-#include <linux/platform_device.h>
 #include <linux/clk.h>
+#include <linux/delay.h>
 #include <linux/err.h>
 #include <linux/i2c.h>
-#include <linux/io.h>
+#include <linux/init.h>
 #include <linux/interrupt.h>
-#include <linux/delay.h>
-#include <linux/slab.h>
-#include <linux/of_device.h>
+#include <linux/io.h>
+#include <linux/iopoll.h>
+#include <linux/kernel.h>
 #include <linux/module.h>
-#include <linux/reset.h>
+#include <linux/of_device.h>
 #include <linux/pinctrl/consumer.h>
+#include <linux/platform_device.h>
 #include <linux/pm_runtime.h>
-#include <linux/iopoll.h>
-
-#include <asm/unaligned.h>
+#include <linux/reset.h>
 
 #define TEGRA_I2C_TIMEOUT (msecs_to_jiffies(1000))
 #define BYTES_PER_FIFO_WORD 4
-- 
2.7.4

^ permalink raw reply related	[flat|nested] 35+ messages in thread

* [PATCH V12 2/5] i2c: tegra: add bus clear Master Support
  2019-02-05 22:46 [PATCH V12 1/5] i2c: tegra: sort all the include headers alphabetically Sowjanya Komatineni
@ 2019-02-05 22:46 ` Sowjanya Komatineni
  2019-02-05 22:46 ` [PATCH V12 3/5] i2c: tegra: Add DMA support Sowjanya Komatineni
                   ` (2 subsequent siblings)
  3 siblings, 0 replies; 35+ messages in thread
From: Sowjanya Komatineni @ 2019-02-05 22:46 UTC (permalink / raw)
  To: thierry.reding, jonathanh, mkarthik, smohammed, talho
  Cc: digetx, linux-tegra, linux-kernel, linux-i2c, Sowjanya Komatineni

Bus clear feature of Tegra I2C controller helps to recover from
bus hang when I2C master loses the bus arbitration due to the
slave device holding SDA LOW continuously for some unknown reasons.

Per I2C specification, the device that held the bus LOW should
release it within 9 clock pulses.

During bus clear operation, Tegra I2C controller sends 9 clock
pulses and terminates the transaction with STOP condition.
Upon successful bus clear operation, bus goes to idle state and
driver retries the transaction.

Acked-by: Thierry Reding <treding@nvidia.com>
Reviewed-by: Dmitry Osipenko <digetx@gmail.com>
Signed-off-by: Sowjanya Komatineni <skomatineni@nvidia.com>
---
 [V9/V10/V11/V12] : Rebased to 5.0-rc4
 [V5/V6/V7/V8]	  : Same as V4
 [V4]		  : Added I2C Bus Clear support patch to this version of series.

 drivers/i2c/busses/i2c-tegra.c | 73 ++++++++++++++++++++++++++++++++++++++++++
 1 file changed, 73 insertions(+)

diff --git a/drivers/i2c/busses/i2c-tegra.c b/drivers/i2c/busses/i2c-tegra.c
index 79c6aa87499b..118b7023a0f4 100644
--- a/drivers/i2c/busses/i2c-tegra.c
+++ b/drivers/i2c/busses/i2c-tegra.c
@@ -51,6 +51,7 @@
 #define I2C_FIFO_STATUS_RX_SHIFT		0
 #define I2C_INT_MASK				0x064
 #define I2C_INT_STATUS				0x068
+#define I2C_INT_BUS_CLR_DONE			BIT(11)
 #define I2C_INT_PACKET_XFER_COMPLETE		BIT(7)
 #define I2C_INT_ALL_PACKETS_XFER_COMPLETE	BIT(6)
 #define I2C_INT_TX_FIFO_OVERFLOW		BIT(5)
@@ -93,6 +94,15 @@
 #define I2C_HEADER_MASTER_ADDR_SHIFT		12
 #define I2C_HEADER_SLAVE_ADDR_SHIFT		1
 
+#define I2C_BUS_CLEAR_CNFG			0x084
+#define I2C_BC_SCLK_THRESHOLD			9
+#define I2C_BC_SCLK_THRESHOLD_SHIFT		16
+#define I2C_BC_STOP_COND			BIT(2)
+#define I2C_BC_TERMINATE			BIT(1)
+#define I2C_BC_ENABLE				BIT(0)
+#define I2C_BUS_CLEAR_STATUS			0x088
+#define I2C_BC_STATUS				BIT(0)
+
 #define I2C_CONFIG_LOAD				0x08C
 #define I2C_MSTR_CONFIG_LOAD			BIT(0)
 #define I2C_SLV_CONFIG_LOAD			BIT(1)
@@ -154,6 +164,8 @@ enum msg_end_type {
  *		be transferred in one go.
  * @quirks: i2c adapter quirks for limiting write/read transfer size and not
  *		allowing 0 length transfers.
+ * @supports_bus_clear: Bus Clear support to recover from bus hang during
+ *		SDA stuck low from device for some unknown reasons.
  */
 struct tegra_i2c_hw_feature {
 	bool has_continue_xfer_support;
@@ -167,6 +179,7 @@ struct tegra_i2c_hw_feature {
 	bool has_slcg_override_reg;
 	bool has_mst_fifo;
 	const struct i2c_adapter_quirks *quirks;
+	bool supports_bus_clear;
 };
 
 /**
@@ -640,6 +653,13 @@ static irqreturn_t tegra_i2c_isr(int irq, void *dev_id)
 		goto err;
 	}
 
+	/*
+	 * I2C transfer is terminated during the bus clear so skip
+	 * processing the other interrupts.
+	 */
+	if (i2c_dev->hw->supports_bus_clear && (status & I2C_INT_BUS_CLR_DONE))
+		goto err;
+
 	if (i2c_dev->msg_read && (status & I2C_INT_RX_FIFO_DATA_REQ)) {
 		if (i2c_dev->msg_buf_remaining)
 			tegra_i2c_empty_rx_fifo(i2c_dev);
@@ -668,6 +688,8 @@ static irqreturn_t tegra_i2c_isr(int irq, void *dev_id)
 	tegra_i2c_mask_irq(i2c_dev, I2C_INT_NO_ACK | I2C_INT_ARBITRATION_LOST |
 		I2C_INT_PACKET_XFER_COMPLETE | I2C_INT_TX_FIFO_DATA_REQ |
 		I2C_INT_RX_FIFO_DATA_REQ);
+	if (i2c_dev->hw->supports_bus_clear)
+		tegra_i2c_mask_irq(i2c_dev, I2C_INT_BUS_CLR_DONE);
 	i2c_writel(i2c_dev, status, I2C_INT_STATUS);
 	if (i2c_dev->is_dvc)
 		dvc_writel(i2c_dev, DVC_STATUS_I2C_DONE_INTR, DVC_STATUS);
@@ -678,6 +700,43 @@ static irqreturn_t tegra_i2c_isr(int irq, void *dev_id)
 	return IRQ_HANDLED;
 }
 
+static int tegra_i2c_issue_bus_clear(struct tegra_i2c_dev *i2c_dev)
+{
+	int err;
+	unsigned long time_left;
+	u32 reg;
+
+	if (i2c_dev->hw->supports_bus_clear) {
+		reinit_completion(&i2c_dev->msg_complete);
+		reg = (I2C_BC_SCLK_THRESHOLD << I2C_BC_SCLK_THRESHOLD_SHIFT) |
+		      I2C_BC_STOP_COND | I2C_BC_TERMINATE;
+		i2c_writel(i2c_dev, reg, I2C_BUS_CLEAR_CNFG);
+		if (i2c_dev->hw->has_config_load_reg) {
+			err = tegra_i2c_wait_for_config_load(i2c_dev);
+			if (err)
+				return err;
+		}
+		reg |= I2C_BC_ENABLE;
+		i2c_writel(i2c_dev, reg, I2C_BUS_CLEAR_CNFG);
+		tegra_i2c_unmask_irq(i2c_dev, I2C_INT_BUS_CLR_DONE);
+
+		time_left = wait_for_completion_timeout(&i2c_dev->msg_complete,
+							TEGRA_I2C_TIMEOUT);
+		if (time_left == 0) {
+			dev_err(i2c_dev->dev, "timed out for bus clear\n");
+			return -ETIMEDOUT;
+		}
+		reg = i2c_readl(i2c_dev, I2C_BUS_CLEAR_STATUS);
+		if (!(reg & I2C_BC_STATUS)) {
+			dev_err(i2c_dev->dev,
+				"Un-recovered arbitration lost\n");
+			return -EIO;
+		}
+	}
+
+	return -EAGAIN;
+}
+
 static int tegra_i2c_xfer_msg(struct tegra_i2c_dev *i2c_dev,
 	struct i2c_msg *msg, enum msg_end_type end_state)
 {
@@ -759,6 +818,13 @@ static int tegra_i2c_xfer_msg(struct tegra_i2c_dev *i2c_dev,
 		return 0;
 
 	tegra_i2c_init(i2c_dev);
+	/* start recovery upon arbitration loss in single master mode */
+	if (i2c_dev->msg_err == I2C_ERR_ARBITRATION_LOST) {
+		if (!i2c_dev->is_multimaster_mode)
+			return tegra_i2c_issue_bus_clear(i2c_dev);
+		return -EAGAIN;
+	}
+
 	if (i2c_dev->msg_err == I2C_ERR_NO_ACK) {
 		if (msg->flags & I2C_M_IGNORE_NAK)
 			return 0;
@@ -853,6 +919,7 @@ static const struct tegra_i2c_hw_feature tegra20_i2c_hw = {
 	.has_slcg_override_reg = false,
 	.has_mst_fifo = false,
 	.quirks = &tegra_i2c_quirks,
+	.supports_bus_clear = false,
 };
 
 static const struct tegra_i2c_hw_feature tegra30_i2c_hw = {
@@ -867,6 +934,7 @@ static const struct tegra_i2c_hw_feature tegra30_i2c_hw = {
 	.has_slcg_override_reg = false,
 	.has_mst_fifo = false,
 	.quirks = &tegra_i2c_quirks,
+	.supports_bus_clear = false,
 };
 
 static const struct tegra_i2c_hw_feature tegra114_i2c_hw = {
@@ -881,6 +949,7 @@ static const struct tegra_i2c_hw_feature tegra114_i2c_hw = {
 	.has_slcg_override_reg = false,
 	.has_mst_fifo = false,
 	.quirks = &tegra_i2c_quirks,
+	.supports_bus_clear = true,
 };
 
 static const struct tegra_i2c_hw_feature tegra124_i2c_hw = {
@@ -895,6 +964,7 @@ static const struct tegra_i2c_hw_feature tegra124_i2c_hw = {
 	.has_slcg_override_reg = true,
 	.has_mst_fifo = false,
 	.quirks = &tegra_i2c_quirks,
+	.supports_bus_clear = true,
 };
 
 static const struct tegra_i2c_hw_feature tegra210_i2c_hw = {
@@ -909,6 +979,7 @@ static const struct tegra_i2c_hw_feature tegra210_i2c_hw = {
 	.has_slcg_override_reg = true,
 	.has_mst_fifo = false,
 	.quirks = &tegra_i2c_quirks,
+	.supports_bus_clear = true,
 };
 
 static const struct tegra_i2c_hw_feature tegra194_i2c_hw = {
@@ -923,6 +994,7 @@ static const struct tegra_i2c_hw_feature tegra194_i2c_hw = {
 	.has_slcg_override_reg = true,
 	.has_mst_fifo = true,
 	.quirks = &tegra194_i2c_quirks,
+	.supports_bus_clear = true,
 };
 
 /* Match table for of_platform binding */
@@ -974,6 +1046,7 @@ static int tegra_i2c_probe(struct platform_device *pdev)
 	i2c_dev->base = base;
 	i2c_dev->div_clk = div_clk;
 	i2c_dev->adapter.algo = &tegra_i2c_algo;
+	i2c_dev->adapter.retries = 1;
 	i2c_dev->irq = irq;
 	i2c_dev->cont_id = pdev->id;
 	i2c_dev->dev = &pdev->dev;
-- 
2.7.4

^ permalink raw reply related	[flat|nested] 35+ messages in thread

* [PATCH V12 3/5] i2c: tegra: Add DMA support
  2019-02-05 22:46 [PATCH V12 1/5] i2c: tegra: sort all the include headers alphabetically Sowjanya Komatineni
  2019-02-05 22:46 ` [PATCH V12 2/5] i2c: tegra: add bus clear Master Support Sowjanya Komatineni
@ 2019-02-05 22:46 ` Sowjanya Komatineni
  2019-02-06 11:55   ` Dmitry Osipenko
  2019-02-06 12:40   ` Dmitry Osipenko
  2019-02-05 22:46 ` [PATCH V12 4/5] i2c: tegra: update transfer timeout Sowjanya Komatineni
  2019-02-05 22:46 ` [PATCH V12 5/5] i2c: tegra: add i2c interface timing support Sowjanya Komatineni
  3 siblings, 2 replies; 35+ messages in thread
From: Sowjanya Komatineni @ 2019-02-05 22:46 UTC (permalink / raw)
  To: thierry.reding, jonathanh, mkarthik, smohammed, talho
  Cc: digetx, linux-tegra, linux-kernel, linux-i2c, Sowjanya Komatineni

This patch adds DMA support for Tegra I2C.

Tegra I2C TX and RX FIFO depth is 8 words. PIO mode is used for
transfer size of the max FIFO depth and DMA mode is used for
transfer size higher than max FIFO depth to save CPU overhead.

PIO mode needs full intervention of CPU to fill or empty FIFO's
and also need to service multiple data requests interrupt for the
same transaction. This adds delay between data bytes of the same
transfer when CPU is fully loaded and some slave devices has
internal timeout for no bus activity and stops transaction to
avoid bus hang. DMA mode is helpful in such cases.

DMA mode is also helpful for Large transfers during downloading or
uploading FW over I2C to some external devices.

Signed-off-by: Sowjanya Komatineni <skomatineni@nvidia.com>
---
 [V12] : Replaced dma_alloc_coherent with dma_alloc_attrs to force the allocated
	 buffer to be contiguous also in physical memory as Tegra194 supports max
	 64K and dma_alloc_coherent doesnt guarentee contiguous memory.
	 Changed return code from EIO to EINVAL incase of failure to obtain dma
	 descriptor.
	 Fixed coding style check issues.	 
 [V11] : Replaced deprecated dmaengine_terminate_all with dmaengine_termine_async
	 from non-atomic context and dmaengine_terminate_sync from atomic context.
	 Fixed to program fifo trigger levels properly when transfer falls back to
	 pio mode in case of dma slave configuration failure and other minor fixes.
 [V10] : APBDMA is replaced with GPCDMA on Tegra186 and Tegra194 designs.
	 Added apbdma hw support flag to now allow Tegra186 and later use
	 APBDMA driver.
	 Added explicit flow control enable for DMA slave config and error handling.
	 Moved releasing DMA resources to seperate function to reuse in
	 multiple places.
	 Updated to register tegra_i2c_driver from module level rather than subsys
	 level.
	 Other minor feedback
 [V9] :  Rebased to 5.0-rc4
	 Removed dependency of APB DMA in Kconfig and added conditional check
 	 in I2C driver to decide on using DMA mode.
	 Changed back the allocation of dma buffer during i2c probe.
	 Fixed FIFO triggers depending on DMA Vs PIO.
 [V8] :  Moved back dma init to i2c probe, removed ALL_PACKETS_XFER_COMPLETE
	 interrupt and using PACKETS_XFER_COMPLETE interrupt only and some
	 other fixes
	 Updated Kconfig for APB_DMA dependency
 [V7] :  Same as V6
 [V6] :  Updated for proper buffer allocation/freeing, channel release.
	 Updated to use exact xfer size for syncing dma buffer.
 [V5] :  Same as V4
 [V4] :  Updated to allocate DMA buffer only when DMA mode.
	 Updated to fall back to PIO mode when DMA channel request or
	 buffer allocation fails.
 [V3] :  Updated without additional buffer allocation.
 [V2] :  Updated based on V1 review feedback along with code cleanup for
	 proper implementation of DMA.


 drivers/i2c/busses/i2c-tegra.c | 413 ++++++++++++++++++++++++++++++++++++-----
 1 file changed, 369 insertions(+), 44 deletions(-)

diff --git a/drivers/i2c/busses/i2c-tegra.c b/drivers/i2c/busses/i2c-tegra.c
index 118b7023a0f4..77277a09e485 100644
--- a/drivers/i2c/busses/i2c-tegra.c
+++ b/drivers/i2c/busses/i2c-tegra.c
@@ -8,6 +8,9 @@
 
 #include <linux/clk.h>
 #include <linux/delay.h>
+#include <linux/dmaengine.h>
+#include <linux/dmapool.h>
+#include <linux/dma-mapping.h>
 #include <linux/err.h>
 #include <linux/i2c.h>
 #include <linux/init.h>
@@ -44,6 +47,8 @@
 #define I2C_FIFO_CONTROL_RX_FLUSH		BIT(0)
 #define I2C_FIFO_CONTROL_TX_TRIG_SHIFT		5
 #define I2C_FIFO_CONTROL_RX_TRIG_SHIFT		2
+#define I2C_FIFO_CONTROL_TX_TRIG(x)		(((x) - 1) << 5)
+#define I2C_FIFO_CONTROL_RX_TRIG(x)		(((x) - 1) << 2)
 #define I2C_FIFO_STATUS				0x060
 #define I2C_FIFO_STATUS_TX_MASK			0xF0
 #define I2C_FIFO_STATUS_TX_SHIFT		4
@@ -125,6 +130,19 @@
 #define I2C_MST_FIFO_STATUS_TX_MASK		0xff0000
 #define I2C_MST_FIFO_STATUS_TX_SHIFT		16
 
+/* Packet header size in bytes */
+#define I2C_PACKET_HEADER_SIZE			12
+
+#define DATA_DMA_DIR_TX				BIT(0)
+#define DATA_DMA_DIR_RX				BIT(1)
+
+/*
+ * Upto I2C_PIO_MODE_MAX_LEN bytes, controller will use PIO mode,
+ * above this, controller will use DMA to fill FIFO.
+ * MAX PIO len is 20 bytes excluding packet header.
+ */
+#define I2C_PIO_MODE_MAX_LEN			32
+
 /*
  * msg_end_type: The bus control which need to be send at end of transfer.
  * @MSG_END_STOP: Send stop pulse at end of transfer.
@@ -166,6 +184,7 @@ enum msg_end_type {
  *		allowing 0 length transfers.
  * @supports_bus_clear: Bus Clear support to recover from bus hang during
  *		SDA stuck low from device for some unknown reasons.
+ * @has_apb_dma: Support of APBDMA on corresponding Tegra chip.
  */
 struct tegra_i2c_hw_feature {
 	bool has_continue_xfer_support;
@@ -180,6 +199,7 @@ struct tegra_i2c_hw_feature {
 	bool has_mst_fifo;
 	const struct i2c_adapter_quirks *quirks;
 	bool supports_bus_clear;
+	bool has_apb_dma;
 };
 
 /**
@@ -191,6 +211,7 @@ struct tegra_i2c_hw_feature {
  * @fast_clk: clock reference for fast clock of I2C controller
  * @rst: reset control for the I2C controller
  * @base: ioremapped registers cookie
+ * @base_phys: Physical base address of the I2C controller
  * @cont_id: I2C controller ID, used for packet header
  * @irq: IRQ number of transfer complete interrupt
  * @irq_disabled: used to track whether or not the interrupt is enabled
@@ -204,6 +225,13 @@ struct tegra_i2c_hw_feature {
  * @clk_divisor_non_hs_mode: clock divider for non-high-speed modes
  * @is_multimaster_mode: track if I2C controller is in multi-master mode
  * @xfer_lock: lock to serialize transfer submission and processing
+ * @tx_dma_chan: DMA transmit channel
+ * @rx_dma_chan: DMA receive channel
+ * @dma_phys: handle to DMA resources
+ * @dma_buf: pointer to allocated DMA buffer
+ * @dma_buf_size: DMA buffer size
+ * @is_curr_dma_xfer: indicates active DMA transfer
+ * @dma_complete: DMA completion notifier
  */
 struct tegra_i2c_dev {
 	struct device *dev;
@@ -213,6 +241,7 @@ struct tegra_i2c_dev {
 	struct clk *fast_clk;
 	struct reset_control *rst;
 	void __iomem *base;
+	phys_addr_t base_phys;
 	int cont_id;
 	int irq;
 	bool irq_disabled;
@@ -226,6 +255,13 @@ struct tegra_i2c_dev {
 	u16 clk_divisor_non_hs_mode;
 	bool is_multimaster_mode;
 	spinlock_t xfer_lock;
+	struct dma_chan *tx_dma_chan;
+	struct dma_chan *rx_dma_chan;
+	dma_addr_t dma_phys;
+	u32 *dma_buf;
+	unsigned int dma_buf_size;
+	bool is_curr_dma_xfer;
+	struct completion dma_complete;
 };
 
 static void dvc_writel(struct tegra_i2c_dev *i2c_dev, u32 val,
@@ -294,6 +330,111 @@ static void tegra_i2c_unmask_irq(struct tegra_i2c_dev *i2c_dev, u32 mask)
 	i2c_writel(i2c_dev, int_mask, I2C_INT_MASK);
 }
 
+static void tegra_i2c_dma_complete(void *args)
+{
+	struct tegra_i2c_dev *i2c_dev = args;
+
+	complete(&i2c_dev->dma_complete);
+}
+
+static int tegra_i2c_dma_submit(struct tegra_i2c_dev *i2c_dev, size_t len)
+{
+	struct dma_async_tx_descriptor *dma_desc;
+	enum dma_transfer_direction dir;
+	struct dma_chan *chan;
+
+	dev_dbg(i2c_dev->dev, "starting DMA for length: %zu\n", len);
+	reinit_completion(&i2c_dev->dma_complete);
+	dir = i2c_dev->msg_read ? DMA_DEV_TO_MEM : DMA_MEM_TO_DEV;
+	chan = i2c_dev->msg_read ? i2c_dev->rx_dma_chan : i2c_dev->tx_dma_chan;
+	dma_desc = dmaengine_prep_slave_single(chan, i2c_dev->dma_phys,
+					       len, dir, DMA_PREP_INTERRUPT |
+					       DMA_CTRL_ACK);
+	if (!dma_desc) {
+		dev_err(i2c_dev->dev, "failed to get DMA descriptor\n");
+		return -EINVAL;
+	}
+
+	dma_desc->callback = tegra_i2c_dma_complete;
+	dma_desc->callback_param = i2c_dev;
+	dmaengine_submit(dma_desc);
+	dma_async_issue_pending(chan);
+	return 0;
+}
+
+static void tegra_i2c_release_dma(struct tegra_i2c_dev *i2c_dev)
+{
+	if (i2c_dev->dma_buf) {
+		dma_free_attrs(i2c_dev->dev, i2c_dev->dma_buf_size,
+			       i2c_dev->dma_buf, i2c_dev->dma_phys,
+			       DMA_ATTR_FORCE_CONTIGUOUS);
+		i2c_dev->dma_buf = NULL;
+	}
+
+	if (i2c_dev->tx_dma_chan) {
+		dma_release_channel(i2c_dev->tx_dma_chan);
+		i2c_dev->tx_dma_chan = NULL;
+	}
+
+	if (i2c_dev->rx_dma_chan) {
+		dma_release_channel(i2c_dev->rx_dma_chan);
+		i2c_dev->rx_dma_chan = NULL;
+	}
+}
+
+static int tegra_i2c_init_dma(struct tegra_i2c_dev *i2c_dev)
+{
+	struct dma_chan *chan;
+	u32 *dma_buf;
+	dma_addr_t dma_phys;
+	int err;
+
+	if (!IS_ENABLED(CONFIG_TEGRA20_APB_DMA) ||
+	    !i2c_dev->hw->has_apb_dma) {
+		err = -ENODEV;
+		goto err_out;
+	}
+
+	chan = dma_request_slave_channel_reason(i2c_dev->dev, "rx");
+	if (IS_ERR(chan)) {
+		err = PTR_ERR(chan);
+		goto err_out;
+	}
+
+	i2c_dev->rx_dma_chan = chan;
+
+	chan = dma_request_slave_channel_reason(i2c_dev->dev, "tx");
+	if (IS_ERR(chan)) {
+		err = PTR_ERR(chan);
+		goto err_out;
+	}
+
+	i2c_dev->tx_dma_chan = chan;
+
+	dma_buf = dma_alloc_attrs(i2c_dev->dev, i2c_dev->dma_buf_size,
+				  &dma_phys, GFP_KERNEL | __GFP_NOWARN,
+				  DMA_ATTR_FORCE_CONTIGUOUS);
+	if (!dma_buf) {
+		dev_err(i2c_dev->dev, "failed to allocate the DMA buffer\n");
+		err = -ENOMEM;
+		goto err_out;
+	}
+
+	i2c_dev->dma_buf = dma_buf;
+	i2c_dev->dma_phys = dma_phys;
+	return 0;
+
+err_out:
+	tegra_i2c_release_dma(i2c_dev);
+	if (err != -EPROBE_DEFER) {
+		dev_err(i2c_dev->dev, "can't use DMA, err: %d, using PIO\n",
+			err);
+		return 0;
+	}
+
+	return err;
+}
+
 static int tegra_i2c_flush_fifos(struct tegra_i2c_dev *i2c_dev)
 {
 	unsigned long timeout = jiffies + HZ;
@@ -571,16 +712,6 @@ static int tegra_i2c_init(struct tegra_i2c_dev *i2c_dev)
 		i2c_writel(i2c_dev, 0x00, I2C_SL_ADDR2);
 	}
 
-	if (i2c_dev->hw->has_mst_fifo) {
-		val = I2C_MST_FIFO_CONTROL_TX_TRIG(8) |
-		      I2C_MST_FIFO_CONTROL_RX_TRIG(1);
-		i2c_writel(i2c_dev, val, I2C_MST_FIFO_CONTROL);
-	} else {
-		val = 7 << I2C_FIFO_CONTROL_TX_TRIG_SHIFT |
-			0 << I2C_FIFO_CONTROL_RX_TRIG_SHIFT;
-		i2c_writel(i2c_dev, val, I2C_FIFO_CONTROL);
-	}
-
 	err = tegra_i2c_flush_fifos(i2c_dev);
 	if (err)
 		goto err;
@@ -660,25 +791,37 @@ static irqreturn_t tegra_i2c_isr(int irq, void *dev_id)
 	if (i2c_dev->hw->supports_bus_clear && (status & I2C_INT_BUS_CLR_DONE))
 		goto err;
 
-	if (i2c_dev->msg_read && (status & I2C_INT_RX_FIFO_DATA_REQ)) {
-		if (i2c_dev->msg_buf_remaining)
-			tegra_i2c_empty_rx_fifo(i2c_dev);
-		else
-			BUG();
-	}
+	if (!i2c_dev->is_curr_dma_xfer) {
+		if (i2c_dev->msg_read && (status & I2C_INT_RX_FIFO_DATA_REQ)) {
+			if (i2c_dev->msg_buf_remaining)
+				tegra_i2c_empty_rx_fifo(i2c_dev);
+			else
+				BUG();
+		}
 
-	if (!i2c_dev->msg_read && (status & I2C_INT_TX_FIFO_DATA_REQ)) {
-		if (i2c_dev->msg_buf_remaining)
-			tegra_i2c_fill_tx_fifo(i2c_dev);
-		else
-			tegra_i2c_mask_irq(i2c_dev, I2C_INT_TX_FIFO_DATA_REQ);
+		if (!i2c_dev->msg_read && (status & I2C_INT_TX_FIFO_DATA_REQ)) {
+			if (i2c_dev->msg_buf_remaining)
+				tegra_i2c_fill_tx_fifo(i2c_dev);
+			else
+				tegra_i2c_mask_irq(i2c_dev,
+						   I2C_INT_TX_FIFO_DATA_REQ);
+		}
 	}
 
 	i2c_writel(i2c_dev, status, I2C_INT_STATUS);
 	if (i2c_dev->is_dvc)
 		dvc_writel(i2c_dev, DVC_STATUS_I2C_DONE_INTR, DVC_STATUS);
 
+	/*
+	 * During message read XFER_COMPLETE interrupt is triggered prior to
+	 * DMA completion and during message write XFER_COMPLETE interrupt is
+	 * triggered after DMA completion.
+	 * PACKETS_XFER_COMPLETE indicates completion of all bytes of transfer.
+	 * so forcing msg_buf_remaining to 0 in DMA mode.
+	 */
 	if (status & I2C_INT_PACKET_XFER_COMPLETE) {
+		if (i2c_dev->is_curr_dma_xfer)
+			i2c_dev->msg_buf_remaining = 0;
 		BUG_ON(i2c_dev->msg_buf_remaining);
 		complete(&i2c_dev->msg_complete);
 	}
@@ -694,12 +837,89 @@ static irqreturn_t tegra_i2c_isr(int irq, void *dev_id)
 	if (i2c_dev->is_dvc)
 		dvc_writel(i2c_dev, DVC_STATUS_I2C_DONE_INTR, DVC_STATUS);
 
+	if (i2c_dev->is_curr_dma_xfer) {
+		if (i2c_dev->msg_read)
+			dmaengine_terminate_async(i2c_dev->rx_dma_chan);
+		else
+			dmaengine_terminate_async(i2c_dev->tx_dma_chan);
+
+		complete(&i2c_dev->dma_complete);
+	}
+
 	complete(&i2c_dev->msg_complete);
 done:
 	spin_unlock(&i2c_dev->xfer_lock);
 	return IRQ_HANDLED;
 }
 
+static void tegra_i2c_config_fifo_trig(struct tegra_i2c_dev *i2c_dev,
+				       size_t len)
+{
+	u32 val, reg;
+	u8 dma_burst = 0;
+	struct dma_slave_config slv_config = {0};
+	struct dma_chan *chan;
+	int ret;
+
+	if (i2c_dev->hw->has_mst_fifo)
+		reg = I2C_MST_FIFO_CONTROL;
+	else
+		reg = I2C_FIFO_CONTROL;
+	val = i2c_readl(i2c_dev, reg);
+
+	if (i2c_dev->is_curr_dma_xfer) {
+		if (len & 0xF)
+			dma_burst = 1;
+		else if (len & 0x10)
+			dma_burst = 4;
+		else
+			dma_burst = 8;
+
+		if (i2c_dev->msg_read) {
+			chan = i2c_dev->rx_dma_chan;
+			slv_config.src_addr = i2c_dev->base_phys + I2C_RX_FIFO;
+			slv_config.src_addr_width = DMA_SLAVE_BUSWIDTH_4_BYTES;
+			slv_config.src_maxburst = dma_burst;
+
+			if (i2c_dev->hw->has_mst_fifo)
+				val |= I2C_MST_FIFO_CONTROL_RX_TRIG(dma_burst);
+			else
+				val |= I2C_FIFO_CONTROL_RX_TRIG(dma_burst);
+		} else {
+			chan = i2c_dev->tx_dma_chan;
+			slv_config.dst_addr = i2c_dev->base_phys + I2C_TX_FIFO;
+			slv_config.dst_addr_width = DMA_SLAVE_BUSWIDTH_4_BYTES;
+			slv_config.dst_maxburst = dma_burst;
+
+			if (i2c_dev->hw->has_mst_fifo)
+				val |= I2C_MST_FIFO_CONTROL_TX_TRIG(dma_burst);
+			else
+				val |= I2C_FIFO_CONTROL_TX_TRIG(dma_burst);
+		}
+
+		slv_config.device_fc = true;
+		ret = dmaengine_slave_config(chan, &slv_config);
+		if (ret < 0) {
+			dev_err(i2c_dev->dev, "DMA slave config failed: %d\n",
+				ret);
+			dev_err(i2c_dev->dev, "fallbacking to PIO\n");
+			tegra_i2c_release_dma(i2c_dev);
+			i2c_dev->is_curr_dma_xfer = false;
+		} else {
+			goto out;
+		}
+	}
+
+	if (i2c_dev->hw->has_mst_fifo)
+		val = I2C_MST_FIFO_CONTROL_TX_TRIG(8) |
+		      I2C_MST_FIFO_CONTROL_RX_TRIG(1);
+	else
+		val = I2C_FIFO_CONTROL_TX_TRIG(8) |
+		      I2C_FIFO_CONTROL_RX_TRIG(1);
+out:
+	i2c_writel(i2c_dev, val, reg);
+}
+
 static int tegra_i2c_issue_bus_clear(struct tegra_i2c_dev *i2c_dev)
 {
 	int err;
@@ -744,6 +964,10 @@ static int tegra_i2c_xfer_msg(struct tegra_i2c_dev *i2c_dev,
 	u32 int_mask;
 	unsigned long time_left;
 	unsigned long flags;
+	size_t xfer_size;
+	u32 *buffer = NULL;
+	int err = 0;
+	bool dma;
 
 	tegra_i2c_flush_fifos(i2c_dev);
 
@@ -753,19 +977,57 @@ static int tegra_i2c_xfer_msg(struct tegra_i2c_dev *i2c_dev,
 	i2c_dev->msg_read = (msg->flags & I2C_M_RD);
 	reinit_completion(&i2c_dev->msg_complete);
 
+	if (i2c_dev->msg_read)
+		xfer_size = msg->len;
+	else
+		xfer_size = msg->len + I2C_PACKET_HEADER_SIZE;
+
+	xfer_size = ALIGN(xfer_size, BYTES_PER_FIFO_WORD);
+	i2c_dev->is_curr_dma_xfer = (xfer_size > I2C_PIO_MODE_MAX_LEN) &&
+				    i2c_dev->dma_buf;
+	tegra_i2c_config_fifo_trig(i2c_dev, xfer_size);
+	dma = i2c_dev->is_curr_dma_xfer;
+
 	spin_lock_irqsave(&i2c_dev->xfer_lock, flags);
 
 	int_mask = I2C_INT_NO_ACK | I2C_INT_ARBITRATION_LOST;
 	tegra_i2c_unmask_irq(i2c_dev, int_mask);
+	if (dma) {
+		if (i2c_dev->msg_read) {
+			dma_sync_single_for_device(i2c_dev->dev,
+						   i2c_dev->dma_phys,
+						   xfer_size,
+						   DMA_FROM_DEVICE);
+			err = tegra_i2c_dma_submit(i2c_dev, xfer_size);
+			if (err < 0) {
+				dev_err(i2c_dev->dev,
+					"starting RX DMA failed, err %d\n",
+					err);
+				goto unlock;
+			}
+		} else {
+			dma_sync_single_for_cpu(i2c_dev->dev,
+						i2c_dev->dma_phys,
+						xfer_size,
+						DMA_TO_DEVICE);
+			buffer = i2c_dev->dma_buf;
+		}
+	}
 
 	packet_header = (0 << PACKET_HEADER0_HEADER_SIZE_SHIFT) |
 			PACKET_HEADER0_PROTOCOL_I2C |
 			(i2c_dev->cont_id << PACKET_HEADER0_CONT_ID_SHIFT) |
 			(1 << PACKET_HEADER0_PACKET_ID_SHIFT);
-	i2c_writel(i2c_dev, packet_header, I2C_TX_FIFO);
+	if (dma && !i2c_dev->msg_read)
+		*buffer++ = packet_header;
+	else
+		i2c_writel(i2c_dev, packet_header, I2C_TX_FIFO);
 
 	packet_header = msg->len - 1;
-	i2c_writel(i2c_dev, packet_header, I2C_TX_FIFO);
+	if (dma && !i2c_dev->msg_read)
+		*buffer++ = packet_header;
+	else
+		i2c_writel(i2c_dev, packet_header, I2C_TX_FIFO);
 
 	packet_header = I2C_HEADER_IE_ENABLE;
 	if (end_state == MSG_END_CONTINUE)
@@ -782,23 +1044,80 @@ static int tegra_i2c_xfer_msg(struct tegra_i2c_dev *i2c_dev,
 		packet_header |= I2C_HEADER_CONT_ON_NAK;
 	if (msg->flags & I2C_M_RD)
 		packet_header |= I2C_HEADER_READ;
-	i2c_writel(i2c_dev, packet_header, I2C_TX_FIFO);
-
-	if (!(msg->flags & I2C_M_RD))
-		tegra_i2c_fill_tx_fifo(i2c_dev);
+	if (dma && !i2c_dev->msg_read)
+		*buffer++ = packet_header;
+	else
+		i2c_writel(i2c_dev, packet_header, I2C_TX_FIFO);
+
+	if (!msg->flags & I2C_M_RD) {
+		if (dma) {
+			memcpy(buffer, msg->buf, msg->len);
+			dma_sync_single_for_device(i2c_dev->dev,
+						   i2c_dev->dma_phys,
+						   xfer_size,
+						   DMA_TO_DEVICE);
+			err = tegra_i2c_dma_submit(i2c_dev, xfer_size);
+			if (err < 0) {
+				dev_err(i2c_dev->dev,
+					"starting TX DMA failed, err %d\n",
+					err);
+				goto unlock;
+			}
+		} else {
+			tegra_i2c_fill_tx_fifo(i2c_dev);
+		}
+	}
 
 	if (i2c_dev->hw->has_per_pkt_xfer_complete_irq)
 		int_mask |= I2C_INT_PACKET_XFER_COMPLETE;
-	if (msg->flags & I2C_M_RD)
-		int_mask |= I2C_INT_RX_FIFO_DATA_REQ;
-	else if (i2c_dev->msg_buf_remaining)
-		int_mask |= I2C_INT_TX_FIFO_DATA_REQ;
+
+	if (!dma) {
+		if (msg->flags & I2C_M_RD)
+			int_mask |= I2C_INT_RX_FIFO_DATA_REQ;
+		else if (i2c_dev->msg_buf_remaining)
+			int_mask |= I2C_INT_TX_FIFO_DATA_REQ;
+	}
 
 	tegra_i2c_unmask_irq(i2c_dev, int_mask);
-	spin_unlock_irqrestore(&i2c_dev->xfer_lock, flags);
 	dev_dbg(i2c_dev->dev, "unmasked irq: %02x\n",
 		i2c_readl(i2c_dev, I2C_INT_MASK));
 
+unlock:
+	spin_unlock_irqrestore(&i2c_dev->xfer_lock, flags);
+
+	if (dma) {
+		if (err)
+			return err;
+
+		time_left = wait_for_completion_timeout(
+						&i2c_dev->dma_complete,
+						TEGRA_I2C_TIMEOUT);
+
+		if (time_left == 0) {
+			dev_err(i2c_dev->dev, "DMA transfer timeout\n");
+			dmaengine_terminate_sync(i2c_dev->msg_read ?
+						  i2c_dev->rx_dma_chan :
+						  i2c_dev->tx_dma_chan);
+			tegra_i2c_init(i2c_dev);
+			return -ETIMEDOUT;
+		}
+
+		if (i2c_dev->msg_read && i2c_dev->msg_err == I2C_ERR_NONE) {
+			dma_sync_single_for_cpu(i2c_dev->dev,
+						i2c_dev->dma_phys,
+						xfer_size,
+						DMA_FROM_DEVICE);
+			memcpy(i2c_dev->msg_buf, i2c_dev->dma_buf,
+			       msg->len);
+		}
+
+		if (i2c_dev->msg_err != I2C_ERR_NONE) {
+			dmaengine_synchronize(i2c_dev->msg_read ?
+					      i2c_dev->rx_dma_chan :
+					      i2c_dev->tx_dma_chan);
+		}
+	}
+
 	time_left = wait_for_completion_timeout(&i2c_dev->msg_complete,
 						TEGRA_I2C_TIMEOUT);
 	tegra_i2c_mask_irq(i2c_dev, int_mask);
@@ -814,6 +1133,7 @@ static int tegra_i2c_xfer_msg(struct tegra_i2c_dev *i2c_dev,
 		time_left, completion_done(&i2c_dev->msg_complete),
 		i2c_dev->msg_err);
 
+	i2c_dev->is_curr_dma_xfer = false;
 	if (likely(i2c_dev->msg_err == I2C_ERR_NONE))
 		return 0;
 
@@ -920,6 +1240,7 @@ static const struct tegra_i2c_hw_feature tegra20_i2c_hw = {
 	.has_mst_fifo = false,
 	.quirks = &tegra_i2c_quirks,
 	.supports_bus_clear = false,
+	.has_apb_dma = true,
 };
 
 static const struct tegra_i2c_hw_feature tegra30_i2c_hw = {
@@ -935,6 +1256,7 @@ static const struct tegra_i2c_hw_feature tegra30_i2c_hw = {
 	.has_mst_fifo = false,
 	.quirks = &tegra_i2c_quirks,
 	.supports_bus_clear = false,
+	.has_apb_dma = true,
 };
 
 static const struct tegra_i2c_hw_feature tegra114_i2c_hw = {
@@ -950,6 +1272,7 @@ static const struct tegra_i2c_hw_feature tegra114_i2c_hw = {
 	.has_mst_fifo = false,
 	.quirks = &tegra_i2c_quirks,
 	.supports_bus_clear = true,
+	.has_apb_dma = true,
 };
 
 static const struct tegra_i2c_hw_feature tegra124_i2c_hw = {
@@ -965,6 +1288,7 @@ static const struct tegra_i2c_hw_feature tegra124_i2c_hw = {
 	.has_mst_fifo = false,
 	.quirks = &tegra_i2c_quirks,
 	.supports_bus_clear = true,
+	.has_apb_dma = true,
 };
 
 static const struct tegra_i2c_hw_feature tegra210_i2c_hw = {
@@ -980,6 +1304,7 @@ static const struct tegra_i2c_hw_feature tegra210_i2c_hw = {
 	.has_mst_fifo = false,
 	.quirks = &tegra_i2c_quirks,
 	.supports_bus_clear = true,
+	.has_apb_dma = true,
 };
 
 static const struct tegra_i2c_hw_feature tegra194_i2c_hw = {
@@ -995,6 +1320,7 @@ static const struct tegra_i2c_hw_feature tegra194_i2c_hw = {
 	.has_mst_fifo = true,
 	.quirks = &tegra194_i2c_quirks,
 	.supports_bus_clear = true,
+	.has_apb_dma = false,
 };
 
 /* Match table for of_platform binding */
@@ -1017,11 +1343,13 @@ static int tegra_i2c_probe(struct platform_device *pdev)
 	struct clk *div_clk;
 	struct clk *fast_clk;
 	void __iomem *base;
+	phys_addr_t base_phys;
 	int irq;
 	int ret = 0;
 	int clk_multiplier = I2C_CLK_MULTIPLIER_STD_FAST_MODE;
 
 	res = platform_get_resource(pdev, IORESOURCE_MEM, 0);
+	base_phys = res->start;
 	base = devm_ioremap_resource(&pdev->dev, res);
 	if (IS_ERR(base))
 		return PTR_ERR(base);
@@ -1044,6 +1372,7 @@ static int tegra_i2c_probe(struct platform_device *pdev)
 		return -ENOMEM;
 
 	i2c_dev->base = base;
+	i2c_dev->base_phys = base_phys;
 	i2c_dev->div_clk = div_clk;
 	i2c_dev->adapter.algo = &tegra_i2c_algo;
 	i2c_dev->adapter.retries = 1;
@@ -1063,7 +1392,9 @@ static int tegra_i2c_probe(struct platform_device *pdev)
 	i2c_dev->is_dvc = of_device_is_compatible(pdev->dev.of_node,
 						  "nvidia,tegra20-i2c-dvc");
 	i2c_dev->adapter.quirks = i2c_dev->hw->quirks;
+	i2c_dev->dma_buf_size = i2c_dev->adapter.quirks->max_write_len;
 	init_completion(&i2c_dev->msg_complete);
+	init_completion(&i2c_dev->dma_complete);
 	spin_lock_init(&i2c_dev->xfer_lock);
 
 	if (!i2c_dev->hw->has_single_clk_source) {
@@ -1124,6 +1455,10 @@ static int tegra_i2c_probe(struct platform_device *pdev)
 		}
 	}
 
+	ret = tegra_i2c_init_dma(i2c_dev);
+	if (ret < 0)
+		goto disable_div_clk;
+
 	ret = tegra_i2c_init(i2c_dev);
 	if (ret) {
 		dev_err(&pdev->dev, "Failed to initialize i2c controller\n");
@@ -1188,6 +1523,7 @@ static int tegra_i2c_remove(struct platform_device *pdev)
 	if (!i2c_dev->hw->has_single_clk_source)
 		clk_unprepare(i2c_dev->fast_clk);
 
+	tegra_i2c_release_dma(i2c_dev);
 	return 0;
 }
 
@@ -1211,18 +1547,7 @@ static struct platform_driver tegra_i2c_driver = {
 	},
 };
 
-static int __init tegra_i2c_init_driver(void)
-{
-	return platform_driver_register(&tegra_i2c_driver);
-}
-
-static void __exit tegra_i2c_exit_driver(void)
-{
-	platform_driver_unregister(&tegra_i2c_driver);
-}
-
-subsys_initcall(tegra_i2c_init_driver);
-module_exit(tegra_i2c_exit_driver);
+module_platform_driver(tegra_i2c_driver);
 
 MODULE_DESCRIPTION("nVidia Tegra2 I2C Bus Controller driver");
 MODULE_AUTHOR("Colin Cross");
-- 
2.7.4

^ permalink raw reply related	[flat|nested] 35+ messages in thread

* [PATCH V12 4/5] i2c: tegra: update transfer timeout
  2019-02-05 22:46 [PATCH V12 1/5] i2c: tegra: sort all the include headers alphabetically Sowjanya Komatineni
  2019-02-05 22:46 ` [PATCH V12 2/5] i2c: tegra: add bus clear Master Support Sowjanya Komatineni
  2019-02-05 22:46 ` [PATCH V12 3/5] i2c: tegra: Add DMA support Sowjanya Komatineni
@ 2019-02-05 22:46 ` Sowjanya Komatineni
  2019-02-05 22:46 ` [PATCH V12 5/5] i2c: tegra: add i2c interface timing support Sowjanya Komatineni
  3 siblings, 0 replies; 35+ messages in thread
From: Sowjanya Komatineni @ 2019-02-05 22:46 UTC (permalink / raw)
  To: thierry.reding, jonathanh, mkarthik, smohammed, talho
  Cc: digetx, linux-tegra, linux-kernel, linux-i2c, Sowjanya Komatineni

Tegra194 allows max of 64K bytes and Tegra186 and prior allows
max of 4K bytes of transfer per packet.

one sec timeout is not enough for transfers more than 10K bytes
at STD bus rate.

This patch updates I2C transfer timeout based on the transfer size
and I2C bus rate to allow enough time during max transfer size at
lower bus speed.

Acked-by: Thierry Reding <treding@nvidia.com>
Reviewed-by: Dmitry Osipenko <digetx@gmail.com>
Signed-off-by: Sowjanya Komatineni <skomatineni@nvidia.com>
---
 [V10/V11/V12] : Reduced the timeout for bus clear operation
	Added adapter timeout to cover worst case transfer rate (max transfer
	size at STD speed) incase if ARB LOST happens during middle/end of 
	the transaction.
 [V9] : Rebased to 5.0-rc4
	Minor updates for readability of xfer time
 [V8] : Added comment with explaination of xfer time calculation
 [V5/V6/V7] : Same as V4
 [V4] : V4 series includes bus clear support and this patch is updated with
	fixed timeout of 1sec for bus clear operation.
 [V3] : Same as V2
 [V2] : Added this patch in V2 series to allow enough time for data transfer
	to happen.
	This patch has dependency with DMA patch as TEGRA_I2C_TIMEOUT define
	takes argument with this patch.

 drivers/i2c/busses/i2c-tegra.c | 22 ++++++++++++++++------
 1 file changed, 16 insertions(+), 6 deletions(-)

diff --git a/drivers/i2c/busses/i2c-tegra.c b/drivers/i2c/busses/i2c-tegra.c
index 77277a09e485..902aa430ffe0 100644
--- a/drivers/i2c/busses/i2c-tegra.c
+++ b/drivers/i2c/busses/i2c-tegra.c
@@ -25,7 +25,6 @@
 #include <linux/pm_runtime.h>
 #include <linux/reset.h>
 
-#define TEGRA_I2C_TIMEOUT (msecs_to_jiffies(1000))
 #define BYTES_PER_FIFO_WORD 4
 
 #define I2C_CNFG				0x000
@@ -940,8 +939,9 @@ static int tegra_i2c_issue_bus_clear(struct tegra_i2c_dev *i2c_dev)
 		i2c_writel(i2c_dev, reg, I2C_BUS_CLEAR_CNFG);
 		tegra_i2c_unmask_irq(i2c_dev, I2C_INT_BUS_CLR_DONE);
 
-		time_left = wait_for_completion_timeout(&i2c_dev->msg_complete,
-							TEGRA_I2C_TIMEOUT);
+		time_left = wait_for_completion_timeout(
+						&i2c_dev->msg_complete,
+						msecs_to_jiffies(50));
 		if (time_left == 0) {
 			dev_err(i2c_dev->dev, "timed out for bus clear\n");
 			return -ETIMEDOUT;
@@ -968,6 +968,7 @@ static int tegra_i2c_xfer_msg(struct tegra_i2c_dev *i2c_dev,
 	u32 *buffer = NULL;
 	int err = 0;
 	bool dma;
+	u16 xfer_time = 100;
 
 	tegra_i2c_flush_fifos(i2c_dev);
 
@@ -988,6 +989,13 @@ static int tegra_i2c_xfer_msg(struct tegra_i2c_dev *i2c_dev,
 	tegra_i2c_config_fifo_trig(i2c_dev, xfer_size);
 	dma = i2c_dev->is_curr_dma_xfer;
 
+	/*
+	 * Transfer time in mSec = Total bits / transfer rate
+	 * Total bits = 9 bits per byte (including ACK bit) + Start & stop bits
+	 */
+	xfer_time += DIV_ROUND_CLOSEST(((xfer_size * 9) + 2) * MSEC_PER_SEC,
+					i2c_dev->bus_clk_rate);
+
 	spin_lock_irqsave(&i2c_dev->xfer_lock, flags);
 
 	int_mask = I2C_INT_NO_ACK | I2C_INT_ARBITRATION_LOST;
@@ -1091,7 +1099,7 @@ static int tegra_i2c_xfer_msg(struct tegra_i2c_dev *i2c_dev,
 
 		time_left = wait_for_completion_timeout(
 						&i2c_dev->dma_complete,
-						TEGRA_I2C_TIMEOUT);
+						msecs_to_jiffies(xfer_time));
 
 		if (time_left == 0) {
 			dev_err(i2c_dev->dev, "DMA transfer timeout\n");
@@ -1118,8 +1126,9 @@ static int tegra_i2c_xfer_msg(struct tegra_i2c_dev *i2c_dev,
 		}
 	}
 
-	time_left = wait_for_completion_timeout(&i2c_dev->msg_complete,
-						TEGRA_I2C_TIMEOUT);
+	time_left = wait_for_completion_timeout(
+					&i2c_dev->msg_complete,
+					msecs_to_jiffies(xfer_time));
 	tegra_i2c_mask_irq(i2c_dev, int_mask);
 
 	if (time_left == 0) {
@@ -1376,6 +1385,7 @@ static int tegra_i2c_probe(struct platform_device *pdev)
 	i2c_dev->div_clk = div_clk;
 	i2c_dev->adapter.algo = &tegra_i2c_algo;
 	i2c_dev->adapter.retries = 1;
+	i2c_dev->adapter.timeout = 6 * HZ;
 	i2c_dev->irq = irq;
 	i2c_dev->cont_id = pdev->id;
 	i2c_dev->dev = &pdev->dev;
-- 
2.7.4

^ permalink raw reply related	[flat|nested] 35+ messages in thread

* [PATCH V12 5/5] i2c: tegra: add i2c interface timing support
  2019-02-05 22:46 [PATCH V12 1/5] i2c: tegra: sort all the include headers alphabetically Sowjanya Komatineni
                   ` (2 preceding siblings ...)
  2019-02-05 22:46 ` [PATCH V12 4/5] i2c: tegra: update transfer timeout Sowjanya Komatineni
@ 2019-02-05 22:46 ` Sowjanya Komatineni
  3 siblings, 0 replies; 35+ messages in thread
From: Sowjanya Komatineni @ 2019-02-05 22:46 UTC (permalink / raw)
  To: thierry.reding, jonathanh, mkarthik, smohammed, talho
  Cc: digetx, linux-tegra, linux-kernel, linux-i2c, Sowjanya Komatineni

This patch adds I2C interface timing registers support for
proper bus rate configuration along with meeting the i2c spec
setup and hold times based on the tuning performed on Tegra210,
Tegra186 and Tegra194 platforms.

I2C_INTERFACE_TIMING_0 register contains TLOW and THIGH field
and Tegra I2C controller design uses them as a part of internal
clock divisor.

I2C_INTERFACE_TIMING_1 register contains the setup and hold times
for start and stop conditions.

Acked-by: Thierry Reding <treding@nvidia.com>
Signed-off-by: Sowjanya Komatineni <skomatineni@nvidia.com>
---
 [V12] 		: Fixed strict coding style check issues
 [V9/V10/V11]	: Same as V8
 [V8] 		: Updated to handle timing implementation within tegra_i2c_init directly
 [V7] 		: Minor updates to timing implementation
 [V5/V6] 	: Added this Interface timing patch in V5 of the patch series.

 drivers/i2c/busses/i2c-tegra.c | 189 ++++++++++++++++++++++++++++++++++-------
 1 file changed, 160 insertions(+), 29 deletions(-)

diff --git a/drivers/i2c/busses/i2c-tegra.c b/drivers/i2c/busses/i2c-tegra.c
index 902aa430ffe0..c538ed5f8e2c 100644
--- a/drivers/i2c/busses/i2c-tegra.c
+++ b/drivers/i2c/busses/i2c-tegra.c
@@ -129,6 +129,15 @@
 #define I2C_MST_FIFO_STATUS_TX_MASK		0xff0000
 #define I2C_MST_FIFO_STATUS_TX_SHIFT		16
 
+#define I2C_INTERFACE_TIMING_0			0x94
+#define I2C_THIGH_SHIFT				8
+#define I2C_INTERFACE_TIMING_1			0x98
+
+#define I2C_STANDARD_MODE			100000
+#define I2C_FAST_MODE				400000
+#define I2C_FAST_PLUS_MODE			1000000
+#define I2C_HS_MODE				3500000
+
 /* Packet header size in bytes */
 #define I2C_PACKET_HEADER_SIZE			12
 
@@ -166,7 +175,10 @@ enum msg_end_type {
  * @has_config_load_reg: Has the config load register to load the new
  *		configuration.
  * @clk_divisor_hs_mode: Clock divisor in HS mode.
- * @clk_divisor_std_fast_mode: Clock divisor in standard/fast mode. It is
+ * @clk_divisor_std_mode: Clock divisor in standard mode. It is
+ *		applicable if there is no fast clock source i.e. single clock
+ *		source.
+ * @clk_divisor_fast_mode: Clock divisor in fast mode. It is
  *		applicable if there is no fast clock source i.e. single clock
  *		source.
  * @clk_divisor_fast_plus_mode: Clock divisor in fast mode plus. It is
@@ -184,6 +196,16 @@ enum msg_end_type {
  * @supports_bus_clear: Bus Clear support to recover from bus hang during
  *		SDA stuck low from device for some unknown reasons.
  * @has_apb_dma: Support of APBDMA on corresponding Tegra chip.
+ * @tlow_std_mode: Low period of the clock in standard mode.
+ * @thigh_std_mode: High period of the clock in standard mode.
+ * @tlow_fast_fastplus_mode: Low period of the clock in fast/fast-plus modes.
+ * @thigh_fast_fastplus_mode: High period of the clock in fast/fast-plus modes.
+ * @setup_hold_time_std_mode: Setup and hold time for start and stop conditions
+ *		in standard mode.
+ * @setup_hold_time_fast_fast_plus_mode: Setup and hold time for start and stop
+ *		conditions in fast/fast-plus modes.
+ * @setup_hold_time_hs_mode: Setup and hold time for start and stop conditions
+ *		in HS mode.
  */
 struct tegra_i2c_hw_feature {
 	bool has_continue_xfer_support;
@@ -191,7 +213,8 @@ struct tegra_i2c_hw_feature {
 	bool has_single_clk_source;
 	bool has_config_load_reg;
 	int clk_divisor_hs_mode;
-	int clk_divisor_std_fast_mode;
+	int clk_divisor_std_mode;
+	int clk_divisor_fast_mode;
 	u16 clk_divisor_fast_plus_mode;
 	bool has_multi_master_mode;
 	bool has_slcg_override_reg;
@@ -199,6 +222,13 @@ struct tegra_i2c_hw_feature {
 	const struct i2c_adapter_quirks *quirks;
 	bool supports_bus_clear;
 	bool has_apb_dma;
+	u8 tlow_std_mode;
+	u8 thigh_std_mode;
+	u8 tlow_fast_fastplus_mode;
+	u8 thigh_fast_fastplus_mode;
+	u32 setup_hold_time_std_mode;
+	u32 setup_hold_time_fast_fast_plus_mode;
+	u32 setup_hold_time_hs_mode;
 };
 
 /**
@@ -668,11 +698,13 @@ static int tegra_i2c_wait_for_config_load(struct tegra_i2c_dev *i2c_dev)
 	return 0;
 }
 
-static int tegra_i2c_init(struct tegra_i2c_dev *i2c_dev)
+static int tegra_i2c_init(struct tegra_i2c_dev *i2c_dev, bool clk_reinit)
 {
 	u32 val;
 	int err;
-	u32 clk_divisor;
+	u32 clk_divisor, clk_multiplier;
+	u32 tsu_thd = 0;
+	u8 tlow, thigh;
 
 	err = pm_runtime_get_sync(i2c_dev->dev);
 	if (err < 0) {
@@ -702,6 +734,36 @@ static int tegra_i2c_init(struct tegra_i2c_dev *i2c_dev)
 					I2C_CLK_DIVISOR_STD_FAST_MODE_SHIFT;
 	i2c_writel(i2c_dev, clk_divisor, I2C_CLK_DIVISOR);
 
+	if (i2c_dev->bus_clk_rate > I2C_STANDARD_MODE &&
+	    i2c_dev->bus_clk_rate <= I2C_FAST_PLUS_MODE) {
+		tlow = i2c_dev->hw->tlow_fast_fastplus_mode;
+		thigh = i2c_dev->hw->thigh_fast_fastplus_mode;
+		tsu_thd = i2c_dev->hw->setup_hold_time_fast_fast_plus_mode;
+	} else {
+		tlow = i2c_dev->hw->tlow_std_mode;
+		thigh = i2c_dev->hw->thigh_std_mode;
+		tsu_thd = i2c_dev->hw->setup_hold_time_std_mode;
+	}
+
+	val = (thigh << I2C_THIGH_SHIFT) | tlow;
+	if (val)
+		i2c_writel(i2c_dev, val, I2C_INTERFACE_TIMING_0);
+
+	if (tsu_thd)
+		i2c_writel(i2c_dev, tsu_thd, I2C_INTERFACE_TIMING_1);
+
+	if (!clk_reinit) {
+		clk_multiplier = (tlow + thigh + 2);
+		clk_multiplier *= (i2c_dev->clk_divisor_non_hs_mode + 1);
+		err = clk_set_rate(i2c_dev->div_clk,
+				   i2c_dev->bus_clk_rate * clk_multiplier);
+		if (err) {
+			dev_err(i2c_dev->dev,
+				"failed changing clock rate: %d\n", err);
+			goto err;
+		}
+	}
+
 	if (!i2c_dev->is_dvc) {
 		u32 sl_cfg = i2c_readl(i2c_dev, I2C_SL_CNFG);
 
@@ -1106,7 +1168,7 @@ static int tegra_i2c_xfer_msg(struct tegra_i2c_dev *i2c_dev,
 			dmaengine_terminate_sync(i2c_dev->msg_read ?
 						  i2c_dev->rx_dma_chan :
 						  i2c_dev->tx_dma_chan);
-			tegra_i2c_init(i2c_dev);
+			tegra_i2c_init(i2c_dev, true);
 			return -ETIMEDOUT;
 		}
 
@@ -1134,7 +1196,7 @@ static int tegra_i2c_xfer_msg(struct tegra_i2c_dev *i2c_dev,
 	if (time_left == 0) {
 		dev_err(i2c_dev->dev, "i2c transfer timed out\n");
 
-		tegra_i2c_init(i2c_dev);
+		tegra_i2c_init(i2c_dev, true);
 		return -ETIMEDOUT;
 	}
 
@@ -1146,7 +1208,7 @@ static int tegra_i2c_xfer_msg(struct tegra_i2c_dev *i2c_dev,
 	if (likely(i2c_dev->msg_err == I2C_ERR_NONE))
 		return 0;
 
-	tegra_i2c_init(i2c_dev);
+	tegra_i2c_init(i2c_dev, true);
 	/* start recovery upon arbitration loss in single master mode */
 	if (i2c_dev->msg_err == I2C_ERR_ARBITRATION_LOST) {
 		if (!i2c_dev->is_multimaster_mode)
@@ -1241,7 +1303,8 @@ static const struct tegra_i2c_hw_feature tegra20_i2c_hw = {
 	.has_per_pkt_xfer_complete_irq = false,
 	.has_single_clk_source = false,
 	.clk_divisor_hs_mode = 3,
-	.clk_divisor_std_fast_mode = 0,
+	.clk_divisor_std_mode = 0,
+	.clk_divisor_fast_mode = 0,
 	.clk_divisor_fast_plus_mode = 0,
 	.has_config_load_reg = false,
 	.has_multi_master_mode = false,
@@ -1250,6 +1313,13 @@ static const struct tegra_i2c_hw_feature tegra20_i2c_hw = {
 	.quirks = &tegra_i2c_quirks,
 	.supports_bus_clear = false,
 	.has_apb_dma = true,
+	.tlow_std_mode = 0x4,
+	.thigh_std_mode = 0x2,
+	.tlow_fast_fastplus_mode = 0x4,
+	.thigh_fast_fastplus_mode = 0x2,
+	.setup_hold_time_std_mode = 0x0,
+	.setup_hold_time_fast_fast_plus_mode = 0x0,
+	.setup_hold_time_hs_mode = 0x0,
 };
 
 static const struct tegra_i2c_hw_feature tegra30_i2c_hw = {
@@ -1257,7 +1327,8 @@ static const struct tegra_i2c_hw_feature tegra30_i2c_hw = {
 	.has_per_pkt_xfer_complete_irq = false,
 	.has_single_clk_source = false,
 	.clk_divisor_hs_mode = 3,
-	.clk_divisor_std_fast_mode = 0,
+	.clk_divisor_std_mode = 0,
+	.clk_divisor_fast_mode = 0,
 	.clk_divisor_fast_plus_mode = 0,
 	.has_config_load_reg = false,
 	.has_multi_master_mode = false,
@@ -1266,6 +1337,13 @@ static const struct tegra_i2c_hw_feature tegra30_i2c_hw = {
 	.quirks = &tegra_i2c_quirks,
 	.supports_bus_clear = false,
 	.has_apb_dma = true,
+	.tlow_std_mode = 0x4,
+	.thigh_std_mode = 0x2,
+	.tlow_fast_fastplus_mode = 0x4,
+	.thigh_fast_fastplus_mode = 0x2,
+	.setup_hold_time_std_mode = 0x0,
+	.setup_hold_time_fast_fast_plus_mode = 0x0,
+	.setup_hold_time_hs_mode = 0x0,
 };
 
 static const struct tegra_i2c_hw_feature tegra114_i2c_hw = {
@@ -1273,7 +1351,8 @@ static const struct tegra_i2c_hw_feature tegra114_i2c_hw = {
 	.has_per_pkt_xfer_complete_irq = true,
 	.has_single_clk_source = true,
 	.clk_divisor_hs_mode = 1,
-	.clk_divisor_std_fast_mode = 0x19,
+	.clk_divisor_std_mode = 0x19,
+	.clk_divisor_fast_mode = 0x19,
 	.clk_divisor_fast_plus_mode = 0x10,
 	.has_config_load_reg = false,
 	.has_multi_master_mode = false,
@@ -1282,6 +1361,13 @@ static const struct tegra_i2c_hw_feature tegra114_i2c_hw = {
 	.quirks = &tegra_i2c_quirks,
 	.supports_bus_clear = true,
 	.has_apb_dma = true,
+	.tlow_std_mode = 0x4,
+	.thigh_std_mode = 0x2,
+	.tlow_fast_fastplus_mode = 0x4,
+	.thigh_fast_fastplus_mode = 0x2,
+	.setup_hold_time_std_mode = 0x0,
+	.setup_hold_time_fast_fast_plus_mode = 0x0,
+	.setup_hold_time_hs_mode = 0x0,
 };
 
 static const struct tegra_i2c_hw_feature tegra124_i2c_hw = {
@@ -1289,7 +1375,8 @@ static const struct tegra_i2c_hw_feature tegra124_i2c_hw = {
 	.has_per_pkt_xfer_complete_irq = true,
 	.has_single_clk_source = true,
 	.clk_divisor_hs_mode = 1,
-	.clk_divisor_std_fast_mode = 0x19,
+	.clk_divisor_std_mode = 0x19,
+	.clk_divisor_fast_mode = 0x19,
 	.clk_divisor_fast_plus_mode = 0x10,
 	.has_config_load_reg = true,
 	.has_multi_master_mode = false,
@@ -1298,6 +1385,13 @@ static const struct tegra_i2c_hw_feature tegra124_i2c_hw = {
 	.quirks = &tegra_i2c_quirks,
 	.supports_bus_clear = true,
 	.has_apb_dma = true,
+	.tlow_std_mode = 0x4,
+	.thigh_std_mode = 0x2,
+	.tlow_fast_fastplus_mode = 0x4,
+	.thigh_fast_fastplus_mode = 0x2,
+	.setup_hold_time_std_mode = 0x0,
+	.setup_hold_time_fast_fast_plus_mode = 0x0,
+	.setup_hold_time_hs_mode = 0x0,
 };
 
 static const struct tegra_i2c_hw_feature tegra210_i2c_hw = {
@@ -1305,7 +1399,8 @@ static const struct tegra_i2c_hw_feature tegra210_i2c_hw = {
 	.has_per_pkt_xfer_complete_irq = true,
 	.has_single_clk_source = true,
 	.clk_divisor_hs_mode = 1,
-	.clk_divisor_std_fast_mode = 0x19,
+	.clk_divisor_std_mode = 0x19,
+	.clk_divisor_fast_mode = 0x19,
 	.clk_divisor_fast_plus_mode = 0x10,
 	.has_config_load_reg = true,
 	.has_multi_master_mode = true,
@@ -1314,27 +1409,67 @@ static const struct tegra_i2c_hw_feature tegra210_i2c_hw = {
 	.quirks = &tegra_i2c_quirks,
 	.supports_bus_clear = true,
 	.has_apb_dma = true,
+	.tlow_std_mode = 0x4,
+	.thigh_std_mode = 0x2,
+	.tlow_fast_fastplus_mode = 0x4,
+	.thigh_fast_fastplus_mode = 0x2,
+	.setup_hold_time_std_mode = 0,
+	.setup_hold_time_fast_fast_plus_mode = 0,
+	.setup_hold_time_hs_mode = 0,
 };
 
-static const struct tegra_i2c_hw_feature tegra194_i2c_hw = {
+static const struct tegra_i2c_hw_feature tegra186_i2c_hw = {
 	.has_continue_xfer_support = true,
 	.has_per_pkt_xfer_complete_irq = true,
 	.has_single_clk_source = true,
 	.clk_divisor_hs_mode = 1,
-	.clk_divisor_std_fast_mode = 0x19,
+	.clk_divisor_std_mode = 0x16,
+	.clk_divisor_fast_mode = 0x19,
 	.clk_divisor_fast_plus_mode = 0x10,
 	.has_config_load_reg = true,
 	.has_multi_master_mode = true,
 	.has_slcg_override_reg = true,
 	.has_mst_fifo = true,
+	.quirks = &tegra_i2c_quirks,
+	.supports_bus_clear = true,
+	.has_apb_dma = false,
+	.tlow_std_mode = 0x4,
+	.thigh_std_mode = 0x3,
+	.tlow_fast_fastplus_mode = 0x4,
+	.thigh_fast_fastplus_mode = 0x2,
+	.setup_hold_time_std_mode = 0,
+	.setup_hold_time_fast_fast_plus_mode = 0,
+	.setup_hold_time_hs_mode = 0,
+};
+
+static const struct tegra_i2c_hw_feature tegra194_i2c_hw = {
+	.has_continue_xfer_support = true,
+	.has_per_pkt_xfer_complete_irq = true,
+	.has_single_clk_source = true,
+	.clk_divisor_hs_mode = 1,
+	.clk_divisor_std_mode = 0x4f,
+	.clk_divisor_fast_mode = 0x3c,
+	.clk_divisor_fast_plus_mode = 0x16,
+	.has_config_load_reg = true,
+	.has_multi_master_mode = true,
+	.has_slcg_override_reg = true,
+	.has_mst_fifo = true,
 	.quirks = &tegra194_i2c_quirks,
 	.supports_bus_clear = true,
 	.has_apb_dma = false,
+	.tlow_std_mode = 0x8,
+	.thigh_std_mode = 0x7,
+	.tlow_fast_fastplus_mode = 0x2,
+	.thigh_fast_fastplus_mode = 0x2,
+	.setup_hold_time_std_mode = 0x08080808,
+	.setup_hold_time_fast_fast_plus_mode = 0x02020202,
+	.setup_hold_time_hs_mode = 0x090909,
 };
 
 /* Match table for of_platform binding */
 static const struct of_device_id tegra_i2c_of_match[] = {
 	{ .compatible = "nvidia,tegra194-i2c", .data = &tegra194_i2c_hw, },
+	{ .compatible = "nvidia,tegra186-i2c", .data = &tegra186_i2c_hw, },
 	{ .compatible = "nvidia,tegra210-i2c", .data = &tegra210_i2c_hw, },
 	{ .compatible = "nvidia,tegra124-i2c", .data = &tegra124_i2c_hw, },
 	{ .compatible = "nvidia,tegra114-i2c", .data = &tegra114_i2c_hw, },
@@ -1355,7 +1490,6 @@ static int tegra_i2c_probe(struct platform_device *pdev)
 	phys_addr_t base_phys;
 	int irq;
 	int ret = 0;
-	int clk_multiplier = I2C_CLK_MULTIPLIER_STD_FAST_MODE;
 
 	res = platform_get_resource(pdev, IORESOURCE_MEM, 0);
 	base_phys = res->start;
@@ -1426,20 +1560,17 @@ static int tegra_i2c_probe(struct platform_device *pdev)
 		}
 	}
 
-	i2c_dev->clk_divisor_non_hs_mode =
-			i2c_dev->hw->clk_divisor_std_fast_mode;
-	if (i2c_dev->hw->clk_divisor_fast_plus_mode &&
-		(i2c_dev->bus_clk_rate == 1000000))
+	if (i2c_dev->bus_clk_rate > I2C_FAST_MODE &&
+	    i2c_dev->bus_clk_rate <= I2C_FAST_PLUS_MODE)
 		i2c_dev->clk_divisor_non_hs_mode =
-			i2c_dev->hw->clk_divisor_fast_plus_mode;
-
-	clk_multiplier *= (i2c_dev->clk_divisor_non_hs_mode + 1);
-	ret = clk_set_rate(i2c_dev->div_clk,
-			   i2c_dev->bus_clk_rate * clk_multiplier);
-	if (ret) {
-		dev_err(i2c_dev->dev, "Clock rate change failed %d\n", ret);
-		goto unprepare_fast_clk;
-	}
+				i2c_dev->hw->clk_divisor_fast_plus_mode;
+	else if (i2c_dev->bus_clk_rate > I2C_STANDARD_MODE &&
+		 i2c_dev->bus_clk_rate <= I2C_FAST_MODE)
+		i2c_dev->clk_divisor_non_hs_mode =
+				i2c_dev->hw->clk_divisor_fast_mode;
+	else
+		i2c_dev->clk_divisor_non_hs_mode =
+				i2c_dev->hw->clk_divisor_std_mode;
 
 	ret = clk_prepare(i2c_dev->div_clk);
 	if (ret < 0) {
@@ -1469,7 +1600,7 @@ static int tegra_i2c_probe(struct platform_device *pdev)
 	if (ret < 0)
 		goto disable_div_clk;
 
-	ret = tegra_i2c_init(i2c_dev);
+	ret = tegra_i2c_init(i2c_dev, false);
 	if (ret) {
 		dev_err(&pdev->dev, "Failed to initialize i2c controller\n");
 		goto disable_div_clk;
-- 
2.7.4

^ permalink raw reply related	[flat|nested] 35+ messages in thread

* Re: [PATCH V12 3/5] i2c: tegra: Add DMA support
  2019-02-05 22:46 ` [PATCH V12 3/5] i2c: tegra: Add DMA support Sowjanya Komatineni
@ 2019-02-06 11:55   ` Dmitry Osipenko
  2019-02-06 12:49     ` Sowjanya Komatineni
                       ` (2 more replies)
  2019-02-06 12:40   ` Dmitry Osipenko
  1 sibling, 3 replies; 35+ messages in thread
From: Dmitry Osipenko @ 2019-02-06 11:55 UTC (permalink / raw)
  To: Sowjanya Komatineni, thierry.reding, jonathanh, mkarthik,
	smohammed, talho
  Cc: linux-tegra, linux-kernel, linux-i2c

06.02.2019 1:46, Sowjanya Komatineni пишет:
> This patch adds DMA support for Tegra I2C.
> 
> Tegra I2C TX and RX FIFO depth is 8 words. PIO mode is used for
> transfer size of the max FIFO depth and DMA mode is used for
> transfer size higher than max FIFO depth to save CPU overhead.
> 
> PIO mode needs full intervention of CPU to fill or empty FIFO's
> and also need to service multiple data requests interrupt for the
> same transaction. This adds delay between data bytes of the same
> transfer when CPU is fully loaded and some slave devices has
> internal timeout for no bus activity and stops transaction to
> avoid bus hang. DMA mode is helpful in such cases.
> 
> DMA mode is also helpful for Large transfers during downloading or
> uploading FW over I2C to some external devices.
> 
> Signed-off-by: Sowjanya Komatineni <skomatineni@nvidia.com>
> ---
>  [V12] : Replaced dma_alloc_coherent with dma_alloc_attrs to force the allocated
> 	 buffer to be contiguous also in physical memory as Tegra194 supports max
> 	 64K and dma_alloc_coherent doesnt guarentee contiguous memory.
> 	 Changed return code from EIO to EINVAL incase of failure to obtain dma
> 	 descriptor.
> 	 Fixed coding style check issues.	 
>  [V11] : Replaced deprecated dmaengine_terminate_all with dmaengine_termine_async
> 	 from non-atomic context and dmaengine_terminate_sync from atomic context.
> 	 Fixed to program fifo trigger levels properly when transfer falls back to
> 	 pio mode in case of dma slave configuration failure and other minor fixes.
>  [V10] : APBDMA is replaced with GPCDMA on Tegra186 and Tegra194 designs.
> 	 Added apbdma hw support flag to now allow Tegra186 and later use
> 	 APBDMA driver.
> 	 Added explicit flow control enable for DMA slave config and error handling.
> 	 Moved releasing DMA resources to seperate function to reuse in
> 	 multiple places.
> 	 Updated to register tegra_i2c_driver from module level rather than subsys
> 	 level.
> 	 Other minor feedback
>  [V9] :  Rebased to 5.0-rc4
> 	 Removed dependency of APB DMA in Kconfig and added conditional check
>  	 in I2C driver to decide on using DMA mode.
> 	 Changed back the allocation of dma buffer during i2c probe.
> 	 Fixed FIFO triggers depending on DMA Vs PIO.
>  [V8] :  Moved back dma init to i2c probe, removed ALL_PACKETS_XFER_COMPLETE
> 	 interrupt and using PACKETS_XFER_COMPLETE interrupt only and some
> 	 other fixes
> 	 Updated Kconfig for APB_DMA dependency
>  [V7] :  Same as V6
>  [V6] :  Updated for proper buffer allocation/freeing, channel release.
> 	 Updated to use exact xfer size for syncing dma buffer.
>  [V5] :  Same as V4
>  [V4] :  Updated to allocate DMA buffer only when DMA mode.
> 	 Updated to fall back to PIO mode when DMA channel request or
> 	 buffer allocation fails.
>  [V3] :  Updated without additional buffer allocation.
>  [V2] :  Updated based on V1 review feedback along with code cleanup for
> 	 proper implementation of DMA.
> 
> 
>  drivers/i2c/busses/i2c-tegra.c | 413 ++++++++++++++++++++++++++++++++++++-----
>  1 file changed, 369 insertions(+), 44 deletions(-)
> 
> diff --git a/drivers/i2c/busses/i2c-tegra.c b/drivers/i2c/busses/i2c-tegra.c
> index 118b7023a0f4..77277a09e485 100644
> --- a/drivers/i2c/busses/i2c-tegra.c
> +++ b/drivers/i2c/busses/i2c-tegra.c
> @@ -8,6 +8,9 @@
>  
>  #include <linux/clk.h>
>  #include <linux/delay.h>
> +#include <linux/dmaengine.h>
> +#include <linux/dmapool.h>

We are not using DMA pools anywhere in the code, <linux/dmapool.h> isn't needed. Let's remove it.

> +#include <linux/dma-mapping.h>
>  #include <linux/err.h>
>  #include <linux/i2c.h>
>  #include <linux/init.h>
> @@ -44,6 +47,8 @@
>  #define I2C_FIFO_CONTROL_RX_FLUSH		BIT(0)
>  #define I2C_FIFO_CONTROL_TX_TRIG_SHIFT		5
>  #define I2C_FIFO_CONTROL_RX_TRIG_SHIFT		2
> +#define I2C_FIFO_CONTROL_TX_TRIG(x)		(((x) - 1) << 5)
> +#define I2C_FIFO_CONTROL_RX_TRIG(x)		(((x) - 1) << 2)
>  #define I2C_FIFO_STATUS				0x060
>  #define I2C_FIFO_STATUS_TX_MASK			0xF0
>  #define I2C_FIFO_STATUS_TX_SHIFT		4
> @@ -125,6 +130,19 @@
>  #define I2C_MST_FIFO_STATUS_TX_MASK		0xff0000
>  #define I2C_MST_FIFO_STATUS_TX_SHIFT		16
>  
> +/* Packet header size in bytes */
> +#define I2C_PACKET_HEADER_SIZE			12
> +
> +#define DATA_DMA_DIR_TX				BIT(0)
> +#define DATA_DMA_DIR_RX				BIT(1)

The DATA_DMA_DIR_TX/RX are not used anywhere in the code, let's remove them.

[snip]

		TEGRA_I2C_TIMEOUT);
>  	tegra_i2c_mask_irq(i2c_dev, int_mask);
> @@ -814,6 +1133,7 @@ static int tegra_i2c_xfer_msg(struct tegra_i2c_dev *i2c_dev,
>  		time_left, completion_done(&i2c_dev->msg_complete),
>  		i2c_dev->msg_err);
>  
> +	i2c_dev->is_curr_dma_xfer = false;

This line could be removed because there is no need to clear "is_curr_dma_xfer" at this point.

>  	if (likely(i2c_dev->msg_err == I2C_ERR_NONE))
>  		return 0;
[snip]


Sowjanya, I tried to enforce DMA transferring + setting DMA burst to a one word and this combination doesn't work well while it should, if I'm not missing something. Could you please take a look at the problem or explain why that happens?

Here is the change I made:

-----------------
diff --git a/drivers/i2c/busses/i2c-tegra.c b/drivers/i2c/busses/i2c-tegra.c
index c538ed5f8e2c..59e245d4417d 100644
--- a/drivers/i2c/busses/i2c-tegra.c
+++ b/drivers/i2c/busses/i2c-tegra.c
@@ -6,6 +6,8 @@
  * Author: Colin Cross <ccross@android.com>
  */
 
+#define DEBUG
+
 #include <linux/clk.h>
 #include <linux/delay.h>
 #include <linux/dmaengine.h>
@@ -929,12 +931,7 @@ static void tegra_i2c_config_fifo_trig(struct tegra_i2c_dev *i2c_dev,
        val = i2c_readl(i2c_dev, reg);
 
        if (i2c_dev->is_curr_dma_xfer) {
-               if (len & 0xF)
                        dma_burst = 1;
-               else if (len & 0x10)
-                       dma_burst = 4;
-               else
-                       dma_burst = 8;
 
                if (i2c_dev->msg_read) {
                        chan = i2c_dev->rx_dma_chan;
@@ -1046,8 +1043,7 @@ static int tegra_i2c_xfer_msg(struct tegra_i2c_dev *i2c_dev,
                xfer_size = msg->len + I2C_PACKET_HEADER_SIZE;
 
        xfer_size = ALIGN(xfer_size, BYTES_PER_FIFO_WORD);
-       i2c_dev->is_curr_dma_xfer = (xfer_size > I2C_PIO_MODE_MAX_LEN) &&
-                                   i2c_dev->dma_buf;
+       i2c_dev->is_curr_dma_xfer = !!i2c_dev->dma_buf;
        tegra_i2c_config_fifo_trig(i2c_dev, xfer_size);
        dma = i2c_dev->is_curr_dma_xfer
-----------------

And here what happens:

-----------------
...
[    0.761144] tegra_rtc 7000e000.rtc: registered as rtc1
[    0.761199] tegra_rtc 7000e000.rtc: Tegra internal Real Time Clock
[    0.761406] i2c /dev entries driver
[    0.919233] tegra-i2c 7000c000.i2c: starting DMA for length: 16
[    0.919246] tegra-i2c 7000c000.i2c: unmasked irq: 0c
[    0.919345] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
[    0.919355] tegra-i2c 7000c000.i2c: starting DMA for length: 8
[    0.919363] tegra-i2c 7000c000.i2c: unmasked irq: 0c
[    0.919628] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
[    0.919641] tegra-i2c 7000c000.i2c: starting DMA for length: 16
[    0.919649] tegra-i2c 7000c000.i2c: unmasked irq: 0c
[    0.919746] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
[    0.919755] tegra-i2c 7000c000.i2c: starting DMA for length: 112
[    0.919763] tegra-i2c 7000c000.i2c: unmasked irq: 0c
[    0.923140] tegra-i2c 7000c000.i2c: transfer complete: 11 0 0
[    0.923150] atmel_mxt_ts 0-004c: Family: 160 Variant: 0 Firmware V1.0.AA Objects: 18
[    0.923208] tegra-i2c 7000c000.i2c: starting DMA for length: 16
[    0.923217] tegra-i2c 7000c000.i2c: unmasked irq: 0c
[    0.923314] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
[    0.923323] tegra-i2c 7000c000.i2c: starting DMA for length: 224
[    0.923331] tegra-i2c 7000c000.i2c: unmasked irq: 0c
[    0.933564] tegra-i2c 7000c000.i2c: transfer complete: 11 0 0
[    0.933599] tegra-i2c 7000c000.i2c: starting DMA for length: 16
[    0.933609] tegra-i2c 7000c000.i2c: unmasked irq: 0c
[    0.933760] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
[    0.933770] tegra-i2c 7000c000.i2c: starting DMA for length: 12
[    0.933779] tegra-i2c 7000c000.i2c: unmasked irq: 0c
[    0.934284] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
[    0.934309] tegra-i2c 7000c000.i2c: starting DMA for length: 16
[    0.934317] tegra-i2c 7000c000.i2c: unmasked irq: 0c
[    0.934500] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
[    0.934509] tegra-i2c 7000c000.i2c: starting DMA for length: 12
[    0.934518] tegra-i2c 7000c000.i2c: unmasked irq: 0c
[    0.935023] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
[    0.935081] tegra-i2c 7000c000.i2c: starting DMA for length: 16
[    0.935091] tegra-i2c 7000c000.i2c: unmasked irq: 0c
[    0.935240] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
[    0.935249] tegra-i2c 7000c000.i2c: starting DMA for length: 4
[    0.935258] tegra-i2c 7000c000.i2c: unmasked irq: 0c
[    0.935399] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
[    0.935416] tegra-i2c 7000c000.i2c: starting DMA for length: 16
[    0.935424] tegra-i2c 7000c000.i2c: unmasked irq: 0c
[    0.935655] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
[    0.945445] tegra-i2c 7000d000.i2c: starting DMA for length: 16
[    0.945456] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.969236] tegra-i2c 7000c000.i2c: starting DMA for length: 16
[    0.969245] tegra-i2c 7000c000.i2c: unmasked irq: 0c
[    0.969361] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
[    0.969370] tegra-i2c 7000c000.i2c: starting DMA for length: 4
[    0.969379] tegra-i2c 7000c000.i2c: unmasked irq: 0c
[    0.969462] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
[    0.982587] tegra-i2c 7000c000.i2c: starting DMA for length: 16
[    0.982596] tegra-i2c 7000c000.i2c: unmasked irq: 0c
[    0.982722] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
[    0.982731] tegra-i2c 7000c000.i2c: starting DMA for length: 12
[    0.982740] tegra-i2c 7000c000.i2c: unmasked irq: 0c
[    0.983071] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
[    0.983090] tegra-i2c 7000c000.i2c: starting DMA for length: 16
[    0.983098] tegra-i2c 7000c000.i2c: unmasked irq: 0c
[    0.983252] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
[    0.983261] tegra-i2c 7000c000.i2c: starting DMA for length: 136
[    0.983269] tegra-i2c 7000c000.i2c: unmasked irq: 0c
[    0.987605] tegra-i2c 7000c000.i2c: transfer complete: 11 0 0
[    0.987623] tegra-i2c 7000c000.i2c: starting DMA for length: 16
[    0.987631] tegra-i2c 7000c000.i2c: unmasked irq: 0c
[    0.987800] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
[    0.987809] tegra-i2c 7000c000.i2c: starting DMA for length: 12
[    0.987817] tegra-i2c 7000c000.i2c: unmasked irq: 0c
[    0.988324] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
[    1.009227] tegra-i2c 7000c000.i2c: starting DMA for length: 16
[    1.009236] tegra-i2c 7000c000.i2c: unmasked irq: 0c
[    1.009374] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
[    1.009383] tegra-i2c 7000c000.i2c: starting DMA for length: 4
[    1.009391] tegra-i2c 7000c000.i2c: unmasked irq: 0c
[    1.009479] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
[    1.009497] atmel_mxt_ts 0-004c: Warning: Info CRC error - device=0xF436DC file=0x000000
[    1.009588] tegra-i2c 7000c000.i2c: starting DMA for length: 272
[    1.009597] tegra-i2c 7000c000.i2c: unmasked irq: 0c
[    1.017483] tegra-i2c 7000c000.i2c: transfer complete: 11 0 0
[    1.017496] tegra-i2c 7000c000.i2c: starting DMA for length: 120
[    1.017504] tegra-i2c 7000c000.i2c: unmasked irq: 0c
[    1.020896] tegra-i2c 7000c000.i2c: transfer complete: 11 0 0
[    1.020909] tegra-i2c 7000c000.i2c: starting DMA for length: 16
[    1.020918] tegra-i2c 7000c000.i2c: unmasked irq: 0c
[    1.021055] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
[    1.032230] tegra-i2c 7000c000.i2c: starting DMA for length: 16
[    1.032239] tegra-i2c 7000c000.i2c: unmasked irq: 0c
[    1.032359] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
[    1.032368] tegra-i2c 7000c000.i2c: starting DMA for length: 12
[    1.032376] tegra-i2c 7000c000.i2c: unmasked irq: 0c
[    1.032704] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
[    1.049224] tegra-i2c 7000d000.i2c: i2c transfer timed out
[    1.049253] tps6586x 3-0034: Chip ID read failed: -110
[    1.049281] tps6586x: probe of 3-0034 failed with error -5
...
-----------------

^ permalink raw reply related	[flat|nested] 35+ messages in thread

* Re: [PATCH V12 3/5] i2c: tegra: Add DMA support
  2019-02-05 22:46 ` [PATCH V12 3/5] i2c: tegra: Add DMA support Sowjanya Komatineni
  2019-02-06 11:55   ` Dmitry Osipenko
@ 2019-02-06 12:40   ` Dmitry Osipenko
  2019-02-06 12:48     ` Thierry Reding
  1 sibling, 1 reply; 35+ messages in thread
From: Dmitry Osipenko @ 2019-02-06 12:40 UTC (permalink / raw)
  To: Sowjanya Komatineni, thierry.reding, jonathanh, mkarthik,
	smohammed, talho
  Cc: linux-tegra, linux-kernel, linux-i2c

06.02.2019 1:46, Sowjanya Komatineni пишет:
> This patch adds DMA support for Tegra I2C.
> 
> Tegra I2C TX and RX FIFO depth is 8 words. PIO mode is used for
> transfer size of the max FIFO depth and DMA mode is used for
> transfer size higher than max FIFO depth to save CPU overhead.
> 
> PIO mode needs full intervention of CPU to fill or empty FIFO's
> and also need to service multiple data requests interrupt for the
> same transaction. This adds delay between data bytes of the same
> transfer when CPU is fully loaded and some slave devices has
> internal timeout for no bus activity and stops transaction to
> avoid bus hang. DMA mode is helpful in such cases.
> 
> DMA mode is also helpful for Large transfers during downloading or
> uploading FW over I2C to some external devices.
> 
> Signed-off-by: Sowjanya Komatineni <skomatineni@nvidia.com>
> ---
>  [V12] : Replaced dma_alloc_coherent with dma_alloc_attrs to force the allocated
> 	 buffer to be contiguous also in physical memory as Tegra194 supports max
> 	 64K and dma_alloc_coherent doesnt guarentee contiguous memory.
> 	 Changed return code from EIO to EINVAL incase of failure to obtain dma
> 	 descriptor.
> 	 Fixed coding style check issues.	 
>  [V11] : Replaced deprecated dmaengine_terminate_all with dmaengine_termine_async
> 	 from non-atomic context and dmaengine_terminate_sync from atomic context.
> 	 Fixed to program fifo trigger levels properly when transfer falls back to
> 	 pio mode in case of dma slave configuration failure and other minor fixes.
>  [V10] : APBDMA is replaced with GPCDMA on Tegra186 and Tegra194 designs.
> 	 Added apbdma hw support flag to now allow Tegra186 and later use
> 	 APBDMA driver.
> 	 Added explicit flow control enable for DMA slave config and error handling.
> 	 Moved releasing DMA resources to seperate function to reuse in
> 	 multiple places.
> 	 Updated to register tegra_i2c_driver from module level rather than subsys
> 	 level.
> 	 Other minor feedback
>  [V9] :  Rebased to 5.0-rc4
> 	 Removed dependency of APB DMA in Kconfig and added conditional check
>  	 in I2C driver to decide on using DMA mode.
> 	 Changed back the allocation of dma buffer during i2c probe.
> 	 Fixed FIFO triggers depending on DMA Vs PIO.
>  [V8] :  Moved back dma init to i2c probe, removed ALL_PACKETS_XFER_COMPLETE
> 	 interrupt and using PACKETS_XFER_COMPLETE interrupt only and some
> 	 other fixes
> 	 Updated Kconfig for APB_DMA dependency
>  [V7] :  Same as V6
>  [V6] :  Updated for proper buffer allocation/freeing, channel release.
> 	 Updated to use exact xfer size for syncing dma buffer.
>  [V5] :  Same as V4
>  [V4] :  Updated to allocate DMA buffer only when DMA mode.
> 	 Updated to fall back to PIO mode when DMA channel request or
> 	 buffer allocation fails.
>  [V3] :  Updated without additional buffer allocation.
>  [V2] :  Updated based on V1 review feedback along with code cleanup for
> 	 proper implementation of DMA.
> 
> 
>  drivers/i2c/busses/i2c-tegra.c | 413 ++++++++++++++++++++++++++++++++++++-----
>  1 file changed, 369 insertions(+), 44 deletions(-)
> 
> diff --git a/drivers/i2c/busses/i2c-tegra.c b/drivers/i2c/busses/i2c-tegra.c
> index 118b7023a0f4..77277a09e485 100644
> --- a/drivers/i2c/busses/i2c-tegra.c
> +++ b/drivers/i2c/busses/i2c-tegra.c
> @@ -8,6 +8,9 @@
>  
>  #include <linux/clk.h>
>  #include <linux/delay.h>
> +#include <linux/dmaengine.h>
> +#include <linux/dmapool.h>
> +#include <linux/dma-mapping.h>
>  #include <linux/err.h>
>  #include <linux/i2c.h>
>  #include <linux/init.h>
> @@ -44,6 +47,8 @@
>  #define I2C_FIFO_CONTROL_RX_FLUSH		BIT(0)
>  #define I2C_FIFO_CONTROL_TX_TRIG_SHIFT		5
>  #define I2C_FIFO_CONTROL_RX_TRIG_SHIFT		2
> +#define I2C_FIFO_CONTROL_TX_TRIG(x)		(((x) - 1) << 5)
> +#define I2C_FIFO_CONTROL_RX_TRIG(x)		(((x) - 1) << 2)
>  #define I2C_FIFO_STATUS				0x060
>  #define I2C_FIFO_STATUS_TX_MASK			0xF0
>  #define I2C_FIFO_STATUS_TX_SHIFT		4
> @@ -125,6 +130,19 @@
>  #define I2C_MST_FIFO_STATUS_TX_MASK		0xff0000
>  #define I2C_MST_FIFO_STATUS_TX_SHIFT		16
>  
> +/* Packet header size in bytes */
> +#define I2C_PACKET_HEADER_SIZE			12
> +
> +#define DATA_DMA_DIR_TX				BIT(0)
> +#define DATA_DMA_DIR_RX				BIT(1)
> +
> +/*
> + * Upto I2C_PIO_MODE_MAX_LEN bytes, controller will use PIO mode,
> + * above this, controller will use DMA to fill FIFO.
> + * MAX PIO len is 20 bytes excluding packet header.
> + */
> +#define I2C_PIO_MODE_MAX_LEN			32
> +
>  /*
>   * msg_end_type: The bus control which need to be send at end of transfer.
>   * @MSG_END_STOP: Send stop pulse at end of transfer.
> @@ -166,6 +184,7 @@ enum msg_end_type {
>   *		allowing 0 length transfers.
>   * @supports_bus_clear: Bus Clear support to recover from bus hang during
>   *		SDA stuck low from device for some unknown reasons.
> + * @has_apb_dma: Support of APBDMA on corresponding Tegra chip.
>   */
>  struct tegra_i2c_hw_feature {
>  	bool has_continue_xfer_support;
> @@ -180,6 +199,7 @@ struct tegra_i2c_hw_feature {
>  	bool has_mst_fifo;
>  	const struct i2c_adapter_quirks *quirks;
>  	bool supports_bus_clear;
> +	bool has_apb_dma;
>  };
>  
>  /**
> @@ -191,6 +211,7 @@ struct tegra_i2c_hw_feature {
>   * @fast_clk: clock reference for fast clock of I2C controller
>   * @rst: reset control for the I2C controller
>   * @base: ioremapped registers cookie
> + * @base_phys: Physical base address of the I2C controller
>   * @cont_id: I2C controller ID, used for packet header
>   * @irq: IRQ number of transfer complete interrupt
>   * @irq_disabled: used to track whether or not the interrupt is enabled
> @@ -204,6 +225,13 @@ struct tegra_i2c_hw_feature {
>   * @clk_divisor_non_hs_mode: clock divider for non-high-speed modes
>   * @is_multimaster_mode: track if I2C controller is in multi-master mode
>   * @xfer_lock: lock to serialize transfer submission and processing
> + * @tx_dma_chan: DMA transmit channel
> + * @rx_dma_chan: DMA receive channel
> + * @dma_phys: handle to DMA resources
> + * @dma_buf: pointer to allocated DMA buffer
> + * @dma_buf_size: DMA buffer size
> + * @is_curr_dma_xfer: indicates active DMA transfer
> + * @dma_complete: DMA completion notifier
>   */
>  struct tegra_i2c_dev {
>  	struct device *dev;
> @@ -213,6 +241,7 @@ struct tegra_i2c_dev {
>  	struct clk *fast_clk;
>  	struct reset_control *rst;
>  	void __iomem *base;
> +	phys_addr_t base_phys;
>  	int cont_id;
>  	int irq;
>  	bool irq_disabled;
> @@ -226,6 +255,13 @@ struct tegra_i2c_dev {
>  	u16 clk_divisor_non_hs_mode;
>  	bool is_multimaster_mode;
>  	spinlock_t xfer_lock;
> +	struct dma_chan *tx_dma_chan;
> +	struct dma_chan *rx_dma_chan;
> +	dma_addr_t dma_phys;
> +	u32 *dma_buf;
> +	unsigned int dma_buf_size;
> +	bool is_curr_dma_xfer;
> +	struct completion dma_complete;
>  };
>  
>  static void dvc_writel(struct tegra_i2c_dev *i2c_dev, u32 val,
> @@ -294,6 +330,111 @@ static void tegra_i2c_unmask_irq(struct tegra_i2c_dev *i2c_dev, u32 mask)
>  	i2c_writel(i2c_dev, int_mask, I2C_INT_MASK);
>  }
>  
> +static void tegra_i2c_dma_complete(void *args)
> +{
> +	struct tegra_i2c_dev *i2c_dev = args;
> +
> +	complete(&i2c_dev->dma_complete);
> +}
> +
> +static int tegra_i2c_dma_submit(struct tegra_i2c_dev *i2c_dev, size_t len)
> +{
> +	struct dma_async_tx_descriptor *dma_desc;
> +	enum dma_transfer_direction dir;
> +	struct dma_chan *chan;
> +
> +	dev_dbg(i2c_dev->dev, "starting DMA for length: %zu\n", len);
> +	reinit_completion(&i2c_dev->dma_complete);
> +	dir = i2c_dev->msg_read ? DMA_DEV_TO_MEM : DMA_MEM_TO_DEV;
> +	chan = i2c_dev->msg_read ? i2c_dev->rx_dma_chan : i2c_dev->tx_dma_chan;
> +	dma_desc = dmaengine_prep_slave_single(chan, i2c_dev->dma_phys,
> +					       len, dir, DMA_PREP_INTERRUPT |
> +					       DMA_CTRL_ACK);
> +	if (!dma_desc) {
> +		dev_err(i2c_dev->dev, "failed to get DMA descriptor\n");
> +		return -EINVAL;
> +	}
> +
> +	dma_desc->callback = tegra_i2c_dma_complete;
> +	dma_desc->callback_param = i2c_dev;
> +	dmaengine_submit(dma_desc);
> +	dma_async_issue_pending(chan);
> +	return 0;
> +}
> +
> +static void tegra_i2c_release_dma(struct tegra_i2c_dev *i2c_dev)
> +{
> +	if (i2c_dev->dma_buf) {
> +		dma_free_attrs(i2c_dev->dev, i2c_dev->dma_buf_size,
> +			       i2c_dev->dma_buf, i2c_dev->dma_phys,
> +			       DMA_ATTR_FORCE_CONTIGUOUS);
> +		i2c_dev->dma_buf = NULL;
> +	}
> +
> +	if (i2c_dev->tx_dma_chan) {
> +		dma_release_channel(i2c_dev->tx_dma_chan);
> +		i2c_dev->tx_dma_chan = NULL;
> +	}
> +
> +	if (i2c_dev->rx_dma_chan) {
> +		dma_release_channel(i2c_dev->rx_dma_chan);
> +		i2c_dev->rx_dma_chan = NULL;
> +	}
> +}
> +
> +static int tegra_i2c_init_dma(struct tegra_i2c_dev *i2c_dev)
> +{
> +	struct dma_chan *chan;
> +	u32 *dma_buf;
> +	dma_addr_t dma_phys;
> +	int err;
> +
> +	if (!IS_ENABLED(CONFIG_TEGRA20_APB_DMA) ||
> +	    !i2c_dev->hw->has_apb_dma) {
> +		err = -ENODEV;
> +		goto err_out;
> +	}
> +
> +	chan = dma_request_slave_channel_reason(i2c_dev->dev, "rx");
> +	if (IS_ERR(chan)) {
> +		err = PTR_ERR(chan);
> +		goto err_out;
> +	}
> +
> +	i2c_dev->rx_dma_chan = chan;
> +
> +	chan = dma_request_slave_channel_reason(i2c_dev->dev, "tx");
> +	if (IS_ERR(chan)) {
> +		err = PTR_ERR(chan);
> +		goto err_out;
> +	}
> +
> +	i2c_dev->tx_dma_chan = chan;
> +
> +	dma_buf = dma_alloc_attrs(i2c_dev->dev, i2c_dev->dma_buf_size,
> +				  &dma_phys, GFP_KERNEL | __GFP_NOWARN,
> +				  DMA_ATTR_FORCE_CONTIGUOUS);
> +	if (!dma_buf) {
> +		dev_err(i2c_dev->dev, "failed to allocate the DMA buffer\n");
> +		err = -ENOMEM;
> +		goto err_out;
> +	}
> +
> +	i2c_dev->dma_buf = dma_buf;
> +	i2c_dev->dma_phys = dma_phys;
> +	return 0;
> +
> +err_out:
> +	tegra_i2c_release_dma(i2c_dev);
> +	if (err != -EPROBE_DEFER) {
> +		dev_err(i2c_dev->dev, "can't use DMA, err: %d, using PIO\n",
> +			err);
> +		return 0;
> +	}
> +
> +	return err;
> +}
> +
>  static int tegra_i2c_flush_fifos(struct tegra_i2c_dev *i2c_dev)
>  {
>  	unsigned long timeout = jiffies + HZ;
> @@ -571,16 +712,6 @@ static int tegra_i2c_init(struct tegra_i2c_dev *i2c_dev)
>  		i2c_writel(i2c_dev, 0x00, I2C_SL_ADDR2);
>  	}
>  
> -	if (i2c_dev->hw->has_mst_fifo) {
> -		val = I2C_MST_FIFO_CONTROL_TX_TRIG(8) |
> -		      I2C_MST_FIFO_CONTROL_RX_TRIG(1);
> -		i2c_writel(i2c_dev, val, I2C_MST_FIFO_CONTROL);
> -	} else {
> -		val = 7 << I2C_FIFO_CONTROL_TX_TRIG_SHIFT |
> -			0 << I2C_FIFO_CONTROL_RX_TRIG_SHIFT;
> -		i2c_writel(i2c_dev, val, I2C_FIFO_CONTROL);
> -	}
> -
>  	err = tegra_i2c_flush_fifos(i2c_dev);
>  	if (err)
>  		goto err;
> @@ -660,25 +791,37 @@ static irqreturn_t tegra_i2c_isr(int irq, void *dev_id)
>  	if (i2c_dev->hw->supports_bus_clear && (status & I2C_INT_BUS_CLR_DONE))
>  		goto err;
>  
> -	if (i2c_dev->msg_read && (status & I2C_INT_RX_FIFO_DATA_REQ)) {
> -		if (i2c_dev->msg_buf_remaining)
> -			tegra_i2c_empty_rx_fifo(i2c_dev);
> -		else
> -			BUG();
> -	}
> +	if (!i2c_dev->is_curr_dma_xfer) {
> +		if (i2c_dev->msg_read && (status & I2C_INT_RX_FIFO_DATA_REQ)) {
> +			if (i2c_dev->msg_buf_remaining)
> +				tegra_i2c_empty_rx_fifo(i2c_dev);
> +			else
> +				BUG();
> +		}
>  
> -	if (!i2c_dev->msg_read && (status & I2C_INT_TX_FIFO_DATA_REQ)) {
> -		if (i2c_dev->msg_buf_remaining)
> -			tegra_i2c_fill_tx_fifo(i2c_dev);
> -		else
> -			tegra_i2c_mask_irq(i2c_dev, I2C_INT_TX_FIFO_DATA_REQ);
> +		if (!i2c_dev->msg_read && (status & I2C_INT_TX_FIFO_DATA_REQ)) {
> +			if (i2c_dev->msg_buf_remaining)
> +				tegra_i2c_fill_tx_fifo(i2c_dev);
> +			else
> +				tegra_i2c_mask_irq(i2c_dev,
> +						   I2C_INT_TX_FIFO_DATA_REQ);
> +		}
>  	}
>  
>  	i2c_writel(i2c_dev, status, I2C_INT_STATUS);
>  	if (i2c_dev->is_dvc)
>  		dvc_writel(i2c_dev, DVC_STATUS_I2C_DONE_INTR, DVC_STATUS);
>  
> +	/*
> +	 * During message read XFER_COMPLETE interrupt is triggered prior to
> +	 * DMA completion and during message write XFER_COMPLETE interrupt is
> +	 * triggered after DMA completion.
> +	 * PACKETS_XFER_COMPLETE indicates completion of all bytes of transfer.
> +	 * so forcing msg_buf_remaining to 0 in DMA mode.
> +	 */
>  	if (status & I2C_INT_PACKET_XFER_COMPLETE) {
> +		if (i2c_dev->is_curr_dma_xfer)
> +			i2c_dev->msg_buf_remaining = 0;
>  		BUG_ON(i2c_dev->msg_buf_remaining);
>  		complete(&i2c_dev->msg_complete);
>  	}
> @@ -694,12 +837,89 @@ static irqreturn_t tegra_i2c_isr(int irq, void *dev_id)
>  	if (i2c_dev->is_dvc)
>  		dvc_writel(i2c_dev, DVC_STATUS_I2C_DONE_INTR, DVC_STATUS);
>  
> +	if (i2c_dev->is_curr_dma_xfer) {
> +		if (i2c_dev->msg_read)
> +			dmaengine_terminate_async(i2c_dev->rx_dma_chan);
> +		else
> +			dmaengine_terminate_async(i2c_dev->tx_dma_chan);
> +
> +		complete(&i2c_dev->dma_complete);
> +	}
> +
>  	complete(&i2c_dev->msg_complete);
>  done:
>  	spin_unlock(&i2c_dev->xfer_lock);
>  	return IRQ_HANDLED;
>  }
>  
> +static void tegra_i2c_config_fifo_trig(struct tegra_i2c_dev *i2c_dev,
> +				       size_t len)
> +{
> +	u32 val, reg;
> +	u8 dma_burst = 0;
> +	struct dma_slave_config slv_config = {0};
> +	struct dma_chan *chan;
> +	int ret;
> +
> +	if (i2c_dev->hw->has_mst_fifo)
> +		reg = I2C_MST_FIFO_CONTROL;
> +	else
> +		reg = I2C_FIFO_CONTROL;
> +	val = i2c_readl(i2c_dev, reg);
> +
> +	if (i2c_dev->is_curr_dma_xfer) {
> +		if (len & 0xF)
> +			dma_burst = 1;
> +		else if (len & 0x10)
> +			dma_burst = 4;
> +		else
> +			dma_burst = 8;
> +
> +		if (i2c_dev->msg_read) {
> +			chan = i2c_dev->rx_dma_chan;
> +			slv_config.src_addr = i2c_dev->base_phys + I2C_RX_FIFO;
> +			slv_config.src_addr_width = DMA_SLAVE_BUSWIDTH_4_BYTES;
> +			slv_config.src_maxburst = dma_burst;
> +
> +			if (i2c_dev->hw->has_mst_fifo)
> +				val |= I2C_MST_FIFO_CONTROL_RX_TRIG(dma_burst);
> +			else
> +				val |= I2C_FIFO_CONTROL_RX_TRIG(dma_burst);
> +		} else {
> +			chan = i2c_dev->tx_dma_chan;
> +			slv_config.dst_addr = i2c_dev->base_phys + I2C_TX_FIFO;
> +			slv_config.dst_addr_width = DMA_SLAVE_BUSWIDTH_4_BYTES;
> +			slv_config.dst_maxburst = dma_burst;
> +
> +			if (i2c_dev->hw->has_mst_fifo)
> +				val |= I2C_MST_FIFO_CONTROL_TX_TRIG(dma_burst);
> +			else
> +				val |= I2C_FIFO_CONTROL_TX_TRIG(dma_burst);
> +		}
> +
> +		slv_config.device_fc = true;
> +		ret = dmaengine_slave_config(chan, &slv_config);
> +		if (ret < 0) {
> +			dev_err(i2c_dev->dev, "DMA slave config failed: %d\n",
> +				ret);
> +			dev_err(i2c_dev->dev, "fallbacking to PIO\n");
> +			tegra_i2c_release_dma(i2c_dev);
> +			i2c_dev->is_curr_dma_xfer = false;
> +		} else {
> +			goto out;
> +		}
> +	}
> +
> +	if (i2c_dev->hw->has_mst_fifo)
> +		val = I2C_MST_FIFO_CONTROL_TX_TRIG(8) |
> +		      I2C_MST_FIFO_CONTROL_RX_TRIG(1);
> +	else
> +		val = I2C_FIFO_CONTROL_TX_TRIG(8) |
> +		      I2C_FIFO_CONTROL_RX_TRIG(1);
> +out:
> +	i2c_writel(i2c_dev, val, reg);
> +}
> +
>  static int tegra_i2c_issue_bus_clear(struct tegra_i2c_dev *i2c_dev)
>  {
>  	int err;
> @@ -744,6 +964,10 @@ static int tegra_i2c_xfer_msg(struct tegra_i2c_dev *i2c_dev,
>  	u32 int_mask;
>  	unsigned long time_left;
>  	unsigned long flags;
> +	size_t xfer_size;
> +	u32 *buffer = NULL;
> +	int err = 0;
> +	bool dma;
>  
>  	tegra_i2c_flush_fifos(i2c_dev);
>  
> @@ -753,19 +977,57 @@ static int tegra_i2c_xfer_msg(struct tegra_i2c_dev *i2c_dev,
>  	i2c_dev->msg_read = (msg->flags & I2C_M_RD);
>  	reinit_completion(&i2c_dev->msg_complete);
>  
> +	if (i2c_dev->msg_read)
> +		xfer_size = msg->len;
> +	else
> +		xfer_size = msg->len + I2C_PACKET_HEADER_SIZE;
> +
> +	xfer_size = ALIGN(xfer_size, BYTES_PER_FIFO_WORD);
> +	i2c_dev->is_curr_dma_xfer = (xfer_size > I2C_PIO_MODE_MAX_LEN) &&
> +				    i2c_dev->dma_buf;
> +	tegra_i2c_config_fifo_trig(i2c_dev, xfer_size);
> +	dma = i2c_dev->is_curr_dma_xfer;
> +
>  	spin_lock_irqsave(&i2c_dev->xfer_lock, flags);
>  
>  	int_mask = I2C_INT_NO_ACK | I2C_INT_ARBITRATION_LOST;
>  	tegra_i2c_unmask_irq(i2c_dev, int_mask);
> +	if (dma) {
> +		if (i2c_dev->msg_read) {
> +			dma_sync_single_for_device(i2c_dev->dev,
> +						   i2c_dev->dma_phys,
> +						   xfer_size,
> +						   DMA_FROM_DEVICE);
> +			err = tegra_i2c_dma_submit(i2c_dev, xfer_size);
> +			if (err < 0) {
> +				dev_err(i2c_dev->dev,
> +					"starting RX DMA failed, err %d\n",
> +					err);
> +				goto unlock;
> +			}
> +		} else {
> +			dma_sync_single_for_cpu(i2c_dev->dev,
> +						i2c_dev->dma_phys,
> +						xfer_size,
> +						DMA_TO_DEVICE);
> +			buffer = i2c_dev->dma_buf;
> +		}
> +	}
>  
>  	packet_header = (0 << PACKET_HEADER0_HEADER_SIZE_SHIFT) |
>  			PACKET_HEADER0_PROTOCOL_I2C |
>  			(i2c_dev->cont_id << PACKET_HEADER0_CONT_ID_SHIFT) |
>  			(1 << PACKET_HEADER0_PACKET_ID_SHIFT);
> -	i2c_writel(i2c_dev, packet_header, I2C_TX_FIFO);
> +	if (dma && !i2c_dev->msg_read)
> +		*buffer++ = packet_header;
> +	else
> +		i2c_writel(i2c_dev, packet_header, I2C_TX_FIFO);
>  
>  	packet_header = msg->len - 1;
> -	i2c_writel(i2c_dev, packet_header, I2C_TX_FIFO);
> +	if (dma && !i2c_dev->msg_read)
> +		*buffer++ = packet_header;
> +	else
> +		i2c_writel(i2c_dev, packet_header, I2C_TX_FIFO);

I'm now also wondering whether that putting packet_header into the dma_buf is really needed at all.. Isn't possible to push packet_header using PIO regardless of whether the rest of the transfer will be in DMA or PIO modes?

Actually I tried to always push packet_header using PIO and apparently DMA works just fine with that:

diff --git a/drivers/i2c/busses/i2c-tegra.c b/drivers/i2c/busses/i2c-tegra.c
index c538ed5f8e2c..a2c4338336d0 100644
--- a/drivers/i2c/busses/i2c-tegra.c
+++ b/drivers/i2c/busses/i2c-tegra.c
@@ -1040,12 +1040,7 @@ static int tegra_i2c_xfer_msg(struct tegra_i2c_dev *i2c_dev,
        i2c_dev->msg_read = (msg->flags & I2C_M_RD);
        reinit_completion(&i2c_dev->msg_complete);
 
-       if (i2c_dev->msg_read)
-               xfer_size = msg->len;
-       else
-               xfer_size = msg->len + I2C_PACKET_HEADER_SIZE;
-
-       xfer_size = ALIGN(xfer_size, BYTES_PER_FIFO_WORD);
+       xfer_size = ALIGN(msg->len, BYTES_PER_FIFO_WORD);
        i2c_dev->is_curr_dma_xfer = (xfer_size > I2C_PIO_MODE_MAX_LEN) &&
                                    i2c_dev->dma_buf;
        tegra_i2c_config_fifo_trig(i2c_dev, xfer_size);
@@ -1088,16 +1083,10 @@ static int tegra_i2c_xfer_msg(struct tegra_i2c_dev *i2c_dev,
                        PACKET_HEADER0_PROTOCOL_I2C |
                        (i2c_dev->cont_id << PACKET_HEADER0_CONT_ID_SHIFT) |
                        (1 << PACKET_HEADER0_PACKET_ID_SHIFT);
-       if (dma && !i2c_dev->msg_read)
-               *buffer++ = packet_header;
-       else
-               i2c_writel(i2c_dev, packet_header, I2C_TX_FIFO);
+       i2c_writel(i2c_dev, packet_header, I2C_TX_FIFO);
 
        packet_header = msg->len - 1;
-       if (dma && !i2c_dev->msg_read)
-               *buffer++ = packet_header;
-       else
-               i2c_writel(i2c_dev, packet_header, I2C_TX_FIFO);
+       i2c_writel(i2c_dev, packet_header, I2C_TX_FIFO);
 
        packet_header = I2C_HEADER_IE_ENABLE;
        if (end_state == MSG_END_CONTINUE)
@@ -1114,10 +1103,7 @@ static int tegra_i2c_xfer_msg(struct tegra_i2c_dev *i2c_dev,
                packet_header |= I2C_HEADER_CONT_ON_NAK;
        if (msg->flags & I2C_M_RD)
                packet_header |= I2C_HEADER_READ;
-       if (dma && !i2c_dev->msg_read)
-               *buffer++ = packet_header;
-       else
-               i2c_writel(i2c_dev, packet_header, I2C_TX_FIFO);
+       i2c_writel(i2c_dev, packet_header, I2C_TX_FIFO);
 
        if (!msg->flags & I2C_M_RD) {
                if (dma) {

^ permalink raw reply related	[flat|nested] 35+ messages in thread

* Re: [PATCH V12 3/5] i2c: tegra: Add DMA support
  2019-02-06 12:40   ` Dmitry Osipenko
@ 2019-02-06 12:48     ` Thierry Reding
  2019-02-06 13:01       ` Dmitry Osipenko
  0 siblings, 1 reply; 35+ messages in thread
From: Thierry Reding @ 2019-02-06 12:48 UTC (permalink / raw)
  To: Dmitry Osipenko
  Cc: Sowjanya Komatineni, jonathanh, mkarthik, smohammed, talho,
	linux-tegra, linux-kernel, linux-i2c

[-- Attachment #1: Type: text/plain, Size: 19166 bytes --]

On Wed, Feb 06, 2019 at 03:40:52PM +0300, Dmitry Osipenko wrote:
> 06.02.2019 1:46, Sowjanya Komatineni пишет:
> > This patch adds DMA support for Tegra I2C.
> > 
> > Tegra I2C TX and RX FIFO depth is 8 words. PIO mode is used for
> > transfer size of the max FIFO depth and DMA mode is used for
> > transfer size higher than max FIFO depth to save CPU overhead.
> > 
> > PIO mode needs full intervention of CPU to fill or empty FIFO's
> > and also need to service multiple data requests interrupt for the
> > same transaction. This adds delay between data bytes of the same
> > transfer when CPU is fully loaded and some slave devices has
> > internal timeout for no bus activity and stops transaction to
> > avoid bus hang. DMA mode is helpful in such cases.
> > 
> > DMA mode is also helpful for Large transfers during downloading or
> > uploading FW over I2C to some external devices.
> > 
> > Signed-off-by: Sowjanya Komatineni <skomatineni@nvidia.com>
> > ---
> >  [V12] : Replaced dma_alloc_coherent with dma_alloc_attrs to force the allocated
> > 	 buffer to be contiguous also in physical memory as Tegra194 supports max
> > 	 64K and dma_alloc_coherent doesnt guarentee contiguous memory.
> > 	 Changed return code from EIO to EINVAL incase of failure to obtain dma
> > 	 descriptor.
> > 	 Fixed coding style check issues.	 
> >  [V11] : Replaced deprecated dmaengine_terminate_all with dmaengine_termine_async
> > 	 from non-atomic context and dmaengine_terminate_sync from atomic context.
> > 	 Fixed to program fifo trigger levels properly when transfer falls back to
> > 	 pio mode in case of dma slave configuration failure and other minor fixes.
> >  [V10] : APBDMA is replaced with GPCDMA on Tegra186 and Tegra194 designs.
> > 	 Added apbdma hw support flag to now allow Tegra186 and later use
> > 	 APBDMA driver.
> > 	 Added explicit flow control enable for DMA slave config and error handling.
> > 	 Moved releasing DMA resources to seperate function to reuse in
> > 	 multiple places.
> > 	 Updated to register tegra_i2c_driver from module level rather than subsys
> > 	 level.
> > 	 Other minor feedback
> >  [V9] :  Rebased to 5.0-rc4
> > 	 Removed dependency of APB DMA in Kconfig and added conditional check
> >  	 in I2C driver to decide on using DMA mode.
> > 	 Changed back the allocation of dma buffer during i2c probe.
> > 	 Fixed FIFO triggers depending on DMA Vs PIO.
> >  [V8] :  Moved back dma init to i2c probe, removed ALL_PACKETS_XFER_COMPLETE
> > 	 interrupt and using PACKETS_XFER_COMPLETE interrupt only and some
> > 	 other fixes
> > 	 Updated Kconfig for APB_DMA dependency
> >  [V7] :  Same as V6
> >  [V6] :  Updated for proper buffer allocation/freeing, channel release.
> > 	 Updated to use exact xfer size for syncing dma buffer.
> >  [V5] :  Same as V4
> >  [V4] :  Updated to allocate DMA buffer only when DMA mode.
> > 	 Updated to fall back to PIO mode when DMA channel request or
> > 	 buffer allocation fails.
> >  [V3] :  Updated without additional buffer allocation.
> >  [V2] :  Updated based on V1 review feedback along with code cleanup for
> > 	 proper implementation of DMA.
> > 
> > 
> >  drivers/i2c/busses/i2c-tegra.c | 413 ++++++++++++++++++++++++++++++++++++-----
> >  1 file changed, 369 insertions(+), 44 deletions(-)
> > 
> > diff --git a/drivers/i2c/busses/i2c-tegra.c b/drivers/i2c/busses/i2c-tegra.c
> > index 118b7023a0f4..77277a09e485 100644
> > --- a/drivers/i2c/busses/i2c-tegra.c
> > +++ b/drivers/i2c/busses/i2c-tegra.c
> > @@ -8,6 +8,9 @@
> >  
> >  #include <linux/clk.h>
> >  #include <linux/delay.h>
> > +#include <linux/dmaengine.h>
> > +#include <linux/dmapool.h>
> > +#include <linux/dma-mapping.h>
> >  #include <linux/err.h>
> >  #include <linux/i2c.h>
> >  #include <linux/init.h>
> > @@ -44,6 +47,8 @@
> >  #define I2C_FIFO_CONTROL_RX_FLUSH		BIT(0)
> >  #define I2C_FIFO_CONTROL_TX_TRIG_SHIFT		5
> >  #define I2C_FIFO_CONTROL_RX_TRIG_SHIFT		2
> > +#define I2C_FIFO_CONTROL_TX_TRIG(x)		(((x) - 1) << 5)
> > +#define I2C_FIFO_CONTROL_RX_TRIG(x)		(((x) - 1) << 2)
> >  #define I2C_FIFO_STATUS				0x060
> >  #define I2C_FIFO_STATUS_TX_MASK			0xF0
> >  #define I2C_FIFO_STATUS_TX_SHIFT		4
> > @@ -125,6 +130,19 @@
> >  #define I2C_MST_FIFO_STATUS_TX_MASK		0xff0000
> >  #define I2C_MST_FIFO_STATUS_TX_SHIFT		16
> >  
> > +/* Packet header size in bytes */
> > +#define I2C_PACKET_HEADER_SIZE			12
> > +
> > +#define DATA_DMA_DIR_TX				BIT(0)
> > +#define DATA_DMA_DIR_RX				BIT(1)
> > +
> > +/*
> > + * Upto I2C_PIO_MODE_MAX_LEN bytes, controller will use PIO mode,
> > + * above this, controller will use DMA to fill FIFO.
> > + * MAX PIO len is 20 bytes excluding packet header.
> > + */
> > +#define I2C_PIO_MODE_MAX_LEN			32
> > +
> >  /*
> >   * msg_end_type: The bus control which need to be send at end of transfer.
> >   * @MSG_END_STOP: Send stop pulse at end of transfer.
> > @@ -166,6 +184,7 @@ enum msg_end_type {
> >   *		allowing 0 length transfers.
> >   * @supports_bus_clear: Bus Clear support to recover from bus hang during
> >   *		SDA stuck low from device for some unknown reasons.
> > + * @has_apb_dma: Support of APBDMA on corresponding Tegra chip.
> >   */
> >  struct tegra_i2c_hw_feature {
> >  	bool has_continue_xfer_support;
> > @@ -180,6 +199,7 @@ struct tegra_i2c_hw_feature {
> >  	bool has_mst_fifo;
> >  	const struct i2c_adapter_quirks *quirks;
> >  	bool supports_bus_clear;
> > +	bool has_apb_dma;
> >  };
> >  
> >  /**
> > @@ -191,6 +211,7 @@ struct tegra_i2c_hw_feature {
> >   * @fast_clk: clock reference for fast clock of I2C controller
> >   * @rst: reset control for the I2C controller
> >   * @base: ioremapped registers cookie
> > + * @base_phys: Physical base address of the I2C controller
> >   * @cont_id: I2C controller ID, used for packet header
> >   * @irq: IRQ number of transfer complete interrupt
> >   * @irq_disabled: used to track whether or not the interrupt is enabled
> > @@ -204,6 +225,13 @@ struct tegra_i2c_hw_feature {
> >   * @clk_divisor_non_hs_mode: clock divider for non-high-speed modes
> >   * @is_multimaster_mode: track if I2C controller is in multi-master mode
> >   * @xfer_lock: lock to serialize transfer submission and processing
> > + * @tx_dma_chan: DMA transmit channel
> > + * @rx_dma_chan: DMA receive channel
> > + * @dma_phys: handle to DMA resources
> > + * @dma_buf: pointer to allocated DMA buffer
> > + * @dma_buf_size: DMA buffer size
> > + * @is_curr_dma_xfer: indicates active DMA transfer
> > + * @dma_complete: DMA completion notifier
> >   */
> >  struct tegra_i2c_dev {
> >  	struct device *dev;
> > @@ -213,6 +241,7 @@ struct tegra_i2c_dev {
> >  	struct clk *fast_clk;
> >  	struct reset_control *rst;
> >  	void __iomem *base;
> > +	phys_addr_t base_phys;
> >  	int cont_id;
> >  	int irq;
> >  	bool irq_disabled;
> > @@ -226,6 +255,13 @@ struct tegra_i2c_dev {
> >  	u16 clk_divisor_non_hs_mode;
> >  	bool is_multimaster_mode;
> >  	spinlock_t xfer_lock;
> > +	struct dma_chan *tx_dma_chan;
> > +	struct dma_chan *rx_dma_chan;
> > +	dma_addr_t dma_phys;
> > +	u32 *dma_buf;
> > +	unsigned int dma_buf_size;
> > +	bool is_curr_dma_xfer;
> > +	struct completion dma_complete;
> >  };
> >  
> >  static void dvc_writel(struct tegra_i2c_dev *i2c_dev, u32 val,
> > @@ -294,6 +330,111 @@ static void tegra_i2c_unmask_irq(struct tegra_i2c_dev *i2c_dev, u32 mask)
> >  	i2c_writel(i2c_dev, int_mask, I2C_INT_MASK);
> >  }
> >  
> > +static void tegra_i2c_dma_complete(void *args)
> > +{
> > +	struct tegra_i2c_dev *i2c_dev = args;
> > +
> > +	complete(&i2c_dev->dma_complete);
> > +}
> > +
> > +static int tegra_i2c_dma_submit(struct tegra_i2c_dev *i2c_dev, size_t len)
> > +{
> > +	struct dma_async_tx_descriptor *dma_desc;
> > +	enum dma_transfer_direction dir;
> > +	struct dma_chan *chan;
> > +
> > +	dev_dbg(i2c_dev->dev, "starting DMA for length: %zu\n", len);
> > +	reinit_completion(&i2c_dev->dma_complete);
> > +	dir = i2c_dev->msg_read ? DMA_DEV_TO_MEM : DMA_MEM_TO_DEV;
> > +	chan = i2c_dev->msg_read ? i2c_dev->rx_dma_chan : i2c_dev->tx_dma_chan;
> > +	dma_desc = dmaengine_prep_slave_single(chan, i2c_dev->dma_phys,
> > +					       len, dir, DMA_PREP_INTERRUPT |
> > +					       DMA_CTRL_ACK);
> > +	if (!dma_desc) {
> > +		dev_err(i2c_dev->dev, "failed to get DMA descriptor\n");
> > +		return -EINVAL;
> > +	}
> > +
> > +	dma_desc->callback = tegra_i2c_dma_complete;
> > +	dma_desc->callback_param = i2c_dev;
> > +	dmaengine_submit(dma_desc);
> > +	dma_async_issue_pending(chan);
> > +	return 0;
> > +}
> > +
> > +static void tegra_i2c_release_dma(struct tegra_i2c_dev *i2c_dev)
> > +{
> > +	if (i2c_dev->dma_buf) {
> > +		dma_free_attrs(i2c_dev->dev, i2c_dev->dma_buf_size,
> > +			       i2c_dev->dma_buf, i2c_dev->dma_phys,
> > +			       DMA_ATTR_FORCE_CONTIGUOUS);
> > +		i2c_dev->dma_buf = NULL;
> > +	}
> > +
> > +	if (i2c_dev->tx_dma_chan) {
> > +		dma_release_channel(i2c_dev->tx_dma_chan);
> > +		i2c_dev->tx_dma_chan = NULL;
> > +	}
> > +
> > +	if (i2c_dev->rx_dma_chan) {
> > +		dma_release_channel(i2c_dev->rx_dma_chan);
> > +		i2c_dev->rx_dma_chan = NULL;
> > +	}
> > +}
> > +
> > +static int tegra_i2c_init_dma(struct tegra_i2c_dev *i2c_dev)
> > +{
> > +	struct dma_chan *chan;
> > +	u32 *dma_buf;
> > +	dma_addr_t dma_phys;
> > +	int err;
> > +
> > +	if (!IS_ENABLED(CONFIG_TEGRA20_APB_DMA) ||
> > +	    !i2c_dev->hw->has_apb_dma) {
> > +		err = -ENODEV;
> > +		goto err_out;
> > +	}
> > +
> > +	chan = dma_request_slave_channel_reason(i2c_dev->dev, "rx");
> > +	if (IS_ERR(chan)) {
> > +		err = PTR_ERR(chan);
> > +		goto err_out;
> > +	}
> > +
> > +	i2c_dev->rx_dma_chan = chan;
> > +
> > +	chan = dma_request_slave_channel_reason(i2c_dev->dev, "tx");
> > +	if (IS_ERR(chan)) {
> > +		err = PTR_ERR(chan);
> > +		goto err_out;
> > +	}
> > +
> > +	i2c_dev->tx_dma_chan = chan;
> > +
> > +	dma_buf = dma_alloc_attrs(i2c_dev->dev, i2c_dev->dma_buf_size,
> > +				  &dma_phys, GFP_KERNEL | __GFP_NOWARN,
> > +				  DMA_ATTR_FORCE_CONTIGUOUS);
> > +	if (!dma_buf) {
> > +		dev_err(i2c_dev->dev, "failed to allocate the DMA buffer\n");
> > +		err = -ENOMEM;
> > +		goto err_out;
> > +	}
> > +
> > +	i2c_dev->dma_buf = dma_buf;
> > +	i2c_dev->dma_phys = dma_phys;
> > +	return 0;
> > +
> > +err_out:
> > +	tegra_i2c_release_dma(i2c_dev);
> > +	if (err != -EPROBE_DEFER) {
> > +		dev_err(i2c_dev->dev, "can't use DMA, err: %d, using PIO\n",
> > +			err);
> > +		return 0;
> > +	}
> > +
> > +	return err;
> > +}
> > +
> >  static int tegra_i2c_flush_fifos(struct tegra_i2c_dev *i2c_dev)
> >  {
> >  	unsigned long timeout = jiffies + HZ;
> > @@ -571,16 +712,6 @@ static int tegra_i2c_init(struct tegra_i2c_dev *i2c_dev)
> >  		i2c_writel(i2c_dev, 0x00, I2C_SL_ADDR2);
> >  	}
> >  
> > -	if (i2c_dev->hw->has_mst_fifo) {
> > -		val = I2C_MST_FIFO_CONTROL_TX_TRIG(8) |
> > -		      I2C_MST_FIFO_CONTROL_RX_TRIG(1);
> > -		i2c_writel(i2c_dev, val, I2C_MST_FIFO_CONTROL);
> > -	} else {
> > -		val = 7 << I2C_FIFO_CONTROL_TX_TRIG_SHIFT |
> > -			0 << I2C_FIFO_CONTROL_RX_TRIG_SHIFT;
> > -		i2c_writel(i2c_dev, val, I2C_FIFO_CONTROL);
> > -	}
> > -
> >  	err = tegra_i2c_flush_fifos(i2c_dev);
> >  	if (err)
> >  		goto err;
> > @@ -660,25 +791,37 @@ static irqreturn_t tegra_i2c_isr(int irq, void *dev_id)
> >  	if (i2c_dev->hw->supports_bus_clear && (status & I2C_INT_BUS_CLR_DONE))
> >  		goto err;
> >  
> > -	if (i2c_dev->msg_read && (status & I2C_INT_RX_FIFO_DATA_REQ)) {
> > -		if (i2c_dev->msg_buf_remaining)
> > -			tegra_i2c_empty_rx_fifo(i2c_dev);
> > -		else
> > -			BUG();
> > -	}
> > +	if (!i2c_dev->is_curr_dma_xfer) {
> > +		if (i2c_dev->msg_read && (status & I2C_INT_RX_FIFO_DATA_REQ)) {
> > +			if (i2c_dev->msg_buf_remaining)
> > +				tegra_i2c_empty_rx_fifo(i2c_dev);
> > +			else
> > +				BUG();
> > +		}
> >  
> > -	if (!i2c_dev->msg_read && (status & I2C_INT_TX_FIFO_DATA_REQ)) {
> > -		if (i2c_dev->msg_buf_remaining)
> > -			tegra_i2c_fill_tx_fifo(i2c_dev);
> > -		else
> > -			tegra_i2c_mask_irq(i2c_dev, I2C_INT_TX_FIFO_DATA_REQ);
> > +		if (!i2c_dev->msg_read && (status & I2C_INT_TX_FIFO_DATA_REQ)) {
> > +			if (i2c_dev->msg_buf_remaining)
> > +				tegra_i2c_fill_tx_fifo(i2c_dev);
> > +			else
> > +				tegra_i2c_mask_irq(i2c_dev,
> > +						   I2C_INT_TX_FIFO_DATA_REQ);
> > +		}
> >  	}
> >  
> >  	i2c_writel(i2c_dev, status, I2C_INT_STATUS);
> >  	if (i2c_dev->is_dvc)
> >  		dvc_writel(i2c_dev, DVC_STATUS_I2C_DONE_INTR, DVC_STATUS);
> >  
> > +	/*
> > +	 * During message read XFER_COMPLETE interrupt is triggered prior to
> > +	 * DMA completion and during message write XFER_COMPLETE interrupt is
> > +	 * triggered after DMA completion.
> > +	 * PACKETS_XFER_COMPLETE indicates completion of all bytes of transfer.
> > +	 * so forcing msg_buf_remaining to 0 in DMA mode.
> > +	 */
> >  	if (status & I2C_INT_PACKET_XFER_COMPLETE) {
> > +		if (i2c_dev->is_curr_dma_xfer)
> > +			i2c_dev->msg_buf_remaining = 0;
> >  		BUG_ON(i2c_dev->msg_buf_remaining);
> >  		complete(&i2c_dev->msg_complete);
> >  	}
> > @@ -694,12 +837,89 @@ static irqreturn_t tegra_i2c_isr(int irq, void *dev_id)
> >  	if (i2c_dev->is_dvc)
> >  		dvc_writel(i2c_dev, DVC_STATUS_I2C_DONE_INTR, DVC_STATUS);
> >  
> > +	if (i2c_dev->is_curr_dma_xfer) {
> > +		if (i2c_dev->msg_read)
> > +			dmaengine_terminate_async(i2c_dev->rx_dma_chan);
> > +		else
> > +			dmaengine_terminate_async(i2c_dev->tx_dma_chan);
> > +
> > +		complete(&i2c_dev->dma_complete);
> > +	}
> > +
> >  	complete(&i2c_dev->msg_complete);
> >  done:
> >  	spin_unlock(&i2c_dev->xfer_lock);
> >  	return IRQ_HANDLED;
> >  }
> >  
> > +static void tegra_i2c_config_fifo_trig(struct tegra_i2c_dev *i2c_dev,
> > +				       size_t len)
> > +{
> > +	u32 val, reg;
> > +	u8 dma_burst = 0;
> > +	struct dma_slave_config slv_config = {0};
> > +	struct dma_chan *chan;
> > +	int ret;
> > +
> > +	if (i2c_dev->hw->has_mst_fifo)
> > +		reg = I2C_MST_FIFO_CONTROL;
> > +	else
> > +		reg = I2C_FIFO_CONTROL;
> > +	val = i2c_readl(i2c_dev, reg);
> > +
> > +	if (i2c_dev->is_curr_dma_xfer) {
> > +		if (len & 0xF)
> > +			dma_burst = 1;
> > +		else if (len & 0x10)
> > +			dma_burst = 4;
> > +		else
> > +			dma_burst = 8;
> > +
> > +		if (i2c_dev->msg_read) {
> > +			chan = i2c_dev->rx_dma_chan;
> > +			slv_config.src_addr = i2c_dev->base_phys + I2C_RX_FIFO;
> > +			slv_config.src_addr_width = DMA_SLAVE_BUSWIDTH_4_BYTES;
> > +			slv_config.src_maxburst = dma_burst;
> > +
> > +			if (i2c_dev->hw->has_mst_fifo)
> > +				val |= I2C_MST_FIFO_CONTROL_RX_TRIG(dma_burst);
> > +			else
> > +				val |= I2C_FIFO_CONTROL_RX_TRIG(dma_burst);
> > +		} else {
> > +			chan = i2c_dev->tx_dma_chan;
> > +			slv_config.dst_addr = i2c_dev->base_phys + I2C_TX_FIFO;
> > +			slv_config.dst_addr_width = DMA_SLAVE_BUSWIDTH_4_BYTES;
> > +			slv_config.dst_maxburst = dma_burst;
> > +
> > +			if (i2c_dev->hw->has_mst_fifo)
> > +				val |= I2C_MST_FIFO_CONTROL_TX_TRIG(dma_burst);
> > +			else
> > +				val |= I2C_FIFO_CONTROL_TX_TRIG(dma_burst);
> > +		}
> > +
> > +		slv_config.device_fc = true;
> > +		ret = dmaengine_slave_config(chan, &slv_config);
> > +		if (ret < 0) {
> > +			dev_err(i2c_dev->dev, "DMA slave config failed: %d\n",
> > +				ret);
> > +			dev_err(i2c_dev->dev, "fallbacking to PIO\n");
> > +			tegra_i2c_release_dma(i2c_dev);
> > +			i2c_dev->is_curr_dma_xfer = false;
> > +		} else {
> > +			goto out;
> > +		}
> > +	}
> > +
> > +	if (i2c_dev->hw->has_mst_fifo)
> > +		val = I2C_MST_FIFO_CONTROL_TX_TRIG(8) |
> > +		      I2C_MST_FIFO_CONTROL_RX_TRIG(1);
> > +	else
> > +		val = I2C_FIFO_CONTROL_TX_TRIG(8) |
> > +		      I2C_FIFO_CONTROL_RX_TRIG(1);
> > +out:
> > +	i2c_writel(i2c_dev, val, reg);
> > +}
> > +
> >  static int tegra_i2c_issue_bus_clear(struct tegra_i2c_dev *i2c_dev)
> >  {
> >  	int err;
> > @@ -744,6 +964,10 @@ static int tegra_i2c_xfer_msg(struct tegra_i2c_dev *i2c_dev,
> >  	u32 int_mask;
> >  	unsigned long time_left;
> >  	unsigned long flags;
> > +	size_t xfer_size;
> > +	u32 *buffer = NULL;
> > +	int err = 0;
> > +	bool dma;
> >  
> >  	tegra_i2c_flush_fifos(i2c_dev);
> >  
> > @@ -753,19 +977,57 @@ static int tegra_i2c_xfer_msg(struct tegra_i2c_dev *i2c_dev,
> >  	i2c_dev->msg_read = (msg->flags & I2C_M_RD);
> >  	reinit_completion(&i2c_dev->msg_complete);
> >  
> > +	if (i2c_dev->msg_read)
> > +		xfer_size = msg->len;
> > +	else
> > +		xfer_size = msg->len + I2C_PACKET_HEADER_SIZE;
> > +
> > +	xfer_size = ALIGN(xfer_size, BYTES_PER_FIFO_WORD);
> > +	i2c_dev->is_curr_dma_xfer = (xfer_size > I2C_PIO_MODE_MAX_LEN) &&
> > +				    i2c_dev->dma_buf;
> > +	tegra_i2c_config_fifo_trig(i2c_dev, xfer_size);
> > +	dma = i2c_dev->is_curr_dma_xfer;
> > +
> >  	spin_lock_irqsave(&i2c_dev->xfer_lock, flags);
> >  
> >  	int_mask = I2C_INT_NO_ACK | I2C_INT_ARBITRATION_LOST;
> >  	tegra_i2c_unmask_irq(i2c_dev, int_mask);
> > +	if (dma) {
> > +		if (i2c_dev->msg_read) {
> > +			dma_sync_single_for_device(i2c_dev->dev,
> > +						   i2c_dev->dma_phys,
> > +						   xfer_size,
> > +						   DMA_FROM_DEVICE);
> > +			err = tegra_i2c_dma_submit(i2c_dev, xfer_size);
> > +			if (err < 0) {
> > +				dev_err(i2c_dev->dev,
> > +					"starting RX DMA failed, err %d\n",
> > +					err);
> > +				goto unlock;
> > +			}
> > +		} else {
> > +			dma_sync_single_for_cpu(i2c_dev->dev,
> > +						i2c_dev->dma_phys,
> > +						xfer_size,
> > +						DMA_TO_DEVICE);
> > +			buffer = i2c_dev->dma_buf;
> > +		}
> > +	}
> >  
> >  	packet_header = (0 << PACKET_HEADER0_HEADER_SIZE_SHIFT) |
> >  			PACKET_HEADER0_PROTOCOL_I2C |
> >  			(i2c_dev->cont_id << PACKET_HEADER0_CONT_ID_SHIFT) |
> >  			(1 << PACKET_HEADER0_PACKET_ID_SHIFT);
> > -	i2c_writel(i2c_dev, packet_header, I2C_TX_FIFO);
> > +	if (dma && !i2c_dev->msg_read)
> > +		*buffer++ = packet_header;
> > +	else
> > +		i2c_writel(i2c_dev, packet_header, I2C_TX_FIFO);
> >  
> >  	packet_header = msg->len - 1;
> > -	i2c_writel(i2c_dev, packet_header, I2C_TX_FIFO);
> > +	if (dma && !i2c_dev->msg_read)
> > +		*buffer++ = packet_header;
> > +	else
> > +		i2c_writel(i2c_dev, packet_header, I2C_TX_FIFO);
> 
> I'm now also wondering whether that putting packet_header into the
> dma_buf is really needed at all.. Isn't possible to push packet_header
> using PIO regardless of whether the rest of the transfer will be in
> DMA or PIO modes?
> 
> Actually I tried to always push packet_header using PIO and apparently
> DMA works just fine with that:

I don't see a reason why that wouldn't work. After all the DMA support
here is really just about some external DMA engine writing to the FIFO
register, so from an I2C controller's point of view it's exactly the
same thing.

But if we already set up DMA for a transfer, might as well transfer the
3 packet header words with that.

Thierry

[-- Attachment #2: signature.asc --]
[-- Type: application/pgp-signature, Size: 833 bytes --]

^ permalink raw reply	[flat|nested] 35+ messages in thread

* RE: [PATCH V12 3/5] i2c: tegra: Add DMA support
  2019-02-06 11:55   ` Dmitry Osipenko
@ 2019-02-06 12:49     ` Sowjanya Komatineni
  2019-02-06 13:06       ` Dmitry Osipenko
  2019-02-06 12:59     ` Dmitry Osipenko
  2019-02-06 13:09     ` Thierry Reding
  2 siblings, 1 reply; 35+ messages in thread
From: Sowjanya Komatineni @ 2019-02-06 12:49 UTC (permalink / raw)
  To: Dmitry Osipenko, thierry.reding@gmail.com, Jonathan Hunter,
	Mantravadi Karthik, Shardar Mohammed, Timo Alho
  Cc: linux-tegra@vger.kernel.org, linux-kernel@vger.kernel.org,
	linux-i2c@vger.kernel.org


> 		TEGRA_I2C_TIMEOUT);
> >  	tegra_i2c_mask_irq(i2c_dev, int_mask); @@ -814,6 +1133,7 @@ static 
> > int tegra_i2c_xfer_msg(struct tegra_i2c_dev *i2c_dev,
> >  		time_left, completion_done(&i2c_dev->msg_complete),
> >  		i2c_dev->msg_err);
> >  
> > +	i2c_dev->is_curr_dma_xfer = false;
>
> This line could be removed because there is no need to clear "is_curr_dma_xfer" at this point.
>

It is needed because in case of ARB_LOST, we terminate dmaengine and then we perform bus clear operation. 
On bus clear done interrupt, it again goes thru I2C error section to mask all interrupts and when curr_dma_xfer is true it does dmaengine terminate again so setting curr_dma_xfer as false when transfer in dma mode is done.

>
>
>Sowjanya, I tried to enforce DMA transferring + setting DMA burst to a one word and this combination doesn't work well while it should, if I'm not missing something. Could >you please take a look at the problem or explain why that happens?
>
>
> [    1.017496] tegra-i2c 7000c000.i2c: starting DMA for length: 120
> [    1.017504] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    1.020896] tegra-i2c 7000c000.i2c: transfer complete: 11 0 0
> [    1.020909] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> [    1.020918] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    1.021055] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> [    1.032230] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> [    1.032239] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    1.032359] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> [    1.032368] tegra-i2c 7000c000.i2c: starting DMA for length: 12
> [    1.032376] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    1.032704] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> [    1.049224] tegra-i2c 7000d000.i2c: i2c transfer timed out
>
>
I don’t see any issue with dma burst of 1 word irrespective of transfers in always dma mode.
One strange thing is in your above log, for last transaction after transfer complete, there is i2c transfer timed which doesn’t make sense.
If transfer timeout happens, it returns from i2c transfer but shouldn’t go thru transfer complete

>
>
>
> I'm now also wondering whether that putting packet_header into the dma_buf is really needed at all.. Isn't possible to push packet_header using PIO regardless of whether > the rest of the transfer will be in DMA or PIO modes?
>
> Actually I tried to always push packet_header using PIO and apparently DMA works just fine with that:
>
Ofcourse it will work using PIO for packet header and dma only for data bytes. But packet header is just 12 bytes so why not we transfer it along with data together thru dma.


^ permalink raw reply	[flat|nested] 35+ messages in thread

* Re: [PATCH V12 3/5] i2c: tegra: Add DMA support
  2019-02-06 11:55   ` Dmitry Osipenko
  2019-02-06 12:49     ` Sowjanya Komatineni
@ 2019-02-06 12:59     ` Dmitry Osipenko
  2019-02-06 13:03       ` Sowjanya Komatineni
  2019-02-06 13:09     ` Thierry Reding
  2 siblings, 1 reply; 35+ messages in thread
From: Dmitry Osipenko @ 2019-02-06 12:59 UTC (permalink / raw)
  To: Sowjanya Komatineni, thierry.reding, jonathanh, mkarthik,
	smohammed, talho
  Cc: linux-tegra, linux-kernel, linux-i2c

06.02.2019 14:55, Dmitry Osipenko пишет:
> 06.02.2019 1:46, Sowjanya Komatineni пишет:
>> This patch adds DMA support for Tegra I2C.
>>
>> Tegra I2C TX and RX FIFO depth is 8 words. PIO mode is used for
>> transfer size of the max FIFO depth and DMA mode is used for
>> transfer size higher than max FIFO depth to save CPU overhead.
>>
>> PIO mode needs full intervention of CPU to fill or empty FIFO's
>> and also need to service multiple data requests interrupt for the
>> same transaction. This adds delay between data bytes of the same
>> transfer when CPU is fully loaded and some slave devices has
>> internal timeout for no bus activity and stops transaction to
>> avoid bus hang. DMA mode is helpful in such cases.
>>
>> DMA mode is also helpful for Large transfers during downloading or
>> uploading FW over I2C to some external devices.
>>
>> Signed-off-by: Sowjanya Komatineni <skomatineni@nvidia.com>
>> ---
>>  [V12] : Replaced dma_alloc_coherent with dma_alloc_attrs to force the allocated
>> 	 buffer to be contiguous also in physical memory as Tegra194 supports max
>> 	 64K and dma_alloc_coherent doesnt guarentee contiguous memory.
>> 	 Changed return code from EIO to EINVAL incase of failure to obtain dma
>> 	 descriptor.
>> 	 Fixed coding style check issues.	 
>>  [V11] : Replaced deprecated dmaengine_terminate_all with dmaengine_termine_async
>> 	 from non-atomic context and dmaengine_terminate_sync from atomic context.
>> 	 Fixed to program fifo trigger levels properly when transfer falls back to
>> 	 pio mode in case of dma slave configuration failure and other minor fixes.
>>  [V10] : APBDMA is replaced with GPCDMA on Tegra186 and Tegra194 designs.
>> 	 Added apbdma hw support flag to now allow Tegra186 and later use
>> 	 APBDMA driver.
>> 	 Added explicit flow control enable for DMA slave config and error handling.
>> 	 Moved releasing DMA resources to seperate function to reuse in
>> 	 multiple places.
>> 	 Updated to register tegra_i2c_driver from module level rather than subsys
>> 	 level.
>> 	 Other minor feedback
>>  [V9] :  Rebased to 5.0-rc4
>> 	 Removed dependency of APB DMA in Kconfig and added conditional check
>>  	 in I2C driver to decide on using DMA mode.
>> 	 Changed back the allocation of dma buffer during i2c probe.
>> 	 Fixed FIFO triggers depending on DMA Vs PIO.
>>  [V8] :  Moved back dma init to i2c probe, removed ALL_PACKETS_XFER_COMPLETE
>> 	 interrupt and using PACKETS_XFER_COMPLETE interrupt only and some
>> 	 other fixes
>> 	 Updated Kconfig for APB_DMA dependency
>>  [V7] :  Same as V6
>>  [V6] :  Updated for proper buffer allocation/freeing, channel release.
>> 	 Updated to use exact xfer size for syncing dma buffer.
>>  [V5] :  Same as V4
>>  [V4] :  Updated to allocate DMA buffer only when DMA mode.
>> 	 Updated to fall back to PIO mode when DMA channel request or
>> 	 buffer allocation fails.
>>  [V3] :  Updated without additional buffer allocation.
>>  [V2] :  Updated based on V1 review feedback along with code cleanup for
>> 	 proper implementation of DMA.
>>
>>
>>  drivers/i2c/busses/i2c-tegra.c | 413 ++++++++++++++++++++++++++++++++++++-----
>>  1 file changed, 369 insertions(+), 44 deletions(-)
>>
>> diff --git a/drivers/i2c/busses/i2c-tegra.c b/drivers/i2c/busses/i2c-tegra.c
>> index 118b7023a0f4..77277a09e485 100644
>> --- a/drivers/i2c/busses/i2c-tegra.c
>> +++ b/drivers/i2c/busses/i2c-tegra.c
>> @@ -8,6 +8,9 @@
>>  
>>  #include <linux/clk.h>
>>  #include <linux/delay.h>
>> +#include <linux/dmaengine.h>
>> +#include <linux/dmapool.h>
> 
> We are not using DMA pools anywhere in the code, <linux/dmapool.h> isn't needed. Let's remove it.
> 
>> +#include <linux/dma-mapping.h>
>>  #include <linux/err.h>
>>  #include <linux/i2c.h>
>>  #include <linux/init.h>
>> @@ -44,6 +47,8 @@
>>  #define I2C_FIFO_CONTROL_RX_FLUSH		BIT(0)
>>  #define I2C_FIFO_CONTROL_TX_TRIG_SHIFT		5
>>  #define I2C_FIFO_CONTROL_RX_TRIG_SHIFT		2
>> +#define I2C_FIFO_CONTROL_TX_TRIG(x)		(((x) - 1) << 5)
>> +#define I2C_FIFO_CONTROL_RX_TRIG(x)		(((x) - 1) << 2)
>>  #define I2C_FIFO_STATUS				0x060
>>  #define I2C_FIFO_STATUS_TX_MASK			0xF0
>>  #define I2C_FIFO_STATUS_TX_SHIFT		4
>> @@ -125,6 +130,19 @@
>>  #define I2C_MST_FIFO_STATUS_TX_MASK		0xff0000
>>  #define I2C_MST_FIFO_STATUS_TX_SHIFT		16
>>  
>> +/* Packet header size in bytes */
>> +#define I2C_PACKET_HEADER_SIZE			12
>> +
>> +#define DATA_DMA_DIR_TX				BIT(0)
>> +#define DATA_DMA_DIR_RX				BIT(1)
> 
> The DATA_DMA_DIR_TX/RX are not used anywhere in the code, let's remove them.
> 
> [snip]
> 
> 		TEGRA_I2C_TIMEOUT);
>>  	tegra_i2c_mask_irq(i2c_dev, int_mask);
>> @@ -814,6 +1133,7 @@ static int tegra_i2c_xfer_msg(struct tegra_i2c_dev *i2c_dev,
>>  		time_left, completion_done(&i2c_dev->msg_complete),
>>  		i2c_dev->msg_err);
>>  
>> +	i2c_dev->is_curr_dma_xfer = false;
> 
> This line could be removed because there is no need to clear "is_curr_dma_xfer" at this point.
> 
>>  	if (likely(i2c_dev->msg_err == I2C_ERR_NONE))
>>  		return 0;
> [snip]
> 
> 
> Sowjanya, I tried to enforce DMA transferring + setting DMA burst to a one word and this combination doesn't work well while it should, if I'm not missing something. Could you please take a look at the problem or explain why that happens?
> 
> Here is the change I made:
> 
> -----------------
> diff --git a/drivers/i2c/busses/i2c-tegra.c b/drivers/i2c/busses/i2c-tegra.c
> index c538ed5f8e2c..59e245d4417d 100644
> --- a/drivers/i2c/busses/i2c-tegra.c
> +++ b/drivers/i2c/busses/i2c-tegra.c
> @@ -6,6 +6,8 @@
>   * Author: Colin Cross <ccross@android.com>
>   */
>  
> +#define DEBUG
> +
>  #include <linux/clk.h>
>  #include <linux/delay.h>
>  #include <linux/dmaengine.h>
> @@ -929,12 +931,7 @@ static void tegra_i2c_config_fifo_trig(struct tegra_i2c_dev *i2c_dev,
>         val = i2c_readl(i2c_dev, reg);
>  
>         if (i2c_dev->is_curr_dma_xfer) {
> -               if (len & 0xF)
>                         dma_burst = 1;
> -               else if (len & 0x10)
> -                       dma_burst = 4;
> -               else
> -                       dma_burst = 8;
>  
>                 if (i2c_dev->msg_read) {
>                         chan = i2c_dev->rx_dma_chan;
> @@ -1046,8 +1043,7 @@ static int tegra_i2c_xfer_msg(struct tegra_i2c_dev *i2c_dev,
>                 xfer_size = msg->len + I2C_PACKET_HEADER_SIZE;
>  
>         xfer_size = ALIGN(xfer_size, BYTES_PER_FIFO_WORD);
> -       i2c_dev->is_curr_dma_xfer = (xfer_size > I2C_PIO_MODE_MAX_LEN) &&
> -                                   i2c_dev->dma_buf;
> +       i2c_dev->is_curr_dma_xfer = !!i2c_dev->dma_buf;
>         tegra_i2c_config_fifo_trig(i2c_dev, xfer_size);
>         dma = i2c_dev->is_curr_dma_xfer
> -----------------
> 
> And here what happens:
> 
> -----------------
> ...
> [    0.761144] tegra_rtc 7000e000.rtc: registered as rtc1
> [    0.761199] tegra_rtc 7000e000.rtc: Tegra internal Real Time Clock
> [    0.761406] i2c /dev entries driver
> [    0.919233] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> [    0.919246] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    0.919345] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> [    0.919355] tegra-i2c 7000c000.i2c: starting DMA for length: 8
> [    0.919363] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    0.919628] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> [    0.919641] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> [    0.919649] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    0.919746] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> [    0.919755] tegra-i2c 7000c000.i2c: starting DMA for length: 112
> [    0.919763] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    0.923140] tegra-i2c 7000c000.i2c: transfer complete: 11 0 0
> [    0.923150] atmel_mxt_ts 0-004c: Family: 160 Variant: 0 Firmware V1.0.AA Objects: 18
> [    0.923208] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> [    0.923217] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    0.923314] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> [    0.923323] tegra-i2c 7000c000.i2c: starting DMA for length: 224
> [    0.923331] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    0.933564] tegra-i2c 7000c000.i2c: transfer complete: 11 0 0
> [    0.933599] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> [    0.933609] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    0.933760] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> [    0.933770] tegra-i2c 7000c000.i2c: starting DMA for length: 12
> [    0.933779] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    0.934284] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> [    0.934309] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> [    0.934317] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    0.934500] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> [    0.934509] tegra-i2c 7000c000.i2c: starting DMA for length: 12
> [    0.934518] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    0.935023] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> [    0.935081] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> [    0.935091] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    0.935240] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> [    0.935249] tegra-i2c 7000c000.i2c: starting DMA for length: 4
> [    0.935258] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    0.935399] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> [    0.935416] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> [    0.935424] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    0.935655] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> [    0.945445] tegra-i2c 7000d000.i2c: starting DMA for length: 16
> [    0.945456] tegra-i2c 7000d000.i2c: unmasked irq: 0c
> [    0.969236] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> [    0.969245] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    0.969361] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> [    0.969370] tegra-i2c 7000c000.i2c: starting DMA for length: 4
> [    0.969379] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    0.969462] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> [    0.982587] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> [    0.982596] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    0.982722] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> [    0.982731] tegra-i2c 7000c000.i2c: starting DMA for length: 12
> [    0.982740] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    0.983071] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> [    0.983090] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> [    0.983098] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    0.983252] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> [    0.983261] tegra-i2c 7000c000.i2c: starting DMA for length: 136
> [    0.983269] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    0.987605] tegra-i2c 7000c000.i2c: transfer complete: 11 0 0
> [    0.987623] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> [    0.987631] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    0.987800] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> [    0.987809] tegra-i2c 7000c000.i2c: starting DMA for length: 12
> [    0.987817] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    0.988324] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> [    1.009227] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> [    1.009236] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    1.009374] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> [    1.009383] tegra-i2c 7000c000.i2c: starting DMA for length: 4
> [    1.009391] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    1.009479] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> [    1.009497] atmel_mxt_ts 0-004c: Warning: Info CRC error - device=0xF436DC file=0x000000
> [    1.009588] tegra-i2c 7000c000.i2c: starting DMA for length: 272
> [    1.009597] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    1.017483] tegra-i2c 7000c000.i2c: transfer complete: 11 0 0
> [    1.017496] tegra-i2c 7000c000.i2c: starting DMA for length: 120
> [    1.017504] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    1.020896] tegra-i2c 7000c000.i2c: transfer complete: 11 0 0
> [    1.020909] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> [    1.020918] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    1.021055] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> [    1.032230] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> [    1.032239] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    1.032359] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> [    1.032368] tegra-i2c 7000c000.i2c: starting DMA for length: 12
> [    1.032376] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    1.032704] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> [    1.049224] tegra-i2c 7000d000.i2c: i2c transfer timed out
> [    1.049253] tps6586x 3-0034: Chip ID read failed: -110
> [    1.049281] tps6586x: probe of 3-0034 failed with error -5
> ...
> -----------------
> 

BTW, I'm seeing "atmel_mxt_ts 0-004c: Warning: Info CRC error - device=0xF436DC file=0x000000" whithout making any modifications to the original patch as well and it shall not happen, hence there is bug somewhere. Probably FIFO triggers are still not set up correctly... ?


[    0.750883] tegra_rtc 7000e000.rtc: registered as rtc1
[    0.750937] tegra_rtc 7000e000.rtc: Tegra internal Real Time Clock
[    0.751137] i2c /dev entries driver
[    0.919076] tegra-i2c 7000c000.i2c: unmasked irq: 0c
[    0.919172] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
[    0.919181] tegra-i2c 7000c000.i2c: unmasked irq: 0d
[    0.919439] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
[    0.919453] tegra-i2c 7000c000.i2c: unmasked irq: 0c
[    0.919548] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
[    0.919559] tegra-i2c 7000c000.i2c: starting DMA for length: 112
[    0.919570] tegra-i2c 7000c000.i2c: unmasked irq: 0c
[    0.922934] tegra-i2c 7000c000.i2c: transfer complete: 11 0 0
[    0.922945] atmel_mxt_ts 0-004c: Family: 160 Variant: 0 Firmware V1.0.AA Objects: 18
[    0.923001] tegra-i2c 7000c000.i2c: unmasked irq: 0c
[    0.923098] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
[    0.923108] tegra-i2c 7000c000.i2c: starting DMA for length: 224
[    0.923116] tegra-i2c 7000c000.i2c: unmasked irq: 0c
[    0.933362] tegra-i2c 7000c000.i2c: transfer complete: 11 0 0
[    0.933397] tegra-i2c 7000c000.i2c: unmasked irq: 0c
[    0.933570] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
[    0.933581] tegra-i2c 7000c000.i2c: unmasked irq: 0d
[    0.934085] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
[    0.934108] tegra-i2c 7000c000.i2c: unmasked irq: 0c
[    0.934313] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
[    0.934323] tegra-i2c 7000c000.i2c: unmasked irq: 0d
[    0.934828] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
[    0.934875] tegra-i2c 7000c000.i2c: unmasked irq: 0c
[    0.935056] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
[    0.935066] tegra-i2c 7000c000.i2c: unmasked irq: 0d
[    0.935204] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
[    0.935221] tegra-i2c 7000c000.i2c: unmasked irq: 0c
[    0.935352] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
[    0.935436] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.935509] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.935518] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.935589] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.935599] tps6586x 3-0034: Found TPS658621C/D, VERSIONCRC is 2c
[    0.935712] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.935812] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.935827] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.935926] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.935939] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.936038] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.936051] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.936150] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.936163] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.936262] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.936275] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.936346] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.936355] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.936501] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.937319] REG-SYS: supplied by vdd_5v0
[    0.937505] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.937580] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.937589] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.937661] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.937674] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.937745] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.937754] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.937824] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.937843] REG-SM_0: supplied by vdd_sys
[    0.937900] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.937972] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.937981] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.938051] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.938071] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.938142] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.938151] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.938221] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.938237] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.938308] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.938317] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.938387] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.938438] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.938511] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.938520] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.938590] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.938696] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.938767] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.938776] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.938847] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.938860] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.938931] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.938939] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.939010] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.939029] REG-SM_1: supplied by vdd_sys
[    0.939124] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.939196] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.939204] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.939276] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.939294] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.939365] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.939374] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.939445] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.939459] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.939530] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.939539] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.939610] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.939656] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.939727] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.939736] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.939806] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.939897] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.939968] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.939977] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.940048] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.940061] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.940132] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.940140] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.940211] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.940224] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.940295] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.940304] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.940374] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.940386] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.940485] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.940504] REG-SM_2: supplied by vdd_sys
[    0.940561] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.940633] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.940642] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.940713] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.940731] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.940802] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.940811] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.940881] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.940926] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.940997] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.941006] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.941076] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.941176] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.941247] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.941256] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.941327] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.941340] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.941411] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.941420] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.941490] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.941510] REG-LDO_0: supplied by vdd_sm2,vin_ldo*
[    0.941584] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.941657] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.941666] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.941737] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.941752] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.941823] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.941832] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.941902] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.941943] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.942014] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.942023] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.942094] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.942180] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.942251] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.942260] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.942331] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.942344] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.942415] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.942424] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.942494] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.942506] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.942577] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.942586] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.942656] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.942668] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.942767] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.942787] REG-LDO_1: supplied by vdd_sm2,vin_ldo*
[    0.942843] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.942914] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.942923] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.942994] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.943008] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.943079] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.943088] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.943158] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.943177] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.943248] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.943256] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.943327] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.943379] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.943450] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.943459] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.943530] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.943627] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.943699] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.943708] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.943780] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.943792] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.943863] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.943872] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.943943] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.943963] REG-LDO_2: supplied by vdd_sm2,vin_ldo*
[    0.944019] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.944091] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.944100] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.944171] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.944186] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.944257] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.944265] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.944336] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.944355] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.944426] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.944434] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.944505] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.944517] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.944616] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.944631] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.944702] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.944711] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.944783] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.944834] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.944905] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.944914] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.944985] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.945107] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.945178] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.945187] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.945258] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.945271] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.945341] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.945350] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.945421] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.945434] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.945504] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.945513] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.945583] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.945595] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.945694] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.945714] REG-LDO_3: supplied by vdd_sm2,vin_ldo*
[    0.945776] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.945848] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.945857] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.945928] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.945942] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.946013] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.946022] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.946092] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.946110] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.946181] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.946189] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.946260] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.946304] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.946376] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.946384] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.946455] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.946556] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.946628] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.946637] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.946707] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.946720] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.946791] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.946800] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.946870] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.946883] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.946954] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.946962] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.947033] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.947045] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.947144] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.947164] REG-LDO_4: supplied by vdd_sm2,vin_ldo*
[    0.947219] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.947291] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.947300] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.947371] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.947385] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.947456] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.947465] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.947536] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.947555] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.947625] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.947634] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.947704] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.947749] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.947820] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.947829] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.947900] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.948015] REG-LDO_5: supplied by vdd_sys
[    0.948086] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.948157] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.948166] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.948237] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.948254] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.948325] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.948334] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.948405] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.948420] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.948491] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.948500] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.948571] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.948622] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.948693] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.948702] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.948773] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.948867] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.948938] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.948947] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.949019] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.949032] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.949100] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.949109] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.949177] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.949198] REG-LDO_6: supplied by vdd_sm2,vin_ldo*
[    0.949254] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.949322] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.949331] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.949399] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.949413] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.949481] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.949490] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.949557] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.949564] vdd_ldo6,avdd_vdac: Bringing 2850000uV into 1800000-1800000uV
[    0.949591] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.949659] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.949668] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.949735] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.949748] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.949816] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.949824] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.949892] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.949905] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.949973] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.949981] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.950050] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.950063] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.950130] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.950139] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.950206] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.950218] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.950314] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.950359] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.950427] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.950436] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.950503] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.950602] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.950671] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.950680] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.950748] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.950760] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.950827] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.950836] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.950903] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.950923] REG-LDO_7: supplied by vdd_sm2,vin_ldo*
[    0.950995] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.951064] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.951073] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.951141] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.951155] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.951223] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.951231] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.951299] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.951351] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.951418] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.951427] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.951495] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.951588] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.951657] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.951666] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.951725] random: fast init done
[    0.951734] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.951751] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.951820] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.951829] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.951897] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.951917] REG-LDO_8: supplied by vdd_sm2,vin_ldo*
[    0.951975] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.952044] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.952053] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.952122] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.952136] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.952204] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.952213] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.952280] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.952324] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.952393] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.952401] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.952469] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.952574] REG-LDO_9: supplied by vdd_sm2,vin_ldo*
[    0.952630] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.952699] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.952708] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.952775] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.952797] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.952865] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.952874] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.952941] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.952958] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.953026] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.953035] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.953102] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.953147] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.953216] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.953225] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.953292] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.953423] REG-LDO_RTC: supplied by vdd_sys
[    0.953486] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.953554] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.953563] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.953631] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.953675] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.953743] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.953752] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.953820] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.953985] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.954082] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.954096] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.954191] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.954203] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.954300] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.954312] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.954407] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.954419] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.954515] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.954682] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.954750] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.954759] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.954826] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.954883] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.954979] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.954991] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.955087] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.955099] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.955195] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.955208] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.955304] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.955316] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.955412] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.955453] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.955549] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.955561] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.955657] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.955669] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.955765] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.955777] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.955873] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.955885] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.955981] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.955996] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.956063] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.956072] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.956262] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.956277] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.956346] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.956355] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.956471] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.956487] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.956554] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.956563] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.956754] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.956910] tps6586x-rtc tps6586x-rtc: registered as rtc0
[    0.958265] i2c i2c-1: Added multiplexed i2c bus 4
[    0.958663] i2c i2c-1: Added multiplexed i2c bus 5
[    0.958804] usbcore: registered new interface driver uvcvideo
[    0.958822] USB Video Class driver (1.1.1)
[    0.958836] gspca_main: v2.14.0 registered
[    0.960393] lm90 3-004c: 3-004c supply vcc not found, using dummy regulator
[    0.960464] lm90 3-004c: Linked as a consumer to regulator.0
[    0.960504] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.960577] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.960587] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.960655] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.960667] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.960763] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.960774] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.960842] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.960850] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.960918] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.961182] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.961251] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.961260] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.961329] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.961340] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.961408] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.961417] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.961484] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.961495] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.961564] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.961572] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.961640] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.961650] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.961718] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.961727] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.961794] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.961805] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.961873] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.961881] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.961948] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.961959] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.962026] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.962035] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.962103] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.962114] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.962182] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.962190] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.962258] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.962269] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.962336] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.962345] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.962412] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.962423] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.962490] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.962499] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.962566] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.962576] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.962645] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.962654] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.962722] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.962733] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.962801] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.962809] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.962877] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.962888] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.962955] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.962963] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.963031] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.963042] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.963110] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.963118] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.963185] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.963196] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.963264] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.963272] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.963340] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.963350] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.963418] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.963426] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.963493] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.963504] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.963571] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.963579] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.963647] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.963657] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    0.963725] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.963733] tegra-i2c 7000d000.i2c: unmasked irq: 0d
[    0.963801] tegra-i2c 7000d000.i2c: transfer complete: 10 0 0
[    0.964667] sdhci: Secure Digital Host Controller Interface driver
[    0.964689] sdhci: Copyright(c) Pierre Ossman
[    0.964703] sdhci-pltfm: SDHCI platform and OF driver helper
[    0.965011] sdhci-tegra c8000000.sdhci: allocated mmc-pwrseq
[    0.969090] tegra-i2c 7000c000.i2c: unmasked irq: 0c
[    0.969244] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
[    0.969253] tegra-i2c 7000c000.i2c: unmasked irq: 0d
[    0.969341] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
[    0.973187] sdhci-tegra c8000000.sdhci: Linked as a consumer to regulator.4
[    0.973328] mmc0: Invalid maximum block size, assuming 512 bytes
[    0.982401] tegra-i2c 7000c000.i2c: unmasked irq: 0c
[    0.982536] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
[    0.982545] tegra-i2c 7000c000.i2c: unmasked irq: 0d
[    0.982874] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
[    0.982895] tegra-i2c 7000c000.i2c: unmasked irq: 0c
[    0.983067] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
[    0.983078] tegra-i2c 7000c000.i2c: starting DMA for length: 136
[    0.983088] tegra-i2c 7000c000.i2c: unmasked irq: 0c
[    0.987427] tegra-i2c 7000c000.i2c: transfer complete: 11 0 0
[    0.987446] tegra-i2c 7000c000.i2c: unmasked irq: 0c
[    0.987613] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
[    0.987622] tegra-i2c 7000c000.i2c: unmasked irq: 0d
[    0.988127] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
[    1.009076] tegra-i2c 7000c000.i2c: unmasked irq: 0c
[    1.009224] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
[    1.009233] tegra-i2c 7000c000.i2c: unmasked irq: 0d
[    1.009322] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
[    1.009339] atmel_mxt_ts 0-004c: Warning: Info CRC error - device=0xF436DC file=0x000000
[    1.009428] tegra-i2c 7000c000.i2c: starting DMA for length: 272
[    1.009437] tegra-i2c 7000c000.i2c: unmasked irq: 0c
[    1.017331] tegra-i2c 7000c000.i2c: transfer complete: 11 0 0
[    1.017345] tegra-i2c 7000c000.i2c: starting DMA for length: 120

^ permalink raw reply	[flat|nested] 35+ messages in thread

* Re: [PATCH V12 3/5] i2c: tegra: Add DMA support
  2019-02-06 12:48     ` Thierry Reding
@ 2019-02-06 13:01       ` Dmitry Osipenko
  0 siblings, 0 replies; 35+ messages in thread
From: Dmitry Osipenko @ 2019-02-06 13:01 UTC (permalink / raw)
  To: Thierry Reding
  Cc: Sowjanya Komatineni, jonathanh, mkarthik, smohammed, talho,
	linux-tegra, linux-kernel, linux-i2c

06.02.2019 15:48, Thierry Reding пишет:
> On Wed, Feb 06, 2019 at 03:40:52PM +0300, Dmitry Osipenko wrote:
>> 06.02.2019 1:46, Sowjanya Komatineni пишет:
>>> This patch adds DMA support for Tegra I2C.
>>>
>>> Tegra I2C TX and RX FIFO depth is 8 words. PIO mode is used for
>>> transfer size of the max FIFO depth and DMA mode is used for
>>> transfer size higher than max FIFO depth to save CPU overhead.
>>>
>>> PIO mode needs full intervention of CPU to fill or empty FIFO's
>>> and also need to service multiple data requests interrupt for the
>>> same transaction. This adds delay between data bytes of the same
>>> transfer when CPU is fully loaded and some slave devices has
>>> internal timeout for no bus activity and stops transaction to
>>> avoid bus hang. DMA mode is helpful in such cases.
>>>
>>> DMA mode is also helpful for Large transfers during downloading or
>>> uploading FW over I2C to some external devices.
>>>
>>> Signed-off-by: Sowjanya Komatineni <skomatineni@nvidia.com>
>>> ---
>>>  [V12] : Replaced dma_alloc_coherent with dma_alloc_attrs to force the allocated
>>> 	 buffer to be contiguous also in physical memory as Tegra194 supports max
>>> 	 64K and dma_alloc_coherent doesnt guarentee contiguous memory.
>>> 	 Changed return code from EIO to EINVAL incase of failure to obtain dma
>>> 	 descriptor.
>>> 	 Fixed coding style check issues.	 
>>>  [V11] : Replaced deprecated dmaengine_terminate_all with dmaengine_termine_async
>>> 	 from non-atomic context and dmaengine_terminate_sync from atomic context.
>>> 	 Fixed to program fifo trigger levels properly when transfer falls back to
>>> 	 pio mode in case of dma slave configuration failure and other minor fixes.
>>>  [V10] : APBDMA is replaced with GPCDMA on Tegra186 and Tegra194 designs.
>>> 	 Added apbdma hw support flag to now allow Tegra186 and later use
>>> 	 APBDMA driver.
>>> 	 Added explicit flow control enable for DMA slave config and error handling.
>>> 	 Moved releasing DMA resources to seperate function to reuse in
>>> 	 multiple places.
>>> 	 Updated to register tegra_i2c_driver from module level rather than subsys
>>> 	 level.
>>> 	 Other minor feedback
>>>  [V9] :  Rebased to 5.0-rc4
>>> 	 Removed dependency of APB DMA in Kconfig and added conditional check
>>>  	 in I2C driver to decide on using DMA mode.
>>> 	 Changed back the allocation of dma buffer during i2c probe.
>>> 	 Fixed FIFO triggers depending on DMA Vs PIO.
>>>  [V8] :  Moved back dma init to i2c probe, removed ALL_PACKETS_XFER_COMPLETE
>>> 	 interrupt and using PACKETS_XFER_COMPLETE interrupt only and some
>>> 	 other fixes
>>> 	 Updated Kconfig for APB_DMA dependency
>>>  [V7] :  Same as V6
>>>  [V6] :  Updated for proper buffer allocation/freeing, channel release.
>>> 	 Updated to use exact xfer size for syncing dma buffer.
>>>  [V5] :  Same as V4
>>>  [V4] :  Updated to allocate DMA buffer only when DMA mode.
>>> 	 Updated to fall back to PIO mode when DMA channel request or
>>> 	 buffer allocation fails.
>>>  [V3] :  Updated without additional buffer allocation.
>>>  [V2] :  Updated based on V1 review feedback along with code cleanup for
>>> 	 proper implementation of DMA.
>>>
>>>
>>>  drivers/i2c/busses/i2c-tegra.c | 413 ++++++++++++++++++++++++++++++++++++-----
>>>  1 file changed, 369 insertions(+), 44 deletions(-)
>>>
>>> diff --git a/drivers/i2c/busses/i2c-tegra.c b/drivers/i2c/busses/i2c-tegra.c
>>> index 118b7023a0f4..77277a09e485 100644
>>> --- a/drivers/i2c/busses/i2c-tegra.c
>>> +++ b/drivers/i2c/busses/i2c-tegra.c
>>> @@ -8,6 +8,9 @@
>>>  
>>>  #include <linux/clk.h>
>>>  #include <linux/delay.h>
>>> +#include <linux/dmaengine.h>
>>> +#include <linux/dmapool.h>
>>> +#include <linux/dma-mapping.h>
>>>  #include <linux/err.h>
>>>  #include <linux/i2c.h>
>>>  #include <linux/init.h>
>>> @@ -44,6 +47,8 @@
>>>  #define I2C_FIFO_CONTROL_RX_FLUSH		BIT(0)
>>>  #define I2C_FIFO_CONTROL_TX_TRIG_SHIFT		5
>>>  #define I2C_FIFO_CONTROL_RX_TRIG_SHIFT		2
>>> +#define I2C_FIFO_CONTROL_TX_TRIG(x)		(((x) - 1) << 5)
>>> +#define I2C_FIFO_CONTROL_RX_TRIG(x)		(((x) - 1) << 2)
>>>  #define I2C_FIFO_STATUS				0x060
>>>  #define I2C_FIFO_STATUS_TX_MASK			0xF0
>>>  #define I2C_FIFO_STATUS_TX_SHIFT		4
>>> @@ -125,6 +130,19 @@
>>>  #define I2C_MST_FIFO_STATUS_TX_MASK		0xff0000
>>>  #define I2C_MST_FIFO_STATUS_TX_SHIFT		16
>>>  
>>> +/* Packet header size in bytes */
>>> +#define I2C_PACKET_HEADER_SIZE			12
>>> +
>>> +#define DATA_DMA_DIR_TX				BIT(0)
>>> +#define DATA_DMA_DIR_RX				BIT(1)
>>> +
>>> +/*
>>> + * Upto I2C_PIO_MODE_MAX_LEN bytes, controller will use PIO mode,
>>> + * above this, controller will use DMA to fill FIFO.
>>> + * MAX PIO len is 20 bytes excluding packet header.
>>> + */
>>> +#define I2C_PIO_MODE_MAX_LEN			32
>>> +
>>>  /*
>>>   * msg_end_type: The bus control which need to be send at end of transfer.
>>>   * @MSG_END_STOP: Send stop pulse at end of transfer.
>>> @@ -166,6 +184,7 @@ enum msg_end_type {
>>>   *		allowing 0 length transfers.
>>>   * @supports_bus_clear: Bus Clear support to recover from bus hang during
>>>   *		SDA stuck low from device for some unknown reasons.
>>> + * @has_apb_dma: Support of APBDMA on corresponding Tegra chip.
>>>   */
>>>  struct tegra_i2c_hw_feature {
>>>  	bool has_continue_xfer_support;
>>> @@ -180,6 +199,7 @@ struct tegra_i2c_hw_feature {
>>>  	bool has_mst_fifo;
>>>  	const struct i2c_adapter_quirks *quirks;
>>>  	bool supports_bus_clear;
>>> +	bool has_apb_dma;
>>>  };
>>>  
>>>  /**
>>> @@ -191,6 +211,7 @@ struct tegra_i2c_hw_feature {
>>>   * @fast_clk: clock reference for fast clock of I2C controller
>>>   * @rst: reset control for the I2C controller
>>>   * @base: ioremapped registers cookie
>>> + * @base_phys: Physical base address of the I2C controller
>>>   * @cont_id: I2C controller ID, used for packet header
>>>   * @irq: IRQ number of transfer complete interrupt
>>>   * @irq_disabled: used to track whether or not the interrupt is enabled
>>> @@ -204,6 +225,13 @@ struct tegra_i2c_hw_feature {
>>>   * @clk_divisor_non_hs_mode: clock divider for non-high-speed modes
>>>   * @is_multimaster_mode: track if I2C controller is in multi-master mode
>>>   * @xfer_lock: lock to serialize transfer submission and processing
>>> + * @tx_dma_chan: DMA transmit channel
>>> + * @rx_dma_chan: DMA receive channel
>>> + * @dma_phys: handle to DMA resources
>>> + * @dma_buf: pointer to allocated DMA buffer
>>> + * @dma_buf_size: DMA buffer size
>>> + * @is_curr_dma_xfer: indicates active DMA transfer
>>> + * @dma_complete: DMA completion notifier
>>>   */
>>>  struct tegra_i2c_dev {
>>>  	struct device *dev;
>>> @@ -213,6 +241,7 @@ struct tegra_i2c_dev {
>>>  	struct clk *fast_clk;
>>>  	struct reset_control *rst;
>>>  	void __iomem *base;
>>> +	phys_addr_t base_phys;
>>>  	int cont_id;
>>>  	int irq;
>>>  	bool irq_disabled;
>>> @@ -226,6 +255,13 @@ struct tegra_i2c_dev {
>>>  	u16 clk_divisor_non_hs_mode;
>>>  	bool is_multimaster_mode;
>>>  	spinlock_t xfer_lock;
>>> +	struct dma_chan *tx_dma_chan;
>>> +	struct dma_chan *rx_dma_chan;
>>> +	dma_addr_t dma_phys;
>>> +	u32 *dma_buf;
>>> +	unsigned int dma_buf_size;
>>> +	bool is_curr_dma_xfer;
>>> +	struct completion dma_complete;
>>>  };
>>>  
>>>  static void dvc_writel(struct tegra_i2c_dev *i2c_dev, u32 val,
>>> @@ -294,6 +330,111 @@ static void tegra_i2c_unmask_irq(struct tegra_i2c_dev *i2c_dev, u32 mask)
>>>  	i2c_writel(i2c_dev, int_mask, I2C_INT_MASK);
>>>  }
>>>  
>>> +static void tegra_i2c_dma_complete(void *args)
>>> +{
>>> +	struct tegra_i2c_dev *i2c_dev = args;
>>> +
>>> +	complete(&i2c_dev->dma_complete);
>>> +}
>>> +
>>> +static int tegra_i2c_dma_submit(struct tegra_i2c_dev *i2c_dev, size_t len)
>>> +{
>>> +	struct dma_async_tx_descriptor *dma_desc;
>>> +	enum dma_transfer_direction dir;
>>> +	struct dma_chan *chan;
>>> +
>>> +	dev_dbg(i2c_dev->dev, "starting DMA for length: %zu\n", len);
>>> +	reinit_completion(&i2c_dev->dma_complete);
>>> +	dir = i2c_dev->msg_read ? DMA_DEV_TO_MEM : DMA_MEM_TO_DEV;
>>> +	chan = i2c_dev->msg_read ? i2c_dev->rx_dma_chan : i2c_dev->tx_dma_chan;
>>> +	dma_desc = dmaengine_prep_slave_single(chan, i2c_dev->dma_phys,
>>> +					       len, dir, DMA_PREP_INTERRUPT |
>>> +					       DMA_CTRL_ACK);
>>> +	if (!dma_desc) {
>>> +		dev_err(i2c_dev->dev, "failed to get DMA descriptor\n");
>>> +		return -EINVAL;
>>> +	}
>>> +
>>> +	dma_desc->callback = tegra_i2c_dma_complete;
>>> +	dma_desc->callback_param = i2c_dev;
>>> +	dmaengine_submit(dma_desc);
>>> +	dma_async_issue_pending(chan);
>>> +	return 0;
>>> +}
>>> +
>>> +static void tegra_i2c_release_dma(struct tegra_i2c_dev *i2c_dev)
>>> +{
>>> +	if (i2c_dev->dma_buf) {
>>> +		dma_free_attrs(i2c_dev->dev, i2c_dev->dma_buf_size,
>>> +			       i2c_dev->dma_buf, i2c_dev->dma_phys,
>>> +			       DMA_ATTR_FORCE_CONTIGUOUS);
>>> +		i2c_dev->dma_buf = NULL;
>>> +	}
>>> +
>>> +	if (i2c_dev->tx_dma_chan) {
>>> +		dma_release_channel(i2c_dev->tx_dma_chan);
>>> +		i2c_dev->tx_dma_chan = NULL;
>>> +	}
>>> +
>>> +	if (i2c_dev->rx_dma_chan) {
>>> +		dma_release_channel(i2c_dev->rx_dma_chan);
>>> +		i2c_dev->rx_dma_chan = NULL;
>>> +	}
>>> +}
>>> +
>>> +static int tegra_i2c_init_dma(struct tegra_i2c_dev *i2c_dev)
>>> +{
>>> +	struct dma_chan *chan;
>>> +	u32 *dma_buf;
>>> +	dma_addr_t dma_phys;
>>> +	int err;
>>> +
>>> +	if (!IS_ENABLED(CONFIG_TEGRA20_APB_DMA) ||
>>> +	    !i2c_dev->hw->has_apb_dma) {
>>> +		err = -ENODEV;
>>> +		goto err_out;
>>> +	}
>>> +
>>> +	chan = dma_request_slave_channel_reason(i2c_dev->dev, "rx");
>>> +	if (IS_ERR(chan)) {
>>> +		err = PTR_ERR(chan);
>>> +		goto err_out;
>>> +	}
>>> +
>>> +	i2c_dev->rx_dma_chan = chan;
>>> +
>>> +	chan = dma_request_slave_channel_reason(i2c_dev->dev, "tx");
>>> +	if (IS_ERR(chan)) {
>>> +		err = PTR_ERR(chan);
>>> +		goto err_out;
>>> +	}
>>> +
>>> +	i2c_dev->tx_dma_chan = chan;
>>> +
>>> +	dma_buf = dma_alloc_attrs(i2c_dev->dev, i2c_dev->dma_buf_size,
>>> +				  &dma_phys, GFP_KERNEL | __GFP_NOWARN,
>>> +				  DMA_ATTR_FORCE_CONTIGUOUS);
>>> +	if (!dma_buf) {
>>> +		dev_err(i2c_dev->dev, "failed to allocate the DMA buffer\n");
>>> +		err = -ENOMEM;
>>> +		goto err_out;
>>> +	}
>>> +
>>> +	i2c_dev->dma_buf = dma_buf;
>>> +	i2c_dev->dma_phys = dma_phys;
>>> +	return 0;
>>> +
>>> +err_out:
>>> +	tegra_i2c_release_dma(i2c_dev);
>>> +	if (err != -EPROBE_DEFER) {
>>> +		dev_err(i2c_dev->dev, "can't use DMA, err: %d, using PIO\n",
>>> +			err);
>>> +		return 0;
>>> +	}
>>> +
>>> +	return err;
>>> +}
>>> +
>>>  static int tegra_i2c_flush_fifos(struct tegra_i2c_dev *i2c_dev)
>>>  {
>>>  	unsigned long timeout = jiffies + HZ;
>>> @@ -571,16 +712,6 @@ static int tegra_i2c_init(struct tegra_i2c_dev *i2c_dev)
>>>  		i2c_writel(i2c_dev, 0x00, I2C_SL_ADDR2);
>>>  	}
>>>  
>>> -	if (i2c_dev->hw->has_mst_fifo) {
>>> -		val = I2C_MST_FIFO_CONTROL_TX_TRIG(8) |
>>> -		      I2C_MST_FIFO_CONTROL_RX_TRIG(1);
>>> -		i2c_writel(i2c_dev, val, I2C_MST_FIFO_CONTROL);
>>> -	} else {
>>> -		val = 7 << I2C_FIFO_CONTROL_TX_TRIG_SHIFT |
>>> -			0 << I2C_FIFO_CONTROL_RX_TRIG_SHIFT;
>>> -		i2c_writel(i2c_dev, val, I2C_FIFO_CONTROL);
>>> -	}
>>> -
>>>  	err = tegra_i2c_flush_fifos(i2c_dev);
>>>  	if (err)
>>>  		goto err;
>>> @@ -660,25 +791,37 @@ static irqreturn_t tegra_i2c_isr(int irq, void *dev_id)
>>>  	if (i2c_dev->hw->supports_bus_clear && (status & I2C_INT_BUS_CLR_DONE))
>>>  		goto err;
>>>  
>>> -	if (i2c_dev->msg_read && (status & I2C_INT_RX_FIFO_DATA_REQ)) {
>>> -		if (i2c_dev->msg_buf_remaining)
>>> -			tegra_i2c_empty_rx_fifo(i2c_dev);
>>> -		else
>>> -			BUG();
>>> -	}
>>> +	if (!i2c_dev->is_curr_dma_xfer) {
>>> +		if (i2c_dev->msg_read && (status & I2C_INT_RX_FIFO_DATA_REQ)) {
>>> +			if (i2c_dev->msg_buf_remaining)
>>> +				tegra_i2c_empty_rx_fifo(i2c_dev);
>>> +			else
>>> +				BUG();
>>> +		}
>>>  
>>> -	if (!i2c_dev->msg_read && (status & I2C_INT_TX_FIFO_DATA_REQ)) {
>>> -		if (i2c_dev->msg_buf_remaining)
>>> -			tegra_i2c_fill_tx_fifo(i2c_dev);
>>> -		else
>>> -			tegra_i2c_mask_irq(i2c_dev, I2C_INT_TX_FIFO_DATA_REQ);
>>> +		if (!i2c_dev->msg_read && (status & I2C_INT_TX_FIFO_DATA_REQ)) {
>>> +			if (i2c_dev->msg_buf_remaining)
>>> +				tegra_i2c_fill_tx_fifo(i2c_dev);
>>> +			else
>>> +				tegra_i2c_mask_irq(i2c_dev,
>>> +						   I2C_INT_TX_FIFO_DATA_REQ);
>>> +		}
>>>  	}
>>>  
>>>  	i2c_writel(i2c_dev, status, I2C_INT_STATUS);
>>>  	if (i2c_dev->is_dvc)
>>>  		dvc_writel(i2c_dev, DVC_STATUS_I2C_DONE_INTR, DVC_STATUS);
>>>  
>>> +	/*
>>> +	 * During message read XFER_COMPLETE interrupt is triggered prior to
>>> +	 * DMA completion and during message write XFER_COMPLETE interrupt is
>>> +	 * triggered after DMA completion.
>>> +	 * PACKETS_XFER_COMPLETE indicates completion of all bytes of transfer.
>>> +	 * so forcing msg_buf_remaining to 0 in DMA mode.
>>> +	 */
>>>  	if (status & I2C_INT_PACKET_XFER_COMPLETE) {
>>> +		if (i2c_dev->is_curr_dma_xfer)
>>> +			i2c_dev->msg_buf_remaining = 0;
>>>  		BUG_ON(i2c_dev->msg_buf_remaining);
>>>  		complete(&i2c_dev->msg_complete);
>>>  	}
>>> @@ -694,12 +837,89 @@ static irqreturn_t tegra_i2c_isr(int irq, void *dev_id)
>>>  	if (i2c_dev->is_dvc)
>>>  		dvc_writel(i2c_dev, DVC_STATUS_I2C_DONE_INTR, DVC_STATUS);
>>>  
>>> +	if (i2c_dev->is_curr_dma_xfer) {
>>> +		if (i2c_dev->msg_read)
>>> +			dmaengine_terminate_async(i2c_dev->rx_dma_chan);
>>> +		else
>>> +			dmaengine_terminate_async(i2c_dev->tx_dma_chan);
>>> +
>>> +		complete(&i2c_dev->dma_complete);
>>> +	}
>>> +
>>>  	complete(&i2c_dev->msg_complete);
>>>  done:
>>>  	spin_unlock(&i2c_dev->xfer_lock);
>>>  	return IRQ_HANDLED;
>>>  }
>>>  
>>> +static void tegra_i2c_config_fifo_trig(struct tegra_i2c_dev *i2c_dev,
>>> +				       size_t len)
>>> +{
>>> +	u32 val, reg;
>>> +	u8 dma_burst = 0;
>>> +	struct dma_slave_config slv_config = {0};
>>> +	struct dma_chan *chan;
>>> +	int ret;
>>> +
>>> +	if (i2c_dev->hw->has_mst_fifo)
>>> +		reg = I2C_MST_FIFO_CONTROL;
>>> +	else
>>> +		reg = I2C_FIFO_CONTROL;
>>> +	val = i2c_readl(i2c_dev, reg);
>>> +
>>> +	if (i2c_dev->is_curr_dma_xfer) {
>>> +		if (len & 0xF)
>>> +			dma_burst = 1;
>>> +		else if (len & 0x10)
>>> +			dma_burst = 4;
>>> +		else
>>> +			dma_burst = 8;
>>> +
>>> +		if (i2c_dev->msg_read) {
>>> +			chan = i2c_dev->rx_dma_chan;
>>> +			slv_config.src_addr = i2c_dev->base_phys + I2C_RX_FIFO;
>>> +			slv_config.src_addr_width = DMA_SLAVE_BUSWIDTH_4_BYTES;
>>> +			slv_config.src_maxburst = dma_burst;
>>> +
>>> +			if (i2c_dev->hw->has_mst_fifo)
>>> +				val |= I2C_MST_FIFO_CONTROL_RX_TRIG(dma_burst);
>>> +			else
>>> +				val |= I2C_FIFO_CONTROL_RX_TRIG(dma_burst);
>>> +		} else {
>>> +			chan = i2c_dev->tx_dma_chan;
>>> +			slv_config.dst_addr = i2c_dev->base_phys + I2C_TX_FIFO;
>>> +			slv_config.dst_addr_width = DMA_SLAVE_BUSWIDTH_4_BYTES;
>>> +			slv_config.dst_maxburst = dma_burst;
>>> +
>>> +			if (i2c_dev->hw->has_mst_fifo)
>>> +				val |= I2C_MST_FIFO_CONTROL_TX_TRIG(dma_burst);
>>> +			else
>>> +				val |= I2C_FIFO_CONTROL_TX_TRIG(dma_burst);
>>> +		}
>>> +
>>> +		slv_config.device_fc = true;
>>> +		ret = dmaengine_slave_config(chan, &slv_config);
>>> +		if (ret < 0) {
>>> +			dev_err(i2c_dev->dev, "DMA slave config failed: %d\n",
>>> +				ret);
>>> +			dev_err(i2c_dev->dev, "fallbacking to PIO\n");
>>> +			tegra_i2c_release_dma(i2c_dev);
>>> +			i2c_dev->is_curr_dma_xfer = false;
>>> +		} else {
>>> +			goto out;
>>> +		}
>>> +	}
>>> +
>>> +	if (i2c_dev->hw->has_mst_fifo)
>>> +		val = I2C_MST_FIFO_CONTROL_TX_TRIG(8) |
>>> +		      I2C_MST_FIFO_CONTROL_RX_TRIG(1);
>>> +	else
>>> +		val = I2C_FIFO_CONTROL_TX_TRIG(8) |
>>> +		      I2C_FIFO_CONTROL_RX_TRIG(1);
>>> +out:
>>> +	i2c_writel(i2c_dev, val, reg);
>>> +}
>>> +
>>>  static int tegra_i2c_issue_bus_clear(struct tegra_i2c_dev *i2c_dev)
>>>  {
>>>  	int err;
>>> @@ -744,6 +964,10 @@ static int tegra_i2c_xfer_msg(struct tegra_i2c_dev *i2c_dev,
>>>  	u32 int_mask;
>>>  	unsigned long time_left;
>>>  	unsigned long flags;
>>> +	size_t xfer_size;
>>> +	u32 *buffer = NULL;
>>> +	int err = 0;
>>> +	bool dma;
>>>  
>>>  	tegra_i2c_flush_fifos(i2c_dev);
>>>  
>>> @@ -753,19 +977,57 @@ static int tegra_i2c_xfer_msg(struct tegra_i2c_dev *i2c_dev,
>>>  	i2c_dev->msg_read = (msg->flags & I2C_M_RD);
>>>  	reinit_completion(&i2c_dev->msg_complete);
>>>  
>>> +	if (i2c_dev->msg_read)
>>> +		xfer_size = msg->len;
>>> +	else
>>> +		xfer_size = msg->len + I2C_PACKET_HEADER_SIZE;
>>> +
>>> +	xfer_size = ALIGN(xfer_size, BYTES_PER_FIFO_WORD);
>>> +	i2c_dev->is_curr_dma_xfer = (xfer_size > I2C_PIO_MODE_MAX_LEN) &&
>>> +				    i2c_dev->dma_buf;
>>> +	tegra_i2c_config_fifo_trig(i2c_dev, xfer_size);
>>> +	dma = i2c_dev->is_curr_dma_xfer;
>>> +
>>>  	spin_lock_irqsave(&i2c_dev->xfer_lock, flags);
>>>  
>>>  	int_mask = I2C_INT_NO_ACK | I2C_INT_ARBITRATION_LOST;
>>>  	tegra_i2c_unmask_irq(i2c_dev, int_mask);
>>> +	if (dma) {
>>> +		if (i2c_dev->msg_read) {
>>> +			dma_sync_single_for_device(i2c_dev->dev,
>>> +						   i2c_dev->dma_phys,
>>> +						   xfer_size,
>>> +						   DMA_FROM_DEVICE);
>>> +			err = tegra_i2c_dma_submit(i2c_dev, xfer_size);
>>> +			if (err < 0) {
>>> +				dev_err(i2c_dev->dev,
>>> +					"starting RX DMA failed, err %d\n",
>>> +					err);
>>> +				goto unlock;
>>> +			}
>>> +		} else {
>>> +			dma_sync_single_for_cpu(i2c_dev->dev,
>>> +						i2c_dev->dma_phys,
>>> +						xfer_size,
>>> +						DMA_TO_DEVICE);
>>> +			buffer = i2c_dev->dma_buf;
>>> +		}
>>> +	}
>>>  
>>>  	packet_header = (0 << PACKET_HEADER0_HEADER_SIZE_SHIFT) |
>>>  			PACKET_HEADER0_PROTOCOL_I2C |
>>>  			(i2c_dev->cont_id << PACKET_HEADER0_CONT_ID_SHIFT) |
>>>  			(1 << PACKET_HEADER0_PACKET_ID_SHIFT);
>>> -	i2c_writel(i2c_dev, packet_header, I2C_TX_FIFO);
>>> +	if (dma && !i2c_dev->msg_read)
>>> +		*buffer++ = packet_header;
>>> +	else
>>> +		i2c_writel(i2c_dev, packet_header, I2C_TX_FIFO);
>>>  
>>>  	packet_header = msg->len - 1;
>>> -	i2c_writel(i2c_dev, packet_header, I2C_TX_FIFO);
>>> +	if (dma && !i2c_dev->msg_read)
>>> +		*buffer++ = packet_header;
>>> +	else
>>> +		i2c_writel(i2c_dev, packet_header, I2C_TX_FIFO);
>>
>> I'm now also wondering whether that putting packet_header into the
>> dma_buf is really needed at all.. Isn't possible to push packet_header
>> using PIO regardless of whether the rest of the transfer will be in
>> DMA or PIO modes?
>>
>> Actually I tried to always push packet_header using PIO and apparently
>> DMA works just fine with that:
> 
> I don't see a reason why that wouldn't work. After all the DMA support
> here is really just about some external DMA engine writing to the FIFO
> register, so from an I2C controller's point of view it's exactly the
> same thing.
> 
> But if we already set up DMA for a transfer, might as well transfer the
> 3 packet header words with that.

Alright!

^ permalink raw reply	[flat|nested] 35+ messages in thread

* RE: [PATCH V12 3/5] i2c: tegra: Add DMA support
  2019-02-06 12:59     ` Dmitry Osipenko
@ 2019-02-06 13:03       ` Sowjanya Komatineni
  2019-02-06 13:05         ` Dmitry Osipenko
  0 siblings, 1 reply; 35+ messages in thread
From: Sowjanya Komatineni @ 2019-02-06 13:03 UTC (permalink / raw)
  To: Dmitry Osipenko, thierry.reding@gmail.com, Jonathan Hunter,
	Mantravadi Karthik, Shardar Mohammed, Timo Alho
  Cc: linux-tegra@vger.kernel.org, linux-kernel@vger.kernel.org,
	linux-i2c@vger.kernel.org

> BTW, I'm seeing "atmel_mxt_ts 0-004c: Warning: Info CRC error - device=0xF436DC file=0x000000" whithout making any modifications to the original patch as well and it shall not happen, hence there is bug somewhere. Probably FIFO triggers are still not set up correctly... ?
>
>
In snippet you sent, I see you are forcing dma_burst to 1 always which is what set for fifo trigger levels as well and also you are forcing dma all the time.
So always it will be 1 word dma burst and 1 word trigger level and that should not be an issue.


^ permalink raw reply	[flat|nested] 35+ messages in thread

* Re: [PATCH V12 3/5] i2c: tegra: Add DMA support
  2019-02-06 13:03       ` Sowjanya Komatineni
@ 2019-02-06 13:05         ` Dmitry Osipenko
  2019-02-06 13:17           ` Sowjanya Komatineni
  0 siblings, 1 reply; 35+ messages in thread
From: Dmitry Osipenko @ 2019-02-06 13:05 UTC (permalink / raw)
  To: Sowjanya Komatineni, thierry.reding@gmail.com, Jonathan Hunter,
	Mantravadi Karthik, Shardar Mohammed, Timo Alho
  Cc: linux-tegra@vger.kernel.org, linux-kernel@vger.kernel.org,
	linux-i2c@vger.kernel.org

06.02.2019 16:03, Sowjanya Komatineni пишет:
>> BTW, I'm seeing "atmel_mxt_ts 0-004c: Warning: Info CRC error - device=0xF436DC file=0x000000" whithout making any modifications to the original patch as well and it shall not happen, hence there is bug somewhere. Probably FIFO triggers are still not set up correctly... ?
>>
>>
> In snippet you sent, I see you are forcing dma_burst to 1 always which is what set for fifo trigger levels as well and also you are forcing dma all the time.
> So always it will be 1 word dma burst and 1 word trigger level and that should not be an issue.
> 

I reverted that snippet, this log is collected with the yours original patch.

^ permalink raw reply	[flat|nested] 35+ messages in thread

* Re: [PATCH V12 3/5] i2c: tegra: Add DMA support
  2019-02-06 12:49     ` Sowjanya Komatineni
@ 2019-02-06 13:06       ` Dmitry Osipenko
  0 siblings, 0 replies; 35+ messages in thread
From: Dmitry Osipenko @ 2019-02-06 13:06 UTC (permalink / raw)
  To: Sowjanya Komatineni, thierry.reding@gmail.com, Jonathan Hunter,
	Mantravadi Karthik, Shardar Mohammed, Timo Alho
  Cc: linux-tegra@vger.kernel.org, linux-kernel@vger.kernel.org,
	linux-i2c@vger.kernel.org

06.02.2019 15:49, Sowjanya Komatineni пишет:
> 
>> 		TEGRA_I2C_TIMEOUT);
>>>  	tegra_i2c_mask_irq(i2c_dev, int_mask); @@ -814,6 +1133,7 @@ static 
>>> int tegra_i2c_xfer_msg(struct tegra_i2c_dev *i2c_dev,
>>>  		time_left, completion_done(&i2c_dev->msg_complete),
>>>  		i2c_dev->msg_err);
>>>  
>>> +	i2c_dev->is_curr_dma_xfer = false;
>>
>> This line could be removed because there is no need to clear "is_curr_dma_xfer" at this point.
>>
> 
> It is needed because in case of ARB_LOST, we terminate dmaengine and then we perform bus clear operation. 
> On bus clear done interrupt, it again goes thru I2C error section to mask all interrupts and when curr_dma_xfer is true it does dmaengine terminate again so setting curr_dma_xfer as false when transfer in dma mode is done.

Ah, okay. Thank you for the clarification.

>>
>>
>> Sowjanya, I tried to enforce DMA transferring + setting DMA burst to a one word and this combination doesn't work well while it should, if I'm not missing something. Could >you please take a look at the problem or explain why that happens?
>>
>>
>> [    1.017496] tegra-i2c 7000c000.i2c: starting DMA for length: 120
>> [    1.017504] tegra-i2c 7000c000.i2c: unmasked irq: 0c
>> [    1.020896] tegra-i2c 7000c000.i2c: transfer complete: 11 0 0
>> [    1.020909] tegra-i2c 7000c000.i2c: starting DMA for length: 16
>> [    1.020918] tegra-i2c 7000c000.i2c: unmasked irq: 0c
>> [    1.021055] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
>> [    1.032230] tegra-i2c 7000c000.i2c: starting DMA for length: 16
>> [    1.032239] tegra-i2c 7000c000.i2c: unmasked irq: 0c
>> [    1.032359] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
>> [    1.032368] tegra-i2c 7000c000.i2c: starting DMA for length: 12
>> [    1.032376] tegra-i2c 7000c000.i2c: unmasked irq: 0c
>> [    1.032704] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
>> [    1.049224] tegra-i2c 7000d000.i2c: i2c transfer timed out
>>
>>
> I don’t see any issue with dma burst of 1 word irrespective of transfers in always dma mode.
> One strange thing is in your above log, for last transaction after transfer complete, there is i2c transfer timed which doesn’t make sense.
> If transfer timeout happens, it returns from i2c transfer but shouldn’t go thru transfer complete

For now I don't have any good ideas about what is wrong, will take a closer look.

>> I'm now also wondering whether that putting packet_header into the dma_buf is really needed at all.. Isn't possible to push packet_header using PIO regardless of whether > the rest of the transfer will be in DMA or PIO modes?
>>
>> Actually I tried to always push packet_header using PIO and apparently DMA works just fine with that:
>>
> Ofcourse it will work using PIO for packet header and dma only for data bytes. But packet header is just 12 bytes so why not we transfer it along with data together thru dma.
> 

Okay!

^ permalink raw reply	[flat|nested] 35+ messages in thread

* Re: [PATCH V12 3/5] i2c: tegra: Add DMA support
  2019-02-06 11:55   ` Dmitry Osipenko
  2019-02-06 12:49     ` Sowjanya Komatineni
  2019-02-06 12:59     ` Dmitry Osipenko
@ 2019-02-06 13:09     ` Thierry Reding
  2019-02-06 13:13       ` Thierry Reding
  2 siblings, 1 reply; 35+ messages in thread
From: Thierry Reding @ 2019-02-06 13:09 UTC (permalink / raw)
  To: Dmitry Osipenko
  Cc: Sowjanya Komatineni, jonathanh, mkarthik, smohammed, talho,
	linux-tegra, linux-kernel, linux-i2c

[-- Attachment #1: Type: text/plain, Size: 13568 bytes --]

On Wed, Feb 06, 2019 at 02:55:01PM +0300, Dmitry Osipenko wrote:
> 06.02.2019 1:46, Sowjanya Komatineni пишет:
> > This patch adds DMA support for Tegra I2C.
> > 
> > Tegra I2C TX and RX FIFO depth is 8 words. PIO mode is used for
> > transfer size of the max FIFO depth and DMA mode is used for
> > transfer size higher than max FIFO depth to save CPU overhead.
> > 
> > PIO mode needs full intervention of CPU to fill or empty FIFO's
> > and also need to service multiple data requests interrupt for the
> > same transaction. This adds delay between data bytes of the same
> > transfer when CPU is fully loaded and some slave devices has
> > internal timeout for no bus activity and stops transaction to
> > avoid bus hang. DMA mode is helpful in such cases.
> > 
> > DMA mode is also helpful for Large transfers during downloading or
> > uploading FW over I2C to some external devices.
> > 
> > Signed-off-by: Sowjanya Komatineni <skomatineni@nvidia.com>
> > ---
> >  [V12] : Replaced dma_alloc_coherent with dma_alloc_attrs to force the allocated
> > 	 buffer to be contiguous also in physical memory as Tegra194 supports max
> > 	 64K and dma_alloc_coherent doesnt guarentee contiguous memory.
> > 	 Changed return code from EIO to EINVAL incase of failure to obtain dma
> > 	 descriptor.
> > 	 Fixed coding style check issues.	 
> >  [V11] : Replaced deprecated dmaengine_terminate_all with dmaengine_termine_async
> > 	 from non-atomic context and dmaengine_terminate_sync from atomic context.
> > 	 Fixed to program fifo trigger levels properly when transfer falls back to
> > 	 pio mode in case of dma slave configuration failure and other minor fixes.
> >  [V10] : APBDMA is replaced with GPCDMA on Tegra186 and Tegra194 designs.
> > 	 Added apbdma hw support flag to now allow Tegra186 and later use
> > 	 APBDMA driver.
> > 	 Added explicit flow control enable for DMA slave config and error handling.
> > 	 Moved releasing DMA resources to seperate function to reuse in
> > 	 multiple places.
> > 	 Updated to register tegra_i2c_driver from module level rather than subsys
> > 	 level.
> > 	 Other minor feedback
> >  [V9] :  Rebased to 5.0-rc4
> > 	 Removed dependency of APB DMA in Kconfig and added conditional check
> >  	 in I2C driver to decide on using DMA mode.
> > 	 Changed back the allocation of dma buffer during i2c probe.
> > 	 Fixed FIFO triggers depending on DMA Vs PIO.
> >  [V8] :  Moved back dma init to i2c probe, removed ALL_PACKETS_XFER_COMPLETE
> > 	 interrupt and using PACKETS_XFER_COMPLETE interrupt only and some
> > 	 other fixes
> > 	 Updated Kconfig for APB_DMA dependency
> >  [V7] :  Same as V6
> >  [V6] :  Updated for proper buffer allocation/freeing, channel release.
> > 	 Updated to use exact xfer size for syncing dma buffer.
> >  [V5] :  Same as V4
> >  [V4] :  Updated to allocate DMA buffer only when DMA mode.
> > 	 Updated to fall back to PIO mode when DMA channel request or
> > 	 buffer allocation fails.
> >  [V3] :  Updated without additional buffer allocation.
> >  [V2] :  Updated based on V1 review feedback along with code cleanup for
> > 	 proper implementation of DMA.
> > 
> > 
> >  drivers/i2c/busses/i2c-tegra.c | 413 ++++++++++++++++++++++++++++++++++++-----
> >  1 file changed, 369 insertions(+), 44 deletions(-)
> > 
> > diff --git a/drivers/i2c/busses/i2c-tegra.c b/drivers/i2c/busses/i2c-tegra.c
> > index 118b7023a0f4..77277a09e485 100644
> > --- a/drivers/i2c/busses/i2c-tegra.c
> > +++ b/drivers/i2c/busses/i2c-tegra.c
> > @@ -8,6 +8,9 @@
> >  
> >  #include <linux/clk.h>
> >  #include <linux/delay.h>
> > +#include <linux/dmaengine.h>
> > +#include <linux/dmapool.h>
> 
> We are not using DMA pools anywhere in the code, <linux/dmapool.h> isn't needed. Let's remove it.
> 
> > +#include <linux/dma-mapping.h>
> >  #include <linux/err.h>
> >  #include <linux/i2c.h>
> >  #include <linux/init.h>
> > @@ -44,6 +47,8 @@
> >  #define I2C_FIFO_CONTROL_RX_FLUSH		BIT(0)
> >  #define I2C_FIFO_CONTROL_TX_TRIG_SHIFT		5
> >  #define I2C_FIFO_CONTROL_RX_TRIG_SHIFT		2
> > +#define I2C_FIFO_CONTROL_TX_TRIG(x)		(((x) - 1) << 5)
> > +#define I2C_FIFO_CONTROL_RX_TRIG(x)		(((x) - 1) << 2)
> >  #define I2C_FIFO_STATUS				0x060
> >  #define I2C_FIFO_STATUS_TX_MASK			0xF0
> >  #define I2C_FIFO_STATUS_TX_SHIFT		4
> > @@ -125,6 +130,19 @@
> >  #define I2C_MST_FIFO_STATUS_TX_MASK		0xff0000
> >  #define I2C_MST_FIFO_STATUS_TX_SHIFT		16
> >  
> > +/* Packet header size in bytes */
> > +#define I2C_PACKET_HEADER_SIZE			12
> > +
> > +#define DATA_DMA_DIR_TX				BIT(0)
> > +#define DATA_DMA_DIR_RX				BIT(1)
> 
> The DATA_DMA_DIR_TX/RX are not used anywhere in the code, let's remove them.
> 
> [snip]
> 
> 		TEGRA_I2C_TIMEOUT);
> >  	tegra_i2c_mask_irq(i2c_dev, int_mask);
> > @@ -814,6 +1133,7 @@ static int tegra_i2c_xfer_msg(struct tegra_i2c_dev *i2c_dev,
> >  		time_left, completion_done(&i2c_dev->msg_complete),
> >  		i2c_dev->msg_err);
> >  
> > +	i2c_dev->is_curr_dma_xfer = false;
> 
> This line could be removed because there is no need to clear "is_curr_dma_xfer" at this point.
> 
> >  	if (likely(i2c_dev->msg_err == I2C_ERR_NONE))
> >  		return 0;
> [snip]
> 
> 
> Sowjanya, I tried to enforce DMA transferring + setting DMA burst to a one word and this combination doesn't work well while it should, if I'm not missing something. Could you please take a look at the problem or explain why that happens?
> 
> Here is the change I made:
> 
> -----------------
> diff --git a/drivers/i2c/busses/i2c-tegra.c b/drivers/i2c/busses/i2c-tegra.c
> index c538ed5f8e2c..59e245d4417d 100644
> --- a/drivers/i2c/busses/i2c-tegra.c
> +++ b/drivers/i2c/busses/i2c-tegra.c
> @@ -6,6 +6,8 @@
>   * Author: Colin Cross <ccross@android.com>
>   */
>  
> +#define DEBUG
> +
>  #include <linux/clk.h>
>  #include <linux/delay.h>
>  #include <linux/dmaengine.h>
> @@ -929,12 +931,7 @@ static void tegra_i2c_config_fifo_trig(struct tegra_i2c_dev *i2c_dev,
>         val = i2c_readl(i2c_dev, reg);
>  
>         if (i2c_dev->is_curr_dma_xfer) {
> -               if (len & 0xF)
>                         dma_burst = 1;
> -               else if (len & 0x10)
> -                       dma_burst = 4;
> -               else
> -                       dma_burst = 8;
>  
>                 if (i2c_dev->msg_read) {
>                         chan = i2c_dev->rx_dma_chan;
> @@ -1046,8 +1043,7 @@ static int tegra_i2c_xfer_msg(struct tegra_i2c_dev *i2c_dev,
>                 xfer_size = msg->len + I2C_PACKET_HEADER_SIZE;
>  
>         xfer_size = ALIGN(xfer_size, BYTES_PER_FIFO_WORD);
> -       i2c_dev->is_curr_dma_xfer = (xfer_size > I2C_PIO_MODE_MAX_LEN) &&
> -                                   i2c_dev->dma_buf;
> +       i2c_dev->is_curr_dma_xfer = !!i2c_dev->dma_buf;
>         tegra_i2c_config_fifo_trig(i2c_dev, xfer_size);
>         dma = i2c_dev->is_curr_dma_xfer
> -----------------
> 
> And here what happens:
> 
> -----------------
> ...
> [    0.761144] tegra_rtc 7000e000.rtc: registered as rtc1
> [    0.761199] tegra_rtc 7000e000.rtc: Tegra internal Real Time Clock
> [    0.761406] i2c /dev entries driver
> [    0.919233] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> [    0.919246] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    0.919345] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> [    0.919355] tegra-i2c 7000c000.i2c: starting DMA for length: 8
> [    0.919363] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    0.919628] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> [    0.919641] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> [    0.919649] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    0.919746] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> [    0.919755] tegra-i2c 7000c000.i2c: starting DMA for length: 112
> [    0.919763] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    0.923140] tegra-i2c 7000c000.i2c: transfer complete: 11 0 0
> [    0.923150] atmel_mxt_ts 0-004c: Family: 160 Variant: 0 Firmware V1.0.AA Objects: 18
> [    0.923208] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> [    0.923217] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    0.923314] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> [    0.923323] tegra-i2c 7000c000.i2c: starting DMA for length: 224
> [    0.923331] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    0.933564] tegra-i2c 7000c000.i2c: transfer complete: 11 0 0
> [    0.933599] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> [    0.933609] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    0.933760] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> [    0.933770] tegra-i2c 7000c000.i2c: starting DMA for length: 12
> [    0.933779] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    0.934284] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> [    0.934309] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> [    0.934317] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    0.934500] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> [    0.934509] tegra-i2c 7000c000.i2c: starting DMA for length: 12
> [    0.934518] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    0.935023] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> [    0.935081] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> [    0.935091] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    0.935240] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> [    0.935249] tegra-i2c 7000c000.i2c: starting DMA for length: 4
> [    0.935258] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    0.935399] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> [    0.935416] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> [    0.935424] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    0.935655] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> [    0.945445] tegra-i2c 7000d000.i2c: starting DMA for length: 16
> [    0.945456] tegra-i2c 7000d000.i2c: unmasked irq: 0c
> [    0.969236] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> [    0.969245] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    0.969361] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> [    0.969370] tegra-i2c 7000c000.i2c: starting DMA for length: 4
> [    0.969379] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    0.969462] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> [    0.982587] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> [    0.982596] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    0.982722] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> [    0.982731] tegra-i2c 7000c000.i2c: starting DMA for length: 12
> [    0.982740] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    0.983071] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> [    0.983090] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> [    0.983098] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    0.983252] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> [    0.983261] tegra-i2c 7000c000.i2c: starting DMA for length: 136
> [    0.983269] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    0.987605] tegra-i2c 7000c000.i2c: transfer complete: 11 0 0
> [    0.987623] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> [    0.987631] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    0.987800] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> [    0.987809] tegra-i2c 7000c000.i2c: starting DMA for length: 12
> [    0.987817] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    0.988324] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> [    1.009227] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> [    1.009236] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    1.009374] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> [    1.009383] tegra-i2c 7000c000.i2c: starting DMA for length: 4
> [    1.009391] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    1.009479] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> [    1.009497] atmel_mxt_ts 0-004c: Warning: Info CRC error - device=0xF436DC file=0x000000
> [    1.009588] tegra-i2c 7000c000.i2c: starting DMA for length: 272
> [    1.009597] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    1.017483] tegra-i2c 7000c000.i2c: transfer complete: 11 0 0
> [    1.017496] tegra-i2c 7000c000.i2c: starting DMA for length: 120
> [    1.017504] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    1.020896] tegra-i2c 7000c000.i2c: transfer complete: 11 0 0
> [    1.020909] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> [    1.020918] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    1.021055] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> [    1.032230] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> [    1.032239] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    1.032359] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> [    1.032368] tegra-i2c 7000c000.i2c: starting DMA for length: 12
> [    1.032376] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    1.032704] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> [    1.049224] tegra-i2c 7000d000.i2c: i2c transfer timed out

That's odd because it suggests that DMA actually completed, but the
message didn't.

I'm not sure I understand how that could happen.

What's also weird above is that there doesn't seem to be a DMA that
is started for that particular message. Or is the timeout message a
response to the prior transfer (length 10)? Seems like that should
not be possible because we get the "transfer complete" message.

Thierry

[-- Attachment #2: signature.asc --]
[-- Type: application/pgp-signature, Size: 833 bytes --]

^ permalink raw reply	[flat|nested] 35+ messages in thread

* Re: [PATCH V12 3/5] i2c: tegra: Add DMA support
  2019-02-06 13:09     ` Thierry Reding
@ 2019-02-06 13:13       ` Thierry Reding
  2019-02-06 13:18         ` Dmitry Osipenko
  0 siblings, 1 reply; 35+ messages in thread
From: Thierry Reding @ 2019-02-06 13:13 UTC (permalink / raw)
  To: Dmitry Osipenko
  Cc: Sowjanya Komatineni, jonathanh, mkarthik, smohammed, talho,
	linux-tegra, linux-kernel, linux-i2c

[-- Attachment #1: Type: text/plain, Size: 9133 bytes --]

On Wed, Feb 06, 2019 at 02:09:09PM +0100, Thierry Reding wrote:
> On Wed, Feb 06, 2019 at 02:55:01PM +0300, Dmitry Osipenko wrote:
[...]
> > Sowjanya, I tried to enforce DMA transferring + setting DMA burst to a one word and this combination doesn't work well while it should, if I'm not missing something. Could you please take a look at the problem or explain why that happens?
> > 
> > Here is the change I made:
> > 
> > -----------------
> > diff --git a/drivers/i2c/busses/i2c-tegra.c b/drivers/i2c/busses/i2c-tegra.c
> > index c538ed5f8e2c..59e245d4417d 100644
> > --- a/drivers/i2c/busses/i2c-tegra.c
> > +++ b/drivers/i2c/busses/i2c-tegra.c
> > @@ -6,6 +6,8 @@
> >   * Author: Colin Cross <ccross@android.com>
> >   */
> >  
> > +#define DEBUG
> > +
> >  #include <linux/clk.h>
> >  #include <linux/delay.h>
> >  #include <linux/dmaengine.h>
> > @@ -929,12 +931,7 @@ static void tegra_i2c_config_fifo_trig(struct tegra_i2c_dev *i2c_dev,
> >         val = i2c_readl(i2c_dev, reg);
> >  
> >         if (i2c_dev->is_curr_dma_xfer) {
> > -               if (len & 0xF)
> >                         dma_burst = 1;
> > -               else if (len & 0x10)
> > -                       dma_burst = 4;
> > -               else
> > -                       dma_burst = 8;
> >  
> >                 if (i2c_dev->msg_read) {
> >                         chan = i2c_dev->rx_dma_chan;
> > @@ -1046,8 +1043,7 @@ static int tegra_i2c_xfer_msg(struct tegra_i2c_dev *i2c_dev,
> >                 xfer_size = msg->len + I2C_PACKET_HEADER_SIZE;
> >  
> >         xfer_size = ALIGN(xfer_size, BYTES_PER_FIFO_WORD);
> > -       i2c_dev->is_curr_dma_xfer = (xfer_size > I2C_PIO_MODE_MAX_LEN) &&
> > -                                   i2c_dev->dma_buf;
> > +       i2c_dev->is_curr_dma_xfer = !!i2c_dev->dma_buf;
> >         tegra_i2c_config_fifo_trig(i2c_dev, xfer_size);
> >         dma = i2c_dev->is_curr_dma_xfer
> > -----------------
> > 
> > And here what happens:
> > 
> > -----------------
> > ...
> > [    0.761144] tegra_rtc 7000e000.rtc: registered as rtc1
> > [    0.761199] tegra_rtc 7000e000.rtc: Tegra internal Real Time Clock
> > [    0.761406] i2c /dev entries driver
> > [    0.919233] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> > [    0.919246] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> > [    0.919345] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> > [    0.919355] tegra-i2c 7000c000.i2c: starting DMA for length: 8
> > [    0.919363] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> > [    0.919628] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> > [    0.919641] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> > [    0.919649] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> > [    0.919746] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> > [    0.919755] tegra-i2c 7000c000.i2c: starting DMA for length: 112
> > [    0.919763] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> > [    0.923140] tegra-i2c 7000c000.i2c: transfer complete: 11 0 0
> > [    0.923150] atmel_mxt_ts 0-004c: Family: 160 Variant: 0 Firmware V1.0.AA Objects: 18
> > [    0.923208] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> > [    0.923217] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> > [    0.923314] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> > [    0.923323] tegra-i2c 7000c000.i2c: starting DMA for length: 224
> > [    0.923331] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> > [    0.933564] tegra-i2c 7000c000.i2c: transfer complete: 11 0 0
> > [    0.933599] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> > [    0.933609] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> > [    0.933760] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> > [    0.933770] tegra-i2c 7000c000.i2c: starting DMA for length: 12
> > [    0.933779] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> > [    0.934284] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> > [    0.934309] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> > [    0.934317] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> > [    0.934500] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> > [    0.934509] tegra-i2c 7000c000.i2c: starting DMA for length: 12
> > [    0.934518] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> > [    0.935023] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> > [    0.935081] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> > [    0.935091] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> > [    0.935240] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> > [    0.935249] tegra-i2c 7000c000.i2c: starting DMA for length: 4
> > [    0.935258] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> > [    0.935399] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> > [    0.935416] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> > [    0.935424] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> > [    0.935655] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> > [    0.945445] tegra-i2c 7000d000.i2c: starting DMA for length: 16
> > [    0.945456] tegra-i2c 7000d000.i2c: unmasked irq: 0c
> > [    0.969236] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> > [    0.969245] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> > [    0.969361] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> > [    0.969370] tegra-i2c 7000c000.i2c: starting DMA for length: 4
> > [    0.969379] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> > [    0.969462] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> > [    0.982587] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> > [    0.982596] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> > [    0.982722] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> > [    0.982731] tegra-i2c 7000c000.i2c: starting DMA for length: 12
> > [    0.982740] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> > [    0.983071] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> > [    0.983090] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> > [    0.983098] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> > [    0.983252] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> > [    0.983261] tegra-i2c 7000c000.i2c: starting DMA for length: 136
> > [    0.983269] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> > [    0.987605] tegra-i2c 7000c000.i2c: transfer complete: 11 0 0
> > [    0.987623] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> > [    0.987631] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> > [    0.987800] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> > [    0.987809] tegra-i2c 7000c000.i2c: starting DMA for length: 12
> > [    0.987817] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> > [    0.988324] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> > [    1.009227] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> > [    1.009236] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> > [    1.009374] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> > [    1.009383] tegra-i2c 7000c000.i2c: starting DMA for length: 4
> > [    1.009391] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> > [    1.009479] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> > [    1.009497] atmel_mxt_ts 0-004c: Warning: Info CRC error - device=0xF436DC file=0x000000
> > [    1.009588] tegra-i2c 7000c000.i2c: starting DMA for length: 272
> > [    1.009597] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> > [    1.017483] tegra-i2c 7000c000.i2c: transfer complete: 11 0 0
> > [    1.017496] tegra-i2c 7000c000.i2c: starting DMA for length: 120
> > [    1.017504] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> > [    1.020896] tegra-i2c 7000c000.i2c: transfer complete: 11 0 0
> > [    1.020909] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> > [    1.020918] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> > [    1.021055] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> > [    1.032230] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> > [    1.032239] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> > [    1.032359] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> > [    1.032368] tegra-i2c 7000c000.i2c: starting DMA for length: 12
> > [    1.032376] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> > [    1.032704] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> > [    1.049224] tegra-i2c 7000d000.i2c: i2c transfer timed out
> 
> That's odd because it suggests that DMA actually completed, but the
> message didn't.
> 
> I'm not sure I understand how that could happen.
> 
> What's also weird above is that there doesn't seem to be a DMA that
> is started for that particular message. Or is the timeout message a
> response to the prior transfer (length 10)? Seems like that should
> not be possible because we get the "transfer complete" message.

Wait, those are actually different instances of the I2C controller, so
the relevant log entries are these:

	[    0.945445] tegra-i2c 7000d000.i2c: starting DMA for length: 16
	[    0.945456] tegra-i2c 7000d000.i2c: unmasked irq: 0c
	...
	[    1.049224] tegra-i2c 7000d000.i2c: i2c transfer timed out

And these don't happen if you use higher burst sizes or before the DMA
series?

Thierry

[-- Attachment #2: signature.asc --]
[-- Type: application/pgp-signature, Size: 833 bytes --]

^ permalink raw reply	[flat|nested] 35+ messages in thread

* RE: [PATCH V12 3/5] i2c: tegra: Add DMA support
  2019-02-06 13:05         ` Dmitry Osipenko
@ 2019-02-06 13:17           ` Sowjanya Komatineni
  2019-02-06 13:23             ` Dmitry Osipenko
  0 siblings, 1 reply; 35+ messages in thread
From: Sowjanya Komatineni @ 2019-02-06 13:17 UTC (permalink / raw)
  To: Dmitry Osipenko, thierry.reding@gmail.com, Jonathan Hunter,
	Mantravadi Karthik, Shardar Mohammed, Timo Alho
  Cc: linux-tegra@vger.kernel.org, linux-kernel@vger.kernel.org,
	linux-i2c@vger.kernel.org



> >> BTW, I'm seeing "atmel_mxt_ts 0-004c: Warning: Info CRC error - device=0xF436DC file=0x000000" whithout making any modifications to the original patch as well and it shall not happen, hence there is bug somewhere. Probably FIFO triggers are still not set up correctly... ?
> >>
> >>
> > In snippet you sent, I see you are forcing dma_burst to 1 always which is what set for fifo trigger levels as well and also you are forcing dma all the time.
> > So always it will be 1 word dma burst and 1 word trigger level and that should not be an issue.
> > 
>
> I reverted that snippet, this log is collected with the yours original patch.
>
From atmel driver, looks like this warning is from maxt_update_cfg and due to CRC mismatch and above values shows read data CRC is 0Xf436dc which is compared against info_crc of all 0's 
Info_crc is based on raw config file and somehow its all 0's. this is not based on data read thru i2c. 
data->info_crc computed on data read is 0Xf436dc

This warning is not related to I2C transfer

^ permalink raw reply	[flat|nested] 35+ messages in thread

* Re: [PATCH V12 3/5] i2c: tegra: Add DMA support
  2019-02-06 13:13       ` Thierry Reding
@ 2019-02-06 13:18         ` Dmitry Osipenko
  2019-02-06 13:25           ` Sowjanya Komatineni
  0 siblings, 1 reply; 35+ messages in thread
From: Dmitry Osipenko @ 2019-02-06 13:18 UTC (permalink / raw)
  To: Thierry Reding
  Cc: Sowjanya Komatineni, jonathanh, mkarthik, smohammed, talho,
	linux-tegra, linux-kernel, linux-i2c

06.02.2019 16:13, Thierry Reding пишет:

[snip]

>> That's odd because it suggests that DMA actually completed, but the
>> message didn't.
>>
>> I'm not sure I understand how that could happen.
>>
>> What's also weird above is that there doesn't seem to be a DMA that
>> is started for that particular message. Or is the timeout message a
>> response to the prior transfer (length 10)? Seems like that should
>> not be possible because we get the "transfer complete" message.
> 
> Wait, those are actually different instances of the I2C controller, so
> the relevant log entries are these:
> 
> 	[    0.945445] tegra-i2c 7000d000.i2c: starting DMA for length: 16
> 	[    0.945456] tegra-i2c 7000d000.i2c: unmasked irq: 0c
> 	...
> 	[    1.049224] tegra-i2c 7000d000.i2c: i2c transfer timed out
> 
> And these don't happen if you use higher burst sizes or before the DMA
> series?

I tried to enforce DMA without changing bursts:

----------
diff --git a/drivers/i2c/busses/i2c-tegra.c b/drivers/i2c/busses/i2c-tegra.c
index c538ed5f8e2c..5d1c54ce7800 100644
--- a/drivers/i2c/busses/i2c-tegra.c
+++ b/drivers/i2c/busses/i2c-tegra.c
@@ -6,6 +6,8 @@
  * Author: Colin Cross <ccross@android.com>
  */
 
+#define DEBUG
+
 #include <linux/clk.h>
 #include <linux/delay.h>
 #include <linux/dmaengine.h>
@@ -1046,8 +1048,7 @@ static int tegra_i2c_xfer_msg(struct tegra_i2c_dev *i2c_dev,
                xfer_size = msg->len + I2C_PACKET_HEADER_SIZE;
 
        xfer_size = ALIGN(xfer_size, BYTES_PER_FIFO_WORD);
-       i2c_dev->is_curr_dma_xfer = (xfer_size > I2C_PIO_MODE_MAX_LEN) &&
-                                   i2c_dev->dma_buf;
+       i2c_dev->is_curr_dma_xfer = !!i2c_dev->dma_buf;
        tegra_i2c_config_fifo_trig(i2c_dev, xfer_size);
        dma = i2c_dev->is_curr_dma_xfer;
----------

Here is the log with this change:

[    0.760796] tegra_rtc 7000e000.rtc: registered as rtc1
[    0.760850] tegra_rtc 7000e000.rtc: Tegra internal Real Time Clock
[    0.761050] i2c /dev entries driver
[    0.918928] tegra-i2c 7000c000.i2c: starting DMA for length: 16
[    0.918940] tegra-i2c 7000c000.i2c: unmasked irq: 0c
[    0.919040] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
[    0.919050] tegra-i2c 7000c000.i2c: starting DMA for length: 8
[    0.919059] tegra-i2c 7000c000.i2c: unmasked irq: 0c
[    0.919322] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
[    0.919335] tegra-i2c 7000c000.i2c: starting DMA for length: 16
[    0.919343] tegra-i2c 7000c000.i2c: unmasked irq: 0c
[    0.919440] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
[    0.919448] tegra-i2c 7000c000.i2c: starting DMA for length: 112
[    0.919456] tegra-i2c 7000c000.i2c: unmasked irq: 0c
[    0.922818] tegra-i2c 7000c000.i2c: transfer complete: 11 0 0
[    0.922829] atmel_mxt_ts 0-004c: Family: 160 Variant: 0 Firmware V1.0.AA Objects: 18
[    0.922886] tegra-i2c 7000c000.i2c: starting DMA for length: 16
[    0.922895] tegra-i2c 7000c000.i2c: unmasked irq: 0c
[    0.922993] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
[    0.923002] tegra-i2c 7000c000.i2c: starting DMA for length: 224
[    0.923011] tegra-i2c 7000c000.i2c: unmasked irq: 0c
[    0.933253] tegra-i2c 7000c000.i2c: transfer complete: 11 0 0
[    0.933287] tegra-i2c 7000c000.i2c: starting DMA for length: 16
[    0.933297] tegra-i2c 7000c000.i2c: unmasked irq: 0c
[    0.933478] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
[    0.933487] tegra-i2c 7000c000.i2c: starting DMA for length: 12
[    0.933496] tegra-i2c 7000c000.i2c: unmasked irq: 0c
[    0.945120] tegra-i2c 7000d000.i2c: starting DMA for length: 16
[    0.945130] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    1.038917] tegra-i2c 7000c000.i2c: DMA transfer timeout
[    1.038982] atmel_mxt_ts 0-004c: __mxt_read_reg: i2c transfer failed (-110)
[    1.039000] tegra-i2c 7000c000.i2c: starting DMA for length: 16
[    1.039006] atmel_mxt_ts 0-004c: Failed to read T44 and T5 (-110)
[    1.039009] tegra-i2c 7000c000.i2c: unmasked irq: 0c
[    1.039148] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
[    1.039157] tegra-i2c 7000c000.i2c: starting DMA for length: 4
[    1.039166] tegra-i2c 7000c000.i2c: unmasked irq: 0c
[    1.039304] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
[    1.039340] tegra-i2c 7000c000.i2c: starting DMA for length: 16
[    1.039349] tegra-i2c 7000c000.i2c: unmasked irq: 0c
[    1.039535] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
[    1.039544] tegra-i2c 7000c000.i2c: starting DMA for length: 12
[    1.039552] tegra-i2c 7000c000.i2c: unmasked irq: 0c
[    1.040055] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
[    1.040083] tegra-i2c 7000c000.i2c: starting DMA for length: 16
[    1.040092] tegra-i2c 7000c000.i2c: unmasked irq: 0c
[    1.040301] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
[    1.048934] tegra-i2c 7000d000.i2c: i2c transfer timed out

^ permalink raw reply related	[flat|nested] 35+ messages in thread

* Re: [PATCH V12 3/5] i2c: tegra: Add DMA support
  2019-02-06 13:17           ` Sowjanya Komatineni
@ 2019-02-06 13:23             ` Dmitry Osipenko
  2019-02-06 13:29               ` Sowjanya Komatineni
  0 siblings, 1 reply; 35+ messages in thread
From: Dmitry Osipenko @ 2019-02-06 13:23 UTC (permalink / raw)
  To: Sowjanya Komatineni, thierry.reding@gmail.com, Jonathan Hunter,
	Mantravadi Karthik, Shardar Mohammed, Timo Alho
  Cc: linux-tegra@vger.kernel.org, linux-kernel@vger.kernel.org,
	linux-i2c@vger.kernel.org

06.02.2019 16:17, Sowjanya Komatineni пишет:
> 
> 
>>>> BTW, I'm seeing "atmel_mxt_ts 0-004c: Warning: Info CRC error - device=0xF436DC file=0x000000" whithout making any modifications to the original patch as well and it shall not happen, hence there is bug somewhere. Probably FIFO triggers are still not set up correctly... ?
>>>>
>>>>
>>> In snippet you sent, I see you are forcing dma_burst to 1 always which is what set for fifo trigger levels as well and also you are forcing dma all the time.
>>> So always it will be 1 word dma burst and 1 word trigger level and that should not be an issue.
>>>
>>
>> I reverted that snippet, this log is collected with the yours original patch.
>>
> From atmel driver, looks like this warning is from maxt_update_cfg and due to CRC mismatch and above values shows read data CRC is 0Xf436dc which is compared against info_crc of all 0's 
> Info_crc is based on raw config file and somehow its all 0's. this is not based on data read thru i2c. 
> data->info_crc computed on data read is 0Xf436dc
> 
> This warning is not related to I2C transfer
> 

It doesn't happen with the I2C PIO mode. Seems it means that the I2C reads out the 0xF436DC value instead of 0x000000.. if I'm not missing anything.

^ permalink raw reply	[flat|nested] 35+ messages in thread

* RE: [PATCH V12 3/5] i2c: tegra: Add DMA support
  2019-02-06 13:18         ` Dmitry Osipenko
@ 2019-02-06 13:25           ` Sowjanya Komatineni
  2019-02-06 13:42             ` Dmitry Osipenko
  0 siblings, 1 reply; 35+ messages in thread
From: Sowjanya Komatineni @ 2019-02-06 13:25 UTC (permalink / raw)
  To: Dmitry Osipenko, Thierry Reding
  Cc: Jonathan Hunter, Mantravadi Karthik, Shardar Mohammed, Timo Alho,
	linux-tegra@vger.kernel.org, linux-kernel@vger.kernel.org,
	linux-i2c@vger.kernel.org



> >> That's odd because it suggests that DMA actually completed, but the 
> >> message didn't.
> >>
> >> I'm not sure I understand how that could happen.
> >>
> >> What's also weird above is that there doesn't seem to be a DMA that 
> >> is started for that particular message. Or is the timeout message a 
> >> response to the prior transfer (length 10)? Seems like that should 
> >> not be possible because we get the "transfer complete" message.
> > 
> > Wait, those are actually different instances of the I2C controller, so 
> > the relevant log entries are these:
> > 
> > 	[    0.945445] tegra-i2c 7000d000.i2c: starting DMA for length: 16
> > 	[    0.945456] tegra-i2c 7000d000.i2c: unmasked irq: 0c
> > 	...
> > 	[    1.049224] tegra-i2c 7000d000.i2c: i2c transfer timed out
> > 
> > And these don't happen if you use higher burst sizes or before the DMA 
> > series?
>
> I tried to enforce DMA without changing bursts:
>
> ----------
> diff --git a/drivers/i2c/busses/i2c-tegra.c b/drivers/i2c/busses/i2c-tegra.c index c538ed5f8e2c..5d1c54ce7800 100644
> --- a/drivers/i2c/busses/i2c-tegra.c
> +++ b/drivers/i2c/busses/i2c-tegra.c
> @@ -6,6 +6,8 @@
>   * Author: Colin Cross <ccross@android.com>
>   */
>  
> +#define DEBUG
> +
>  #include <linux/clk.h>
>  #include <linux/delay.h>
>  #include <linux/dmaengine.h>
> @@ -1046,8 +1048,7 @@ static int tegra_i2c_xfer_msg(struct tegra_i2c_dev *i2c_dev,
>                 xfer_size = msg->len + I2C_PACKET_HEADER_SIZE;
>  
>         xfer_size = ALIGN(xfer_size, BYTES_PER_FIFO_WORD);
> -       i2c_dev->is_curr_dma_xfer = (xfer_size > I2C_PIO_MODE_MAX_LEN) &&
> -                                   i2c_dev->dma_buf;
> +       i2c_dev->is_curr_dma_xfer = !!i2c_dev->dma_buf;
>         tegra_i2c_config_fifo_trig(i2c_dev, xfer_size);
>         dma = i2c_dev->is_curr_dma_xfer;
> ----------
>
> Here is the log with this change:
>
> [    0.760796] tegra_rtc 7000e000.rtc: registered as rtc1
> [    0.760850] tegra_rtc 7000e000.rtc: Tegra internal Real Time Clock
> [    0.761050] i2c /dev entries driver
> [    0.918928] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> [    0.918940] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    0.919040] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> [    0.919050] tegra-i2c 7000c000.i2c: starting DMA for length: 8
> [    0.919059] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    0.919322] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> [    0.919335] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> [    0.919343] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    0.919440] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> [    0.919448] tegra-i2c 7000c000.i2c: starting DMA for length: 112
> [    0.919456] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    0.922818] tegra-i2c 7000c000.i2c: transfer complete: 11 0 0
> [    0.922829] atmel_mxt_ts 0-004c: Family: 160 Variant: 0 Firmware V1.0.AA Objects: 18
> [    0.922886] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> [    0.922895] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    0.922993] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> [    0.923002] tegra-i2c 7000c000.i2c: starting DMA for length: 224
> [    0.923011] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    0.933253] tegra-i2c 7000c000.i2c: transfer complete: 11 0 0
> [    0.933287] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> [    0.933297] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    0.933478] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> [    0.933487] tegra-i2c 7000c000.i2c: starting DMA for length: 12
> [    0.933496] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    0.945120] tegra-i2c 7000d000.i2c: starting DMA for length: 16
> [    0.945130] tegra-i2c 7000d000.i2c: unmasked irq: 0c
> [    1.038917] tegra-i2c 7000c000.i2c: DMA transfer timeout
> [    1.038982] atmel_mxt_ts 0-004c: __mxt_read_reg: i2c transfer failed (-110)
> [    1.039000] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> [    1.039006] atmel_mxt_ts 0-004c: Failed to read T44 and T5 (-110)
> [    1.039009] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    1.039148] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> [    1.039157] tegra-i2c 7000c000.i2c: starting DMA for length: 4
> [    1.039166] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    1.039304] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> [    1.039340] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> [    1.039349] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    1.039535] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> [    1.039544] tegra-i2c 7000c000.i2c: starting DMA for length: 12
> [    1.039552] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    1.040055] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> [    1.040083] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> [    1.040092] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> [    1.040301] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> [    1.048934] tegra-i2c 7000d000.i2c: i2c transfer timed out

This log shows DMA transfer timeout for atmel read.
Do you see issue if you don’t enforce dma all time and let it choose PIO Vs DMA?

^ permalink raw reply	[flat|nested] 35+ messages in thread

* RE: [PATCH V12 3/5] i2c: tegra: Add DMA support
  2019-02-06 13:23             ` Dmitry Osipenko
@ 2019-02-06 13:29               ` Sowjanya Komatineni
  2019-02-06 13:30                 ` Sowjanya Komatineni
  0 siblings, 1 reply; 35+ messages in thread
From: Sowjanya Komatineni @ 2019-02-06 13:29 UTC (permalink / raw)
  To: Dmitry Osipenko, thierry.reding@gmail.com, Jonathan Hunter,
	Mantravadi Karthik, Shardar Mohammed, Timo Alho
  Cc: linux-tegra@vger.kernel.org, linux-kernel@vger.kernel.org,
	linux-i2c@vger.kernel.org


> > 
> >>>> BTW, I'm seeing "atmel_mxt_ts 0-004c: Warning: Info CRC error - device=0xF436DC file=0x000000" whithout making any modifications to the original patch as well and it shall not happen, hence there is bug somewhere. Probably FIFO triggers are still not set up correctly... ?
> >>>>
> >>>>
> >>> In snippet you sent, I see you are forcing dma_burst to 1 always which is what set for fifo trigger levels as well and also you are forcing dma all the time.
> >>> So always it will be 1 word dma burst and 1 word trigger level and that should not be an issue.
> >>>
> >>
> >> I reverted that snippet, this log is collected with the yours original patch.
> >>
> > From atmel driver, looks like this warning is from maxt_update_cfg and 
> > due to CRC mismatch and above values shows read data CRC is 0Xf436dc which is compared against info_crc of all 0's Info_crc is based on raw config file and somehow its all 0's. this is not based on data read thru i2c.
> > data->info_crc computed on data read is 0Xf436dc
> > 
> > This warning is not related to I2C transfer
> > 
>
> It doesn't happen with the I2C PIO mode. Seems it means that the I2C reads out the 0xF436DC value instead of 0x000000.. if I'm not missing anything.
>
Log that you shared this warning, doesn’t show any i2c failures with atmel and CRC based on i2c read  data is 0Xf436dc.
During this log, there are not DMA timeouts associated during this warning timeframe. So i2c read data is thru DMA which is non-zero.

^ permalink raw reply	[flat|nested] 35+ messages in thread

* RE: [PATCH V12 3/5] i2c: tegra: Add DMA support
  2019-02-06 13:29               ` Sowjanya Komatineni
@ 2019-02-06 13:30                 ` Sowjanya Komatineni
  2019-02-06 13:34                   ` Dmitry Osipenko
  0 siblings, 1 reply; 35+ messages in thread
From: Sowjanya Komatineni @ 2019-02-06 13:30 UTC (permalink / raw)
  To: Dmitry Osipenko, thierry.reding@gmail.com, Jonathan Hunter,
	Mantravadi Karthik, Shardar Mohammed, Timo Alho
  Cc: linux-tegra@vger.kernel.org, linux-kernel@vger.kernel.org,
	linux-i2c@vger.kernel.org



> > 
> >>>> BTW, I'm seeing "atmel_mxt_ts 0-004c: Warning: Info CRC error - device=0xF436DC file=0x000000" whithout making any modifications to the original patch as well and it shall not happen, hence there is bug somewhere. Probably FIFO triggers are still not set up correctly... ?
> >>>>
> >>>>
> >>> In snippet you sent, I see you are forcing dma_burst to 1 always which is what set for fifo trigger levels as well and also you are forcing dma all the time.
> >>> So always it will be 1 word dma burst and 1 word trigger level and that should not be an issue.
> >>>
> >>
> >> I reverted that snippet, this log is collected with the yours original patch.
> >>
> > From atmel driver, looks like this warning is from maxt_update_cfg 
> > and due to CRC mismatch and above values shows read data CRC is 0Xf436dc which is compared against info_crc of all 0's Info_crc is based on raw config file and somehow its all 0's. this is not based on data read thru i2c.
> > data->info_crc computed on data read is 0Xf436dc
> > 
> > This warning is not related to I2C transfer
> > 
>
> It doesn't happen with the I2C PIO mode. Seems it means that the I2C reads out the 0xF436DC value instead of 0x000000.. if I'm not missing anything.
>
Log that you shared this warning, doesn’t show any i2c failures with atmel and CRC based on i2c read  data is 0Xf436dc.
During this log, there are not DMA timeouts associated during this warning timeframe. So i2c read data is thru DMA which is non-zero.

Do you see DMA timeouts associated with this warning? I meant any DMA or I2C timeout during that time frame of warning?

^ permalink raw reply	[flat|nested] 35+ messages in thread

* Re: [PATCH V12 3/5] i2c: tegra: Add DMA support
  2019-02-06 13:30                 ` Sowjanya Komatineni
@ 2019-02-06 13:34                   ` Dmitry Osipenko
  2019-02-06 13:40                     ` Dmitry Osipenko
  0 siblings, 1 reply; 35+ messages in thread
From: Dmitry Osipenko @ 2019-02-06 13:34 UTC (permalink / raw)
  To: Sowjanya Komatineni, thierry.reding@gmail.com, Jonathan Hunter,
	Mantravadi Karthik, Shardar Mohammed, Timo Alho
  Cc: linux-tegra@vger.kernel.org, linux-kernel@vger.kernel.org,
	linux-i2c@vger.kernel.org

06.02.2019 16:30, Sowjanya Komatineni пишет:
> 
> 
>>>
>>>>>> BTW, I'm seeing "atmel_mxt_ts 0-004c: Warning: Info CRC error - device=0xF436DC file=0x000000" whithout making any modifications to the original patch as well and it shall not happen, hence there is bug somewhere. Probably FIFO triggers are still not set up correctly... ?
>>>>>>
>>>>>>
>>>>> In snippet you sent, I see you are forcing dma_burst to 1 always which is what set for fifo trigger levels as well and also you are forcing dma all the time.
>>>>> So always it will be 1 word dma burst and 1 word trigger level and that should not be an issue.
>>>>>
>>>>
>>>> I reverted that snippet, this log is collected with the yours original patch.
>>>>
>>> From atmel driver, looks like this warning is from maxt_update_cfg 
>>> and due to CRC mismatch and above values shows read data CRC is 0Xf436dc which is compared against info_crc of all 0's Info_crc is based on raw config file and somehow its all 0's. this is not based on data read thru i2c.
>>> data->info_crc computed on data read is 0Xf436dc
>>>
>>> This warning is not related to I2C transfer
>>>
>>
>> It doesn't happen with the I2C PIO mode. Seems it means that the I2C reads out the 0xF436DC value instead of 0x000000.. if I'm not missing anything.
>>
> Log that you shared this warning, doesn’t show any i2c failures with atmel and CRC based on i2c read  data is 0Xf436dc.
> During this log, there are not DMA timeouts associated during this warning timeframe. So i2c read data is thru DMA which is non-zero.
> 
> Do you see DMA timeouts associated with this warning? I meant any DMA or I2C timeout during that time frame of warning?
> 

Actually you're right, my bad. That atmel error and atmel I2C timeout (due to I2C_ERR_NO_ACK) happens in the PIO mode too, hence that part is fine.

PIO log:

[    1.028889] atmel_mxt_ts 0-004c: Warning: Info CRC error - device=0xF436DC file=0x000000
[    1.078907] atmel_mxt_ts 0-004c: Resetting device
[    1.128646] usb 1-1: new full-speed USB device number 2 using tegra-ehci
[    1.198708] atmel_mxt_ts 0-004c: __mxt_read_reg: i2c transfer failed (-121)
[    1.198732] atmel_mxt_ts 0-004c: Failed to read 28 messages (-121)

^ permalink raw reply	[flat|nested] 35+ messages in thread

* Re: [PATCH V12 3/5] i2c: tegra: Add DMA support
  2019-02-06 13:34                   ` Dmitry Osipenko
@ 2019-02-06 13:40                     ` Dmitry Osipenko
  0 siblings, 0 replies; 35+ messages in thread
From: Dmitry Osipenko @ 2019-02-06 13:40 UTC (permalink / raw)
  To: Sowjanya Komatineni, thierry.reding@gmail.com, Jonathan Hunter,
	Mantravadi Karthik, Shardar Mohammed, Timo Alho
  Cc: linux-tegra@vger.kernel.org, linux-kernel@vger.kernel.org,
	linux-i2c@vger.kernel.org

06.02.2019 16:34, Dmitry Osipenko пишет:
> 06.02.2019 16:30, Sowjanya Komatineni пишет:
>>
>>
>>>>
>>>>>>> BTW, I'm seeing "atmel_mxt_ts 0-004c: Warning: Info CRC error - device=0xF436DC file=0x000000" whithout making any modifications to the original patch as well and it shall not happen, hence there is bug somewhere. Probably FIFO triggers are still not set up correctly... ?
>>>>>>>
>>>>>>>
>>>>>> In snippet you sent, I see you are forcing dma_burst to 1 always which is what set for fifo trigger levels as well and also you are forcing dma all the time.
>>>>>> So always it will be 1 word dma burst and 1 word trigger level and that should not be an issue.
>>>>>>
>>>>>
>>>>> I reverted that snippet, this log is collected with the yours original patch.
>>>>>
>>>> From atmel driver, looks like this warning is from maxt_update_cfg 
>>>> and due to CRC mismatch and above values shows read data CRC is 0Xf436dc which is compared against info_crc of all 0's Info_crc is based on raw config file and somehow its all 0's. this is not based on data read thru i2c.
>>>> data->info_crc computed on data read is 0Xf436dc
>>>>
>>>> This warning is not related to I2C transfer
>>>>
>>>
>>> It doesn't happen with the I2C PIO mode. Seems it means that the I2C reads out the 0xF436DC value instead of 0x000000.. if I'm not missing anything.
>>>
>> Log that you shared this warning, doesn’t show any i2c failures with atmel and CRC based on i2c read  data is 0Xf436dc.
>> During this log, there are not DMA timeouts associated during this warning timeframe. So i2c read data is thru DMA which is non-zero.
>>
>> Do you see DMA timeouts associated with this warning? I meant any DMA or I2C timeout during that time frame of warning?
>>
> 
> Actually you're right, my bad. That atmel error and atmel I2C timeout (due to I2C_ERR_NO_ACK) happens in the PIO mode too, hence that part is fine.
> 
> PIO log:
> 
> [    1.028889] atmel_mxt_ts 0-004c: Warning: Info CRC error - device=0xF436DC file=0x000000
> [    1.078907] atmel_mxt_ts 0-004c: Resetting device
> [    1.128646] usb 1-1: new full-speed USB device number 2 using tegra-ehci
> [    1.198708] atmel_mxt_ts 0-004c: __mxt_read_reg: i2c transfer failed (-121)
> [    1.198732] atmel_mxt_ts 0-004c: Failed to read 28 messages (-121)
> 

Oh gosh.. there is no I2C timeout, but instant NO_ACK. I'll make some coffee...

^ permalink raw reply	[flat|nested] 35+ messages in thread

* Re: [PATCH V12 3/5] i2c: tegra: Add DMA support
  2019-02-06 13:25           ` Sowjanya Komatineni
@ 2019-02-06 13:42             ` Dmitry Osipenko
  2019-02-06 13:45               ` Sowjanya Komatineni
  0 siblings, 1 reply; 35+ messages in thread
From: Dmitry Osipenko @ 2019-02-06 13:42 UTC (permalink / raw)
  To: Sowjanya Komatineni, Thierry Reding
  Cc: Jonathan Hunter, Mantravadi Karthik, Shardar Mohammed, Timo Alho,
	linux-tegra@vger.kernel.org, linux-kernel@vger.kernel.org,
	linux-i2c@vger.kernel.org

06.02.2019 16:25, Sowjanya Komatineni пишет:
> 
> 
>>>> That's odd because it suggests that DMA actually completed, but the 
>>>> message didn't.
>>>>
>>>> I'm not sure I understand how that could happen.
>>>>
>>>> What's also weird above is that there doesn't seem to be a DMA that 
>>>> is started for that particular message. Or is the timeout message a 
>>>> response to the prior transfer (length 10)? Seems like that should 
>>>> not be possible because we get the "transfer complete" message.
>>>
>>> Wait, those are actually different instances of the I2C controller, so 
>>> the relevant log entries are these:
>>>
>>> 	[    0.945445] tegra-i2c 7000d000.i2c: starting DMA for length: 16
>>> 	[    0.945456] tegra-i2c 7000d000.i2c: unmasked irq: 0c
>>> 	...
>>> 	[    1.049224] tegra-i2c 7000d000.i2c: i2c transfer timed out
>>>
>>> And these don't happen if you use higher burst sizes or before the DMA 
>>> series?
>>
>> I tried to enforce DMA without changing bursts:
>>
>> ----------
>> diff --git a/drivers/i2c/busses/i2c-tegra.c b/drivers/i2c/busses/i2c-tegra.c index c538ed5f8e2c..5d1c54ce7800 100644
>> --- a/drivers/i2c/busses/i2c-tegra.c
>> +++ b/drivers/i2c/busses/i2c-tegra.c
>> @@ -6,6 +6,8 @@
>>   * Author: Colin Cross <ccross@android.com>
>>   */
>>  
>> +#define DEBUG
>> +
>>  #include <linux/clk.h>
>>  #include <linux/delay.h>
>>  #include <linux/dmaengine.h>
>> @@ -1046,8 +1048,7 @@ static int tegra_i2c_xfer_msg(struct tegra_i2c_dev *i2c_dev,
>>                 xfer_size = msg->len + I2C_PACKET_HEADER_SIZE;
>>  
>>         xfer_size = ALIGN(xfer_size, BYTES_PER_FIFO_WORD);
>> -       i2c_dev->is_curr_dma_xfer = (xfer_size > I2C_PIO_MODE_MAX_LEN) &&
>> -                                   i2c_dev->dma_buf;
>> +       i2c_dev->is_curr_dma_xfer = !!i2c_dev->dma_buf;
>>         tegra_i2c_config_fifo_trig(i2c_dev, xfer_size);
>>         dma = i2c_dev->is_curr_dma_xfer;
>> ----------
>>
>> Here is the log with this change:
>>
>> [    0.760796] tegra_rtc 7000e000.rtc: registered as rtc1
>> [    0.760850] tegra_rtc 7000e000.rtc: Tegra internal Real Time Clock
>> [    0.761050] i2c /dev entries driver
>> [    0.918928] tegra-i2c 7000c000.i2c: starting DMA for length: 16
>> [    0.918940] tegra-i2c 7000c000.i2c: unmasked irq: 0c
>> [    0.919040] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
>> [    0.919050] tegra-i2c 7000c000.i2c: starting DMA for length: 8
>> [    0.919059] tegra-i2c 7000c000.i2c: unmasked irq: 0c
>> [    0.919322] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
>> [    0.919335] tegra-i2c 7000c000.i2c: starting DMA for length: 16
>> [    0.919343] tegra-i2c 7000c000.i2c: unmasked irq: 0c
>> [    0.919440] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
>> [    0.919448] tegra-i2c 7000c000.i2c: starting DMA for length: 112
>> [    0.919456] tegra-i2c 7000c000.i2c: unmasked irq: 0c
>> [    0.922818] tegra-i2c 7000c000.i2c: transfer complete: 11 0 0
>> [    0.922829] atmel_mxt_ts 0-004c: Family: 160 Variant: 0 Firmware V1.0.AA Objects: 18
>> [    0.922886] tegra-i2c 7000c000.i2c: starting DMA for length: 16
>> [    0.922895] tegra-i2c 7000c000.i2c: unmasked irq: 0c
>> [    0.922993] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
>> [    0.923002] tegra-i2c 7000c000.i2c: starting DMA for length: 224
>> [    0.923011] tegra-i2c 7000c000.i2c: unmasked irq: 0c
>> [    0.933253] tegra-i2c 7000c000.i2c: transfer complete: 11 0 0
>> [    0.933287] tegra-i2c 7000c000.i2c: starting DMA for length: 16
>> [    0.933297] tegra-i2c 7000c000.i2c: unmasked irq: 0c
>> [    0.933478] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
>> [    0.933487] tegra-i2c 7000c000.i2c: starting DMA for length: 12
>> [    0.933496] tegra-i2c 7000c000.i2c: unmasked irq: 0c
>> [    0.945120] tegra-i2c 7000d000.i2c: starting DMA for length: 16
>> [    0.945130] tegra-i2c 7000d000.i2c: unmasked irq: 0c
>> [    1.038917] tegra-i2c 7000c000.i2c: DMA transfer timeout
>> [    1.038982] atmel_mxt_ts 0-004c: __mxt_read_reg: i2c transfer failed (-110)
>> [    1.039000] tegra-i2c 7000c000.i2c: starting DMA for length: 16
>> [    1.039006] atmel_mxt_ts 0-004c: Failed to read T44 and T5 (-110)



>> [    1.039009] tegra-i2c 7000c000.i2c: unmasked irq: 0c
>> [    1.039148] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
>> [    1.039157] tegra-i2c 7000c000.i2c: starting DMA for length: 4
>> [    1.039166] tegra-i2c 7000c000.i2c: unmasked irq: 0c
>> [    1.039304] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
>> [    1.039340] tegra-i2c 7000c000.i2c: starting DMA for length: 16
>> [    1.039349] tegra-i2c 7000c000.i2c: unmasked irq: 0c
>> [    1.039535] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
>> [    1.039544] tegra-i2c 7000c000.i2c: starting DMA for length: 12
>> [    1.039552] tegra-i2c 7000c000.i2c: unmasked irq: 0c
>> [    1.040055] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
>> [    1.040083] tegra-i2c 7000c000.i2c: starting DMA for length: 16
>> [    1.040092] tegra-i2c 7000c000.i2c: unmasked irq: 0c
>> [    1.040301] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
>> [    1.048934] tegra-i2c 7000d000.i2c: i2c transfer timed out
> 
> This log shows DMA transfer timeout for atmel read.
> Do you see issue if you don’t enforce dma all time and let it choose PIO Vs DMA?
> 

No, there are no timeout errors in PIO mode. I could post full log with the PIO-only mode if you want.

^ permalink raw reply	[flat|nested] 35+ messages in thread

* RE: [PATCH V12 3/5] i2c: tegra: Add DMA support
  2019-02-06 13:42             ` Dmitry Osipenko
@ 2019-02-06 13:45               ` Sowjanya Komatineni
  2019-02-06 13:51                 ` Sowjanya Komatineni
  0 siblings, 1 reply; 35+ messages in thread
From: Sowjanya Komatineni @ 2019-02-06 13:45 UTC (permalink / raw)
  To: Dmitry Osipenko, Thierry Reding
  Cc: Jonathan Hunter, Mantravadi Karthik, Shardar Mohammed, Timo Alho,
	linux-tegra@vger.kernel.org, linux-kernel@vger.kernel.org,
	linux-i2c@vger.kernel.org



> >>>> That's odd because it suggests that DMA actually completed, but the 
> >>>> message didn't.
> >>>>
> >>>> I'm not sure I understand how that could happen.
> >>>>
> >>>> What's also weird above is that there doesn't seem to be a DMA that 
> >>>> is started for that particular message. Or is the timeout message a 
> >>>> response to the prior transfer (length 10)? Seems like that should 
> >>>> not be possible because we get the "transfer complete" message.
> >>>
> >>> Wait, those are actually different instances of the I2C controller, 
> >>> so the relevant log entries are these:
> >>>
> >>> 	[    0.945445] tegra-i2c 7000d000.i2c: starting DMA for length: 16
> >>> 	[    0.945456] tegra-i2c 7000d000.i2c: unmasked irq: 0c
> >>> 	...
> >>> 	[    1.049224] tegra-i2c 7000d000.i2c: i2c transfer timed out
> >>>
> >>> And these don't happen if you use higher burst sizes or before the 
> >>> DMA series?
> >>
> >> I tried to enforce DMA without changing bursts:
> >>
> >> ----------
> >> diff --git a/drivers/i2c/busses/i2c-tegra.c 
> >> b/drivers/i2c/busses/i2c-tegra.c index c538ed5f8e2c..5d1c54ce7800 
> >> 100644
> >> --- a/drivers/i2c/busses/i2c-tegra.c
> >> +++ b/drivers/i2c/busses/i2c-tegra.c
> >> @@ -6,6 +6,8 @@
> >>   * Author: Colin Cross <ccross@android.com>
> >>   */
> >>  
> >> +#define DEBUG
> >> +
> >>  #include <linux/clk.h>
> >>  #include <linux/delay.h>
> >>  #include <linux/dmaengine.h>
> >> @@ -1046,8 +1048,7 @@ static int tegra_i2c_xfer_msg(struct tegra_i2c_dev *i2c_dev,
> >>                 xfer_size = msg->len + I2C_PACKET_HEADER_SIZE;
> >>  
> >>         xfer_size = ALIGN(xfer_size, BYTES_PER_FIFO_WORD);
> >> -       i2c_dev->is_curr_dma_xfer = (xfer_size > I2C_PIO_MODE_MAX_LEN) &&
> >> -                                   i2c_dev->dma_buf;
> >> +       i2c_dev->is_curr_dma_xfer = !!i2c_dev->dma_buf;
> >>         tegra_i2c_config_fifo_trig(i2c_dev, xfer_size);
> >>         dma = i2c_dev->is_curr_dma_xfer;
> >> ----------
> >>
> >> Here is the log with this change:
> >>
> >> [    0.760796] tegra_rtc 7000e000.rtc: registered as rtc1
> >> [    0.760850] tegra_rtc 7000e000.rtc: Tegra internal Real Time Clock
> >> [    0.761050] i2c /dev entries driver
> >> [    0.918928] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> >> [    0.918940] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> >> [    0.919040] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> >> [    0.919050] tegra-i2c 7000c000.i2c: starting DMA for length: 8
> >> [    0.919059] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> >> [    0.919322] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> >> [    0.919335] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> >> [    0.919343] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> >> [    0.919440] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> >> [    0.919448] tegra-i2c 7000c000.i2c: starting DMA for length: 112
> >> [    0.919456] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> >> [    0.922818] tegra-i2c 7000c000.i2c: transfer complete: 11 0 0
> >> [    0.922829] atmel_mxt_ts 0-004c: Family: 160 Variant: 0 Firmware V1.0.AA Objects: 18
> >> [    0.922886] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> >> [    0.922895] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> >> [    0.922993] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> >> [    0.923002] tegra-i2c 7000c000.i2c: starting DMA for length: 224
> >> [    0.923011] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> >> [    0.933253] tegra-i2c 7000c000.i2c: transfer complete: 11 0 0
> >> [    0.933287] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> >> [    0.933297] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> >> [    0.933478] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> >> [    0.933487] tegra-i2c 7000c000.i2c: starting DMA for length: 12
> >> [    0.933496] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> >> [    0.945120] tegra-i2c 7000d000.i2c: starting DMA for length: 16
> >> [    0.945130] tegra-i2c 7000d000.i2c: unmasked irq: 0c
> >> [    1.038917] tegra-i2c 7000c000.i2c: DMA transfer timeout
> >> [    1.038982] atmel_mxt_ts 0-004c: __mxt_read_reg: i2c transfer failed (-110)
> >> [    1.039000] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> >> [    1.039006] atmel_mxt_ts 0-004c: Failed to read T44 and T5 (-110)



> >> [    1.039009] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> >> [    1.039148] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> >> [    1.039157] tegra-i2c 7000c000.i2c: starting DMA for length: 4
> >> [    1.039166] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> >> [    1.039304] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> >> [    1.039340] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> >> [    1.039349] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> >> [    1.039535] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> >> [    1.039544] tegra-i2c 7000c000.i2c: starting DMA for length: 12
> >> [    1.039552] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> >> [    1.040055] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> >> [    1.040083] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> >> [    1.040092] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> >> [    1.040301] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> >> [    1.048934] tegra-i2c 7000d000.i2c: i2c transfer timed out
> > 
> > This log shows DMA transfer timeout for atmel read.
> > Do you see issue if you don’t enforce dma all time and let it choose PIO Vs DMA?
> > 
> 
> No, there are no timeout errors in PIO mode. I could post full log with the PIO-only mode if you want.
>
Yes please post full log of PIO only and DMA only

^ permalink raw reply	[flat|nested] 35+ messages in thread

* RE: [PATCH V12 3/5] i2c: tegra: Add DMA support
  2019-02-06 13:45               ` Sowjanya Komatineni
@ 2019-02-06 13:51                 ` Sowjanya Komatineni
  2019-02-06 14:01                   ` Thierry Reding
  0 siblings, 1 reply; 35+ messages in thread
From: Sowjanya Komatineni @ 2019-02-06 13:51 UTC (permalink / raw)
  To: Dmitry Osipenko, Thierry Reding
  Cc: Jonathan Hunter, Mantravadi Karthik, Shardar Mohammed, Timo Alho,
	linux-tegra@vger.kernel.org, linux-kernel@vger.kernel.org,
	linux-i2c@vger.kernel.org


> >>>> That's odd because it suggests that DMA actually completed, but 
> >>>> the message didn't.
> >>>>
> >>>> I'm not sure I understand how that could happen.
> >>>>
> >>>> What's also weird above is that there doesn't seem to be a DMA 
> >>>> that is started for that particular message. Or is the timeout 
> >>>> message a response to the prior transfer (length 10)? Seems like 
> >>>> that should not be possible because we get the "transfer complete" message.
> >>>
> >>> Wait, those are actually different instances of the I2C 
> >>> controller, so the relevant log entries are these:
> >>>
> >>> 	[    0.945445] tegra-i2c 7000d000.i2c: starting DMA for length: 16
> >>> 	[    0.945456] tegra-i2c 7000d000.i2c: unmasked irq: 0c
> >>> 	...
> >>> 	[    1.049224] tegra-i2c 7000d000.i2c: i2c transfer timed out
> >>>
> >>> And these don't happen if you use higher burst sizes or before the 
> >>> DMA series?
> >>
> >> I tried to enforce DMA without changing bursts:
> >>
> >> ----------
> >> diff --git a/drivers/i2c/busses/i2c-tegra.c 
> >> b/drivers/i2c/busses/i2c-tegra.c index c538ed5f8e2c..5d1c54ce7800
> >> 100644
> >> --- a/drivers/i2c/busses/i2c-tegra.c
> >> +++ b/drivers/i2c/busses/i2c-tegra.c
> >> @@ -6,6 +6,8 @@
> >>   * Author: Colin Cross <ccross@android.com>
> >>   */
> >>  
> >> +#define DEBUG
> >> +
> >>  #include <linux/clk.h>
> >>  #include <linux/delay.h>
> >>  #include <linux/dmaengine.h>
> >> @@ -1046,8 +1048,7 @@ static int tegra_i2c_xfer_msg(struct tegra_i2c_dev *i2c_dev,
> >>                 xfer_size = msg->len + I2C_PACKET_HEADER_SIZE;
> >>  
> >>         xfer_size = ALIGN(xfer_size, BYTES_PER_FIFO_WORD);
> >> -       i2c_dev->is_curr_dma_xfer = (xfer_size > I2C_PIO_MODE_MAX_LEN) &&
> >> -                                   i2c_dev->dma_buf;
> >> +       i2c_dev->is_curr_dma_xfer = !!i2c_dev->dma_buf;
> >>         tegra_i2c_config_fifo_trig(i2c_dev, xfer_size);
> >>         dma = i2c_dev->is_curr_dma_xfer;
> >> ----------
> >>
> >> Here is the log with this change:
> >>
> >> [    0.760796] tegra_rtc 7000e000.rtc: registered as rtc1
> >> [    0.760850] tegra_rtc 7000e000.rtc: Tegra internal Real Time Clock
> >> [    0.761050] i2c /dev entries driver
> >> [    0.918928] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> >> [    0.918940] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> >> [    0.919040] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> >> [    0.919050] tegra-i2c 7000c000.i2c: starting DMA for length: 8
> >> [    0.919059] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> >> [    0.919322] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> >> [    0.919335] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> >> [    0.919343] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> >> [    0.919440] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> >> [    0.919448] tegra-i2c 7000c000.i2c: starting DMA for length: 112
> >> [    0.919456] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> >> [    0.922818] tegra-i2c 7000c000.i2c: transfer complete: 11 0 0
> >> [    0.922829] atmel_mxt_ts 0-004c: Family: 160 Variant: 0 Firmware V1.0.AA Objects: 18
> >> [    0.922886] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> >> [    0.922895] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> >> [    0.922993] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> >> [    0.923002] tegra-i2c 7000c000.i2c: starting DMA for length: 224
> >> [    0.923011] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> >> [    0.933253] tegra-i2c 7000c000.i2c: transfer complete: 11 0 0
> >> [    0.933287] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> >> [    0.933297] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> >> [    0.933478] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> >> [    0.933487] tegra-i2c 7000c000.i2c: starting DMA for length: 12
> >> [    0.933496] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> >> [    0.945120] tegra-i2c 7000d000.i2c: starting DMA for length: 16
> >> [    0.945130] tegra-i2c 7000d000.i2c: unmasked irq: 0c
> >> [    1.038917] tegra-i2c 7000c000.i2c: DMA transfer timeout
> >> [    1.038982] atmel_mxt_ts 0-004c: __mxt_read_reg: i2c transfer failed (-110)
> >> [    1.039000] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> >> [    1.039006] atmel_mxt_ts 0-004c: Failed to read T44 and T5 (-110)



> >> [    1.039009] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> >> [    1.039148] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> >> [    1.039157] tegra-i2c 7000c000.i2c: starting DMA for length: 4
> >> [    1.039166] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> >> [    1.039304] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> >> [    1.039340] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> >> [    1.039349] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> >> [    1.039535] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> >> [    1.039544] tegra-i2c 7000c000.i2c: starting DMA for length: 12
> >> [    1.039552] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> >> [    1.040055] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> >> [    1.040083] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> >> [    1.040092] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> >> [    1.040301] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> >> [    1.048934] tegra-i2c 7000d000.i2c: i2c transfer timed out
> > 
> > This log shows DMA transfer timeout for atmel read.
> > Do you see issue if you don’t enforce dma all time and let it choose PIO Vs DMA?
> > 
> 
> No, there are no timeout errors in PIO mode. I could post full log with the PIO-only mode if you want.
>
Yes please post full log of PIO only and DMA only
Also, in above log, lots of DMA transfer went thru fine except this one transfer where DMA timed out.
DMA completion doesnt happen on DMA submit during this particular transaction timeframe for some reason.

^ permalink raw reply	[flat|nested] 35+ messages in thread

* Re: [PATCH V12 3/5] i2c: tegra: Add DMA support
  2019-02-06 13:51                 ` Sowjanya Komatineni
@ 2019-02-06 14:01                   ` Thierry Reding
  2019-02-06 14:10                     ` Sowjanya Komatineni
  2019-02-06 14:13                     ` Dmitry Osipenko
  0 siblings, 2 replies; 35+ messages in thread
From: Thierry Reding @ 2019-02-06 14:01 UTC (permalink / raw)
  To: Sowjanya Komatineni
  Cc: Dmitry Osipenko, Jonathan Hunter, Mantravadi Karthik,
	Shardar Mohammed, Timo Alho, linux-tegra@vger.kernel.org,
	linux-kernel@vger.kernel.org, linux-i2c@vger.kernel.org

[-- Attachment #1: Type: text/plain, Size: 6932 bytes --]

On Wed, Feb 06, 2019 at 01:51:12PM +0000, Sowjanya Komatineni wrote:
> 
> > >>>> That's odd because it suggests that DMA actually completed, but 
> > >>>> the message didn't.
> > >>>>
> > >>>> I'm not sure I understand how that could happen.
> > >>>>
> > >>>> What's also weird above is that there doesn't seem to be a DMA 
> > >>>> that is started for that particular message. Or is the timeout 
> > >>>> message a response to the prior transfer (length 10)? Seems like 
> > >>>> that should not be possible because we get the "transfer complete" message.
> > >>>
> > >>> Wait, those are actually different instances of the I2C 
> > >>> controller, so the relevant log entries are these:
> > >>>
> > >>> 	[    0.945445] tegra-i2c 7000d000.i2c: starting DMA for length: 16
> > >>> 	[    0.945456] tegra-i2c 7000d000.i2c: unmasked irq: 0c
> > >>> 	...
> > >>> 	[    1.049224] tegra-i2c 7000d000.i2c: i2c transfer timed out
> > >>>
> > >>> And these don't happen if you use higher burst sizes or before the 
> > >>> DMA series?
> > >>
> > >> I tried to enforce DMA without changing bursts:
> > >>
> > >> ----------
> > >> diff --git a/drivers/i2c/busses/i2c-tegra.c 
> > >> b/drivers/i2c/busses/i2c-tegra.c index c538ed5f8e2c..5d1c54ce7800
> > >> 100644
> > >> --- a/drivers/i2c/busses/i2c-tegra.c
> > >> +++ b/drivers/i2c/busses/i2c-tegra.c
> > >> @@ -6,6 +6,8 @@
> > >>   * Author: Colin Cross <ccross@android.com>
> > >>   */
> > >>  
> > >> +#define DEBUG
> > >> +
> > >>  #include <linux/clk.h>
> > >>  #include <linux/delay.h>
> > >>  #include <linux/dmaengine.h>
> > >> @@ -1046,8 +1048,7 @@ static int tegra_i2c_xfer_msg(struct tegra_i2c_dev *i2c_dev,
> > >>                 xfer_size = msg->len + I2C_PACKET_HEADER_SIZE;
> > >>  
> > >>         xfer_size = ALIGN(xfer_size, BYTES_PER_FIFO_WORD);
> > >> -       i2c_dev->is_curr_dma_xfer = (xfer_size > I2C_PIO_MODE_MAX_LEN) &&
> > >> -                                   i2c_dev->dma_buf;
> > >> +       i2c_dev->is_curr_dma_xfer = !!i2c_dev->dma_buf;
> > >>         tegra_i2c_config_fifo_trig(i2c_dev, xfer_size);
> > >>         dma = i2c_dev->is_curr_dma_xfer;
> > >> ----------
> > >>
> > >> Here is the log with this change:
> > >>
> > >> [    0.760796] tegra_rtc 7000e000.rtc: registered as rtc1
> > >> [    0.760850] tegra_rtc 7000e000.rtc: Tegra internal Real Time Clock
> > >> [    0.761050] i2c /dev entries driver
> > >> [    0.918928] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> > >> [    0.918940] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> > >> [    0.919040] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> > >> [    0.919050] tegra-i2c 7000c000.i2c: starting DMA for length: 8
> > >> [    0.919059] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> > >> [    0.919322] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> > >> [    0.919335] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> > >> [    0.919343] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> > >> [    0.919440] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> > >> [    0.919448] tegra-i2c 7000c000.i2c: starting DMA for length: 112
> > >> [    0.919456] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> > >> [    0.922818] tegra-i2c 7000c000.i2c: transfer complete: 11 0 0
> > >> [    0.922829] atmel_mxt_ts 0-004c: Family: 160 Variant: 0 Firmware V1.0.AA Objects: 18
> > >> [    0.922886] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> > >> [    0.922895] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> > >> [    0.922993] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> > >> [    0.923002] tegra-i2c 7000c000.i2c: starting DMA for length: 224
> > >> [    0.923011] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> > >> [    0.933253] tegra-i2c 7000c000.i2c: transfer complete: 11 0 0
> > >> [    0.933287] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> > >> [    0.933297] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> > >> [    0.933478] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> > >> [    0.933487] tegra-i2c 7000c000.i2c: starting DMA for length: 12
> > >> [    0.933496] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> > >> [    0.945120] tegra-i2c 7000d000.i2c: starting DMA for length: 16
> > >> [    0.945130] tegra-i2c 7000d000.i2c: unmasked irq: 0c
> > >> [    1.038917] tegra-i2c 7000c000.i2c: DMA transfer timeout
> > >> [    1.038982] atmel_mxt_ts 0-004c: __mxt_read_reg: i2c transfer failed (-110)
> > >> [    1.039000] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> > >> [    1.039006] atmel_mxt_ts 0-004c: Failed to read T44 and T5 (-110)
> 
> 
> 
> > >> [    1.039009] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> > >> [    1.039148] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> > >> [    1.039157] tegra-i2c 7000c000.i2c: starting DMA for length: 4
> > >> [    1.039166] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> > >> [    1.039304] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> > >> [    1.039340] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> > >> [    1.039349] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> > >> [    1.039535] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> > >> [    1.039544] tegra-i2c 7000c000.i2c: starting DMA for length: 12
> > >> [    1.039552] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> > >> [    1.040055] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> > >> [    1.040083] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> > >> [    1.040092] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> > >> [    1.040301] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> > >> [    1.048934] tegra-i2c 7000d000.i2c: i2c transfer timed out
> > > 
> > > This log shows DMA transfer timeout for atmel read.
> > > Do you see issue if you don’t enforce dma all time and let it choose PIO Vs DMA?
> > > 
> > 
> > No, there are no timeout errors in PIO mode. I could post full log with the PIO-only mode if you want.
> >
> Yes please post full log of PIO only and DMA only
> Also, in above log, lots of DMA transfer went thru fine except this
> one transfer where DMA timed out.
> DMA completion doesnt happen on DMA submit during this particular
> transaction timeframe for some reason.

Dmitry, can you provide some background information on the setup that
you're using? I vaguely remember something about i2c@7000d000 being
special on older Tegra devices. Perhaps there's something additional
that we need to take into account?

Aha! Look at tegra_i2c_reg_addr() which special-cases I2C_TX_FIFO on
the DVC variant of the controller, which is exactly the one that you
are seeing the timeouts on and it's exactly the register that we use
as destination for the DMA transfer.

I think we need to do something like this:

	slv_config.dst_addr = i2c_dev->base_phys + tegra_i2c_reg_addr(i2c_dev, I2C_TX_FIFO);

to make sure we pass the right FIFO register address to DMA.

Thierry

[-- Attachment #2: signature.asc --]
[-- Type: application/pgp-signature, Size: 833 bytes --]

^ permalink raw reply	[flat|nested] 35+ messages in thread

* RE: [PATCH V12 3/5] i2c: tegra: Add DMA support
  2019-02-06 14:01                   ` Thierry Reding
@ 2019-02-06 14:10                     ` Sowjanya Komatineni
  2019-02-06 14:13                     ` Dmitry Osipenko
  1 sibling, 0 replies; 35+ messages in thread
From: Sowjanya Komatineni @ 2019-02-06 14:10 UTC (permalink / raw)
  To: Thierry Reding
  Cc: Dmitry Osipenko, Jonathan Hunter, Mantravadi Karthik,
	Shardar Mohammed, Timo Alho, linux-tegra@vger.kernel.org,
	linux-kernel@vger.kernel.org, linux-i2c@vger.kernel.org


> > > >>>> That's odd because it suggests that DMA actually completed, but 
> > > >>>> the message didn't.
> > > >>>>
> > > >>>> I'm not sure I understand how that could happen.
> > > >>>>
> > > >>>> What's also weird above is that there doesn't seem to be a DMA 
> > > >>>> that is started for that particular message. Or is the timeout 
> > > >>>> message a response to the prior transfer (length 10)? Seems 
> > > >>>> like that should not be possible because we get the "transfer complete" message.
> > > >>>
> > > >>> Wait, those are actually different instances of the I2C 
> > > >>> controller, so the relevant log entries are these:
> > > >>>
> > > >>> 	[    0.945445] tegra-i2c 7000d000.i2c: starting DMA for length: 16
> > > >>> 	[    0.945456] tegra-i2c 7000d000.i2c: unmasked irq: 0c
> > > >>> 	...
> > > >>> 	[    1.049224] tegra-i2c 7000d000.i2c: i2c transfer timed out
> > > >>>
> > > >>> And these don't happen if you use higher burst sizes or before 
> > > >>> the DMA series?
> > > >>
> > > >> I tried to enforce DMA without changing bursts:
> > > >>
> > > >> ----------
> > > >> diff --git a/drivers/i2c/busses/i2c-tegra.c 
> > > >> b/drivers/i2c/busses/i2c-tegra.c index c538ed5f8e2c..5d1c54ce7800
> > > >> 100644
> > > >> --- a/drivers/i2c/busses/i2c-tegra.c
> > > >> +++ b/drivers/i2c/busses/i2c-tegra.c
> > > >> @@ -6,6 +6,8 @@
> > > >>   * Author: Colin Cross <ccross@android.com>
> > > >>   */
> > > >>  
> > > >> +#define DEBUG
> > > >> +
> > > >>  #include <linux/clk.h>
> > > >>  #include <linux/delay.h>
> > > >>  #include <linux/dmaengine.h>
> > > >> @@ -1046,8 +1048,7 @@ static int tegra_i2c_xfer_msg(struct tegra_i2c_dev *i2c_dev,
> > > >>                 xfer_size = msg->len + I2C_PACKET_HEADER_SIZE;
> > > >>  
> > > >>         xfer_size = ALIGN(xfer_size, BYTES_PER_FIFO_WORD);
> > > >> -       i2c_dev->is_curr_dma_xfer = (xfer_size > I2C_PIO_MODE_MAX_LEN) &&
> > > >> -                                   i2c_dev->dma_buf;
> > > >> +       i2c_dev->is_curr_dma_xfer = !!i2c_dev->dma_buf;
> > > >>         tegra_i2c_config_fifo_trig(i2c_dev, xfer_size);
> > > >>         dma = i2c_dev->is_curr_dma_xfer;
> > > >> ----------
> > > >>
> > > >> Here is the log with this change:
> > > >>
> > > >> [    0.760796] tegra_rtc 7000e000.rtc: registered as rtc1
> > > >> [    0.760850] tegra_rtc 7000e000.rtc: Tegra internal Real Time Clock
> > > >> [    0.761050] i2c /dev entries driver
> > > >> [    0.918928] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> > > >> [    0.918940] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> > > >> [    0.919040] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> > > >> [    0.919050] tegra-i2c 7000c000.i2c: starting DMA for length: 8
> > > >> [    0.919059] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> > > >> [    0.919322] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> > > >> [    0.919335] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> > > >> [    0.919343] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> > > >> [    0.919440] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> > > >> [    0.919448] tegra-i2c 7000c000.i2c: starting DMA for length: 112
> > > >> [    0.919456] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> > > >> [    0.922818] tegra-i2c 7000c000.i2c: transfer complete: 11 0 0
> > > >> [    0.922829] atmel_mxt_ts 0-004c: Family: 160 Variant: 0 Firmware V1.0.AA Objects: 18
> > > >> [    0.922886] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> > > >> [    0.922895] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> > > >> [    0.922993] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> > > >> [    0.923002] tegra-i2c 7000c000.i2c: starting DMA for length: 224
> > > >> [    0.923011] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> > > >> [    0.933253] tegra-i2c 7000c000.i2c: transfer complete: 11 0 0
> > > >> [    0.933287] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> > > >> [    0.933297] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> > > >> [    0.933478] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> > > >> [    0.933487] tegra-i2c 7000c000.i2c: starting DMA for length: 12
> > > >> [    0.933496] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> > > >> [    0.945120] tegra-i2c 7000d000.i2c: starting DMA for length: 16
> > > >> [    0.945130] tegra-i2c 7000d000.i2c: unmasked irq: 0c
> > > >> [    1.038917] tegra-i2c 7000c000.i2c: DMA transfer timeout
> > > >> [    1.038982] atmel_mxt_ts 0-004c: __mxt_read_reg: i2c transfer failed (-110)
> > > >> [    1.039000] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> > > >> [    1.039006] atmel_mxt_ts 0-004c: Failed to read T44 and T5 (-110)
> > 
> > 
> > 
> > > >> [    1.039009] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> > > >> [    1.039148] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> > > >> [    1.039157] tegra-i2c 7000c000.i2c: starting DMA for length: 4
> > > >> [    1.039166] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> > > >> [    1.039304] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> > > >> [    1.039340] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> > > >> [    1.039349] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> > > >> [    1.039535] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> > > >> [    1.039544] tegra-i2c 7000c000.i2c: starting DMA for length: 12
> > > >> [    1.039552] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> > > >> [    1.040055] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> > > >> [    1.040083] tegra-i2c 7000c000.i2c: starting DMA for length: 16
> > > >> [    1.040092] tegra-i2c 7000c000.i2c: unmasked irq: 0c
> > > >> [    1.040301] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
> > > >> [    1.048934] tegra-i2c 7000d000.i2c: i2c transfer timed out
> > > > 
> > > > This log shows DMA transfer timeout for atmel read.
> > > > Do you see issue if you don’t enforce dma all time and let it choose PIO Vs DMA?
> > > > 
> > > 
> > > No, there are no timeout errors in PIO mode. I could post full log with the PIO-only mode if you want.
> > >
> > Yes please post full log of PIO only and DMA only Also, in above log, 
> > lots of DMA transfer went thru fine except this one transfer where DMA 
> > timed out.
> > DMA completion doesnt happen on DMA submit during this particular 
> > transaction timeframe for some reason.
> 
> Dmitry, can you provide some background information on the setup that you're using? I vaguely remember something about i2c@7000d000 being special on > older Tegra devices. Perhaps there's something additional that we need to take into account?
> 
> Aha! Look at tegra_i2c_reg_addr() which special-cases I2C_TX_FIFO on the DVC variant of the controller, which is exactly the one that you are seeing > the timeouts on and it's exactly the register that we use as destination for the DMA transfer.
> 
> I think we need to do something like this:
> 
> 	slv_config.dst_addr = i2c_dev->base_phys + tegra_i2c_reg_addr(i2c_dev, I2C_TX_FIFO);
> 
> to make sure we pass the right FIFO register address to DMA.
> 
> Thierry
> 
Yeah DVC FIFO register offset is different. Yes we need to use tegra_i2c_reg_addr which takes care of DVC FIFO address. Will fix it.

Atmel touch is on I2C1 (7000C000). DMA Timeout happened for only 1 transaction for this device and lots of other transfers to this device are fine.
in other log dmitry sent, we see one transfer timeout from 7000D000 and this could be due to FIFO Addresses.

Sowjanya

^ permalink raw reply	[flat|nested] 35+ messages in thread

* Re: [PATCH V12 3/5] i2c: tegra: Add DMA support
  2019-02-06 14:01                   ` Thierry Reding
  2019-02-06 14:10                     ` Sowjanya Komatineni
@ 2019-02-06 14:13                     ` Dmitry Osipenko
  2019-02-06 14:19                       ` Sowjanya Komatineni
  1 sibling, 1 reply; 35+ messages in thread
From: Dmitry Osipenko @ 2019-02-06 14:13 UTC (permalink / raw)
  To: Thierry Reding, Sowjanya Komatineni
  Cc: Jonathan Hunter, Mantravadi Karthik, Shardar Mohammed, Timo Alho,
	linux-tegra@vger.kernel.org, linux-kernel@vger.kernel.org,
	linux-i2c@vger.kernel.org

06.02.2019 17:01, Thierry Reding пишет:
> On Wed, Feb 06, 2019 at 01:51:12PM +0000, Sowjanya Komatineni wrote:
>>
>>>>>>> That's odd because it suggests that DMA actually completed, but 
>>>>>>> the message didn't.
>>>>>>>
>>>>>>> I'm not sure I understand how that could happen.
>>>>>>>
>>>>>>> What's also weird above is that there doesn't seem to be a DMA 
>>>>>>> that is started for that particular message. Or is the timeout 
>>>>>>> message a response to the prior transfer (length 10)? Seems like 
>>>>>>> that should not be possible because we get the "transfer complete" message.
>>>>>>
>>>>>> Wait, those are actually different instances of the I2C 
>>>>>> controller, so the relevant log entries are these:
>>>>>>
>>>>>> 	[    0.945445] tegra-i2c 7000d000.i2c: starting DMA for length: 16
>>>>>> 	[    0.945456] tegra-i2c 7000d000.i2c: unmasked irq: 0c
>>>>>> 	...
>>>>>> 	[    1.049224] tegra-i2c 7000d000.i2c: i2c transfer timed out
>>>>>>
>>>>>> And these don't happen if you use higher burst sizes or before the 
>>>>>> DMA series?
>>>>>
>>>>> I tried to enforce DMA without changing bursts:
>>>>>
>>>>> ----------
>>>>> diff --git a/drivers/i2c/busses/i2c-tegra.c 
>>>>> b/drivers/i2c/busses/i2c-tegra.c index c538ed5f8e2c..5d1c54ce7800
>>>>> 100644
>>>>> --- a/drivers/i2c/busses/i2c-tegra.c
>>>>> +++ b/drivers/i2c/busses/i2c-tegra.c
>>>>> @@ -6,6 +6,8 @@
>>>>>   * Author: Colin Cross <ccross@android.com>
>>>>>   */
>>>>>  
>>>>> +#define DEBUG
>>>>> +
>>>>>  #include <linux/clk.h>
>>>>>  #include <linux/delay.h>
>>>>>  #include <linux/dmaengine.h>
>>>>> @@ -1046,8 +1048,7 @@ static int tegra_i2c_xfer_msg(struct tegra_i2c_dev *i2c_dev,
>>>>>                 xfer_size = msg->len + I2C_PACKET_HEADER_SIZE;
>>>>>  
>>>>>         xfer_size = ALIGN(xfer_size, BYTES_PER_FIFO_WORD);
>>>>> -       i2c_dev->is_curr_dma_xfer = (xfer_size > I2C_PIO_MODE_MAX_LEN) &&
>>>>> -                                   i2c_dev->dma_buf;
>>>>> +       i2c_dev->is_curr_dma_xfer = !!i2c_dev->dma_buf;
>>>>>         tegra_i2c_config_fifo_trig(i2c_dev, xfer_size);
>>>>>         dma = i2c_dev->is_curr_dma_xfer;
>>>>> ----------
>>>>>
>>>>> Here is the log with this change:
>>>>>
>>>>> [    0.760796] tegra_rtc 7000e000.rtc: registered as rtc1
>>>>> [    0.760850] tegra_rtc 7000e000.rtc: Tegra internal Real Time Clock
>>>>> [    0.761050] i2c /dev entries driver
>>>>> [    0.918928] tegra-i2c 7000c000.i2c: starting DMA for length: 16
>>>>> [    0.918940] tegra-i2c 7000c000.i2c: unmasked irq: 0c
>>>>> [    0.919040] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
>>>>> [    0.919050] tegra-i2c 7000c000.i2c: starting DMA for length: 8
>>>>> [    0.919059] tegra-i2c 7000c000.i2c: unmasked irq: 0c
>>>>> [    0.919322] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
>>>>> [    0.919335] tegra-i2c 7000c000.i2c: starting DMA for length: 16
>>>>> [    0.919343] tegra-i2c 7000c000.i2c: unmasked irq: 0c
>>>>> [    0.919440] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
>>>>> [    0.919448] tegra-i2c 7000c000.i2c: starting DMA for length: 112
>>>>> [    0.919456] tegra-i2c 7000c000.i2c: unmasked irq: 0c
>>>>> [    0.922818] tegra-i2c 7000c000.i2c: transfer complete: 11 0 0
>>>>> [    0.922829] atmel_mxt_ts 0-004c: Family: 160 Variant: 0 Firmware V1.0.AA Objects: 18
>>>>> [    0.922886] tegra-i2c 7000c000.i2c: starting DMA for length: 16
>>>>> [    0.922895] tegra-i2c 7000c000.i2c: unmasked irq: 0c
>>>>> [    0.922993] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
>>>>> [    0.923002] tegra-i2c 7000c000.i2c: starting DMA for length: 224
>>>>> [    0.923011] tegra-i2c 7000c000.i2c: unmasked irq: 0c
>>>>> [    0.933253] tegra-i2c 7000c000.i2c: transfer complete: 11 0 0
>>>>> [    0.933287] tegra-i2c 7000c000.i2c: starting DMA for length: 16
>>>>> [    0.933297] tegra-i2c 7000c000.i2c: unmasked irq: 0c
>>>>> [    0.933478] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
>>>>> [    0.933487] tegra-i2c 7000c000.i2c: starting DMA for length: 12
>>>>> [    0.933496] tegra-i2c 7000c000.i2c: unmasked irq: 0c
>>>>> [    0.945120] tegra-i2c 7000d000.i2c: starting DMA for length: 16
>>>>> [    0.945130] tegra-i2c 7000d000.i2c: unmasked irq: 0c
>>>>> [    1.038917] tegra-i2c 7000c000.i2c: DMA transfer timeout
>>>>> [    1.038982] atmel_mxt_ts 0-004c: __mxt_read_reg: i2c transfer failed (-110)
>>>>> [    1.039000] tegra-i2c 7000c000.i2c: starting DMA for length: 16
>>>>> [    1.039006] atmel_mxt_ts 0-004c: Failed to read T44 and T5 (-110)
>>
>>
>>
>>>>> [    1.039009] tegra-i2c 7000c000.i2c: unmasked irq: 0c
>>>>> [    1.039148] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
>>>>> [    1.039157] tegra-i2c 7000c000.i2c: starting DMA for length: 4
>>>>> [    1.039166] tegra-i2c 7000c000.i2c: unmasked irq: 0c
>>>>> [    1.039304] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
>>>>> [    1.039340] tegra-i2c 7000c000.i2c: starting DMA for length: 16
>>>>> [    1.039349] tegra-i2c 7000c000.i2c: unmasked irq: 0c
>>>>> [    1.039535] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
>>>>> [    1.039544] tegra-i2c 7000c000.i2c: starting DMA for length: 12
>>>>> [    1.039552] tegra-i2c 7000c000.i2c: unmasked irq: 0c
>>>>> [    1.040055] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
>>>>> [    1.040083] tegra-i2c 7000c000.i2c: starting DMA for length: 16
>>>>> [    1.040092] tegra-i2c 7000c000.i2c: unmasked irq: 0c
>>>>> [    1.040301] tegra-i2c 7000c000.i2c: transfer complete: 10 0 0
>>>>> [    1.048934] tegra-i2c 7000d000.i2c: i2c transfer timed out
>>>>
>>>> This log shows DMA transfer timeout for atmel read.
>>>> Do you see issue if you don’t enforce dma all time and let it choose PIO Vs DMA?
>>>>
>>>
>>> No, there are no timeout errors in PIO mode. I could post full log with the PIO-only mode if you want.
>>>
>> Yes please post full log of PIO only and DMA only
>> Also, in above log, lots of DMA transfer went thru fine except this
>> one transfer where DMA timed out.
>> DMA completion doesnt happen on DMA submit during this particular
>> transaction timeframe for some reason.
> 
> Dmitry, can you provide some background information on the setup that
> you're using? I vaguely remember something about i2c@7000d000 being
> special on older Tegra devices. Perhaps there's something additional
> that we need to take into account?
> 
> Aha! Look at tegra_i2c_reg_addr() which special-cases I2C_TX_FIFO on
> the DVC variant of the controller, which is exactly the one that you
> are seeing the timeouts on and it's exactly the register that we use
> as destination for the DMA transfer.
> 
> I think we need to do something like this:
> 
> 	slv_config.dst_addr = i2c_dev->base_phys + tegra_i2c_reg_addr(i2c_dev, I2C_TX_FIFO);
> 
> to make sure we pass the right FIFO register address to DMA.

I'm running it on T20 at the moment. I don't know about the DVC quirks, but sounds plausible. Please let me know if you need any other info.

Here the full logs:

PIO-only: http://dpaste.com/2MX3EAN.txt
DMA-only: http://dpaste.com/3VXZSSM.txt

Note the "Failed to read T44 and T5 (-110)" error that happens in DMA-only. And it happens on i2c@7000c000, DVC is i2c@7000d000.

^ permalink raw reply	[flat|nested] 35+ messages in thread

* RE: [PATCH V12 3/5] i2c: tegra: Add DMA support
  2019-02-06 14:13                     ` Dmitry Osipenko
@ 2019-02-06 14:19                       ` Sowjanya Komatineni
  2019-02-06 14:24                         ` Dmitry Osipenko
  0 siblings, 1 reply; 35+ messages in thread
From: Sowjanya Komatineni @ 2019-02-06 14:19 UTC (permalink / raw)
  To: Dmitry Osipenko, Thierry Reding
  Cc: Jonathan Hunter, Mantravadi Karthik, Shardar Mohammed, Timo Alho,
	linux-tegra@vger.kernel.org, linux-kernel@vger.kernel.org,
	linux-i2c@vger.kernel.org

> >>> No, there are no timeout errors in PIO mode. I could post full log with the PIO-only mode if you want.
> >>>
> >> Yes please post full log of PIO only and DMA only Also, in above log, 
> >> lots of DMA transfer went thru fine except this one transfer where 
> >> DMA timed out.
> >> DMA completion doesnt happen on DMA submit during this particular 
> >> transaction timeframe for some reason.
> > 
> > Dmitry, can you provide some background information on the setup that 
> > you're using? I vaguely remember something about i2c@7000d000 being 
> > special on older Tegra devices. Perhaps there's something additional 
> > that we need to take into account?
> > 
> > Aha! Look at tegra_i2c_reg_addr() which special-cases I2C_TX_FIFO on 
> > the DVC variant of the controller, which is exactly the one that you 
> > are seeing the timeouts on and it's exactly the register that we use 
> > as destination for the DMA transfer.
> > 
> > I think we need to do something like this:
> > 
> > 	slv_config.dst_addr = i2c_dev->base_phys + 
> > tegra_i2c_reg_addr(i2c_dev, I2C_TX_FIFO);
> > 
> > to make sure we pass the right FIFO register address to DMA.
>
> I'm running it on T20 at the moment. I don't know about the DVC quirks, but sounds plausible. Please let me know if you need any other info.
>
> Here the full logs:
>
> PIO-only: http://dpaste.com/2MX3EAN.txt
> DMA-only: http://dpaste.com/3VXZSSM.txt
>
> Note the "Failed to read T44 and T5 (-110)" error that happens in DMA-only. And it happens on i2c@7000c000, DVC is i2c@7000d000.

Yes this is due to same issue theirry mentioned.
Prior to transfer timeout for touch, tps6586x regulator probe failed due to i2c timeout which uses DVC (7000D000) and since DMA mode is enforced all DVC/PWR I2C transactions also go thru DMA and FIFO register for DVC offset is not accounted when configure to dma slave.
Will fix and send so you can see for repro with updated patch..


[    0.925155] tegra-i2c 7000d000.i2c: starting DMA for length: 16
[    0.925165] tegra-i2c 7000d000.i2c: unmasked irq: 0c
[    1.028961] tegra-i2c 7000d000.i2c: i2c transfer timed out
[    1.028968] tegra-i2c 7000c000.i2c: DMA transfer timeout
[    1.028995] tps6586x 3-0034: Chip ID read failed: -110
[    1.029029] tps6586x: probe of 3-0034 failed with error -5
[    1.029045] atmel_mxt_ts 0-004c: __mxt_read_reg: i2c transfer failed (-110)
[    1.029051] atmel_mxt_ts 0-004c: Failed to read T44 and T5 (-110)

^ permalink raw reply	[flat|nested] 35+ messages in thread

* Re: [PATCH V12 3/5] i2c: tegra: Add DMA support
  2019-02-06 14:19                       ` Sowjanya Komatineni
@ 2019-02-06 14:24                         ` Dmitry Osipenko
  2019-02-06 14:29                           ` Sowjanya Komatineni
  0 siblings, 1 reply; 35+ messages in thread
From: Dmitry Osipenko @ 2019-02-06 14:24 UTC (permalink / raw)
  To: Sowjanya Komatineni, Thierry Reding
  Cc: Jonathan Hunter, Mantravadi Karthik, Shardar Mohammed, Timo Alho,
	linux-tegra@vger.kernel.org, linux-kernel@vger.kernel.org,
	linux-i2c@vger.kernel.org

06.02.2019 17:19, Sowjanya Komatineni пишет:
>>>>> No, there are no timeout errors in PIO mode. I could post full log with the PIO-only mode if you want.
>>>>>
>>>> Yes please post full log of PIO only and DMA only Also, in above log, 
>>>> lots of DMA transfer went thru fine except this one transfer where 
>>>> DMA timed out.
>>>> DMA completion doesnt happen on DMA submit during this particular 
>>>> transaction timeframe for some reason.
>>>
>>> Dmitry, can you provide some background information on the setup that 
>>> you're using? I vaguely remember something about i2c@7000d000 being 
>>> special on older Tegra devices. Perhaps there's something additional 
>>> that we need to take into account?
>>>
>>> Aha! Look at tegra_i2c_reg_addr() which special-cases I2C_TX_FIFO on 
>>> the DVC variant of the controller, which is exactly the one that you 
>>> are seeing the timeouts on and it's exactly the register that we use 
>>> as destination for the DMA transfer.
>>>
>>> I think we need to do something like this:
>>>
>>> 	slv_config.dst_addr = i2c_dev->base_phys + 
>>> tegra_i2c_reg_addr(i2c_dev, I2C_TX_FIFO);
>>>
>>> to make sure we pass the right FIFO register address to DMA.
>>
>> I'm running it on T20 at the moment. I don't know about the DVC quirks, but sounds plausible. Please let me know if you need any other info.
>>
>> Here the full logs:
>>
>> PIO-only: http://dpaste.com/2MX3EAN.txt
>> DMA-only: http://dpaste.com/3VXZSSM.txt
>>
>> Note the "Failed to read T44 and T5 (-110)" error that happens in DMA-only. And it happens on i2c@7000c000, DVC is i2c@7000d000.
> 
> Yes this is due to same issue theirry mentioned.
> Prior to transfer timeout for touch, tps6586x regulator probe failed due to i2c timeout which uses DVC (7000D000) and since DMA mode is enforced all DVC/PWR I2C transactions also go thru DMA and FIFO register for DVC offset is not accounted when configure to dma slave.
> Will fix and send so you can see for repro with updated patch..
> 
> 
> [    0.925155] tegra-i2c 7000d000.i2c: starting DMA for length: 16
> [    0.925165] tegra-i2c 7000d000.i2c: unmasked irq: 0c
> [    1.028961] tegra-i2c 7000d000.i2c: i2c transfer timed out
> [    1.028968] tegra-i2c 7000c000.i2c: DMA transfer timeout
> [    1.028995] tps6586x 3-0034: Chip ID read failed: -110
> [    1.029029] tps6586x: probe of 3-0034 failed with error -5
> [    1.029045] atmel_mxt_ts 0-004c: __mxt_read_reg: i2c transfer failed (-110)
> [    1.029051] atmel_mxt_ts 0-004c: Failed to read T44 and T5 (-110)
> 

I think tps6586x and atmel-touch should be independent issues, but will see. Thanks!

^ permalink raw reply	[flat|nested] 35+ messages in thread

* RE: [PATCH V12 3/5] i2c: tegra: Add DMA support
  2019-02-06 14:24                         ` Dmitry Osipenko
@ 2019-02-06 14:29                           ` Sowjanya Komatineni
  2019-02-06 14:35                             ` Dmitry Osipenko
  0 siblings, 1 reply; 35+ messages in thread
From: Sowjanya Komatineni @ 2019-02-06 14:29 UTC (permalink / raw)
  To: Dmitry Osipenko, Thierry Reding
  Cc: Jonathan Hunter, Mantravadi Karthik, Shardar Mohammed, Timo Alho,
	linux-tegra@vger.kernel.org, linux-kernel@vger.kernel.org,
	linux-i2c@vger.kernel.org


> >>>> Yes please post full log of PIO only and DMA only Also, in above 
> >>>> log, lots of DMA transfer went thru fine except this one transfer 
> >>>> where DMA timed out.
> >>>> DMA completion doesnt happen on DMA submit during this particular 
> >>>> transaction timeframe for some reason.
> >>>
> >>> Dmitry, can you provide some background information on the setup 
> >>> that you're using? I vaguely remember something about i2c@7000d000 
> >>> being special on older Tegra devices. Perhaps there's something 
> >>> additional that we need to take into account?
> >>>
> >>> Aha! Look at tegra_i2c_reg_addr() which special-cases I2C_TX_FIFO on 
> >>> the DVC variant of the controller, which is exactly the one that you 
> >>> are seeing the timeouts on and it's exactly the register that we use 
> >>> as destination for the DMA transfer.
> >>>
> >>> I think we need to do something like this:
> >>>
> >>> 	slv_config.dst_addr = i2c_dev->base_phys + 
> >>> tegra_i2c_reg_addr(i2c_dev, I2C_TX_FIFO);
> >>>
> >>> to make sure we pass the right FIFO register address to DMA.
> >>
> >> I'm running it on T20 at the moment. I don't know about the DVC quirks, but sounds plausible. Please let me know if you need any other info.
> >>
> >> Here the full logs:
> >>
> >> PIO-only: http://dpaste.com/2MX3EAN.txt
> >> DMA-only: http://dpaste.com/3VXZSSM.txt
> >>
> >> Note the "Failed to read T44 and T5 (-110)" error that happens in DMA-only. And it happens on i2c@7000c000, DVC is i2c@7000d000.
> > 
> > Yes this is due to same issue theirry mentioned.
> > Prior to transfer timeout for touch, tps6586x regulator probe failed due to i2c timeout which uses DVC (7000D000) and since DMA mode is enforced all DVC/PWR I2C transactions also go thru DMA and FIFO register for DVC offset is not accounted when configure to dma slave.
> > Will fix and send so you can see for repro with updated patch..
> > 
> > 
> > [    0.925155] tegra-i2c 7000d000.i2c: starting DMA for length: 16
> > [    0.925165] tegra-i2c 7000d000.i2c: unmasked irq: 0c
> > [    1.028961] tegra-i2c 7000d000.i2c: i2c transfer timed out
> > [    1.028968] tegra-i2c 7000c000.i2c: DMA transfer timeout
> > [    1.028995] tps6586x 3-0034: Chip ID read failed: -110
> > [    1.029029] tps6586x: probe of 3-0034 failed with error -5
> > [    1.029045] atmel_mxt_ts 0-004c: __mxt_read_reg: i2c transfer failed (-110)
> > [    1.029051] atmel_mxt_ts 0-004c: Failed to read T44 and T5 (-110)
> > 
> 
> I think tps6586x and atmel-touch should be independent issues, but will see. Thanks!
Whats your platform setup? Is atmel touch power ON default or its programmed during boot by SW whcih need to use DVC?

^ permalink raw reply	[flat|nested] 35+ messages in thread

* Re: [PATCH V12 3/5] i2c: tegra: Add DMA support
  2019-02-06 14:29                           ` Sowjanya Komatineni
@ 2019-02-06 14:35                             ` Dmitry Osipenko
  2019-02-06 14:48                               ` Sowjanya Komatineni
  0 siblings, 1 reply; 35+ messages in thread
From: Dmitry Osipenko @ 2019-02-06 14:35 UTC (permalink / raw)
  To: Sowjanya Komatineni, Thierry Reding
  Cc: Jonathan Hunter, Mantravadi Karthik, Shardar Mohammed, Timo Alho,
	linux-tegra@vger.kernel.org, linux-kernel@vger.kernel.org,
	linux-i2c@vger.kernel.org

06.02.2019 17:29, Sowjanya Komatineni пишет:
> 
>>>>>> Yes please post full log of PIO only and DMA only Also, in above 
>>>>>> log, lots of DMA transfer went thru fine except this one transfer 
>>>>>> where DMA timed out.
>>>>>> DMA completion doesnt happen on DMA submit during this particular 
>>>>>> transaction timeframe for some reason.
>>>>>
>>>>> Dmitry, can you provide some background information on the setup 
>>>>> that you're using? I vaguely remember something about i2c@7000d000 
>>>>> being special on older Tegra devices. Perhaps there's something 
>>>>> additional that we need to take into account?
>>>>>
>>>>> Aha! Look at tegra_i2c_reg_addr() which special-cases I2C_TX_FIFO on 
>>>>> the DVC variant of the controller, which is exactly the one that you 
>>>>> are seeing the timeouts on and it's exactly the register that we use 
>>>>> as destination for the DMA transfer.
>>>>>
>>>>> I think we need to do something like this:
>>>>>
>>>>> 	slv_config.dst_addr = i2c_dev->base_phys + 
>>>>> tegra_i2c_reg_addr(i2c_dev, I2C_TX_FIFO);
>>>>>
>>>>> to make sure we pass the right FIFO register address to DMA.
>>>>
>>>> I'm running it on T20 at the moment. I don't know about the DVC quirks, but sounds plausible. Please let me know if you need any other info.
>>>>
>>>> Here the full logs:
>>>>
>>>> PIO-only: http://dpaste.com/2MX3EAN.txt
>>>> DMA-only: http://dpaste.com/3VXZSSM.txt
>>>>
>>>> Note the "Failed to read T44 and T5 (-110)" error that happens in DMA-only. And it happens on i2c@7000c000, DVC is i2c@7000d000.
>>>
>>> Yes this is due to same issue theirry mentioned.
>>> Prior to transfer timeout for touch, tps6586x regulator probe failed due to i2c timeout which uses DVC (7000D000) and since DMA mode is enforced all DVC/PWR I2C transactions also go thru DMA and FIFO register for DVC offset is not accounted when configure to dma slave.
>>> Will fix and send so you can see for repro with updated patch..
>>>
>>>
>>> [    0.925155] tegra-i2c 7000d000.i2c: starting DMA for length: 16
>>> [    0.925165] tegra-i2c 7000d000.i2c: unmasked irq: 0c
>>> [    1.028961] tegra-i2c 7000d000.i2c: i2c transfer timed out
>>> [    1.028968] tegra-i2c 7000c000.i2c: DMA transfer timeout
>>> [    1.028995] tps6586x 3-0034: Chip ID read failed: -110
>>> [    1.029029] tps6586x: probe of 3-0034 failed with error -5
>>> [    1.029045] atmel_mxt_ts 0-004c: __mxt_read_reg: i2c transfer failed (-110)
>>> [    1.029051] atmel_mxt_ts 0-004c: Failed to read T44 and T5 (-110)
>>>
>>
>> I think tps6586x and atmel-touch should be independent issues, but will see. Thanks!
> Whats your platform setup? Is atmel touch power ON default or its programmed during boot by SW whcih need to use DVC?
> 

It's "power ON default". I tried to boot in PIO-only mode with tps6586x disabled and there is no "Failed to read T44 and T5" error, atmel probed successfully.

^ permalink raw reply	[flat|nested] 35+ messages in thread

* RE: [PATCH V12 3/5] i2c: tegra: Add DMA support
  2019-02-06 14:35                             ` Dmitry Osipenko
@ 2019-02-06 14:48                               ` Sowjanya Komatineni
  0 siblings, 0 replies; 35+ messages in thread
From: Sowjanya Komatineni @ 2019-02-06 14:48 UTC (permalink / raw)
  To: Dmitry Osipenko, Thierry Reding
  Cc: Jonathan Hunter, Mantravadi Karthik, Shardar Mohammed, Timo Alho,
	linux-tegra@vger.kernel.org, linux-kernel@vger.kernel.org,
	linux-i2c@vger.kernel.org

> >>>>>> Yes please post full log of PIO only and DMA only Also, in above 
> >>>>>> log, lots of DMA transfer went thru fine except this one transfer 
> >>>>>> where DMA timed out.
> >>>>>> DMA completion doesnt happen on DMA submit during this particular 
> >>>>>> transaction timeframe for some reason.
> >>>>>
> >>>>> Dmitry, can you provide some background information on the setup 
> >>>>> that you're using? I vaguely remember something about i2c@7000d000 
> >>>>> being special on older Tegra devices. Perhaps there's something 
> >>>>> additional that we need to take into account?
> >>>>>
> >>>>> Aha! Look at tegra_i2c_reg_addr() which special-cases I2C_TX_FIFO 
> >>>>> on the DVC variant of the controller, which is exactly the one 
> >>>>> that you are seeing the timeouts on and it's exactly the register 
> >>>>> that we use as destination for the DMA transfer.
> >>>>>
> >>>>> I think we need to do something like this:
> >>>>>
> >>>>> 	slv_config.dst_addr = i2c_dev->base_phys + 
> >>>>> tegra_i2c_reg_addr(i2c_dev, I2C_TX_FIFO);
> >>>>>
> >>>>> to make sure we pass the right FIFO register address to DMA.
> >>>>
> >>>> I'm running it on T20 at the moment. I don't know about the DVC quirks, but sounds plausible. Please let me know if you need any other info.
> >>>>
> >>>> Here the full logs:
> >>>>
> >>>> PIO-only: http://dpaste.com/2MX3EAN.txt
> >>>> DMA-only: http://dpaste.com/3VXZSSM.txt
> >>>>
> >>>> Note the "Failed to read T44 and T5 (-110)" error that happens in DMA-only. And it happens on i2c@7000c000, DVC is i2c@7000d000.
> >>>
> >>> Yes this is due to same issue theirry mentioned.
> >>> Prior to transfer timeout for touch, tps6586x regulator probe failed due to i2c timeout which uses DVC (7000D000) and since DMA mode is enforced > all DVC/PWR I2C transactions also go thru DMA and FIFO register for DVC offset is not accounted when configure to dma slave.
> >>> Will fix and send so you can see for repro with updated patch..
> >>>

> >> I think tps6586x and atmel-touch should be independent issues, but will see. Thanks!
> > Whats your platform setup? Is atmel touch power ON default or its programmed during boot by SW whcih need to use DVC?
> > 
> 
> It's "power ON default". I tried to boot in PIO-only mode with tps6586x disabled and there is no "Failed to read T44 and T5" error, atmel probed > successfully.

I see in DMA log bunch of 7000D000 i2c transfers before atmel touch probe. VDD-SYS for 5V is not seen.
So still could be related to power due to DVC transactions timedout as change doesnt account for DVC offset.

Please try updated patch which has fix for DVC transaction failures.

^ permalink raw reply	[flat|nested] 35+ messages in thread

end of thread, other threads:[~2019-02-06 14:48 UTC | newest]

Thread overview: 35+ messages (download: mbox.gz follow: Atom feed
-- links below jump to the message on this page --
2019-02-05 22:46 [PATCH V12 1/5] i2c: tegra: sort all the include headers alphabetically Sowjanya Komatineni
2019-02-05 22:46 ` [PATCH V12 2/5] i2c: tegra: add bus clear Master Support Sowjanya Komatineni
2019-02-05 22:46 ` [PATCH V12 3/5] i2c: tegra: Add DMA support Sowjanya Komatineni
2019-02-06 11:55   ` Dmitry Osipenko
2019-02-06 12:49     ` Sowjanya Komatineni
2019-02-06 13:06       ` Dmitry Osipenko
2019-02-06 12:59     ` Dmitry Osipenko
2019-02-06 13:03       ` Sowjanya Komatineni
2019-02-06 13:05         ` Dmitry Osipenko
2019-02-06 13:17           ` Sowjanya Komatineni
2019-02-06 13:23             ` Dmitry Osipenko
2019-02-06 13:29               ` Sowjanya Komatineni
2019-02-06 13:30                 ` Sowjanya Komatineni
2019-02-06 13:34                   ` Dmitry Osipenko
2019-02-06 13:40                     ` Dmitry Osipenko
2019-02-06 13:09     ` Thierry Reding
2019-02-06 13:13       ` Thierry Reding
2019-02-06 13:18         ` Dmitry Osipenko
2019-02-06 13:25           ` Sowjanya Komatineni
2019-02-06 13:42             ` Dmitry Osipenko
2019-02-06 13:45               ` Sowjanya Komatineni
2019-02-06 13:51                 ` Sowjanya Komatineni
2019-02-06 14:01                   ` Thierry Reding
2019-02-06 14:10                     ` Sowjanya Komatineni
2019-02-06 14:13                     ` Dmitry Osipenko
2019-02-06 14:19                       ` Sowjanya Komatineni
2019-02-06 14:24                         ` Dmitry Osipenko
2019-02-06 14:29                           ` Sowjanya Komatineni
2019-02-06 14:35                             ` Dmitry Osipenko
2019-02-06 14:48                               ` Sowjanya Komatineni
2019-02-06 12:40   ` Dmitry Osipenko
2019-02-06 12:48     ` Thierry Reding
2019-02-06 13:01       ` Dmitry Osipenko
2019-02-05 22:46 ` [PATCH V12 4/5] i2c: tegra: update transfer timeout Sowjanya Komatineni
2019-02-05 22:46 ` [PATCH V12 5/5] i2c: tegra: add i2c interface timing support Sowjanya Komatineni

This is a public inbox, see mirroring instructions
for how to clone and mirror all data and code used for this inbox;
as well as URLs for NNTP newsgroup(s).