linux-arm-kernel.lists.infradead.org archive mirror
 help / color / mirror / Atom feed
* [PATCH 0/4] can: c_can: Add suspend/resume and pinctrl support
@ 2012-09-03 11:52 AnilKumar Ch
  2012-09-03 11:52 ` [PATCH 1/4] can: c_can: Adopt " AnilKumar Ch
                   ` (3 more replies)
  0 siblings, 4 replies; 23+ messages in thread
From: AnilKumar Ch @ 2012-09-03 11:52 UTC (permalink / raw)
  To: linux-arm-kernel

Adds suspend/resume functionality of d_can driver along with d_can
raminit support which is required to initialize RAM while data
transmission.

This patch series also adds pinctrl support to c_can driver. These
patches were tested on AM335x-EVM.

This patch-series is based ontop of runtimePM patch submitted
earlier - https://patchwork.kernel.org/patch/1348081/

AnilKumar Ch (4):
  can: c_can: Adopt pinctrl support
  can: c_can: Add d_can raminit support
  ARM: AM33XX: board-generic: Add of_dev_auxdata to pass d_can raminit
  can: c_can: Add d_can suspend resume support

 arch/arm/mach-omap2/board-generic.c    |   40 +++++++++++++-
 arch/arm/mach-omap2/control.h          |    4 ++
 drivers/net/can/c_can/c_can.c          |   91 ++++++++++++++++++++++++++++++++
 drivers/net/can/c_can/c_can.h          |    7 +++
 drivers/net/can/c_can/c_can_platform.c |   87 ++++++++++++++++++++++++++++--
 include/linux/can/platform/c_can.h     |   36 +++++++++++++
 6 files changed, 261 insertions(+), 4 deletions(-)
 create mode 100644 include/linux/can/platform/c_can.h

-- 
1.7.9.5

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

* [PATCH 1/4] can: c_can: Adopt pinctrl support
  2012-09-03 11:52 [PATCH 0/4] can: c_can: Add suspend/resume and pinctrl support AnilKumar Ch
@ 2012-09-03 11:52 ` AnilKumar Ch
  2012-09-03 20:42   ` Marc Kleine-Budde
  2012-09-03 11:52 ` [PATCH 2/4] can: c_can: Add d_can raminit support AnilKumar Ch
                   ` (2 subsequent siblings)
  3 siblings, 1 reply; 23+ messages in thread
From: AnilKumar Ch @ 2012-09-03 11:52 UTC (permalink / raw)
  To: linux-arm-kernel

Adopt pinctrl support to c_can driver based on c_can device
pointer, pinctrl driver configure SoC pins to d_can mode
according to definitions provided in .dts file.

In device specific device tree file 'pinctrl-names = "default";'
and 'pinctrl-0 = <&d_can1_pins>;' needs to add to configure pins
from c_can driver. d_can1_pins node contains the pinmux/config
details of d_can L/H pins.

Signed-off-by: AnilKumar Ch <anilkumar@ti.com>
---
 drivers/net/can/c_can/c_can_platform.c |    7 +++++++
 1 file changed, 7 insertions(+)

diff --git a/drivers/net/can/c_can/c_can_platform.c b/drivers/net/can/c_can/c_can_platform.c
index 90801c4..c351975 100644
--- a/drivers/net/can/c_can/c_can_platform.c
+++ b/drivers/net/can/c_can/c_can_platform.c
@@ -33,6 +33,7 @@
 #include <linux/of.h>
 #include <linux/of_device.h>
 #include <linux/pm_runtime.h>
+#include <linux/pinctrl/consumer.h>
 
 #include <linux/can/dev.h>
 
@@ -98,6 +99,7 @@ static int __devinit c_can_plat_probe(struct platform_device *pdev)
 	struct c_can_priv *priv;
 	const struct of_device_id *match;
 	const struct platform_device_id *id;
+	struct pinctrl *pinctrl;
 	struct resource *mem;
 	int irq;
 	struct clk *clk;
@@ -114,6 +116,11 @@ static int __devinit c_can_plat_probe(struct platform_device *pdev)
 		id = platform_get_device_id(pdev);
 	}
 
+	pinctrl = devm_pinctrl_get_select_default(&pdev->dev);
+	if (IS_ERR(pinctrl))
+		dev_warn(&pdev->dev,
+			"failed to configure pins from driver\n");
+
 	/* get the appropriate clk */
 	clk = clk_get(&pdev->dev, NULL);
 	if (IS_ERR(clk)) {
-- 
1.7.9.5

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

* [PATCH 2/4] can: c_can: Add d_can raminit support
  2012-09-03 11:52 [PATCH 0/4] can: c_can: Add suspend/resume and pinctrl support AnilKumar Ch
  2012-09-03 11:52 ` [PATCH 1/4] can: c_can: Adopt " AnilKumar Ch
@ 2012-09-03 11:52 ` AnilKumar Ch
  2012-09-03 20:39   ` Marc Kleine-Budde
  2012-09-03 11:52 ` [PATCH 3/4] ARM: AM33XX: board-generic: Add of_dev_auxdata to pass d_can raminit AnilKumar Ch
  2012-09-03 11:52 ` [PATCH 4/4] can: c_can: Add d_can suspend resume support AnilKumar Ch
  3 siblings, 1 reply; 23+ messages in thread
From: AnilKumar Ch @ 2012-09-03 11:52 UTC (permalink / raw)
  To: linux-arm-kernel

Add D_CAN raminit support to C_CAN driver to enable D_CAN RAM.
DCAN RAM holds all the message objects during transmission or
receiving of data. This initialization/de-initialization should
be done in synchronous with D_CAN clock.

Signed-off-by: AnilKumar Ch <anilkumar@ti.com>
---
 drivers/net/can/c_can/c_can.c          |   13 ++++++++++++
 drivers/net/can/c_can/c_can.h          |    2 ++
 drivers/net/can/c_can/c_can_platform.c |   10 +++++++++
 include/linux/can/platform/c_can.h     |   36 ++++++++++++++++++++++++++++++++
 4 files changed, 61 insertions(+)
 create mode 100644 include/linux/can/platform/c_can.h

diff --git a/drivers/net/can/c_can/c_can.c b/drivers/net/can/c_can/c_can.c
index aa6c5eb..c175410 100644
--- a/drivers/net/can/c_can/c_can.c
+++ b/drivers/net/can/c_can/c_can.c
@@ -214,6 +214,12 @@ static inline void c_can_pm_runtime_put_sync(const struct c_can_priv *priv)
 		pm_runtime_put_sync(priv->device);
 }
 
+static inline void c_can_reset_ram(const struct c_can_priv *priv, bool enable)
+{
+	if (priv->ram_init)
+		priv->ram_init(priv->instance, enable);
+}
+
 static inline int get_tx_next_msg_obj(const struct c_can_priv *priv)
 {
 	return (priv->tx_next & C_CAN_NEXT_MSG_OBJ_MASK) +
@@ -1071,6 +1077,8 @@ static int c_can_open(struct net_device *dev)
 	struct c_can_priv *priv = netdev_priv(dev);
 
 	c_can_pm_runtime_get_sync(priv);
+	/* Initialize DCAN RAM */
+	c_can_reset_ram(priv, true);
 
 	/* open the can device */
 	err = open_candev(dev);
@@ -1099,6 +1107,8 @@ static int c_can_open(struct net_device *dev)
 exit_irq_fail:
 	close_candev(dev);
 exit_open_fail:
+	/* De-Initialize DCAN RAM */
+	c_can_reset_ram(priv, false);
 	c_can_pm_runtime_put_sync(priv);
 	return err;
 }
@@ -1112,6 +1122,9 @@ static int c_can_close(struct net_device *dev)
 	c_can_stop(dev);
 	free_irq(dev->irq, dev);
 	close_candev(dev);
+
+	/* De-Initialize DCAN RAM */
+	c_can_reset_ram(priv, false);
 	c_can_pm_runtime_put_sync(priv);
 
 	return 0;
diff --git a/drivers/net/can/c_can/c_can.h b/drivers/net/can/c_can/c_can.h
index 1437a6d..5f6339c 100644
--- a/drivers/net/can/c_can/c_can.h
+++ b/drivers/net/can/c_can/c_can.h
@@ -166,6 +166,8 @@ struct c_can_priv {
 	unsigned int tx_echo;
 	void *priv;		/* for board-specific data */
 	u16 irqstatus;
+	unsigned int instance;
+	void (*ram_init) (unsigned int instance, bool enable);
 };
 
 struct net_device *alloc_c_can_dev(void);
diff --git a/drivers/net/can/c_can/c_can_platform.c b/drivers/net/can/c_can/c_can_platform.c
index c351975..c6963b2 100644
--- a/drivers/net/can/c_can/c_can_platform.c
+++ b/drivers/net/can/c_can/c_can_platform.c
@@ -34,6 +34,7 @@
 #include <linux/of_device.h>
 #include <linux/pm_runtime.h>
 #include <linux/pinctrl/consumer.h>
+#include <linux/can/platform/c_can.h>
 
 #include <linux/can/dev.h>
 
@@ -98,6 +99,7 @@ static int __devinit c_can_plat_probe(struct platform_device *pdev)
 	struct net_device *dev;
 	struct c_can_priv *priv;
 	const struct of_device_id *match;
+	struct c_can_platform_data *pdata = NULL;
 	const struct platform_device_id *id;
 	struct pinctrl *pinctrl;
 	struct resource *mem;
@@ -179,6 +181,14 @@ static int __devinit c_can_plat_probe(struct platform_device *pdev)
 		priv->can.ctrlmode_supported |= CAN_CTRLMODE_3_SAMPLES;
 		priv->read_reg = c_can_plat_read_reg_aligned_to_16bit;
 		priv->write_reg = c_can_plat_write_reg_aligned_to_16bit;
+		pdata = pdev->dev.platform_data;
+		if (!pdata) {
+			dev_err(&pdev->dev, "d_can platform data missing\n");
+			ret = -EINVAL;
+			goto exit_free_device;
+		}
+		priv->ram_init = pdata->ram_init;
+		priv->instance = pdata->instance;
 		break;
 	default:
 		ret = -EINVAL;
diff --git a/include/linux/can/platform/c_can.h b/include/linux/can/platform/c_can.h
new file mode 100644
index 0000000..84b27d2
--- /dev/null
+++ b/include/linux/can/platform/c_can.h
@@ -0,0 +1,36 @@
+/*
+ * C_CAN controller driver platform header
+ *
+ * Copyright (C) 2012 Texas Instruments Incorporated - http://www.ti.com/
+ *
+ * Bosch C_CAN/D_CAN controller is compliant to CAN protocol version 2.0
+ * part A and B.
+ *
+ * This program is free software; you can redistribute it and/or
+ * modify it under the terms of the GNU General Public License as
+ * published by the Free Software Foundation version 2.
+ *
+ * This program is distributed "as is" WITHOUT ANY WARRANTY of any
+ * kind, whether express or implied; without even the implied warranty
+ * of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * GNU General Public License for more details.
+ */
+
+#ifndef __CAN_PLATFORM_C_CAN_H__
+#define __CAN_PLATFORM_C_CAN_H__
+
+/**
+ * struct c_can_platform_data - C_CAN/D_CAN Platform Data
+ *
+ * @instance:		CAN instance, required for d_can raminit
+ * @ram_init:		CAN RAM initialization
+ *
+ * Platform data structure to get all platform specific settings.
+ * this structure also accounts the fact that the IP may have different
+ * RAM for different SOC's
+ */
+struct c_can_platform_data {
+	unsigned int instance;
+	void (*ram_init) (unsigned int instance, bool enable);
+};
+#endif
-- 
1.7.9.5

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

* [PATCH 3/4] ARM: AM33XX: board-generic: Add of_dev_auxdata to pass d_can raminit
  2012-09-03 11:52 [PATCH 0/4] can: c_can: Add suspend/resume and pinctrl support AnilKumar Ch
  2012-09-03 11:52 ` [PATCH 1/4] can: c_can: Adopt " AnilKumar Ch
  2012-09-03 11:52 ` [PATCH 2/4] can: c_can: Add d_can raminit support AnilKumar Ch
@ 2012-09-03 11:52 ` AnilKumar Ch
  2012-09-03 20:11   ` Marc Kleine-Budde
  2012-09-03 11:52 ` [PATCH 4/4] can: c_can: Add d_can suspend resume support AnilKumar Ch
  3 siblings, 1 reply; 23+ messages in thread
From: AnilKumar Ch @ 2012-09-03 11:52 UTC (permalink / raw)
  To: linux-arm-kernel

Add of_dev_auxdata to pass d_can raminit callback APIs to initialize
d_can RAM. D_CAN RAM initialization bits are present in CONTROL module
address space, which can be accessed by platform specific code. So
callback functions are added to serve this purpose, this can done by
using of_dev_auxdata.

Callback API is added to of_dev_auxdata with different instance numbers
for two instances of D_CAN IP. These callback functions are used to
enable/disable D_CAN RAM from CAN driver.

Signed-off-by: AnilKumar Ch <anilkumar@ti.com>
---
 arch/arm/mach-omap2/board-generic.c |   40 ++++++++++++++++++++++++++++++++++-
 arch/arm/mach-omap2/control.h       |    4 ++++
 2 files changed, 43 insertions(+), 1 deletion(-)

diff --git a/arch/arm/mach-omap2/board-generic.c b/arch/arm/mach-omap2/board-generic.c
index 6f93a20..b68e642 100644
--- a/arch/arm/mach-omap2/board-generic.c
+++ b/arch/arm/mach-omap2/board-generic.c
@@ -15,6 +15,7 @@
 #include <linux/of_irq.h>
 #include <linux/of_platform.h>
 #include <linux/irqdomain.h>
+#include <linux/can/platform/c_can.h>
 
 #include <mach/hardware.h>
 #include <asm/hardware/gic.h>
@@ -22,6 +23,8 @@
 
 #include <plat/board.h>
 #include "common.h"
+#include "control.h"
+#include "iomap.h"
 #include "common-board-devices.h"
 
 #if !(defined(CONFIG_ARCH_OMAP2) || defined(CONFIG_ARCH_OMAP3))
@@ -37,11 +40,46 @@ static struct of_device_id omap_dt_match_table[] __initdata = {
 	{ }
 };
 
+void d_can_hw_raminit(unsigned int instance, bool enable)
+{
+	u32 val;
+
+	val = readl(AM33XX_CTRL_REGADDR(AM33XX_CONTROL_DCAN_RAMINIT));
+	if (enable) {
+		val &= ~AM33XX_DCAN_RAMINIT_START_MASK(instance);
+		val |= AM33XX_DCAN_RAMINIT_START_MASK(instance);
+		writel(val, AM33XX_CTRL_REGADDR(AM33XX_CONTROL_DCAN_RAMINIT));
+	} else {
+		val &= ~AM33XX_DCAN_RAMINIT_START_MASK(instance);
+		writel(val, AM33XX_CTRL_REGADDR(AM33XX_CONTROL_DCAN_RAMINIT));
+	}
+}
+
+static struct c_can_platform_data d_can0_pdata = {
+	.ram_init	= d_can_hw_raminit,
+	.instance	= 0,
+};
+
+static struct c_can_platform_data d_can1_pdata = {
+	.ram_init	= d_can_hw_raminit,
+	.instance	= 1,
+};
+
+static const struct of_dev_auxdata am33xx_auxdata_lookup[] __initconst = {
+	OF_DEV_AUXDATA("bosch,d_can", 0x481cc000, NULL, &d_can0_pdata),
+	OF_DEV_AUXDATA("bosch,d_can", 0x481d0000, NULL, &d_can1_pdata),
+	{ },
+};
+
 static void __init omap_generic_init(void)
 {
 	omap_sdrc_init(NULL, NULL);
 
-	of_platform_populate(NULL, omap_dt_match_table, NULL, NULL);
+	if (of_machine_is_compatible("ti,am33xx"))
+		of_platform_populate(NULL, omap_dt_match_table,
+				am33xx_auxdata_lookup, NULL);
+	else
+		of_platform_populate(NULL, omap_dt_match_table, NULL, NULL);
 }
 
 #ifdef CONFIG_SOC_OMAP2420
diff --git a/arch/arm/mach-omap2/control.h b/arch/arm/mach-omap2/control.h
index b8cdc85..afd189b 100644
--- a/arch/arm/mach-omap2/control.h
+++ b/arch/arm/mach-omap2/control.h
@@ -356,6 +356,10 @@
 #define AM33XX_CONTROL_STATUS_SYSBOOT1_SHIFT		22
 #define AM33XX_CONTROL_STATUS_SYSBOOT1_MASK		(0x3 << 22)
 
+/* AM33XX DCAN bitfields */
+#define AM33XX_CONTROL_DCAN_RAMINIT		0x644
+#define AM33XX_DCAN_RAMINIT_START_MASK(i)	(1 << (i))
+
 /* CONTROL OMAP STATUS register to identify OMAP3 features */
 #define OMAP3_CONTROL_OMAP_STATUS	0x044c
 
-- 
1.7.9.5

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

* [PATCH 4/4] can: c_can: Add d_can suspend resume support
  2012-09-03 11:52 [PATCH 0/4] can: c_can: Add suspend/resume and pinctrl support AnilKumar Ch
                   ` (2 preceding siblings ...)
  2012-09-03 11:52 ` [PATCH 3/4] ARM: AM33XX: board-generic: Add of_dev_auxdata to pass d_can raminit AnilKumar Ch
@ 2012-09-03 11:52 ` AnilKumar Ch
  2012-09-03 20:01   ` Marc Kleine-Budde
  3 siblings, 1 reply; 23+ messages in thread
From: AnilKumar Ch @ 2012-09-03 11:52 UTC (permalink / raw)
  To: linux-arm-kernel

Adds suspend resume support to DCAN driver which enables
DCAN power down mode bit (PDR). Then DCAN will ack the local
power-down mode by setting PDA bit in STATUS register.

Also adds a status flag to know the status of DCAN module,
whether it is opened or not.

Signed-off-by: AnilKumar Ch <anilkumar@ti.com>
---
 drivers/net/can/c_can/c_can.c          |   78 ++++++++++++++++++++++++++++++++
 drivers/net/can/c_can/c_can.h          |    5 ++
 drivers/net/can/c_can/c_can_platform.c |   70 ++++++++++++++++++++++++++--
 3 files changed, 150 insertions(+), 3 deletions(-)

diff --git a/drivers/net/can/c_can/c_can.c b/drivers/net/can/c_can/c_can.c
index c175410..36d5db4 100644
--- a/drivers/net/can/c_can/c_can.c
+++ b/drivers/net/can/c_can/c_can.c
@@ -46,6 +46,9 @@
 #define IF_ENUM_REG_LEN		11
 #define C_CAN_IFACE(reg, iface)	(C_CAN_IF1_##reg + (iface) * IF_ENUM_REG_LEN)
 
+/* control extension register D_CAN specific */
+#define CONTROL_EX_PDR		BIT(8)
+
 /* control register */
 #define CONTROL_TEST		BIT(7)
 #define CONTROL_CCE		BIT(6)
@@ -65,6 +68,7 @@
 #define TEST_BASIC		BIT(2)
 
 /* status register */
+#define STATUS_PDA		BIT(10)
 #define STATUS_BOFF		BIT(7)
 #define STATUS_EWARN		BIT(6)
 #define STATUS_EPASS		BIT(5)
@@ -164,6 +168,9 @@
 /* minimum timeout for checking BUSY status */
 #define MIN_TIMEOUT_VALUE	6
 
+/* Wait for ~1 sec for INIT bit */
+#define INIT_WAIT_COUNT		1000
+
 /* napi related */
 #define C_CAN_NAPI_WEIGHT	C_CAN_MSG_OBJ_RX_NUM
 
@@ -1102,6 +1109,7 @@ static int c_can_open(struct net_device *dev)
 
 	netif_start_queue(dev);
 
+	priv->is_opened = true;
 	return 0;
 
 exit_irq_fail:
@@ -1126,6 +1134,7 @@ static int c_can_close(struct net_device *dev)
 	/* De-Initialize DCAN RAM */
 	c_can_reset_ram(priv, false);
 	c_can_pm_runtime_put_sync(priv);
+	priv->is_opened = false;
 
 	return 0;
 }
@@ -1154,6 +1163,75 @@ struct net_device *alloc_c_can_dev(void)
 }
 EXPORT_SYMBOL_GPL(alloc_c_can_dev);
 
+#ifdef CONFIG_PM
+int c_can_power_down(struct net_device *dev)
+{
+	unsigned long time_out;
+	struct c_can_priv *priv = netdev_priv(dev);
+
+	if (!priv->is_opened)
+		return 0;
+
+	/* set `PDR` value so the device goes to power down mode */
+	priv->write_reg(priv, C_CAN_CTRL_EX_REG,
+		priv->read_reg(priv, C_CAN_CTRL_EX_REG) | CONTROL_EX_PDR);
+
+	/* Wait for the PDA bit to get set */
+	time_out = jiffies + msecs_to_jiffies(INIT_WAIT_COUNT);
+	while (!(priv->read_reg(priv, C_CAN_STS_REG) & STATUS_PDA) &&
+				time_after(time_out, jiffies))
+		cpu_relax();
+
+	if (time_after(jiffies, time_out))
+		return -ETIMEDOUT;
+
+	c_can_stop(dev);
+
+	/* De-initialize DCAN RAM */
+	c_can_reset_ram(priv, false);
+	c_can_pm_runtime_put_sync(priv);
+
+	return 0;
+}
+EXPORT_SYMBOL_GPL(c_can_power_down);
+
+int c_can_power_up(struct net_device *dev)
+{
+	unsigned long time_out;
+	struct c_can_priv *priv = netdev_priv(dev);
+
+	if (!priv->is_opened)
+		return 0;
+
+	c_can_pm_runtime_get_sync(priv);
+	/* Initialize DCAN RAM */
+	c_can_reset_ram(priv, true);
+
+	/* Clear PDR and INIT bits */
+	priv->write_reg(priv, C_CAN_CTRL_EX_REG,
+		priv->read_reg(priv, C_CAN_CTRL_EX_REG) & ~CONTROL_EX_PDR);
+	priv->write_reg(priv, C_CAN_CTRL_REG,
+		priv->read_reg(priv, C_CAN_CTRL_REG) & ~CONTROL_INIT);
+
+	/* Wait for the PDA bit to get clear */
+	time_out = jiffies + msecs_to_jiffies(INIT_WAIT_COUNT);
+	while ((priv->read_reg(priv, C_CAN_STS_REG) & STATUS_PDA) &&
+				time_after(time_out, jiffies))
+		cpu_relax();
+
+	if (time_after(jiffies, time_out))
+		return -ETIMEDOUT;
+
+	c_can_start(dev);
+
+	return 0;
+}
+EXPORT_SYMBOL_GPL(c_can_power_up);
+#else
+#define c_can_power_down NULL
+#define c_can_power_up NULL
+#endif
+
 void free_c_can_dev(struct net_device *dev)
 {
 	free_candev(dev);
diff --git a/drivers/net/can/c_can/c_can.h b/drivers/net/can/c_can/c_can.h
index 5f6339c..e5dd7ef 100644
--- a/drivers/net/can/c_can/c_can.h
+++ b/drivers/net/can/c_can/c_can.h
@@ -24,6 +24,7 @@
 
 enum reg {
 	C_CAN_CTRL_REG = 0,
+	C_CAN_CTRL_EX_REG,
 	C_CAN_STS_REG,
 	C_CAN_ERR_CNT_REG,
 	C_CAN_BTR_REG,
@@ -104,6 +105,7 @@ static const u16 reg_map_c_can[] = {
 
 static const u16 reg_map_d_can[] = {
 	[C_CAN_CTRL_REG]	= 0x00,
+	[C_CAN_CTRL_EX_REG]	= 0x02,
 	[C_CAN_STS_REG]		= 0x04,
 	[C_CAN_ERR_CNT_REG]	= 0x08,
 	[C_CAN_BTR_REG]		= 0x0C,
@@ -166,6 +168,7 @@ struct c_can_priv {
 	unsigned int tx_echo;
 	void *priv;		/* for board-specific data */
 	u16 irqstatus;
+	bool is_opened;
 	unsigned int instance;
 	void (*ram_init) (unsigned int instance, bool enable);
 };
@@ -174,5 +177,7 @@ struct net_device *alloc_c_can_dev(void);
 void free_c_can_dev(struct net_device *dev);
 int register_c_can_dev(struct net_device *dev);
 void unregister_c_can_dev(struct net_device *dev);
+int c_can_power_up(struct net_device *dev);
+int c_can_power_down(struct net_device *dev);
 
 #endif /* C_CAN_H */
diff --git a/drivers/net/can/c_can/c_can_platform.c b/drivers/net/can/c_can/c_can_platform.c
index c6963b2..65ec232 100644
--- a/drivers/net/can/c_can/c_can_platform.c
+++ b/drivers/net/can/c_can/c_can_platform.c
@@ -255,15 +255,79 @@ static int __devexit c_can_plat_remove(struct platform_device *pdev)
 	return 0;
 }
 
+#ifdef CONFIG_PM
+static int c_can_suspend(struct platform_device *pdev, pm_message_t state)
+{
+	int ret;
+	struct net_device *ndev = platform_get_drvdata(pdev);
+	struct c_can_priv *priv = netdev_priv(ndev);
+	const struct platform_device_id *id = platform_get_device_id(pdev);
+
+	if (id->driver_data != BOSCH_D_CAN) {
+		dev_warn(&pdev->dev, "Not supported\n");
+		return 0;
+	}
+
+	if (netif_running(ndev)) {
+		netif_stop_queue(ndev);
+		netif_device_detach(ndev);
+	}
+
+	ret = c_can_power_down(ndev);
+	if (ret) {
+		dev_err(&pdev->dev, "failed to enter power down mode\n");
+		return ret;
+	}
+
+	priv->can.state = CAN_STATE_SLEEPING;
+
+	return 0;
+}
+
+static int c_can_resume(struct platform_device *pdev)
+{
+	int ret;
+
+	struct net_device *ndev = platform_get_drvdata(pdev);
+	struct c_can_priv *priv = netdev_priv(ndev);
+	const struct platform_device_id *id = platform_get_device_id(pdev);
+
+	if (id->driver_data != BOSCH_D_CAN) {
+		dev_warn(&pdev->dev, "Not supported\n");
+		return 0;
+	}
+
+	ret = c_can_power_up(ndev);
+	if (ret) {
+		dev_err(&pdev->dev, "Still in power down mode\n");
+		return ret;
+	}
+
+	priv->can.state = CAN_STATE_ERROR_ACTIVE;
+
+	if (netif_running(ndev)) {
+		netif_device_attach(ndev);
+		netif_start_queue(ndev);
+	}
+
+	return 0;
+}
+#else
+#define c_can_suspend NULL
+#define c_can_resume NULL
+#endif
+
 static struct platform_driver c_can_plat_driver = {
 	.driver = {
 		.name = KBUILD_MODNAME,
 		.owner = THIS_MODULE,
 		.of_match_table = of_match_ptr(c_can_of_table),
 	},
-	.probe = c_can_plat_probe,
-	.remove = __devexit_p(c_can_plat_remove),
-	.id_table = c_can_id_table,
+	.probe		= c_can_plat_probe,
+	.remove		= __devexit_p(c_can_plat_remove),
+	.suspend	= c_can_suspend,
+	.resume		= c_can_resume,
+	.id_table	= c_can_id_table,
 };
 
 module_platform_driver(c_can_plat_driver);
-- 
1.7.9.5

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

* [PATCH 4/4] can: c_can: Add d_can suspend resume support
  2012-09-03 11:52 ` [PATCH 4/4] can: c_can: Add d_can suspend resume support AnilKumar Ch
@ 2012-09-03 20:01   ` Marc Kleine-Budde
  2012-09-04  6:14     ` AnilKumar, Chimata
  0 siblings, 1 reply; 23+ messages in thread
From: Marc Kleine-Budde @ 2012-09-03 20:01 UTC (permalink / raw)
  To: linux-arm-kernel

On 09/03/2012 01:52 PM, AnilKumar Ch wrote:
> Adds suspend resume support to DCAN driver which enables
> DCAN power down mode bit (PDR). Then DCAN will ack the local
> power-down mode by setting PDA bit in STATUS register.
> 
> Also adds a status flag to know the status of DCAN module,
> whether it is opened or not.

Use "ndev->flags & IFF_UP" for that. Have a look at the at91_can driver
[1]. I'm not sure if you need locking here.

[1] http://lxr.free-electrons.com/source/drivers/net/can/at91_can.c#L1198

> Signed-off-by: AnilKumar Ch <anilkumar@ti.com>
> ---
>  drivers/net/can/c_can/c_can.c          |   78 ++++++++++++++++++++++++++++++++
>  drivers/net/can/c_can/c_can.h          |    5 ++
>  drivers/net/can/c_can/c_can_platform.c |   70 ++++++++++++++++++++++++++--
>  3 files changed, 150 insertions(+), 3 deletions(-)
> 
> diff --git a/drivers/net/can/c_can/c_can.c b/drivers/net/can/c_can/c_can.c
> index c175410..36d5db4 100644
> --- a/drivers/net/can/c_can/c_can.c
> +++ b/drivers/net/can/c_can/c_can.c
> @@ -46,6 +46,9 @@
>  #define IF_ENUM_REG_LEN		11
>  #define C_CAN_IFACE(reg, iface)	(C_CAN_IF1_##reg + (iface) * IF_ENUM_REG_LEN)
>  
> +/* control extension register D_CAN specific */
> +#define CONTROL_EX_PDR		BIT(8)
> +
>  /* control register */
>  #define CONTROL_TEST		BIT(7)
>  #define CONTROL_CCE		BIT(6)
> @@ -65,6 +68,7 @@
>  #define TEST_BASIC		BIT(2)
>  
>  /* status register */
> +#define STATUS_PDA		BIT(10)
>  #define STATUS_BOFF		BIT(7)
>  #define STATUS_EWARN		BIT(6)
>  #define STATUS_EPASS		BIT(5)
> @@ -164,6 +168,9 @@
>  /* minimum timeout for checking BUSY status */
>  #define MIN_TIMEOUT_VALUE	6
>  
> +/* Wait for ~1 sec for INIT bit */
> +#define INIT_WAIT_COUNT		1000

What unit? INIT_WAIT_MS would be a better name.

> +
>  /* napi related */
>  #define C_CAN_NAPI_WEIGHT	C_CAN_MSG_OBJ_RX_NUM
>  
> @@ -1102,6 +1109,7 @@ static int c_can_open(struct net_device *dev)
>  
>  	netif_start_queue(dev);
>  
> +	priv->is_opened = true;
>  	return 0;
>  
>  exit_irq_fail:
> @@ -1126,6 +1134,7 @@ static int c_can_close(struct net_device *dev)
>  	/* De-Initialize DCAN RAM */
>  	c_can_reset_ram(priv, false);
>  	c_can_pm_runtime_put_sync(priv);
> +	priv->is_opened = false;
>  
>  	return 0;
>  }
> @@ -1154,6 +1163,75 @@ struct net_device *alloc_c_can_dev(void)
>  }
>  EXPORT_SYMBOL_GPL(alloc_c_can_dev);
>  
> +#ifdef CONFIG_PM
> +int c_can_power_down(struct net_device *dev)
> +{
> +	unsigned long time_out;
> +	struct c_can_priv *priv = netdev_priv(dev);
> +
> +	if (!priv->is_opened)
> +		return 0;

Should we add a BUG_ON(id->driver_data != BOSCH_D_CAN)?

> +
> +	/* set `PDR` value so the device goes to power down mode */
> +	priv->write_reg(priv, C_CAN_CTRL_EX_REG,
> +		priv->read_reg(priv, C_CAN_CTRL_EX_REG) | CONTROL_EX_PDR);

Please use an intermediate variable:

u32 val;

val = priv->read_reg(priv, C_CAN_CTRL_EX_REG);
val |= CONTROL_EX_PDR;
priv->write_reg(priv, C_CAN_CTRL_EX_REG, val);

> +
> +	/* Wait for the PDA bit to get set */
> +	time_out = jiffies + msecs_to_jiffies(INIT_WAIT_COUNT);
> +	while (!(priv->read_reg(priv, C_CAN_STS_REG) & STATUS_PDA) &&
> +				time_after(time_out, jiffies))
> +		cpu_relax();
> +
> +	if (time_after(jiffies, time_out))
> +		return -ETIMEDOUT;
> +
> +	c_can_stop(dev);
> +
> +	/* De-initialize DCAN RAM */
> +	c_can_reset_ram(priv, false);
> +	c_can_pm_runtime_put_sync(priv);
> +
> +	return 0;
> +}
> +EXPORT_SYMBOL_GPL(c_can_power_down);
> +
> +int c_can_power_up(struct net_device *dev)
> +{
> +	unsigned long time_out;
> +	struct c_can_priv *priv = netdev_priv(dev);
> +

BUG_ON?

> +	if (!priv->is_opened)
> +		return 0;
> +
> +	c_can_pm_runtime_get_sync(priv);
> +	/* Initialize DCAN RAM */
> +	c_can_reset_ram(priv, true);
> +
> +	/* Clear PDR and INIT bits */
> +	priv->write_reg(priv, C_CAN_CTRL_EX_REG,
> +		priv->read_reg(priv, C_CAN_CTRL_EX_REG) & ~CONTROL_EX_PDR);
> +	priv->write_reg(priv, C_CAN_CTRL_REG,
> +		priv->read_reg(priv, C_CAN_CTRL_REG) & ~CONTROL_INIT);
> +
> +	/* Wait for the PDA bit to get clear */
> +	time_out = jiffies + msecs_to_jiffies(INIT_WAIT_COUNT);
> +	while ((priv->read_reg(priv, C_CAN_STS_REG) & STATUS_PDA) &&
> +				time_after(time_out, jiffies))
> +		cpu_relax();
> +
> +	if (time_after(jiffies, time_out))
> +		return -ETIMEDOUT;
> +
> +	c_can_start(dev);
> +
> +	return 0;
> +}
> +EXPORT_SYMBOL_GPL(c_can_power_up);
> +#else
> +#define c_can_power_down NULL
> +#define c_can_power_up NULL

These are not used, are they?

> +#endif
> +
>  void free_c_can_dev(struct net_device *dev)
>  {
>  	free_candev(dev);
> diff --git a/drivers/net/can/c_can/c_can.h b/drivers/net/can/c_can/c_can.h
> index 5f6339c..e5dd7ef 100644
> --- a/drivers/net/can/c_can/c_can.h
> +++ b/drivers/net/can/c_can/c_can.h
> @@ -24,6 +24,7 @@
>  
>  enum reg {
>  	C_CAN_CTRL_REG = 0,
> +	C_CAN_CTRL_EX_REG,
>  	C_CAN_STS_REG,
>  	C_CAN_ERR_CNT_REG,
>  	C_CAN_BTR_REG,
> @@ -104,6 +105,7 @@ static const u16 reg_map_c_can[] = {
>  
>  static const u16 reg_map_d_can[] = {
>  	[C_CAN_CTRL_REG]	= 0x00,
> +	[C_CAN_CTRL_EX_REG]	= 0x02,
>  	[C_CAN_STS_REG]		= 0x04,
>  	[C_CAN_ERR_CNT_REG]	= 0x08,
>  	[C_CAN_BTR_REG]		= 0x0C,
> @@ -166,6 +168,7 @@ struct c_can_priv {
>  	unsigned int tx_echo;
>  	void *priv;		/* for board-specific data */
>  	u16 irqstatus;
> +	bool is_opened;
>  	unsigned int instance;
>  	void (*ram_init) (unsigned int instance, bool enable);
>  };
> @@ -174,5 +177,7 @@ struct net_device *alloc_c_can_dev(void);
>  void free_c_can_dev(struct net_device *dev);
>  int register_c_can_dev(struct net_device *dev);
>  void unregister_c_can_dev(struct net_device *dev);
> +int c_can_power_up(struct net_device *dev);
> +int c_can_power_down(struct net_device *dev);
>  
>  #endif /* C_CAN_H */
> diff --git a/drivers/net/can/c_can/c_can_platform.c b/drivers/net/can/c_can/c_can_platform.c
> index c6963b2..65ec232 100644
> --- a/drivers/net/can/c_can/c_can_platform.c
> +++ b/drivers/net/can/c_can/c_can_platform.c
> @@ -255,15 +255,79 @@ static int __devexit c_can_plat_remove(struct platform_device *pdev)
>  	return 0;
>  }
>  
> +#ifdef CONFIG_PM
> +static int c_can_suspend(struct platform_device *pdev, pm_message_t state)
> +{
> +	int ret;
> +	struct net_device *ndev = platform_get_drvdata(pdev);
> +	struct c_can_priv *priv = netdev_priv(ndev);
> +	const struct platform_device_id *id = platform_get_device_id(pdev);

Does that work on DT probed devices? You probably have to save the
id->driver_data in struct c_can_priv.

> +
> +	if (id->driver_data != BOSCH_D_CAN) {
> +		dev_warn(&pdev->dev, "Not supported\n");
> +		return 0;
> +	}
> +
> +	if (netif_running(ndev)) {
> +		netif_stop_queue(ndev);
> +		netif_device_detach(ndev);
> +	}
> +
> +	ret = c_can_power_down(ndev);
> +	if (ret) {
> +		dev_err(&pdev->dev, "failed to enter power down mode\n");
netdev_err
> +		return ret;
> +	}
> +
> +	priv->can.state = CAN_STATE_SLEEPING;
> +
> +	return 0;
> +}
> +
> +static int c_can_resume(struct platform_device *pdev)
> +{
> +	int ret;
> +
please remove the empty line ^^
> +	struct net_device *ndev = platform_get_drvdata(pdev);
> +	struct c_can_priv *priv = netdev_priv(ndev);
> +	const struct platform_device_id *id = platform_get_device_id(pdev);
> +
> +	if (id->driver_data != BOSCH_D_CAN) {
> +		dev_warn(&pdev->dev, "Not supported\n");
> +		return 0;
> +	}
> +
> +	ret = c_can_power_up(ndev);
> +	if (ret) {
> +		dev_err(&pdev->dev, "Still in power down mode\n");

netdev_err

> +		return ret;
> +	}
> +
> +	priv->can.state = CAN_STATE_ERROR_ACTIVE;
> +
> +	if (netif_running(ndev)) {
> +		netif_device_attach(ndev);
> +		netif_start_queue(ndev);
> +	}
> +
> +	return 0;
> +}
> +#else
> +#define c_can_suspend NULL
> +#define c_can_resume NULL
> +#endif
> +
>  static struct platform_driver c_can_plat_driver = {
>  	.driver = {
>  		.name = KBUILD_MODNAME,
>  		.owner = THIS_MODULE,
>  		.of_match_table = of_match_ptr(c_can_of_table),
>  	},
> -	.probe = c_can_plat_probe,
> -	.remove = __devexit_p(c_can_plat_remove),
> -	.id_table = c_can_id_table,
> +	.probe		= c_can_plat_probe,
> +	.remove		= __devexit_p(c_can_plat_remove),
> +	.suspend	= c_can_suspend,
> +	.resume		= c_can_resume,
> +	.id_table	= c_can_id_table,

Please don't indent here with tab. Just stay with one space on both
sides of the "=".

>  };
>  
>  module_platform_driver(c_can_plat_driver);
> 

Marc

-- 
Pengutronix e.K.                  | Marc Kleine-Budde           |
Industrial Linux Solutions        | Phone: +49-231-2826-924     |
Vertretung West/Dortmund          | Fax:   +49-5121-206917-5555 |
Amtsgericht Hildesheim, HRA 2686  | http://www.pengutronix.de   |

-------------- next part --------------
A non-text attachment was scrubbed...
Name: signature.asc
Type: application/pgp-signature
Size: 259 bytes
Desc: OpenPGP digital signature
URL: <http://lists.infradead.org/pipermail/linux-arm-kernel/attachments/20120903/99b010f7/attachment.sig>

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

* [PATCH 3/4] ARM: AM33XX: board-generic: Add of_dev_auxdata to pass d_can raminit
  2012-09-03 11:52 ` [PATCH 3/4] ARM: AM33XX: board-generic: Add of_dev_auxdata to pass d_can raminit AnilKumar Ch
@ 2012-09-03 20:11   ` Marc Kleine-Budde
  2012-09-04  6:26     ` AnilKumar, Chimata
  0 siblings, 1 reply; 23+ messages in thread
From: Marc Kleine-Budde @ 2012-09-03 20:11 UTC (permalink / raw)
  To: linux-arm-kernel

On 09/03/2012 01:52 PM, AnilKumar Ch wrote:
> Add of_dev_auxdata to pass d_can raminit callback APIs to initialize
> d_can RAM. D_CAN RAM initialization bits are present in CONTROL module
> address space, which can be accessed by platform specific code. So
> callback functions are added to serve this purpose, this can done by
> using of_dev_auxdata.
> 
> Callback API is added to of_dev_auxdata with different instance numbers
> for two instances of D_CAN IP. These callback functions are used to
> enable/disable D_CAN RAM from CAN driver.
> 
> Signed-off-by: AnilKumar Ch <anilkumar@ti.com>

This will be a more complicated. This patch will go over the arm tree,
but needs a header going via net.

Marc

> ---
>  arch/arm/mach-omap2/board-generic.c |   40 ++++++++++++++++++++++++++++++++++-
>  arch/arm/mach-omap2/control.h       |    4 ++++
>  2 files changed, 43 insertions(+), 1 deletion(-)
> 
> diff --git a/arch/arm/mach-omap2/board-generic.c b/arch/arm/mach-omap2/board-generic.c
> index 6f93a20..b68e642 100644
> --- a/arch/arm/mach-omap2/board-generic.c
> +++ b/arch/arm/mach-omap2/board-generic.c
> @@ -15,6 +15,7 @@
>  #include <linux/of_irq.h>
>  #include <linux/of_platform.h>
>  #include <linux/irqdomain.h>
> +#include <linux/can/platform/c_can.h>
>  
>  #include <mach/hardware.h>
>  #include <asm/hardware/gic.h>
> @@ -22,6 +23,8 @@
>  
>  #include <plat/board.h>
>  #include "common.h"
> +#include "control.h"
> +#include "iomap.h"
>  #include "common-board-devices.h"
>  
>  #if !(defined(CONFIG_ARCH_OMAP2) || defined(CONFIG_ARCH_OMAP3))
> @@ -37,11 +40,46 @@ static struct of_device_id omap_dt_match_table[] __initdata = {
>  	{ }
>  };
>  
> +void d_can_hw_raminit(unsigned int instance, bool enable)
> +{
> +	u32 val;
> +
> +	val = readl(AM33XX_CTRL_REGADDR(AM33XX_CONTROL_DCAN_RAMINIT));
> +	if (enable) {
> +		val &= ~AM33XX_DCAN_RAMINIT_START_MASK(instance);
> +		val |= AM33XX_DCAN_RAMINIT_START_MASK(instance);
> +		writel(val, AM33XX_CTRL_REGADDR(AM33XX_CONTROL_DCAN_RAMINIT));
> +	} else {
> +		val &= ~AM33XX_DCAN_RAMINIT_START_MASK(instance);
> +		writel(val, AM33XX_CTRL_REGADDR(AM33XX_CONTROL_DCAN_RAMINIT));
> +	}
> +}
> +
> +static struct c_can_platform_data d_can0_pdata = {
> +	.ram_init	= d_can_hw_raminit,
> +	.instance	= 0,
> +};
> +
> +static struct c_can_platform_data d_can1_pdata = {
> +	.ram_init	= d_can_hw_raminit,
> +	.instance	= 1,
> +};
> +
> +static const struct of_dev_auxdata am33xx_auxdata_lookup[] __initconst = {
> +	OF_DEV_AUXDATA("bosch,d_can", 0x481cc000, NULL, &d_can0_pdata),
> +	OF_DEV_AUXDATA("bosch,d_can", 0x481d0000, NULL, &d_can1_pdata),
> +	{ },
> +};
> +
>  static void __init omap_generic_init(void)
>  {
>  	omap_sdrc_init(NULL, NULL);
>  
> -	of_platform_populate(NULL, omap_dt_match_table, NULL, NULL);
> +	if (of_machine_is_compatible("ti,am33xx"))
> +		of_platform_populate(NULL, omap_dt_match_table,
> +				am33xx_auxdata_lookup, NULL);
> +	else
> +		of_platform_populate(NULL, omap_dt_match_table, NULL, NULL);
>  }
>  
>  #ifdef CONFIG_SOC_OMAP2420
> diff --git a/arch/arm/mach-omap2/control.h b/arch/arm/mach-omap2/control.h
> index b8cdc85..afd189b 100644
> --- a/arch/arm/mach-omap2/control.h
> +++ b/arch/arm/mach-omap2/control.h
> @@ -356,6 +356,10 @@
>  #define AM33XX_CONTROL_STATUS_SYSBOOT1_SHIFT		22
>  #define AM33XX_CONTROL_STATUS_SYSBOOT1_MASK		(0x3 << 22)
>  
> +/* AM33XX DCAN bitfields */
> +#define AM33XX_CONTROL_DCAN_RAMINIT		0x644
> +#define AM33XX_DCAN_RAMINIT_START_MASK(i)	(1 << (i))
> +
>  /* CONTROL OMAP STATUS register to identify OMAP3 features */
>  #define OMAP3_CONTROL_OMAP_STATUS	0x044c
>  
> 


-- 
Pengutronix e.K.                  | Marc Kleine-Budde           |
Industrial Linux Solutions        | Phone: +49-231-2826-924     |
Vertretung West/Dortmund          | Fax:   +49-5121-206917-5555 |
Amtsgericht Hildesheim, HRA 2686  | http://www.pengutronix.de   |

-------------- next part --------------
A non-text attachment was scrubbed...
Name: signature.asc
Type: application/pgp-signature
Size: 259 bytes
Desc: OpenPGP digital signature
URL: <http://lists.infradead.org/pipermail/linux-arm-kernel/attachments/20120903/dd972ef0/attachment-0001.sig>

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

* [PATCH 2/4] can: c_can: Add d_can raminit support
  2012-09-03 11:52 ` [PATCH 2/4] can: c_can: Add d_can raminit support AnilKumar Ch
@ 2012-09-03 20:39   ` Marc Kleine-Budde
  2012-09-04  6:14     ` AnilKumar, Chimata
  0 siblings, 1 reply; 23+ messages in thread
From: Marc Kleine-Budde @ 2012-09-03 20:39 UTC (permalink / raw)
  To: linux-arm-kernel

On 09/03/2012 01:52 PM, AnilKumar Ch wrote:
> Add D_CAN raminit support to C_CAN driver to enable D_CAN RAM.
> DCAN RAM holds all the message objects during transmission or
> receiving of data. This initialization/de-initialization should
> be done in synchronous with D_CAN clock.
> 
> Signed-off-by: AnilKumar Ch <anilkumar@ti.com>
> ---
>  drivers/net/can/c_can/c_can.c          |   13 ++++++++++++
>  drivers/net/can/c_can/c_can.h          |    2 ++
>  drivers/net/can/c_can/c_can_platform.c |   10 +++++++++
>  include/linux/can/platform/c_can.h     |   36 ++++++++++++++++++++++++++++++++
>  4 files changed, 61 insertions(+)
>  create mode 100644 include/linux/can/platform/c_can.h
> 
> diff --git a/drivers/net/can/c_can/c_can.c b/drivers/net/can/c_can/c_can.c
> index aa6c5eb..c175410 100644
> --- a/drivers/net/can/c_can/c_can.c
> +++ b/drivers/net/can/c_can/c_can.c
> @@ -214,6 +214,12 @@ static inline void c_can_pm_runtime_put_sync(const struct c_can_priv *priv)
>  		pm_runtime_put_sync(priv->device);
>  }
>  
> +static inline void c_can_reset_ram(const struct c_can_priv *priv, bool enable)
> +{
> +	if (priv->ram_init)
> +		priv->ram_init(priv->instance, enable);
> +}
> +
>  static inline int get_tx_next_msg_obj(const struct c_can_priv *priv)
>  {
>  	return (priv->tx_next & C_CAN_NEXT_MSG_OBJ_MASK) +
> @@ -1071,6 +1077,8 @@ static int c_can_open(struct net_device *dev)
>  	struct c_can_priv *priv = netdev_priv(dev);
>  
>  	c_can_pm_runtime_get_sync(priv);
> +	/* Initialize DCAN RAM */
> +	c_can_reset_ram(priv, true);
>  
>  	/* open the can device */
>  	err = open_candev(dev);
> @@ -1099,6 +1107,8 @@ static int c_can_open(struct net_device *dev)
>  exit_irq_fail:
>  	close_candev(dev);
>  exit_open_fail:
> +	/* De-Initialize DCAN RAM */
> +	c_can_reset_ram(priv, false);
>  	c_can_pm_runtime_put_sync(priv);
>  	return err;
>  }
> @@ -1112,6 +1122,9 @@ static int c_can_close(struct net_device *dev)
>  	c_can_stop(dev);
>  	free_irq(dev->irq, dev);
>  	close_candev(dev);
> +
> +	/* De-Initialize DCAN RAM */
> +	c_can_reset_ram(priv, false);
>  	c_can_pm_runtime_put_sync(priv);
>  
>  	return 0;
> diff --git a/drivers/net/can/c_can/c_can.h b/drivers/net/can/c_can/c_can.h
> index 1437a6d..5f6339c 100644
> --- a/drivers/net/can/c_can/c_can.h
> +++ b/drivers/net/can/c_can/c_can.h
> @@ -166,6 +166,8 @@ struct c_can_priv {
>  	unsigned int tx_echo;
>  	void *priv;		/* for board-specific data */
>  	u16 irqstatus;
> +	unsigned int instance;
> +	void (*ram_init) (unsigned int instance, bool enable);
>  };
>  
>  struct net_device *alloc_c_can_dev(void);
> diff --git a/drivers/net/can/c_can/c_can_platform.c b/drivers/net/can/c_can/c_can_platform.c
> index c351975..c6963b2 100644
> --- a/drivers/net/can/c_can/c_can_platform.c
> +++ b/drivers/net/can/c_can/c_can_platform.c
> @@ -34,6 +34,7 @@
>  #include <linux/of_device.h>
>  #include <linux/pm_runtime.h>
>  #include <linux/pinctrl/consumer.h>
> +#include <linux/can/platform/c_can.h>
>  
>  #include <linux/can/dev.h>
>  
> @@ -98,6 +99,7 @@ static int __devinit c_can_plat_probe(struct platform_device *pdev)
>  	struct net_device *dev;
>  	struct c_can_priv *priv;
>  	const struct of_device_id *match;
> +	struct c_can_platform_data *pdata = NULL;
>  	const struct platform_device_id *id;
>  	struct pinctrl *pinctrl;
>  	struct resource *mem;
> @@ -179,6 +181,14 @@ static int __devinit c_can_plat_probe(struct platform_device *pdev)
>  		priv->can.ctrlmode_supported |= CAN_CTRLMODE_3_SAMPLES;
>  		priv->read_reg = c_can_plat_read_reg_aligned_to_16bit;
>  		priv->write_reg = c_can_plat_write_reg_aligned_to_16bit;
> +		pdata = pdev->dev.platform_data;
> +		if (!pdata) {
> +			dev_err(&pdev->dev, "d_can platform data missing\n");
> +			ret = -EINVAL;

Is the ram_init mandatory on all d_can? There might be non omap d_can users.

Marc

> +			goto exit_free_device;
> +		}
> +		priv->ram_init = pdata->ram_init;
> +		priv->instance = pdata->instance;
>  		break;
>  	default:
>  		ret = -EINVAL;
> diff --git a/include/linux/can/platform/c_can.h b/include/linux/can/platform/c_can.h
> new file mode 100644
> index 0000000..84b27d2
> --- /dev/null
> +++ b/include/linux/can/platform/c_can.h
> @@ -0,0 +1,36 @@
> +/*
> + * C_CAN controller driver platform header
> + *
> + * Copyright (C) 2012 Texas Instruments Incorporated - http://www.ti.com/
> + *
> + * Bosch C_CAN/D_CAN controller is compliant to CAN protocol version 2.0
> + * part A and B.
> + *
> + * This program is free software; you can redistribute it and/or
> + * modify it under the terms of the GNU General Public License as
> + * published by the Free Software Foundation version 2.
> + *
> + * This program is distributed "as is" WITHOUT ANY WARRANTY of any
> + * kind, whether express or implied; without even the implied warranty
> + * of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
> + * GNU General Public License for more details.
> + */
> +
> +#ifndef __CAN_PLATFORM_C_CAN_H__
> +#define __CAN_PLATFORM_C_CAN_H__
> +
> +/**
> + * struct c_can_platform_data - C_CAN/D_CAN Platform Data
> + *
> + * @instance:		CAN instance, required for d_can raminit
> + * @ram_init:		CAN RAM initialization
> + *
> + * Platform data structure to get all platform specific settings.
> + * this structure also accounts the fact that the IP may have different
> + * RAM for different SOC's
> + */
> +struct c_can_platform_data {
> +	unsigned int instance;
> +	void (*ram_init) (unsigned int instance, bool enable);
> +};
> +#endif
> 


-- 
Pengutronix e.K.                  | Marc Kleine-Budde           |
Industrial Linux Solutions        | Phone: +49-231-2826-924     |
Vertretung West/Dortmund          | Fax:   +49-5121-206917-5555 |
Amtsgericht Hildesheim, HRA 2686  | http://www.pengutronix.de   |

-------------- next part --------------
A non-text attachment was scrubbed...
Name: signature.asc
Type: application/pgp-signature
Size: 259 bytes
Desc: OpenPGP digital signature
URL: <http://lists.infradead.org/pipermail/linux-arm-kernel/attachments/20120903/4f9a8eb4/attachment.sig>

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

* [PATCH 1/4] can: c_can: Adopt pinctrl support
  2012-09-03 11:52 ` [PATCH 1/4] can: c_can: Adopt " AnilKumar Ch
@ 2012-09-03 20:42   ` Marc Kleine-Budde
  2012-09-04  6:14     ` AnilKumar, Chimata
  0 siblings, 1 reply; 23+ messages in thread
From: Marc Kleine-Budde @ 2012-09-03 20:42 UTC (permalink / raw)
  To: linux-arm-kernel

On 09/03/2012 01:52 PM, AnilKumar Ch wrote:
> Adopt pinctrl support to c_can driver based on c_can device
> pointer, pinctrl driver configure SoC pins to d_can mode
> according to definitions provided in .dts file.
> 
> In device specific device tree file 'pinctrl-names = "default";'
> and 'pinctrl-0 = <&d_can1_pins>;' needs to add to configure pins
> from c_can driver. d_can1_pins node contains the pinmux/config
> details of d_can L/H pins.

Looks good, is the pinctrl property documented in the dt bindings already?

Marc

> 
> Signed-off-by: AnilKumar Ch <anilkumar@ti.com>
> ---
>  drivers/net/can/c_can/c_can_platform.c |    7 +++++++
>  1 file changed, 7 insertions(+)
> 
> diff --git a/drivers/net/can/c_can/c_can_platform.c b/drivers/net/can/c_can/c_can_platform.c
> index 90801c4..c351975 100644
> --- a/drivers/net/can/c_can/c_can_platform.c
> +++ b/drivers/net/can/c_can/c_can_platform.c
> @@ -33,6 +33,7 @@
>  #include <linux/of.h>
>  #include <linux/of_device.h>
>  #include <linux/pm_runtime.h>
> +#include <linux/pinctrl/consumer.h>
>  
>  #include <linux/can/dev.h>
>  
> @@ -98,6 +99,7 @@ static int __devinit c_can_plat_probe(struct platform_device *pdev)
>  	struct c_can_priv *priv;
>  	const struct of_device_id *match;
>  	const struct platform_device_id *id;
> +	struct pinctrl *pinctrl;
>  	struct resource *mem;
>  	int irq;
>  	struct clk *clk;
> @@ -114,6 +116,11 @@ static int __devinit c_can_plat_probe(struct platform_device *pdev)
>  		id = platform_get_device_id(pdev);
>  	}
>  
> +	pinctrl = devm_pinctrl_get_select_default(&pdev->dev);
> +	if (IS_ERR(pinctrl))
> +		dev_warn(&pdev->dev,
> +			"failed to configure pins from driver\n");
> +
>  	/* get the appropriate clk */
>  	clk = clk_get(&pdev->dev, NULL);
>  	if (IS_ERR(clk)) {
> 


-- 
Pengutronix e.K.                  | Marc Kleine-Budde           |
Industrial Linux Solutions        | Phone: +49-231-2826-924     |
Vertretung West/Dortmund          | Fax:   +49-5121-206917-5555 |
Amtsgericht Hildesheim, HRA 2686  | http://www.pengutronix.de   |

-------------- next part --------------
A non-text attachment was scrubbed...
Name: signature.asc
Type: application/pgp-signature
Size: 259 bytes
Desc: OpenPGP digital signature
URL: <http://lists.infradead.org/pipermail/linux-arm-kernel/attachments/20120903/17105472/attachment.sig>

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

* [PATCH 4/4] can: c_can: Add d_can suspend resume support
  2012-09-03 20:01   ` Marc Kleine-Budde
@ 2012-09-04  6:14     ` AnilKumar, Chimata
  2012-09-04  7:27       ` Marc Kleine-Budde
  0 siblings, 1 reply; 23+ messages in thread
From: AnilKumar, Chimata @ 2012-09-04  6:14 UTC (permalink / raw)
  To: linux-arm-kernel

Marc,

Thanks for the comments,

On Tue, Sep 04, 2012 at 01:31:35, Marc Kleine-Budde wrote:
> On 09/03/2012 01:52 PM, AnilKumar Ch wrote:
> > Adds suspend resume support to DCAN driver which enables
> > DCAN power down mode bit (PDR). Then DCAN will ack the local
> > power-down mode by setting PDA bit in STATUS register.
> > 
> > Also adds a status flag to know the status of DCAN module,
> > whether it is opened or not.
> 
> Use "ndev->flags & IFF_UP" for that. Have a look at the at91_can driver
> [1]. I'm not sure if you need locking here.
> 

Then I can use this to check the status, lock is not
required.

> [1] http://lxr.free-electrons.com/source/drivers/net/can/at91_can.c#L1198
> 
> > Signed-off-by: AnilKumar Ch <anilkumar@ti.com>
> > ---
> >  drivers/net/can/c_can/c_can.c          |   78 ++++++++++++++++++++++++++++++++
> >  drivers/net/can/c_can/c_can.h          |    5 ++
> >  drivers/net/can/c_can/c_can_platform.c |   70 ++++++++++++++++++++++++++--
> >  3 files changed, 150 insertions(+), 3 deletions(-)
> > 
> > diff --git a/drivers/net/can/c_can/c_can.c b/drivers/net/can/c_can/c_can.c
> > index c175410..36d5db4 100644
> > --- a/drivers/net/can/c_can/c_can.c
> > +++ b/drivers/net/can/c_can/c_can.c
> > @@ -46,6 +46,9 @@
> >  #define IF_ENUM_REG_LEN		11
> >  #define C_CAN_IFACE(reg, iface)	(C_CAN_IF1_##reg + (iface) * IF_ENUM_REG_LEN)
> >  
> > +/* control extension register D_CAN specific */
> > +#define CONTROL_EX_PDR		BIT(8)
> > +
> >  /* control register */
> >  #define CONTROL_TEST		BIT(7)
> >  #define CONTROL_CCE		BIT(6)
> > @@ -65,6 +68,7 @@
> >  #define TEST_BASIC		BIT(2)
> >  
> >  /* status register */
> > +#define STATUS_PDA		BIT(10)
> >  #define STATUS_BOFF		BIT(7)
> >  #define STATUS_EWARN		BIT(6)
> >  #define STATUS_EPASS		BIT(5)
> > @@ -164,6 +168,9 @@
> >  /* minimum timeout for checking BUSY status */
> >  #define MIN_TIMEOUT_VALUE	6
> >  
> > +/* Wait for ~1 sec for INIT bit */
> > +#define INIT_WAIT_COUNT		1000
> 
> What unit? INIT_WAIT_MS would be a better name.
> 

Sure, will change

> > +
> >  /* napi related */
> >  #define C_CAN_NAPI_WEIGHT	C_CAN_MSG_OBJ_RX_NUM
> >  
> > @@ -1102,6 +1109,7 @@ static int c_can_open(struct net_device *dev)
> >  
> >  	netif_start_queue(dev);
> >  
> > +	priv->is_opened = true;
> >  	return 0;
> >  
> >  exit_irq_fail:
> > @@ -1126,6 +1134,7 @@ static int c_can_close(struct net_device *dev)
> >  	/* De-Initialize DCAN RAM */
> >  	c_can_reset_ram(priv, false);
> >  	c_can_pm_runtime_put_sync(priv);
> > +	priv->is_opened = false;
> >  
> >  	return 0;
> >  }
> > @@ -1154,6 +1163,75 @@ struct net_device *alloc_c_can_dev(void)
> >  }
> >  EXPORT_SYMBOL_GPL(alloc_c_can_dev);
> >  
> > +#ifdef CONFIG_PM
> > +int c_can_power_down(struct net_device *dev)
> > +{
> > +	unsigned long time_out;
> > +	struct c_can_priv *priv = netdev_priv(dev);
> > +
> > +	if (!priv->is_opened)
> > +		return 0;
> 
> Should we add a BUG_ON(id->driver_data != BOSCH_D_CAN)?

These APIs are called from platform driver where device type
device type is verified. I think we have to add BUG_ON() in
platform driver.

> 
> > +
> > +	/* set `PDR` value so the device goes to power down mode */
> > +	priv->write_reg(priv, C_CAN_CTRL_EX_REG,
> > +		priv->read_reg(priv, C_CAN_CTRL_EX_REG) | CONTROL_EX_PDR);
> 
> Please use an intermediate variable:
> 
> u32 val;
> 
> val = priv->read_reg(priv, C_CAN_CTRL_EX_REG);
> val |= CONTROL_EX_PDR;
> priv->write_reg(priv, C_CAN_CTRL_EX_REG, val);

I will change

> 
> > +
> > +	/* Wait for the PDA bit to get set */
> > +	time_out = jiffies + msecs_to_jiffies(INIT_WAIT_COUNT);
> > +	while (!(priv->read_reg(priv, C_CAN_STS_REG) & STATUS_PDA) &&
> > +				time_after(time_out, jiffies))
> > +		cpu_relax();
> > +
> > +	if (time_after(jiffies, time_out))
> > +		return -ETIMEDOUT;
> > +
> > +	c_can_stop(dev);
> > +
> > +	/* De-initialize DCAN RAM */
> > +	c_can_reset_ram(priv, false);
> > +	c_can_pm_runtime_put_sync(priv);
> > +
> > +	return 0;
> > +}
> > +EXPORT_SYMBOL_GPL(c_can_power_down);
> > +
> > +int c_can_power_up(struct net_device *dev)
> > +{
> > +	unsigned long time_out;
> > +	struct c_can_priv *priv = netdev_priv(dev);
> > +
> 
> BUG_ON?
> 
> > +	if (!priv->is_opened)
> > +		return 0;
> > +
> > +	c_can_pm_runtime_get_sync(priv);
> > +	/* Initialize DCAN RAM */
> > +	c_can_reset_ram(priv, true);
> > +
> > +	/* Clear PDR and INIT bits */
> > +	priv->write_reg(priv, C_CAN_CTRL_EX_REG,
> > +		priv->read_reg(priv, C_CAN_CTRL_EX_REG) & ~CONTROL_EX_PDR);
> > +	priv->write_reg(priv, C_CAN_CTRL_REG,
> > +		priv->read_reg(priv, C_CAN_CTRL_REG) & ~CONTROL_INIT);
> > +
> > +	/* Wait for the PDA bit to get clear */
> > +	time_out = jiffies + msecs_to_jiffies(INIT_WAIT_COUNT);
> > +	while ((priv->read_reg(priv, C_CAN_STS_REG) & STATUS_PDA) &&
> > +				time_after(time_out, jiffies))
> > +		cpu_relax();
> > +
> > +	if (time_after(jiffies, time_out))
> > +		return -ETIMEDOUT;
> > +
> > +	c_can_start(dev);
> > +
> > +	return 0;
> > +}
> > +EXPORT_SYMBOL_GPL(c_can_power_up);
> > +#else
> > +#define c_can_power_down NULL
> > +#define c_can_power_up NULL
> 
> These are not used, are they?

Not used, I will remove this else part and adding
#ifdef CONFIG_PM in header file as well.

> 
> > +#endif
> > +
> >  void free_c_can_dev(struct net_device *dev)
> >  {
> >  	free_candev(dev);
> > diff --git a/drivers/net/can/c_can/c_can.h b/drivers/net/can/c_can/c_can.h
> > index 5f6339c..e5dd7ef 100644
> > --- a/drivers/net/can/c_can/c_can.h
> > +++ b/drivers/net/can/c_can/c_can.h
> > @@ -24,6 +24,7 @@
> >  
> >  enum reg {
> >  	C_CAN_CTRL_REG = 0,
> > +	C_CAN_CTRL_EX_REG,
> >  	C_CAN_STS_REG,
> >  	C_CAN_ERR_CNT_REG,
> >  	C_CAN_BTR_REG,
> > @@ -104,6 +105,7 @@ static const u16 reg_map_c_can[] = {
> >  
> >  static const u16 reg_map_d_can[] = {
> >  	[C_CAN_CTRL_REG]	= 0x00,
> > +	[C_CAN_CTRL_EX_REG]	= 0x02,
> >  	[C_CAN_STS_REG]		= 0x04,
> >  	[C_CAN_ERR_CNT_REG]	= 0x08,
> >  	[C_CAN_BTR_REG]		= 0x0C,
> > @@ -166,6 +168,7 @@ struct c_can_priv {
> >  	unsigned int tx_echo;
> >  	void *priv;		/* for board-specific data */
> >  	u16 irqstatus;
> > +	bool is_opened;
> >  	unsigned int instance;
> >  	void (*ram_init) (unsigned int instance, bool enable);
> >  };
> > @@ -174,5 +177,7 @@ struct net_device *alloc_c_can_dev(void);
> >  void free_c_can_dev(struct net_device *dev);
> >  int register_c_can_dev(struct net_device *dev);
> >  void unregister_c_can_dev(struct net_device *dev);
> > +int c_can_power_up(struct net_device *dev);
> > +int c_can_power_down(struct net_device *dev);
> >  
> >  #endif /* C_CAN_H */
> > diff --git a/drivers/net/can/c_can/c_can_platform.c b/drivers/net/can/c_can/c_can_platform.c
> > index c6963b2..65ec232 100644
> > --- a/drivers/net/can/c_can/c_can_platform.c
> > +++ b/drivers/net/can/c_can/c_can_platform.c
> > @@ -255,15 +255,79 @@ static int __devexit c_can_plat_remove(struct platform_device *pdev)
> >  	return 0;
> >  }
> >  
> > +#ifdef CONFIG_PM
> > +static int c_can_suspend(struct platform_device *pdev, pm_message_t state)
> > +{
> > +	int ret;
> > +	struct net_device *ndev = platform_get_drvdata(pdev);
> > +	struct c_can_priv *priv = netdev_priv(ndev);
> > +	const struct platform_device_id *id = platform_get_device_id(pdev);
> 
> Does that work on DT probed devices? You probably have to save the
> id->driver_data in struct c_can_priv.

I will add extra variable to c_can_priv to save the dev_id so
that it will work for dt case as well.

> 
> > +
> > +	if (id->driver_data != BOSCH_D_CAN) {
> > +		dev_warn(&pdev->dev, "Not supported\n");
> > +		return 0;
> > +	}
> > +
> > +	if (netif_running(ndev)) {
> > +		netif_stop_queue(ndev);
> > +		netif_device_detach(ndev);
> > +	}
> > +
> > +	ret = c_can_power_down(ndev);
> > +	if (ret) {
> > +		dev_err(&pdev->dev, "failed to enter power down mode\n");
> netdev_err
> > +		return ret;
> > +	}
> > +
> > +	priv->can.state = CAN_STATE_SLEEPING;
> > +
> > +	return 0;
> > +}
> > +
> > +static int c_can_resume(struct platform_device *pdev)
> > +{
> > +	int ret;
> > +
> please remove the empty line ^^

Sure

> > +	struct net_device *ndev = platform_get_drvdata(pdev);
> > +	struct c_can_priv *priv = netdev_priv(ndev);
> > +	const struct platform_device_id *id = platform_get_device_id(pdev);
> > +
> > +	if (id->driver_data != BOSCH_D_CAN) {
> > +		dev_warn(&pdev->dev, "Not supported\n");
> > +		return 0;
> > +	}
> > +
> > +	ret = c_can_power_up(ndev);
> > +	if (ret) {
> > +		dev_err(&pdev->dev, "Still in power down mode\n");
> 
> netdev_err

I will change.

> 
> > +		return ret;
> > +	}
> > +
> > +	priv->can.state = CAN_STATE_ERROR_ACTIVE;
> > +
> > +	if (netif_running(ndev)) {
> > +		netif_device_attach(ndev);
> > +		netif_start_queue(ndev);
> > +	}
> > +
> > +	return 0;
> > +}
> > +#else
> > +#define c_can_suspend NULL
> > +#define c_can_resume NULL
> > +#endif
> > +
> >  static struct platform_driver c_can_plat_driver = {
> >  	.driver = {
> >  		.name = KBUILD_MODNAME,
> >  		.owner = THIS_MODULE,
> >  		.of_match_table = of_match_ptr(c_can_of_table),
> >  	},
> > -	.probe = c_can_plat_probe,
> > -	.remove = __devexit_p(c_can_plat_remove),
> > -	.id_table = c_can_id_table,
> > +	.probe		= c_can_plat_probe,
> > +	.remove		= __devexit_p(c_can_plat_remove),
> > +	.suspend	= c_can_suspend,
> > +	.resume		= c_can_resume,
> > +	.id_table	= c_can_id_table,
> 
> Please don't indent here with tab. Just stay with one space on both
> sides of the "=".
> 

Point taken

Thanks
AnilKumar

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

* [PATCH 2/4] can: c_can: Add d_can raminit support
  2012-09-03 20:39   ` Marc Kleine-Budde
@ 2012-09-04  6:14     ` AnilKumar, Chimata
  2012-09-04  7:36       ` Vaibhav Hiremath
  0 siblings, 1 reply; 23+ messages in thread
From: AnilKumar, Chimata @ 2012-09-04  6:14 UTC (permalink / raw)
  To: linux-arm-kernel

Hi Marc,

On Tue, Sep 04, 2012 at 02:09:15, Marc Kleine-Budde wrote:
> On 09/03/2012 01:52 PM, AnilKumar Ch wrote:
> > Add D_CAN raminit support to C_CAN driver to enable D_CAN RAM.
> > DCAN RAM holds all the message objects during transmission or
> > receiving of data. This initialization/de-initialization should
> > be done in synchronous with D_CAN clock.
> > 
> > Signed-off-by: AnilKumar Ch <anilkumar@ti.com>
> > ---
> >  drivers/net/can/c_can/c_can.c          |   13 ++++++++++++
> >  drivers/net/can/c_can/c_can.h          |    2 ++
> >  drivers/net/can/c_can/c_can_platform.c |   10 +++++++++
> >  include/linux/can/platform/c_can.h     |   36 ++++++++++++++++++++++++++++++++
> >  4 files changed, 61 insertions(+)
> >  create mode 100644 include/linux/can/platform/c_can.h
> > 
> > diff --git a/drivers/net/can/c_can/c_can.c b/drivers/net/can/c_can/c_can.c
> > index aa6c5eb..c175410 100644
> > --- a/drivers/net/can/c_can/c_can.c
> > +++ b/drivers/net/can/c_can/c_can.c
> > @@ -214,6 +214,12 @@ static inline void c_can_pm_runtime_put_sync(const struct c_can_priv *priv)
> >  		pm_runtime_put_sync(priv->device);
> >  }
> >  
> > +static inline void c_can_reset_ram(const struct c_can_priv *priv, bool enable)
> > +{
> > +	if (priv->ram_init)
> > +		priv->ram_init(priv->instance, enable);
> > +}
> > +
> >  static inline int get_tx_next_msg_obj(const struct c_can_priv *priv)
> >  {
> >  	return (priv->tx_next & C_CAN_NEXT_MSG_OBJ_MASK) +
> > @@ -1071,6 +1077,8 @@ static int c_can_open(struct net_device *dev)
> >  	struct c_can_priv *priv = netdev_priv(dev);
> >  
> >  	c_can_pm_runtime_get_sync(priv);
> > +	/* Initialize DCAN RAM */
> > +	c_can_reset_ram(priv, true);
> >  
> >  	/* open the can device */
> >  	err = open_candev(dev);
> > @@ -1099,6 +1107,8 @@ static int c_can_open(struct net_device *dev)
> >  exit_irq_fail:
> >  	close_candev(dev);
> >  exit_open_fail:
> > +	/* De-Initialize DCAN RAM */
> > +	c_can_reset_ram(priv, false);
> >  	c_can_pm_runtime_put_sync(priv);
> >  	return err;
> >  }
> > @@ -1112,6 +1122,9 @@ static int c_can_close(struct net_device *dev)
> >  	c_can_stop(dev);
> >  	free_irq(dev->irq, dev);
> >  	close_candev(dev);
> > +
> > +	/* De-Initialize DCAN RAM */
> > +	c_can_reset_ram(priv, false);
> >  	c_can_pm_runtime_put_sync(priv);
> >  
> >  	return 0;
> > diff --git a/drivers/net/can/c_can/c_can.h b/drivers/net/can/c_can/c_can.h
> > index 1437a6d..5f6339c 100644
> > --- a/drivers/net/can/c_can/c_can.h
> > +++ b/drivers/net/can/c_can/c_can.h
> > @@ -166,6 +166,8 @@ struct c_can_priv {
> >  	unsigned int tx_echo;
> >  	void *priv;		/* for board-specific data */
> >  	u16 irqstatus;
> > +	unsigned int instance;
> > +	void (*ram_init) (unsigned int instance, bool enable);
> >  };
> >  
> >  struct net_device *alloc_c_can_dev(void);
> > diff --git a/drivers/net/can/c_can/c_can_platform.c b/drivers/net/can/c_can/c_can_platform.c
> > index c351975..c6963b2 100644
> > --- a/drivers/net/can/c_can/c_can_platform.c
> > +++ b/drivers/net/can/c_can/c_can_platform.c
> > @@ -34,6 +34,7 @@
> >  #include <linux/of_device.h>
> >  #include <linux/pm_runtime.h>
> >  #include <linux/pinctrl/consumer.h>
> > +#include <linux/can/platform/c_can.h>
> >  
> >  #include <linux/can/dev.h>
> >  
> > @@ -98,6 +99,7 @@ static int __devinit c_can_plat_probe(struct platform_device *pdev)
> >  	struct net_device *dev;
> >  	struct c_can_priv *priv;
> >  	const struct of_device_id *match;
> > +	struct c_can_platform_data *pdata = NULL;
> >  	const struct platform_device_id *id;
> >  	struct pinctrl *pinctrl;
> >  	struct resource *mem;
> > @@ -179,6 +181,14 @@ static int __devinit c_can_plat_probe(struct platform_device *pdev)
> >  		priv->can.ctrlmode_supported |= CAN_CTRLMODE_3_SAMPLES;
> >  		priv->read_reg = c_can_plat_read_reg_aligned_to_16bit;
> >  		priv->write_reg = c_can_plat_write_reg_aligned_to_16bit;
> > +		pdata = pdev->dev.platform_data;
> > +		if (!pdata) {
> > +			dev_err(&pdev->dev, "d_can platform data missing\n");
> > +			ret = -EINVAL;
> 
> Is the ram_init mandatory on all d_can? There might be non omap d_can users.

As per AM335x specifications d_can module should have ram_init.
In that case it's better to print warning and break the switch.

> 
> Marc
> 
> > +			goto exit_free_device;
> > +		}
> > +		priv->ram_init = pdata->ram_init;
> > +		priv->instance = pdata->instance;
> >  		break;
> >  	default:
> >  		ret = -EINVAL;
> > diff --git a/include/linux/can/platform/c_can.h b/include/linux/can/platform/c_can.h
> > new file mode 100644
> > index 0000000..84b27d2
> > --- /dev/null
> > +++ b/include/linux/can/platform/c_can.h
> > @@ -0,0 +1,36 @@
> > +/*
> > + * C_CAN controller driver platform header
> > + *
> > + * Copyright (C) 2012 Texas Instruments Incorporated - http://www.ti.com/
> > + *
> > + * Bosch C_CAN/D_CAN controller is compliant to CAN protocol version 2.0
> > + * part A and B.
> > + *
> > + * This program is free software; you can redistribute it and/or
> > + * modify it under the terms of the GNU General Public License as
> > + * published by the Free Software Foundation version 2.
> > + *
> > + * This program is distributed "as is" WITHOUT ANY WARRANTY of any
> > + * kind, whether express or implied; without even the implied warranty
> > + * of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
> > + * GNU General Public License for more details.
> > + */
> > +
> > +#ifndef __CAN_PLATFORM_C_CAN_H__
> > +#define __CAN_PLATFORM_C_CAN_H__
> > +
> > +/**
> > + * struct c_can_platform_data - C_CAN/D_CAN Platform Data
> > + *
> > + * @instance:		CAN instance, required for d_can raminit
> > + * @ram_init:		CAN RAM initialization
> > + *
> > + * Platform data structure to get all platform specific settings.
> > + * this structure also accounts the fact that the IP may have different
> > + * RAM for different SOC's
> > + */
> > +struct c_can_platform_data {
> > +	unsigned int instance;
> > +	void (*ram_init) (unsigned int instance, bool enable);
> > +};
> > +#endif
> > 
> 
> 
> -- 
> Pengutronix e.K.                  | Marc Kleine-Budde           |
> Industrial Linux Solutions        | Phone: +49-231-2826-924     |
> Vertretung West/Dortmund          | Fax:   +49-5121-206917-5555 |
> Amtsgericht Hildesheim, HRA 2686  | http://www.pengutronix.de   |
> 
> 

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

* [PATCH 1/4] can: c_can: Adopt pinctrl support
  2012-09-03 20:42   ` Marc Kleine-Budde
@ 2012-09-04  6:14     ` AnilKumar, Chimata
  2012-09-04  7:42       ` Marc Kleine-Budde
  0 siblings, 1 reply; 23+ messages in thread
From: AnilKumar, Chimata @ 2012-09-04  6:14 UTC (permalink / raw)
  To: linux-arm-kernel

Hi Marc,

On Tue, Sep 04, 2012 at 02:12:04, Marc Kleine-Budde wrote:
> On 09/03/2012 01:52 PM, AnilKumar Ch wrote:
> > Adopt pinctrl support to c_can driver based on c_can device
> > pointer, pinctrl driver configure SoC pins to d_can mode
> > according to definitions provided in .dts file.
> > 
> > In device specific device tree file 'pinctrl-names = "default";'
> > and 'pinctrl-0 = <&d_can1_pins>;' needs to add to configure pins
> > from c_can driver. d_can1_pins node contains the pinmux/config
> > details of d_can L/H pins.
> 
> Looks good, is the pinctrl property documented in the dt bindings already?
> 

Yes, its here Documentation/devicetree/bindings/pinctrl/pinctrl-single.txt

Thanks
AnilKumar

> 
> > 
> > Signed-off-by: AnilKumar Ch <anilkumar@ti.com>
> > ---
> >  drivers/net/can/c_can/c_can_platform.c |    7 +++++++
> >  1 file changed, 7 insertions(+)
> > 
> > diff --git a/drivers/net/can/c_can/c_can_platform.c b/drivers/net/can/c_can/c_can_platform.c
> > index 90801c4..c351975 100644
> > --- a/drivers/net/can/c_can/c_can_platform.c
> > +++ b/drivers/net/can/c_can/c_can_platform.c
> > @@ -33,6 +33,7 @@
> >  #include <linux/of.h>
> >  #include <linux/of_device.h>
> >  #include <linux/pm_runtime.h>
> > +#include <linux/pinctrl/consumer.h>
> >  
> >  #include <linux/can/dev.h>
> >  
> > @@ -98,6 +99,7 @@ static int __devinit c_can_plat_probe(struct platform_device *pdev)
> >  	struct c_can_priv *priv;
> >  	const struct of_device_id *match;
> >  	const struct platform_device_id *id;
> > +	struct pinctrl *pinctrl;
> >  	struct resource *mem;
> >  	int irq;
> >  	struct clk *clk;
> > @@ -114,6 +116,11 @@ static int __devinit c_can_plat_probe(struct platform_device *pdev)
> >  		id = platform_get_device_id(pdev);
> >  	}
> >  
> > +	pinctrl = devm_pinctrl_get_select_default(&pdev->dev);
> > +	if (IS_ERR(pinctrl))
> > +		dev_warn(&pdev->dev,
> > +			"failed to configure pins from driver\n");
> > +
> >  	/* get the appropriate clk */
> >  	clk = clk_get(&pdev->dev, NULL);
> >  	if (IS_ERR(clk)) {
> > 
> 
> 
> -- 
> Pengutronix e.K.                  | Marc Kleine-Budde           |
> Industrial Linux Solutions        | Phone: +49-231-2826-924     |
> Vertretung West/Dortmund          | Fax:   +49-5121-206917-5555 |
> Amtsgericht Hildesheim, HRA 2686  | http://www.pengutronix.de   |
> 
> 

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

* [PATCH 3/4] ARM: AM33XX: board-generic: Add of_dev_auxdata to pass d_can raminit
  2012-09-03 20:11   ` Marc Kleine-Budde
@ 2012-09-04  6:26     ` AnilKumar, Chimata
  2012-09-04  7:35       ` Marc Kleine-Budde
  0 siblings, 1 reply; 23+ messages in thread
From: AnilKumar, Chimata @ 2012-09-04  6:26 UTC (permalink / raw)
  To: linux-arm-kernel

On Tue, Sep 04, 2012 at 01:41:14, Marc Kleine-Budde wrote:
> On 09/03/2012 01:52 PM, AnilKumar Ch wrote:
> > Add of_dev_auxdata to pass d_can raminit callback APIs to initialize
> > d_can RAM. D_CAN RAM initialization bits are present in CONTROL module
> > address space, which can be accessed by platform specific code. So
> > callback functions are added to serve this purpose, this can done by
> > using of_dev_auxdata.
> > 
> > Callback API is added to of_dev_auxdata with different instance numbers
> > for two instances of D_CAN IP. These callback functions are used to
> > enable/disable D_CAN RAM from CAN driver.
> > 
> > Signed-off-by: AnilKumar Ch <anilkumar@ti.com>
> 
> This will be a more complicated. This patch will go over the arm tree,
> but needs a header going via net.
> 

Marc,

I agree this is a bit complicated but this has to go along with
this patch series otherwise build will break. If there are no
changes required I will request Tony to ack it.

Tony,

If there are no changes required, could you please ack this patch
so that this will go to linux-can tree.

Thanks
AnilKumar

> 
> > ---
> >  arch/arm/mach-omap2/board-generic.c |   40 ++++++++++++++++++++++++++++++++++-
> >  arch/arm/mach-omap2/control.h       |    4 ++++
> >  2 files changed, 43 insertions(+), 1 deletion(-)
> > 
> > diff --git a/arch/arm/mach-omap2/board-generic.c b/arch/arm/mach-omap2/board-generic.c
> > index 6f93a20..b68e642 100644
> > --- a/arch/arm/mach-omap2/board-generic.c
> > +++ b/arch/arm/mach-omap2/board-generic.c
> > @@ -15,6 +15,7 @@
> >  #include <linux/of_irq.h>
> >  #include <linux/of_platform.h>
> >  #include <linux/irqdomain.h>
> > +#include <linux/can/platform/c_can.h>
> >  
> >  #include <mach/hardware.h>
> >  #include <asm/hardware/gic.h>
> > @@ -22,6 +23,8 @@
> >  
> >  #include <plat/board.h>
> >  #include "common.h"
> > +#include "control.h"
> > +#include "iomap.h"
> >  #include "common-board-devices.h"
> >  
> >  #if !(defined(CONFIG_ARCH_OMAP2) || defined(CONFIG_ARCH_OMAP3))
> > @@ -37,11 +40,46 @@ static struct of_device_id omap_dt_match_table[] __initdata = {
> >  	{ }
> >  };
> >  
> > +void d_can_hw_raminit(unsigned int instance, bool enable)
> > +{
> > +	u32 val;
> > +
> > +	val = readl(AM33XX_CTRL_REGADDR(AM33XX_CONTROL_DCAN_RAMINIT));
> > +	if (enable) {
> > +		val &= ~AM33XX_DCAN_RAMINIT_START_MASK(instance);
> > +		val |= AM33XX_DCAN_RAMINIT_START_MASK(instance);
> > +		writel(val, AM33XX_CTRL_REGADDR(AM33XX_CONTROL_DCAN_RAMINIT));
> > +	} else {
> > +		val &= ~AM33XX_DCAN_RAMINIT_START_MASK(instance);
> > +		writel(val, AM33XX_CTRL_REGADDR(AM33XX_CONTROL_DCAN_RAMINIT));
> > +	}
> > +}
> > +
> > +static struct c_can_platform_data d_can0_pdata = {
> > +	.ram_init	= d_can_hw_raminit,
> > +	.instance	= 0,
> > +};
> > +
> > +static struct c_can_platform_data d_can1_pdata = {
> > +	.ram_init	= d_can_hw_raminit,
> > +	.instance	= 1,
> > +};
> > +
> > +static const struct of_dev_auxdata am33xx_auxdata_lookup[] __initconst = {
> > +	OF_DEV_AUXDATA("bosch,d_can", 0x481cc000, NULL, &d_can0_pdata),
> > +	OF_DEV_AUXDATA("bosch,d_can", 0x481d0000, NULL, &d_can1_pdata),
> > +	{ },
> > +};
> > +
> >  static void __init omap_generic_init(void)
> >  {
> >  	omap_sdrc_init(NULL, NULL);
> >  
> > -	of_platform_populate(NULL, omap_dt_match_table, NULL, NULL);
> > +	if (of_machine_is_compatible("ti,am33xx"))
> > +		of_platform_populate(NULL, omap_dt_match_table,
> > +				am33xx_auxdata_lookup, NULL);
> > +	else
> > +		of_platform_populate(NULL, omap_dt_match_table, NULL, NULL);
> >  }
> >  
> >  #ifdef CONFIG_SOC_OMAP2420
> > diff --git a/arch/arm/mach-omap2/control.h b/arch/arm/mach-omap2/control.h
> > index b8cdc85..afd189b 100644
> > --- a/arch/arm/mach-omap2/control.h
> > +++ b/arch/arm/mach-omap2/control.h
> > @@ -356,6 +356,10 @@
> >  #define AM33XX_CONTROL_STATUS_SYSBOOT1_SHIFT		22
> >  #define AM33XX_CONTROL_STATUS_SYSBOOT1_MASK		(0x3 << 22)
> >  
> > +/* AM33XX DCAN bitfields */
> > +#define AM33XX_CONTROL_DCAN_RAMINIT		0x644
> > +#define AM33XX_DCAN_RAMINIT_START_MASK(i)	(1 << (i))
> > +
> >  /* CONTROL OMAP STATUS register to identify OMAP3 features */
> >  #define OMAP3_CONTROL_OMAP_STATUS	0x044c
> >  
> > 
> 
> 
> -- 
> Pengutronix e.K.                  | Marc Kleine-Budde           |
> Industrial Linux Solutions        | Phone: +49-231-2826-924     |
> Vertretung West/Dortmund          | Fax:   +49-5121-206917-5555 |
> Amtsgericht Hildesheim, HRA 2686  | http://www.pengutronix.de   |
> 
> 

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

* [PATCH 4/4] can: c_can: Add d_can suspend resume support
  2012-09-04  6:14     ` AnilKumar, Chimata
@ 2012-09-04  7:27       ` Marc Kleine-Budde
  2012-09-12 12:48         ` AnilKumar, Chimata
  0 siblings, 1 reply; 23+ messages in thread
From: Marc Kleine-Budde @ 2012-09-04  7:27 UTC (permalink / raw)
  To: linux-arm-kernel

On 09/04/2012 08:14 AM, AnilKumar, Chimata wrote:
> Marc,
> 
> Thanks for the comments,
> 
> On Tue, Sep 04, 2012 at 01:31:35, Marc Kleine-Budde wrote:
>> On 09/03/2012 01:52 PM, AnilKumar Ch wrote:
>>> Adds suspend resume support to DCAN driver which enables
>>> DCAN power down mode bit (PDR). Then DCAN will ack the local
>>> power-down mode by setting PDA bit in STATUS register.
>>>
>>> Also adds a status flag to know the status of DCAN module,
>>> whether it is opened or not.
>>
>> Use "ndev->flags & IFF_UP" for that. Have a look at the at91_can driver
>> [1]. I'm not sure if you need locking here.
>>
> 
> Then I can use this to check the status, lock is not
> required.
> 
>> [1] http://lxr.free-electrons.com/source/drivers/net/can/at91_can.c#L1198
>>
>>> Signed-off-by: AnilKumar Ch <anilkumar@ti.com>
>>> ---
>>>  drivers/net/can/c_can/c_can.c          |   78 ++++++++++++++++++++++++++++++++
>>>  drivers/net/can/c_can/c_can.h          |    5 ++
>>>  drivers/net/can/c_can/c_can_platform.c |   70 ++++++++++++++++++++++++++--
>>>  3 files changed, 150 insertions(+), 3 deletions(-)
>>>
>>> diff --git a/drivers/net/can/c_can/c_can.c b/drivers/net/can/c_can/c_can.c
>>> index c175410..36d5db4 100644
>>> --- a/drivers/net/can/c_can/c_can.c
>>> +++ b/drivers/net/can/c_can/c_can.c
>>> @@ -46,6 +46,9 @@
>>>  #define IF_ENUM_REG_LEN		11
>>>  #define C_CAN_IFACE(reg, iface)	(C_CAN_IF1_##reg + (iface) * IF_ENUM_REG_LEN)
>>>  
>>> +/* control extension register D_CAN specific */
>>> +#define CONTROL_EX_PDR		BIT(8)
>>> +
>>>  /* control register */
>>>  #define CONTROL_TEST		BIT(7)
>>>  #define CONTROL_CCE		BIT(6)
>>> @@ -65,6 +68,7 @@
>>>  #define TEST_BASIC		BIT(2)
>>>  
>>>  /* status register */
>>> +#define STATUS_PDA		BIT(10)
>>>  #define STATUS_BOFF		BIT(7)
>>>  #define STATUS_EWARN		BIT(6)
>>>  #define STATUS_EPASS		BIT(5)
>>> @@ -164,6 +168,9 @@
>>>  /* minimum timeout for checking BUSY status */
>>>  #define MIN_TIMEOUT_VALUE	6
>>>  
>>> +/* Wait for ~1 sec for INIT bit */
>>> +#define INIT_WAIT_COUNT		1000
>>
>> What unit? INIT_WAIT_MS would be a better name.
>>
> 
> Sure, will change
> 
>>> +
>>>  /* napi related */
>>>  #define C_CAN_NAPI_WEIGHT	C_CAN_MSG_OBJ_RX_NUM
>>>  
>>> @@ -1102,6 +1109,7 @@ static int c_can_open(struct net_device *dev)
>>>  
>>>  	netif_start_queue(dev);
>>>  
>>> +	priv->is_opened = true;
>>>  	return 0;
>>>  
>>>  exit_irq_fail:
>>> @@ -1126,6 +1134,7 @@ static int c_can_close(struct net_device *dev)
>>>  	/* De-Initialize DCAN RAM */
>>>  	c_can_reset_ram(priv, false);
>>>  	c_can_pm_runtime_put_sync(priv);
>>> +	priv->is_opened = false;
>>>  
>>>  	return 0;
>>>  }
>>> @@ -1154,6 +1163,75 @@ struct net_device *alloc_c_can_dev(void)
>>>  }
>>>  EXPORT_SYMBOL_GPL(alloc_c_can_dev);
>>>  
>>> +#ifdef CONFIG_PM
>>> +int c_can_power_down(struct net_device *dev)
>>> +{
>>> +	unsigned long time_out;
>>> +	struct c_can_priv *priv = netdev_priv(dev);
>>> +
>>> +	if (!priv->is_opened)
>>> +		return 0;
>>
>> Should we add a BUG_ON(id->driver_data != BOSCH_D_CAN)?
> 
> These APIs are called from platform driver where device type
> device type is verified. I think we have to add BUG_ON() in
> platform driver.

The platform driver returns if not on D_CAN and will not call this
function. But this functions are exported, so can be called by someone
else. So if the caller is not D_CAN, it's a bug.

>>> +
>>> +	/* set `PDR` value so the device goes to power down mode */
>>> +	priv->write_reg(priv, C_CAN_CTRL_EX_REG,
>>> +		priv->read_reg(priv, C_CAN_CTRL_EX_REG) | CONTROL_EX_PDR);
>>
>> Please use an intermediate variable:
>>
>> u32 val;
>>
>> val = priv->read_reg(priv, C_CAN_CTRL_EX_REG);
>> val |= CONTROL_EX_PDR;
>> priv->write_reg(priv, C_CAN_CTRL_EX_REG, val);
> 
> I will change
> 
>>
>>> +
>>> +	/* Wait for the PDA bit to get set */
>>> +	time_out = jiffies + msecs_to_jiffies(INIT_WAIT_COUNT);
>>> +	while (!(priv->read_reg(priv, C_CAN_STS_REG) & STATUS_PDA) &&
>>> +				time_after(time_out, jiffies))
>>> +		cpu_relax();
>>> +
>>> +	if (time_after(jiffies, time_out))
>>> +		return -ETIMEDOUT;
>>> +
>>> +	c_can_stop(dev);
>>> +
>>> +	/* De-initialize DCAN RAM */
>>> +	c_can_reset_ram(priv, false);
>>> +	c_can_pm_runtime_put_sync(priv);
>>> +
>>> +	return 0;
>>> +}
>>> +EXPORT_SYMBOL_GPL(c_can_power_down);
>>> +
>>> +int c_can_power_up(struct net_device *dev)
>>> +{
>>> +	unsigned long time_out;
>>> +	struct c_can_priv *priv = netdev_priv(dev);
>>> +
>>
>> BUG_ON?
>>
>>> +	if (!priv->is_opened)
>>> +		return 0;
>>> +
>>> +	c_can_pm_runtime_get_sync(priv);
>>> +	/* Initialize DCAN RAM */
>>> +	c_can_reset_ram(priv, true);
>>> +
>>> +	/* Clear PDR and INIT bits */
>>> +	priv->write_reg(priv, C_CAN_CTRL_EX_REG,
>>> +		priv->read_reg(priv, C_CAN_CTRL_EX_REG) & ~CONTROL_EX_PDR);
>>> +	priv->write_reg(priv, C_CAN_CTRL_REG,
>>> +		priv->read_reg(priv, C_CAN_CTRL_REG) & ~CONTROL_INIT);
>>> +
>>> +	/* Wait for the PDA bit to get clear */
>>> +	time_out = jiffies + msecs_to_jiffies(INIT_WAIT_COUNT);
>>> +	while ((priv->read_reg(priv, C_CAN_STS_REG) & STATUS_PDA) &&
>>> +				time_after(time_out, jiffies))
>>> +		cpu_relax();
>>> +
>>> +	if (time_after(jiffies, time_out))
>>> +		return -ETIMEDOUT;
>>> +
>>> +	c_can_start(dev);
>>> +
>>> +	return 0;
>>> +}
>>> +EXPORT_SYMBOL_GPL(c_can_power_up);
>>> +#else
>>> +#define c_can_power_down NULL
>>> +#define c_can_power_up NULL
>>
>> These are not used, are they?
> 
> Not used, I will remove this else part and adding
> #ifdef CONFIG_PM in header file as well.


okay.

>>> +#endif
>>> +
>>>  void free_c_can_dev(struct net_device *dev)
>>>  {
>>>  	free_candev(dev);
>>> diff --git a/drivers/net/can/c_can/c_can.h b/drivers/net/can/c_can/c_can.h
>>> index 5f6339c..e5dd7ef 100644
>>> --- a/drivers/net/can/c_can/c_can.h
>>> +++ b/drivers/net/can/c_can/c_can.h
>>> @@ -24,6 +24,7 @@
>>>  
>>>  enum reg {
>>>  	C_CAN_CTRL_REG = 0,
>>> +	C_CAN_CTRL_EX_REG,
>>>  	C_CAN_STS_REG,
>>>  	C_CAN_ERR_CNT_REG,
>>>  	C_CAN_BTR_REG,
>>> @@ -104,6 +105,7 @@ static const u16 reg_map_c_can[] = {
>>>  
>>>  static const u16 reg_map_d_can[] = {
>>>  	[C_CAN_CTRL_REG]	= 0x00,
>>> +	[C_CAN_CTRL_EX_REG]	= 0x02,
>>>  	[C_CAN_STS_REG]		= 0x04,
>>>  	[C_CAN_ERR_CNT_REG]	= 0x08,
>>>  	[C_CAN_BTR_REG]		= 0x0C,
>>> @@ -166,6 +168,7 @@ struct c_can_priv {
>>>  	unsigned int tx_echo;
>>>  	void *priv;		/* for board-specific data */
>>>  	u16 irqstatus;
>>> +	bool is_opened;
>>>  	unsigned int instance;
>>>  	void (*ram_init) (unsigned int instance, bool enable);
>>>  };
>>> @@ -174,5 +177,7 @@ struct net_device *alloc_c_can_dev(void);
>>>  void free_c_can_dev(struct net_device *dev);
>>>  int register_c_can_dev(struct net_device *dev);
>>>  void unregister_c_can_dev(struct net_device *dev);
>>> +int c_can_power_up(struct net_device *dev);
>>> +int c_can_power_down(struct net_device *dev);
>>>  
>>>  #endif /* C_CAN_H */
>>> diff --git a/drivers/net/can/c_can/c_can_platform.c b/drivers/net/can/c_can/c_can_platform.c
>>> index c6963b2..65ec232 100644
>>> --- a/drivers/net/can/c_can/c_can_platform.c
>>> +++ b/drivers/net/can/c_can/c_can_platform.c
>>> @@ -255,15 +255,79 @@ static int __devexit c_can_plat_remove(struct platform_device *pdev)
>>>  	return 0;
>>>  }
>>>  
>>> +#ifdef CONFIG_PM
>>> +static int c_can_suspend(struct platform_device *pdev, pm_message_t state)
>>> +{
>>> +	int ret;
>>> +	struct net_device *ndev = platform_get_drvdata(pdev);
>>> +	struct c_can_priv *priv = netdev_priv(ndev);
>>> +	const struct platform_device_id *id = platform_get_device_id(pdev);
>>
>> Does that work on DT probed devices? You probably have to save the
>> id->driver_data in struct c_can_priv.
> 
> I will add extra variable to c_can_priv to save the dev_id so
> that it will work for dt case as well.
> 
>>
>>> +
>>> +	if (id->driver_data != BOSCH_D_CAN) {
>>> +		dev_warn(&pdev->dev, "Not supported\n");
>>> +		return 0;
>>> +	}
>>> +
>>> +	if (netif_running(ndev)) {
>>> +		netif_stop_queue(ndev);
>>> +		netif_device_detach(ndev);
>>> +	}
>>> +
>>> +	ret = c_can_power_down(ndev);
>>> +	if (ret) {
>>> +		dev_err(&pdev->dev, "failed to enter power down mode\n");
>> netdev_err
>>> +		return ret;
>>> +	}
>>> +
>>> +	priv->can.state = CAN_STATE_SLEEPING;
>>> +
>>> +	return 0;
>>> +}
>>> +
>>> +static int c_can_resume(struct platform_device *pdev)
>>> +{
>>> +	int ret;
>>> +
>> please remove the empty line ^^
> 
> Sure
> 
>>> +	struct net_device *ndev = platform_get_drvdata(pdev);
>>> +	struct c_can_priv *priv = netdev_priv(ndev);
>>> +	const struct platform_device_id *id = platform_get_device_id(pdev);
>>> +
>>> +	if (id->driver_data != BOSCH_D_CAN) {
>>> +		dev_warn(&pdev->dev, "Not supported\n");
>>> +		return 0;
>>> +	}
>>> +
>>> +	ret = c_can_power_up(ndev);
>>> +	if (ret) {
>>> +		dev_err(&pdev->dev, "Still in power down mode\n");
>>
>> netdev_err
> 
> I will change.
> 
>>
>>> +		return ret;
>>> +	}
>>> +
>>> +	priv->can.state = CAN_STATE_ERROR_ACTIVE;
>>> +
>>> +	if (netif_running(ndev)) {
>>> +		netif_device_attach(ndev);
>>> +		netif_start_queue(ndev);
>>> +	}
>>> +
>>> +	return 0;
>>> +}
>>> +#else
>>> +#define c_can_suspend NULL
>>> +#define c_can_resume NULL
>>> +#endif
>>> +
>>>  static struct platform_driver c_can_plat_driver = {
>>>  	.driver = {
>>>  		.name = KBUILD_MODNAME,
>>>  		.owner = THIS_MODULE,
>>>  		.of_match_table = of_match_ptr(c_can_of_table),
>>>  	},
>>> -	.probe = c_can_plat_probe,
>>> -	.remove = __devexit_p(c_can_plat_remove),
>>> -	.id_table = c_can_id_table,
>>> +	.probe		= c_can_plat_probe,
>>> +	.remove		= __devexit_p(c_can_plat_remove),
>>> +	.suspend	= c_can_suspend,
>>> +	.resume		= c_can_resume,
>>> +	.id_table	= c_can_id_table,
>>
>> Please don't indent here with tab. Just stay with one space on both
>> sides of the "=".
>>
> 
> Point taken
> 
> Thanks
> AnilKumar
> 

Marc

-- 
Pengutronix e.K.                  | Marc Kleine-Budde           |
Industrial Linux Solutions        | Phone: +49-231-2826-924     |
Vertretung West/Dortmund          | Fax:   +49-5121-206917-5555 |
Amtsgericht Hildesheim, HRA 2686  | http://www.pengutronix.de   |

-------------- next part --------------
A non-text attachment was scrubbed...
Name: signature.asc
Type: application/pgp-signature
Size: 259 bytes
Desc: OpenPGP digital signature
URL: <http://lists.infradead.org/pipermail/linux-arm-kernel/attachments/20120904/a0f96a43/attachment.sig>

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

* [PATCH 3/4] ARM: AM33XX: board-generic: Add of_dev_auxdata to pass d_can raminit
  2012-09-04  6:26     ` AnilKumar, Chimata
@ 2012-09-04  7:35       ` Marc Kleine-Budde
  0 siblings, 0 replies; 23+ messages in thread
From: Marc Kleine-Budde @ 2012-09-04  7:35 UTC (permalink / raw)
  To: linux-arm-kernel

On 09/04/2012 08:26 AM, AnilKumar, Chimata wrote:
> On Tue, Sep 04, 2012 at 01:41:14, Marc Kleine-Budde wrote:
>> On 09/03/2012 01:52 PM, AnilKumar Ch wrote:
>>> Add of_dev_auxdata to pass d_can raminit callback APIs to initialize
>>> d_can RAM. D_CAN RAM initialization bits are present in CONTROL module
>>> address space, which can be accessed by platform specific code. So
>>> callback functions are added to serve this purpose, this can done by
>>> using of_dev_auxdata.
>>>
>>> Callback API is added to of_dev_auxdata with different instance numbers
>>> for two instances of D_CAN IP. These callback functions are used to
>>> enable/disable D_CAN RAM from CAN driver.
>>>
>>> Signed-off-by: AnilKumar Ch <anilkumar@ti.com>
>>
>> This will be a more complicated. This patch will go over the arm tree,
>> but needs a header going via net.
>>
> 
> Marc,
> 
> I agree this is a bit complicated but this has to go along with
> this patch series otherwise build will break. If there are no
> changes required I will request Tony to ack it.

Yes, an Ack by Tony will help.

> 
> Tony,
> 
> If there are no changes required, could you please ack this patch
> so that this will go to linux-can tree.

Marc

> 
> Thanks
> AnilKumar
> 
>>
>>> ---
>>>  arch/arm/mach-omap2/board-generic.c |   40 ++++++++++++++++++++++++++++++++++-
>>>  arch/arm/mach-omap2/control.h       |    4 ++++
>>>  2 files changed, 43 insertions(+), 1 deletion(-)
>>>
>>> diff --git a/arch/arm/mach-omap2/board-generic.c b/arch/arm/mach-omap2/board-generic.c
>>> index 6f93a20..b68e642 100644
>>> --- a/arch/arm/mach-omap2/board-generic.c
>>> +++ b/arch/arm/mach-omap2/board-generic.c
>>> @@ -15,6 +15,7 @@
>>>  #include <linux/of_irq.h>
>>>  #include <linux/of_platform.h>
>>>  #include <linux/irqdomain.h>
>>> +#include <linux/can/platform/c_can.h>
>>>  
>>>  #include <mach/hardware.h>
>>>  #include <asm/hardware/gic.h>
>>> @@ -22,6 +23,8 @@
>>>  
>>>  #include <plat/board.h>
>>>  #include "common.h"
>>> +#include "control.h"
>>> +#include "iomap.h"
>>>  #include "common-board-devices.h"
>>>  
>>>  #if !(defined(CONFIG_ARCH_OMAP2) || defined(CONFIG_ARCH_OMAP3))
>>> @@ -37,11 +40,46 @@ static struct of_device_id omap_dt_match_table[] __initdata = {
>>>  	{ }
>>>  };
>>>  
>>> +void d_can_hw_raminit(unsigned int instance, bool enable)
>>> +{
>>> +	u32 val;
>>> +
>>> +	val = readl(AM33XX_CTRL_REGADDR(AM33XX_CONTROL_DCAN_RAMINIT));
>>> +	if (enable) {
>>> +		val &= ~AM33XX_DCAN_RAMINIT_START_MASK(instance);
>>> +		val |= AM33XX_DCAN_RAMINIT_START_MASK(instance);
>>> +		writel(val, AM33XX_CTRL_REGADDR(AM33XX_CONTROL_DCAN_RAMINIT));
>>> +	} else {
>>> +		val &= ~AM33XX_DCAN_RAMINIT_START_MASK(instance);
>>> +		writel(val, AM33XX_CTRL_REGADDR(AM33XX_CONTROL_DCAN_RAMINIT));
>>> +	}
>>> +}
>>> +
>>> +static struct c_can_platform_data d_can0_pdata = {
>>> +	.ram_init	= d_can_hw_raminit,
>>> +	.instance	= 0,
>>> +};
>>> +
>>> +static struct c_can_platform_data d_can1_pdata = {
>>> +	.ram_init	= d_can_hw_raminit,
>>> +	.instance	= 1,
>>> +};
>>> +
>>> +static const struct of_dev_auxdata am33xx_auxdata_lookup[] __initconst = {
>>> +	OF_DEV_AUXDATA("bosch,d_can", 0x481cc000, NULL, &d_can0_pdata),
>>> +	OF_DEV_AUXDATA("bosch,d_can", 0x481d0000, NULL, &d_can1_pdata),
>>> +	{ },
>>> +};
>>> +
>>>  static void __init omap_generic_init(void)
>>>  {
>>>  	omap_sdrc_init(NULL, NULL);
>>>  
>>> -	of_platform_populate(NULL, omap_dt_match_table, NULL, NULL);
>>> +	if (of_machine_is_compatible("ti,am33xx"))
>>> +		of_platform_populate(NULL, omap_dt_match_table,
>>> +				am33xx_auxdata_lookup, NULL);
>>> +	else
>>> +		of_platform_populate(NULL, omap_dt_match_table, NULL, NULL);
>>>  }
>>>  
>>>  #ifdef CONFIG_SOC_OMAP2420
>>> diff --git a/arch/arm/mach-omap2/control.h b/arch/arm/mach-omap2/control.h
>>> index b8cdc85..afd189b 100644
>>> --- a/arch/arm/mach-omap2/control.h
>>> +++ b/arch/arm/mach-omap2/control.h
>>> @@ -356,6 +356,10 @@
>>>  #define AM33XX_CONTROL_STATUS_SYSBOOT1_SHIFT		22
>>>  #define AM33XX_CONTROL_STATUS_SYSBOOT1_MASK		(0x3 << 22)
>>>  
>>> +/* AM33XX DCAN bitfields */
>>> +#define AM33XX_CONTROL_DCAN_RAMINIT		0x644
>>> +#define AM33XX_DCAN_RAMINIT_START_MASK(i)	(1 << (i))
>>> +
>>>  /* CONTROL OMAP STATUS register to identify OMAP3 features */
>>>  #define OMAP3_CONTROL_OMAP_STATUS	0x044c
>>>  
>>>
>>
>>
>> -- 
>> Pengutronix e.K.                  | Marc Kleine-Budde           |
>> Industrial Linux Solutions        | Phone: +49-231-2826-924     |
>> Vertretung West/Dortmund          | Fax:   +49-5121-206917-5555 |
>> Amtsgericht Hildesheim, HRA 2686  | http://www.pengutronix.de   |
>>
>>
> 


-- 
Pengutronix e.K.                  | Marc Kleine-Budde           |
Industrial Linux Solutions        | Phone: +49-231-2826-924     |
Vertretung West/Dortmund          | Fax:   +49-5121-206917-5555 |
Amtsgericht Hildesheim, HRA 2686  | http://www.pengutronix.de   |

-------------- next part --------------
A non-text attachment was scrubbed...
Name: signature.asc
Type: application/pgp-signature
Size: 259 bytes
Desc: OpenPGP digital signature
URL: <http://lists.infradead.org/pipermail/linux-arm-kernel/attachments/20120904/150e12e5/attachment.sig>

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

* [PATCH 2/4] can: c_can: Add d_can raminit support
  2012-09-04  6:14     ` AnilKumar, Chimata
@ 2012-09-04  7:36       ` Vaibhav Hiremath
  2012-09-04  7:39         ` Marc Kleine-Budde
  0 siblings, 1 reply; 23+ messages in thread
From: Vaibhav Hiremath @ 2012-09-04  7:36 UTC (permalink / raw)
  To: linux-arm-kernel



On 9/4/2012 11:44 AM, AnilKumar, Chimata wrote:
> Hi Marc,
> 
> On Tue, Sep 04, 2012 at 02:09:15, Marc Kleine-Budde wrote:
>> On 09/03/2012 01:52 PM, AnilKumar Ch wrote:
>>> Add D_CAN raminit support to C_CAN driver to enable D_CAN RAM.
>>> DCAN RAM holds all the message objects during transmission or
>>> receiving of data. This initialization/de-initialization should
>>> be done in synchronous with D_CAN clock.
>>>
>>> Signed-off-by: AnilKumar Ch <anilkumar@ti.com>
>>> ---
>>>  drivers/net/can/c_can/c_can.c          |   13 ++++++++++++
>>>  drivers/net/can/c_can/c_can.h          |    2 ++
>>>  drivers/net/can/c_can/c_can_platform.c |   10 +++++++++
>>>  include/linux/can/platform/c_can.h     |   36 ++++++++++++++++++++++++++++++++
>>>  4 files changed, 61 insertions(+)
>>>  create mode 100644 include/linux/can/platform/c_can.h
>>>
>>> diff --git a/drivers/net/can/c_can/c_can.c b/drivers/net/can/c_can/c_can.c
>>> index aa6c5eb..c175410 100644
>>> --- a/drivers/net/can/c_can/c_can.c
>>> +++ b/drivers/net/can/c_can/c_can.c
>>> @@ -214,6 +214,12 @@ static inline void c_can_pm_runtime_put_sync(const struct c_can_priv *priv)
>>>  		pm_runtime_put_sync(priv->device);
>>>  }
>>>  
>>> +static inline void c_can_reset_ram(const struct c_can_priv *priv, bool enable)
>>> +{
>>> +	if (priv->ram_init)
>>> +		priv->ram_init(priv->instance, enable);
>>> +}
>>> +
>>>  static inline int get_tx_next_msg_obj(const struct c_can_priv *priv)
>>>  {
>>>  	return (priv->tx_next & C_CAN_NEXT_MSG_OBJ_MASK) +
>>> @@ -1071,6 +1077,8 @@ static int c_can_open(struct net_device *dev)
>>>  	struct c_can_priv *priv = netdev_priv(dev);
>>>  
>>>  	c_can_pm_runtime_get_sync(priv);
>>> +	/* Initialize DCAN RAM */
>>> +	c_can_reset_ram(priv, true);
>>>  
>>>  	/* open the can device */
>>>  	err = open_candev(dev);
>>> @@ -1099,6 +1107,8 @@ static int c_can_open(struct net_device *dev)
>>>  exit_irq_fail:
>>>  	close_candev(dev);
>>>  exit_open_fail:
>>> +	/* De-Initialize DCAN RAM */
>>> +	c_can_reset_ram(priv, false);
>>>  	c_can_pm_runtime_put_sync(priv);
>>>  	return err;
>>>  }
>>> @@ -1112,6 +1122,9 @@ static int c_can_close(struct net_device *dev)
>>>  	c_can_stop(dev);
>>>  	free_irq(dev->irq, dev);
>>>  	close_candev(dev);
>>> +
>>> +	/* De-Initialize DCAN RAM */
>>> +	c_can_reset_ram(priv, false);
>>>  	c_can_pm_runtime_put_sync(priv);
>>>  
>>>  	return 0;
>>> diff --git a/drivers/net/can/c_can/c_can.h b/drivers/net/can/c_can/c_can.h
>>> index 1437a6d..5f6339c 100644
>>> --- a/drivers/net/can/c_can/c_can.h
>>> +++ b/drivers/net/can/c_can/c_can.h
>>> @@ -166,6 +166,8 @@ struct c_can_priv {
>>>  	unsigned int tx_echo;
>>>  	void *priv;		/* for board-specific data */
>>>  	u16 irqstatus;
>>> +	unsigned int instance;
>>> +	void (*ram_init) (unsigned int instance, bool enable);
>>>  };
>>>  
>>>  struct net_device *alloc_c_can_dev(void);
>>> diff --git a/drivers/net/can/c_can/c_can_platform.c b/drivers/net/can/c_can/c_can_platform.c
>>> index c351975..c6963b2 100644
>>> --- a/drivers/net/can/c_can/c_can_platform.c
>>> +++ b/drivers/net/can/c_can/c_can_platform.c
>>> @@ -34,6 +34,7 @@
>>>  #include <linux/of_device.h>
>>>  #include <linux/pm_runtime.h>
>>>  #include <linux/pinctrl/consumer.h>
>>> +#include <linux/can/platform/c_can.h>
>>>  
>>>  #include <linux/can/dev.h>
>>>  
>>> @@ -98,6 +99,7 @@ static int __devinit c_can_plat_probe(struct platform_device *pdev)
>>>  	struct net_device *dev;
>>>  	struct c_can_priv *priv;
>>>  	const struct of_device_id *match;
>>> +	struct c_can_platform_data *pdata = NULL;
>>>  	const struct platform_device_id *id;
>>>  	struct pinctrl *pinctrl;
>>>  	struct resource *mem;
>>> @@ -179,6 +181,14 @@ static int __devinit c_can_plat_probe(struct platform_device *pdev)
>>>  		priv->can.ctrlmode_supported |= CAN_CTRLMODE_3_SAMPLES;
>>>  		priv->read_reg = c_can_plat_read_reg_aligned_to_16bit;
>>>  		priv->write_reg = c_can_plat_write_reg_aligned_to_16bit;
>>> +		pdata = pdev->dev.platform_data;
>>> +		if (!pdata) {
>>> +			dev_err(&pdev->dev, "d_can platform data missing\n");
>>> +			ret = -EINVAL;
>>
>> Is the ram_init mandatory on all d_can? There might be non omap d_can users.
> 
> As per AM335x specifications d_can module should have ram_init.
> In that case it's better to print warning and break the switch.
> 

As far as I know, "ram_init" is part of IP spec, how it is controlled
does varies based on SoC integration.

Thanks,
Vaibhav
>>
>> Marc
>>
>>> +			goto exit_free_device;
>>> +		}
>>> +		priv->ram_init = pdata->ram_init;
>>> +		priv->instance = pdata->instance;
>>>  		break;
>>>  	default:
>>>  		ret = -EINVAL;
>>> diff --git a/include/linux/can/platform/c_can.h b/include/linux/can/platform/c_can.h
>>> new file mode 100644
>>> index 0000000..84b27d2
>>> --- /dev/null
>>> +++ b/include/linux/can/platform/c_can.h
>>> @@ -0,0 +1,36 @@
>>> +/*
>>> + * C_CAN controller driver platform header
>>> + *
>>> + * Copyright (C) 2012 Texas Instruments Incorporated - http://www.ti.com/
>>> + *
>>> + * Bosch C_CAN/D_CAN controller is compliant to CAN protocol version 2.0
>>> + * part A and B.
>>> + *
>>> + * This program is free software; you can redistribute it and/or
>>> + * modify it under the terms of the GNU General Public License as
>>> + * published by the Free Software Foundation version 2.
>>> + *
>>> + * This program is distributed "as is" WITHOUT ANY WARRANTY of any
>>> + * kind, whether express or implied; without even the implied warranty
>>> + * of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
>>> + * GNU General Public License for more details.
>>> + */
>>> +
>>> +#ifndef __CAN_PLATFORM_C_CAN_H__
>>> +#define __CAN_PLATFORM_C_CAN_H__
>>> +
>>> +/**
>>> + * struct c_can_platform_data - C_CAN/D_CAN Platform Data
>>> + *
>>> + * @instance:		CAN instance, required for d_can raminit
>>> + * @ram_init:		CAN RAM initialization
>>> + *
>>> + * Platform data structure to get all platform specific settings.
>>> + * this structure also accounts the fact that the IP may have different
>>> + * RAM for different SOC's
>>> + */
>>> +struct c_can_platform_data {
>>> +	unsigned int instance;
>>> +	void (*ram_init) (unsigned int instance, bool enable);
>>> +};
>>> +#endif
>>>
>>
>>
>> -- 
>> Pengutronix e.K.                  | Marc Kleine-Budde           |
>> Industrial Linux Solutions        | Phone: +49-231-2826-924     |
>> Vertretung West/Dortmund          | Fax:   +49-5121-206917-5555 |
>> Amtsgericht Hildesheim, HRA 2686  | http://www.pengutronix.de   |
>>
>>
> 
> 
> _______________________________________________
> linux-arm-kernel mailing list
> linux-arm-kernel at lists.infradead.org
> http://lists.infradead.org/mailman/listinfo/linux-arm-kernel
> 

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

* [PATCH 2/4] can: c_can: Add d_can raminit support
  2012-09-04  7:36       ` Vaibhav Hiremath
@ 2012-09-04  7:39         ` Marc Kleine-Budde
  0 siblings, 0 replies; 23+ messages in thread
From: Marc Kleine-Budde @ 2012-09-04  7:39 UTC (permalink / raw)
  To: linux-arm-kernel

On 09/04/2012 09:36 AM, Vaibhav Hiremath wrote:
> 
> 
> On 9/4/2012 11:44 AM, AnilKumar, Chimata wrote:
>> Hi Marc,
>>
>> On Tue, Sep 04, 2012 at 02:09:15, Marc Kleine-Budde wrote:
>>> On 09/03/2012 01:52 PM, AnilKumar Ch wrote:
>>>> Add D_CAN raminit support to C_CAN driver to enable D_CAN RAM.
>>>> DCAN RAM holds all the message objects during transmission or
>>>> receiving of data. This initialization/de-initialization should
>>>> be done in synchronous with D_CAN clock.
>>>>
>>>> Signed-off-by: AnilKumar Ch <anilkumar@ti.com>
>>>> ---
>>>>  drivers/net/can/c_can/c_can.c          |   13 ++++++++++++
>>>>  drivers/net/can/c_can/c_can.h          |    2 ++
>>>>  drivers/net/can/c_can/c_can_platform.c |   10 +++++++++
>>>>  include/linux/can/platform/c_can.h     |   36 ++++++++++++++++++++++++++++++++
>>>>  4 files changed, 61 insertions(+)
>>>>  create mode 100644 include/linux/can/platform/c_can.h
>>>>
>>>> diff --git a/drivers/net/can/c_can/c_can.c b/drivers/net/can/c_can/c_can.c
>>>> index aa6c5eb..c175410 100644
>>>> --- a/drivers/net/can/c_can/c_can.c
>>>> +++ b/drivers/net/can/c_can/c_can.c
>>>> @@ -214,6 +214,12 @@ static inline void c_can_pm_runtime_put_sync(const struct c_can_priv *priv)
>>>>  		pm_runtime_put_sync(priv->device);
>>>>  }
>>>>  
>>>> +static inline void c_can_reset_ram(const struct c_can_priv *priv, bool enable)
>>>> +{
>>>> +	if (priv->ram_init)
>>>> +		priv->ram_init(priv->instance, enable);
>>>> +}
>>>> +
>>>>  static inline int get_tx_next_msg_obj(const struct c_can_priv *priv)
>>>>  {
>>>>  	return (priv->tx_next & C_CAN_NEXT_MSG_OBJ_MASK) +
>>>> @@ -1071,6 +1077,8 @@ static int c_can_open(struct net_device *dev)
>>>>  	struct c_can_priv *priv = netdev_priv(dev);
>>>>  
>>>>  	c_can_pm_runtime_get_sync(priv);
>>>> +	/* Initialize DCAN RAM */
>>>> +	c_can_reset_ram(priv, true);
>>>>  
>>>>  	/* open the can device */
>>>>  	err = open_candev(dev);
>>>> @@ -1099,6 +1107,8 @@ static int c_can_open(struct net_device *dev)
>>>>  exit_irq_fail:
>>>>  	close_candev(dev);
>>>>  exit_open_fail:
>>>> +	/* De-Initialize DCAN RAM */
>>>> +	c_can_reset_ram(priv, false);
>>>>  	c_can_pm_runtime_put_sync(priv);
>>>>  	return err;
>>>>  }
>>>> @@ -1112,6 +1122,9 @@ static int c_can_close(struct net_device *dev)
>>>>  	c_can_stop(dev);
>>>>  	free_irq(dev->irq, dev);
>>>>  	close_candev(dev);
>>>> +
>>>> +	/* De-Initialize DCAN RAM */
>>>> +	c_can_reset_ram(priv, false);
>>>>  	c_can_pm_runtime_put_sync(priv);
>>>>  
>>>>  	return 0;
>>>> diff --git a/drivers/net/can/c_can/c_can.h b/drivers/net/can/c_can/c_can.h
>>>> index 1437a6d..5f6339c 100644
>>>> --- a/drivers/net/can/c_can/c_can.h
>>>> +++ b/drivers/net/can/c_can/c_can.h
>>>> @@ -166,6 +166,8 @@ struct c_can_priv {
>>>>  	unsigned int tx_echo;
>>>>  	void *priv;		/* for board-specific data */
>>>>  	u16 irqstatus;
>>>> +	unsigned int instance;
>>>> +	void (*ram_init) (unsigned int instance, bool enable);
>>>>  };
>>>>  
>>>>  struct net_device *alloc_c_can_dev(void);
>>>> diff --git a/drivers/net/can/c_can/c_can_platform.c b/drivers/net/can/c_can/c_can_platform.c
>>>> index c351975..c6963b2 100644
>>>> --- a/drivers/net/can/c_can/c_can_platform.c
>>>> +++ b/drivers/net/can/c_can/c_can_platform.c
>>>> @@ -34,6 +34,7 @@
>>>>  #include <linux/of_device.h>
>>>>  #include <linux/pm_runtime.h>
>>>>  #include <linux/pinctrl/consumer.h>
>>>> +#include <linux/can/platform/c_can.h>
>>>>  
>>>>  #include <linux/can/dev.h>
>>>>  
>>>> @@ -98,6 +99,7 @@ static int __devinit c_can_plat_probe(struct platform_device *pdev)
>>>>  	struct net_device *dev;
>>>>  	struct c_can_priv *priv;
>>>>  	const struct of_device_id *match;
>>>> +	struct c_can_platform_data *pdata = NULL;
>>>>  	const struct platform_device_id *id;
>>>>  	struct pinctrl *pinctrl;
>>>>  	struct resource *mem;
>>>> @@ -179,6 +181,14 @@ static int __devinit c_can_plat_probe(struct platform_device *pdev)
>>>>  		priv->can.ctrlmode_supported |= CAN_CTRLMODE_3_SAMPLES;
>>>>  		priv->read_reg = c_can_plat_read_reg_aligned_to_16bit;
>>>>  		priv->write_reg = c_can_plat_write_reg_aligned_to_16bit;
>>>> +		pdata = pdev->dev.platform_data;
>>>> +		if (!pdata) {
>>>> +			dev_err(&pdev->dev, "d_can platform data missing\n");
>>>> +			ret = -EINVAL;
>>>
>>> Is the ram_init mandatory on all d_can? There might be non omap d_can users.
>>
>> As per AM335x specifications d_can module should have ram_init.
>> In that case it's better to print warning and break the switch.
>>
> 
> As far as I know, "ram_init" is part of IP spec, how it is controlled
> does varies based on SoC integration.

Thanks for your insight. Leave the code as it is. If there is another
d_can user we know more and will improve/fix the code :)

Marc

-- 
Pengutronix e.K.                  | Marc Kleine-Budde           |
Industrial Linux Solutions        | Phone: +49-231-2826-924     |
Vertretung West/Dortmund          | Fax:   +49-5121-206917-5555 |
Amtsgericht Hildesheim, HRA 2686  | http://www.pengutronix.de   |

-------------- next part --------------
A non-text attachment was scrubbed...
Name: signature.asc
Type: application/pgp-signature
Size: 259 bytes
Desc: OpenPGP digital signature
URL: <http://lists.infradead.org/pipermail/linux-arm-kernel/attachments/20120904/b8ea6cca/attachment.sig>

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

* [PATCH 1/4] can: c_can: Adopt pinctrl support
  2012-09-04  6:14     ` AnilKumar, Chimata
@ 2012-09-04  7:42       ` Marc Kleine-Budde
  2012-09-04  8:34         ` AnilKumar, Chimata
  0 siblings, 1 reply; 23+ messages in thread
From: Marc Kleine-Budde @ 2012-09-04  7:42 UTC (permalink / raw)
  To: linux-arm-kernel

On 09/04/2012 08:14 AM, AnilKumar, Chimata wrote:
> Hi Marc,
> 
> On Tue, Sep 04, 2012 at 02:12:04, Marc Kleine-Budde wrote:
>> On 09/03/2012 01:52 PM, AnilKumar Ch wrote:
>>> Adopt pinctrl support to c_can driver based on c_can device
>>> pointer, pinctrl driver configure SoC pins to d_can mode
>>> according to definitions provided in .dts file.
>>>
>>> In device specific device tree file 'pinctrl-names = "default";'
>>> and 'pinctrl-0 = <&d_can1_pins>;' needs to add to configure pins
>>> from c_can driver. d_can1_pins node contains the pinmux/config
>>> details of d_can L/H pins.
>>
>> Looks good, is the pinctrl property documented in the dt bindings already?
>>
> 
> Yes, its here Documentation/devicetree/bindings/pinctrl/pinctrl-single.txt

Sorry, I meant not the generic pinctrl, but the c_can/d_can bindings
documentation (Documentation/devicetree/bindings/net/can/).

Marc

-- 
Pengutronix e.K.                  | Marc Kleine-Budde           |
Industrial Linux Solutions        | Phone: +49-231-2826-924     |
Vertretung West/Dortmund          | Fax:   +49-5121-206917-5555 |
Amtsgericht Hildesheim, HRA 2686  | http://www.pengutronix.de   |

-------------- next part --------------
A non-text attachment was scrubbed...
Name: signature.asc
Type: application/pgp-signature
Size: 259 bytes
Desc: OpenPGP digital signature
URL: <http://lists.infradead.org/pipermail/linux-arm-kernel/attachments/20120904/07c12490/attachment.sig>

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

* [PATCH 1/4] can: c_can: Adopt pinctrl support
  2012-09-04  7:42       ` Marc Kleine-Budde
@ 2012-09-04  8:34         ` AnilKumar, Chimata
  0 siblings, 0 replies; 23+ messages in thread
From: AnilKumar, Chimata @ 2012-09-04  8:34 UTC (permalink / raw)
  To: linux-arm-kernel

On Tue, Sep 04, 2012 at 13:12:17, Marc Kleine-Budde wrote:
> On 09/04/2012 08:14 AM, AnilKumar, Chimata wrote:
> > Hi Marc,
> > 
> > On Tue, Sep 04, 2012 at 02:12:04, Marc Kleine-Budde wrote:
> >> On 09/03/2012 01:52 PM, AnilKumar Ch wrote:
> >>> Adopt pinctrl support to c_can driver based on c_can device
> >>> pointer, pinctrl driver configure SoC pins to d_can mode
> >>> according to definitions provided in .dts file.
> >>>
> >>> In device specific device tree file 'pinctrl-names = "default";'
> >>> and 'pinctrl-0 = <&d_can1_pins>;' needs to add to configure pins
> >>> from c_can driver. d_can1_pins node contains the pinmux/config
> >>> details of d_can L/H pins.
> >>
> >> Looks good, is the pinctrl property documented in the dt bindings already?
> >>
> > 
> > Yes, its here Documentation/devicetree/bindings/pinctrl/pinctrl-single.txt
> 
> Sorry, I meant not the generic pinctrl, but the c_can/d_can bindings
> documentation (Documentation/devicetree/bindings/net/can/).
> 

No, I have not included because those are pinctrl driver specific
bindings. If the SoC supports pinmux/conf feature then those should
be added according to pinctrl driver. If the SoC is not supported pinmux/config then this configuration is not required.

Thanks
AnilKumar

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

* [PATCH 4/4] can: c_can: Add d_can suspend resume support
  2012-09-04  7:27       ` Marc Kleine-Budde
@ 2012-09-12 12:48         ` AnilKumar, Chimata
  2012-09-12 13:02           ` Marc Kleine-Budde
  0 siblings, 1 reply; 23+ messages in thread
From: AnilKumar, Chimata @ 2012-09-12 12:48 UTC (permalink / raw)
  To: linux-arm-kernel

Hi Marc,

On Tue, Sep 04, 2012 at 12:57:18, Marc Kleine-Budde wrote:
> On 09/04/2012 08:14 AM, AnilKumar, Chimata wrote:
> > Marc,
> > 
> > Thanks for the comments,
> > 
> > On Tue, Sep 04, 2012 at 01:31:35, Marc Kleine-Budde wrote:
> >> On 09/03/2012 01:52 PM, AnilKumar Ch wrote:
> >>> Adds suspend resume support to DCAN driver which enables
> >>> DCAN power down mode bit (PDR). Then DCAN will ack the local
> >>> power-down mode by setting PDA bit in STATUS register.
> >>>
> >>> Also adds a status flag to know the status of DCAN module,
> >>> whether it is opened or not.
> >>
> >> Use "ndev->flags & IFF_UP" for that. Have a look at the at91_can driver
> >> [1]. I'm not sure if you need locking here.
> >>
> > 
> > Then I can use this to check the status, lock is not
> > required.
> > 
> >> [1] http://lxr.free-electrons.com/source/drivers/net/can/at91_can.c#L1198
> >>
> >>> Signed-off-by: AnilKumar Ch <anilkumar@ti.com>
> >>> ---
> >>>  drivers/net/can/c_can/c_can.c          |   78 ++++++++++++++++++++++++++++++++
> >>>  drivers/net/can/c_can/c_can.h          |    5 ++
> >>>  drivers/net/can/c_can/c_can_platform.c |   70 ++++++++++++++++++++++++++--
> >>>  3 files changed, 150 insertions(+), 3 deletions(-)

[snip]

> >>> +#ifdef CONFIG_PM
> >>> +int c_can_power_down(struct net_device *dev)
> >>> +{
> >>> +	unsigned long time_out;
> >>> +	struct c_can_priv *priv = netdev_priv(dev);
> >>> +
> >>> +	if (!priv->is_opened)
> >>> +		return 0;
> >>
> >> Should we add a BUG_ON(id->driver_data != BOSCH_D_CAN)?
> > 
> > These APIs are called from platform driver where device type
> > device type is verified. I think we have to add BUG_ON() in
> > platform driver.
> 
> The platform driver returns if not on D_CAN and will not call this
> function. But this functions are exported, so can be called by someone
> else. So if the caller is not D_CAN, it's a bug.
>

I agree with you, but I have some concern here.
I think we should do "return 0;" instead of BUG_ON(). With
BUG_ON() system will hang and ultimately user lost his/her
contents.

Thanks
AnilKumar

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

* [PATCH 4/4] can: c_can: Add d_can suspend resume support
  2012-09-12 12:48         ` AnilKumar, Chimata
@ 2012-09-12 13:02           ` Marc Kleine-Budde
  2012-09-13  7:24             ` AnilKumar, Chimata
  0 siblings, 1 reply; 23+ messages in thread
From: Marc Kleine-Budde @ 2012-09-12 13:02 UTC (permalink / raw)
  To: linux-arm-kernel

On 09/12/2012 02:48 PM, AnilKumar, Chimata wrote:
> Hi Marc,
> 
> On Tue, Sep 04, 2012 at 12:57:18, Marc Kleine-Budde wrote:
>> On 09/04/2012 08:14 AM, AnilKumar, Chimata wrote:
>>> Marc,
>>>
>>> Thanks for the comments,
>>>
>>> On Tue, Sep 04, 2012 at 01:31:35, Marc Kleine-Budde wrote:
>>>> On 09/03/2012 01:52 PM, AnilKumar Ch wrote:
>>>>> Adds suspend resume support to DCAN driver which enables
>>>>> DCAN power down mode bit (PDR). Then DCAN will ack the local
>>>>> power-down mode by setting PDA bit in STATUS register.
>>>>>
>>>>> Also adds a status flag to know the status of DCAN module,
>>>>> whether it is opened or not.
>>>>
>>>> Use "ndev->flags & IFF_UP" for that. Have a look at the at91_can driver
>>>> [1]. I'm not sure if you need locking here.
>>>>
>>>
>>> Then I can use this to check the status, lock is not
>>> required.
>>>
>>>> [1] http://lxr.free-electrons.com/source/drivers/net/can/at91_can.c#L1198
>>>>
>>>>> Signed-off-by: AnilKumar Ch <anilkumar@ti.com>
>>>>> ---
>>>>>  drivers/net/can/c_can/c_can.c          |   78 ++++++++++++++++++++++++++++++++
>>>>>  drivers/net/can/c_can/c_can.h          |    5 ++
>>>>>  drivers/net/can/c_can/c_can_platform.c |   70 ++++++++++++++++++++++++++--
>>>>>  3 files changed, 150 insertions(+), 3 deletions(-)
> 
> [snip]
> 
>>>>> +#ifdef CONFIG_PM
>>>>> +int c_can_power_down(struct net_device *dev)
>>>>> +{
>>>>> +	unsigned long time_out;
>>>>> +	struct c_can_priv *priv = netdev_priv(dev);
>>>>> +
>>>>> +	if (!priv->is_opened)
>>>>> +		return 0;
>>>>
>>>> Should we add a BUG_ON(id->driver_data != BOSCH_D_CAN)?
>>>
>>> These APIs are called from platform driver where device type
>>> device type is verified. I think we have to add BUG_ON() in
>>> platform driver.
>>
>> The platform driver returns if not on D_CAN and will not call this
>> function. But this functions are exported, so can be called by someone
>> else. So if the caller is not D_CAN, it's a bug.
>>
> 
> I agree with you, but I have some concern here.
> I think we should do "return 0;" instead of BUG_ON(). With
> BUG_ON() system will hang and ultimately user lost his/her
> contents.

Good point, better safe then sorry.
But this should not happen. What about WARN_ON()?

Marc
-- 
Pengutronix e.K.                  | Marc Kleine-Budde           |
Industrial Linux Solutions        | Phone: +49-231-2826-924     |
Vertretung West/Dortmund          | Fax:   +49-5121-206917-5555 |
Amtsgericht Hildesheim, HRA 2686  | http://www.pengutronix.de   |

-------------- next part --------------
A non-text attachment was scrubbed...
Name: signature.asc
Type: application/pgp-signature
Size: 259 bytes
Desc: OpenPGP digital signature
URL: <http://lists.infradead.org/pipermail/linux-arm-kernel/attachments/20120912/684e24fd/attachment.sig>

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

* [PATCH 4/4] can: c_can: Add d_can suspend resume support
  2012-09-12 13:02           ` Marc Kleine-Budde
@ 2012-09-13  7:24             ` AnilKumar, Chimata
  2012-09-13  8:30               ` Marc Kleine-Budde
  0 siblings, 1 reply; 23+ messages in thread
From: AnilKumar, Chimata @ 2012-09-13  7:24 UTC (permalink / raw)
  To: linux-arm-kernel

Marc,

On Wed, Sep 12, 2012 at 18:32:53, Marc Kleine-Budde wrote:
> On 09/12/2012 02:48 PM, AnilKumar, Chimata wrote:
> > Hi Marc,
> > 
> > On Tue, Sep 04, 2012 at 12:57:18, Marc Kleine-Budde wrote:
> >> On 09/04/2012 08:14 AM, AnilKumar, Chimata wrote:
> >>> Marc,
> >>>
> >>> Thanks for the comments,
> >>>
> >>> On Tue, Sep 04, 2012 at 01:31:35, Marc Kleine-Budde wrote:
> >>>> On 09/03/2012 01:52 PM, AnilKumar Ch wrote:
> >>>>> Adds suspend resume support to DCAN driver which enables
> >>>>> DCAN power down mode bit (PDR). Then DCAN will ack the local
> >>>>> power-down mode by setting PDA bit in STATUS register.
> >>>>>
> >>>>> Also adds a status flag to know the status of DCAN module,
> >>>>> whether it is opened or not.
> >>>>
> >>>> Use "ndev->flags & IFF_UP" for that. Have a look at the at91_can driver
> >>>> [1]. I'm not sure if you need locking here.
> >>>>
> >>>
> >>> Then I can use this to check the status, lock is not
> >>> required.
> >>>
> >>>> [1] http://lxr.free-electrons.com/source/drivers/net/can/at91_can.c#L1198
> >>>>
> >>>>> Signed-off-by: AnilKumar Ch <anilkumar@ti.com>
> >>>>> ---
> >>>>>  drivers/net/can/c_can/c_can.c          |   78 ++++++++++++++++++++++++++++++++
> >>>>>  drivers/net/can/c_can/c_can.h          |    5 ++
> >>>>>  drivers/net/can/c_can/c_can_platform.c |   70 ++++++++++++++++++++++++++--
> >>>>>  3 files changed, 150 insertions(+), 3 deletions(-)
> > 
> > [snip]
> > 
> >>>>> +#ifdef CONFIG_PM
> >>>>> +int c_can_power_down(struct net_device *dev)
> >>>>> +{
> >>>>> +	unsigned long time_out;
> >>>>> +	struct c_can_priv *priv = netdev_priv(dev);
> >>>>> +
> >>>>> +	if (!priv->is_opened)
> >>>>> +		return 0;
> >>>>
> >>>> Should we add a BUG_ON(id->driver_data != BOSCH_D_CAN)?
> >>>
> >>> These APIs are called from platform driver where device type
> >>> device type is verified. I think we have to add BUG_ON() in
> >>> platform driver.
> >>
> >> The platform driver returns if not on D_CAN and will not call this
> >> function. But this functions are exported, so can be called by someone
> >> else. So if the caller is not D_CAN, it's a bug.
> >>
> > 
> > I agree with you, but I have some concern here.
> > I think we should do "return 0;" instead of BUG_ON(). With
> > BUG_ON() system will hang and ultimately user lost his/her
> > contents.
> 
> Good point, better safe then sorry.
> But this should not happen. What about WARN_ON()?
> 

Either would be fine printing a warning message or WARN_ON()

Thanks
AnilKumar

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

* [PATCH 4/4] can: c_can: Add d_can suspend resume support
  2012-09-13  7:24             ` AnilKumar, Chimata
@ 2012-09-13  8:30               ` Marc Kleine-Budde
  0 siblings, 0 replies; 23+ messages in thread
From: Marc Kleine-Budde @ 2012-09-13  8:30 UTC (permalink / raw)
  To: linux-arm-kernel

On 09/13/2012 09:24 AM, AnilKumar, Chimata wrote:
> Marc,
> 
> On Wed, Sep 12, 2012 at 18:32:53, Marc Kleine-Budde wrote:
>> On 09/12/2012 02:48 PM, AnilKumar, Chimata wrote:
>>> Hi Marc,
>>>
>>> On Tue, Sep 04, 2012 at 12:57:18, Marc Kleine-Budde wrote:
>>>> On 09/04/2012 08:14 AM, AnilKumar, Chimata wrote:
>>>>> Marc,
>>>>>
>>>>> Thanks for the comments,
>>>>>
>>>>> On Tue, Sep 04, 2012 at 01:31:35, Marc Kleine-Budde wrote:
>>>>>> On 09/03/2012 01:52 PM, AnilKumar Ch wrote:
>>>>>>> Adds suspend resume support to DCAN driver which enables
>>>>>>> DCAN power down mode bit (PDR). Then DCAN will ack the local
>>>>>>> power-down mode by setting PDA bit in STATUS register.
>>>>>>>
>>>>>>> Also adds a status flag to know the status of DCAN module,
>>>>>>> whether it is opened or not.
>>>>>>
>>>>>> Use "ndev->flags & IFF_UP" for that. Have a look at the at91_can driver
>>>>>> [1]. I'm not sure if you need locking here.
>>>>>>
>>>>>
>>>>> Then I can use this to check the status, lock is not
>>>>> required.
>>>>>
>>>>>> [1] http://lxr.free-electrons.com/source/drivers/net/can/at91_can.c#L1198
>>>>>>
>>>>>>> Signed-off-by: AnilKumar Ch <anilkumar@ti.com>
>>>>>>> ---
>>>>>>>  drivers/net/can/c_can/c_can.c          |   78 ++++++++++++++++++++++++++++++++
>>>>>>>  drivers/net/can/c_can/c_can.h          |    5 ++
>>>>>>>  drivers/net/can/c_can/c_can_platform.c |   70 ++++++++++++++++++++++++++--
>>>>>>>  3 files changed, 150 insertions(+), 3 deletions(-)
>>>
>>> [snip]
>>>
>>>>>>> +#ifdef CONFIG_PM
>>>>>>> +int c_can_power_down(struct net_device *dev)
>>>>>>> +{
>>>>>>> +	unsigned long time_out;
>>>>>>> +	struct c_can_priv *priv = netdev_priv(dev);
>>>>>>> +
>>>>>>> +	if (!priv->is_opened)
>>>>>>> +		return 0;
>>>>>>
>>>>>> Should we add a BUG_ON(id->driver_data != BOSCH_D_CAN)?
>>>>>
>>>>> These APIs are called from platform driver where device type
>>>>> device type is verified. I think we have to add BUG_ON() in
>>>>> platform driver.
>>>>
>>>> The platform driver returns if not on D_CAN and will not call this
>>>> function. But this functions are exported, so can be called by someone
>>>> else. So if the caller is not D_CAN, it's a bug.
>>>>
>>>
>>> I agree with you, but I have some concern here.
>>> I think we should do "return 0;" instead of BUG_ON(). With
>>> BUG_ON() system will hang and ultimately user lost his/her
>>> contents.
>>
>> Good point, better safe then sorry.
>> But this should not happen. What about WARN_ON()?
>>
> 
> Either would be fine printing a warning message or WARN_ON()

I'm for a  WARN_ON()

Marc

-- 
Pengutronix e.K.                  | Marc Kleine-Budde           |
Industrial Linux Solutions        | Phone: +49-231-2826-924     |
Vertretung West/Dortmund          | Fax:   +49-5121-206917-5555 |
Amtsgericht Hildesheim, HRA 2686  | http://www.pengutronix.de   |

-------------- next part --------------
A non-text attachment was scrubbed...
Name: signature.asc
Type: application/pgp-signature
Size: 259 bytes
Desc: OpenPGP digital signature
URL: <http://lists.infradead.org/pipermail/linux-arm-kernel/attachments/20120913/1f206acc/attachment.sig>

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

end of thread, other threads:[~2012-09-13  8:30 UTC | newest]

Thread overview: 23+ messages (download: mbox.gz follow: Atom feed
-- links below jump to the message on this page --
2012-09-03 11:52 [PATCH 0/4] can: c_can: Add suspend/resume and pinctrl support AnilKumar Ch
2012-09-03 11:52 ` [PATCH 1/4] can: c_can: Adopt " AnilKumar Ch
2012-09-03 20:42   ` Marc Kleine-Budde
2012-09-04  6:14     ` AnilKumar, Chimata
2012-09-04  7:42       ` Marc Kleine-Budde
2012-09-04  8:34         ` AnilKumar, Chimata
2012-09-03 11:52 ` [PATCH 2/4] can: c_can: Add d_can raminit support AnilKumar Ch
2012-09-03 20:39   ` Marc Kleine-Budde
2012-09-04  6:14     ` AnilKumar, Chimata
2012-09-04  7:36       ` Vaibhav Hiremath
2012-09-04  7:39         ` Marc Kleine-Budde
2012-09-03 11:52 ` [PATCH 3/4] ARM: AM33XX: board-generic: Add of_dev_auxdata to pass d_can raminit AnilKumar Ch
2012-09-03 20:11   ` Marc Kleine-Budde
2012-09-04  6:26     ` AnilKumar, Chimata
2012-09-04  7:35       ` Marc Kleine-Budde
2012-09-03 11:52 ` [PATCH 4/4] can: c_can: Add d_can suspend resume support AnilKumar Ch
2012-09-03 20:01   ` Marc Kleine-Budde
2012-09-04  6:14     ` AnilKumar, Chimata
2012-09-04  7:27       ` Marc Kleine-Budde
2012-09-12 12:48         ` AnilKumar, Chimata
2012-09-12 13:02           ` Marc Kleine-Budde
2012-09-13  7:24             ` AnilKumar, Chimata
2012-09-13  8:30               ` Marc Kleine-Budde

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).