linux-iio.vger.kernel.org archive mirror
 help / color / mirror / Atom feed
* [PATCH 0/3] i.MX28 LRADC driver
@ 2012-08-03 15:28 Marek Vasut
  2012-08-03 15:28 ` [PATCH 1/3] IIO: Add 4-byte unsigned reads into generic-buffer example Marek Vasut
                   ` (3 more replies)
  0 siblings, 4 replies; 26+ messages in thread
From: Marek Vasut @ 2012-08-03 15:28 UTC (permalink / raw)
  To: linux-iio
  Cc: linux-arm-kernel, Marek Vasut, Jonathan Cameron, Juergen Beisert,
	Lars-Peter Clausen, Wolfgang Denk

Introduce the i.MX28 LRADC driver and support tech that comes with it.

Marek Vasut (3):
  IIO: Add 4-byte unsigned reads into generic-buffer example
  IIO: Add basic MXS LRADC driver
  IIO: arm: Add LRADC to i.MX28 dts

 arch/arm/boot/dts/imx28.dtsi                       |    3 +
 drivers/staging/iio/Documentation/generic_buffer.c |   10 +
 drivers/staging/iio/adc/Kconfig                    |   12 +
 drivers/staging/iio/adc/Makefile                   |    1 +
 drivers/staging/iio/adc/mxs-lradc.c                |  591 ++++++++++++++++++++
 5 files changed, 617 insertions(+)
 create mode 100644 drivers/staging/iio/adc/mxs-lradc.c

Cc: Jonathan Cameron <jic23@kernel.org>
Cc: Juergen Beisert <jbe@pengutronix.de>
Cc: Lars-Peter Clausen <lars@metafoo.de>
Cc: Wolfgang Denk <wd@denx.de>
-- 
1.7.10.4

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

* [PATCH 1/3] IIO: Add 4-byte unsigned reads into generic-buffer example
  2012-08-03 15:28 [PATCH 0/3] i.MX28 LRADC driver Marek Vasut
@ 2012-08-03 15:28 ` Marek Vasut
  2012-08-03 15:28 ` [PATCH 2/3 V2] IIO: Add basic MXS LRADC driver Marek Vasut
                   ` (2 subsequent siblings)
  3 siblings, 0 replies; 26+ messages in thread
From: Marek Vasut @ 2012-08-03 15:28 UTC (permalink / raw)
  To: linux-iio
  Cc: linux-arm-kernel, Marek Vasut, Jonathan Cameron, Juergen Beisert,
	Lars-Peter Clausen, Wolfgang Denk

Add unsigned 32bit-wide reads into the generic-buffer.c

Signed-off-by: Marek Vasut <marex@denx.de>
Cc: Jonathan Cameron <jic23@kernel.org>
Cc: Juergen Beisert <jbe@pengutronix.de>
Cc: Lars-Peter Clausen <lars@metafoo.de>
Cc: Wolfgang Denk <wd@denx.de>
---
 drivers/staging/iio/Documentation/generic_buffer.c |   10 ++++++++++
 1 file changed, 10 insertions(+)

diff --git a/drivers/staging/iio/Documentation/generic_buffer.c b/drivers/staging/iio/Documentation/generic_buffer.c
index 827e92d..40d0eca 100644
--- a/drivers/staging/iio/Documentation/generic_buffer.c
+++ b/drivers/staging/iio/Documentation/generic_buffer.c
@@ -104,6 +104,16 @@ void process_scan(char *data,
 			print2byte(*(uint16_t *)(data + channels[k].location),
 				   &channels[k]);
 			break;
+		case 4:
+			if (!channels[k].is_signed) {
+				uint32_t val = *(uint32_t *)
+					(data + channels[k].location);
+				printf("%05f ", ((float)val +
+						 channels[k].offset)*
+				       channels[k].scale);
+
+			}
+			break;
 		case 8:
 			if (channels[k].is_signed) {
 				int64_t val = *(int64_t *)
-- 
1.7.10.4

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

* [PATCH 2/3 V2] IIO: Add basic MXS LRADC driver
  2012-08-03 15:28 [PATCH 0/3] i.MX28 LRADC driver Marek Vasut
  2012-08-03 15:28 ` [PATCH 1/3] IIO: Add 4-byte unsigned reads into generic-buffer example Marek Vasut
@ 2012-08-03 15:28 ` Marek Vasut
  2012-08-06  2:37   ` Shawn Guo
  2012-08-06  8:49   ` Lars-Peter Clausen
  2012-08-03 15:28 ` [PATCH 3/3] IIO: arm: Add LRADC to i.MX28 dts Marek Vasut
  2012-08-12 14:23 ` [PATCH 0/3] i.MX28 LRADC driver Marek Vasut
  3 siblings, 2 replies; 26+ messages in thread
From: Marek Vasut @ 2012-08-03 15:28 UTC (permalink / raw)
  To: linux-iio
  Cc: linux-arm-kernel, Marek Vasut, Jonathan Cameron, Juergen Beisert,
	Lars-Peter Clausen, Shawn Guo, Wolfgang Denk

This driver is very basic. It supports userland trigger, buffer and
raw access to channels. The support for delay channels is missing
altogether.

Signed-off-by: Marek Vasut <marex@denx.de>
Cc: Jonathan Cameron <jic23@kernel.org>
Cc: Juergen Beisert <jbe@pengutronix.de>
Cc: Lars-Peter Clausen <lars@metafoo.de>
Cc: Shawn Guo <shawn.guo@linaro.org>
Cc: Wolfgang Denk <wd@denx.de>
---
 drivers/staging/iio/adc/Kconfig     |   12 +
 drivers/staging/iio/adc/Makefile    |    1 +
 drivers/staging/iio/adc/mxs-lradc.c |  591 +++++++++++++++++++++++++++++++++++
 3 files changed, 604 insertions(+)
 create mode 100644 drivers/staging/iio/adc/mxs-lradc.c

V2: Use delay channel 0 in case of buffered sampling so the samples are deployed
    continuously.
    Disallow RAW sampling while buffered mode is enabled to simplify code.

diff --git a/drivers/staging/iio/adc/Kconfig b/drivers/staging/iio/adc/Kconfig
index 67711b7..97ca697 100644
--- a/drivers/staging/iio/adc/Kconfig
+++ b/drivers/staging/iio/adc/Kconfig
@@ -200,6 +200,18 @@ config LPC32XX_ADC
 	  activate only one via device tree selection.  Provides direct access
 	  via sysfs.
 
+config MXS_LRADC
+	tristate "Freescale i.MX23/i.MX28 LRADC"
+	depends on ARCH_MXS
+	select IIO_BUFFER
+	select IIO_TRIGGERED_BUFFER
+	help
+	  Say yes here to build support for i.MX23/i.MX28 LRADC convertor
+	  built into these chips.
+
+	  To compile this driver as a module, choose M here: the
+	  module will be called mxs-lradc.
+
 config SPEAR_ADC
 	tristate "ST SPEAr ADC"
 	depends on PLAT_SPEAR
diff --git a/drivers/staging/iio/adc/Makefile b/drivers/staging/iio/adc/Makefile
index 14e98b6..ecac9a0 100644
--- a/drivers/staging/iio/adc/Makefile
+++ b/drivers/staging/iio/adc/Makefile
@@ -38,4 +38,5 @@ obj-$(CONFIG_ADT7310) += adt7310.o
 obj-$(CONFIG_ADT7410) += adt7410.o
 obj-$(CONFIG_AD7280) += ad7280a.o
 obj-$(CONFIG_LPC32XX_ADC) += lpc32xx_adc.o
+obj-$(CONFIG_MXS_LRADC) += mxs-lradc.o
 obj-$(CONFIG_SPEAR_ADC) += spear_adc.o
diff --git a/drivers/staging/iio/adc/mxs-lradc.c b/drivers/staging/iio/adc/mxs-lradc.c
new file mode 100644
index 0000000..58eb50e
--- /dev/null
+++ b/drivers/staging/iio/adc/mxs-lradc.c
@@ -0,0 +1,591 @@
+/*
+ * Freescale i.MX233/i.MX28 LRADC driver
+ *
+ * Copyright (c) 2012 DENX Software Engineering, GmbH.
+ * Marek Vasut <marex@denx.de>
+ *
+ * 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; either version 2 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ */
+
+#include <linux/interrupt.h>
+#include <linux/device.h>
+#include <linux/kernel.h>
+#include <linux/slab.h>
+#include <linux/of.h>
+#include <linux/of_device.h>
+#include <linux/sysfs.h>
+#include <linux/list.h>
+#include <linux/io.h>
+#include <linux/module.h>
+#include <linux/platform_device.h>
+#include <linux/spinlock.h>
+#include <linux/wait.h>
+#include <linux/sched.h>
+#include <linux/stmp_device.h>
+#include <linux/bitops.h>
+#include <linux/completion.h>
+
+#include <mach/mxs.h>
+#include <mach/common.h>
+
+#include <linux/iio/iio.h>
+#include <linux/iio/buffer.h>
+#include <linux/iio/trigger.h>
+#include <linux/iio/trigger_consumer.h>
+#include <linux/iio/triggered_buffer.h>
+
+#define DRIVER_NAME		"mxs-lradc"
+
+#define LRADC_MAX_DELAY_CHANS	4
+#define LRADC_MAX_MAPPED_CHANS	8
+#define LRADC_MAX_TOTAL_CHANS	16
+
+#define LRADC_DELAY_TIMER_HZ	2000
+
+/*
+ * Make this runtime configurable if necessary. Currently, if the buffered mode
+ * is enabled, the LRADC takes LRADC_DELAY_TIMER_LOOP samples of data before
+ * triggering IRQ. The sampling happens every (LRADC_DELAY_TIMER_PER / 2000)
+ * seconds. The result is that the samples arrive every 500mS.
+ */
+#define LRADC_DELAY_TIMER_PER	200
+#define LRADC_DELAY_TIMER_LOOP	5
+
+static const char * const mxs_lradc_irq_name[] = {
+	"mxs-lradc-touchscreen",
+	"mxs-lradc-thresh0",
+	"mxs-lradc-thresh1",
+	"mxs-lradc-channel0",
+	"mxs-lradc-channel1",
+	"mxs-lradc-channel2",
+	"mxs-lradc-channel3",
+	"mxs-lradc-channel4",
+	"mxs-lradc-channel5",
+	"mxs-lradc-channel6",
+	"mxs-lradc-channel7",
+	"mxs-lradc-button0",
+	"mxs-lradc-button1",
+};
+
+struct mxs_lradc_chan {
+	uint8_t				slot;
+	uint8_t				flags;
+};
+
+struct mxs_lradc {
+	struct device		*dev;
+	void __iomem		*base;
+	int			irq[13];
+
+	uint32_t		*buffer;
+	struct iio_trigger	*trig;
+
+	struct mutex		lock;
+
+	uint8_t			enable;
+
+	struct completion	completion;
+};
+
+#define	LRADC_CTRL0				0x00
+#define LRADC_CTRL0_TOUCH_DETECT_ENABLE		(1 << 23)
+#define LRADC_CTRL0_TOUCH_SCREEN_TYPE		(1 << 22)
+
+#define	LRADC_CTRL1				0x10
+#define	LRADC_CTRL1_LRADC_IRQ(n)		(1 << (n))
+#define	LRADC_CTRL1_LRADC_IRQ_MASK		0x1fff
+#define	LRADC_CTRL1_LRADC_IRQ_EN(n)		(1 << ((n) + 16))
+#define	LRADC_CTRL1_LRADC_IRQ_EN_MASK		(0x1fff << 16)
+
+#define	LRADC_CTRL2				0x20
+#define	LRADC_CTRL2_TEMPSENSE_PWD		(1 << 15)
+
+#define	LRADC_CH(n)				(0x50 + (0x10 * (n)))
+#define	LRADC_CH_ACCUMULATE			(1 << 29)
+#define	LRADC_CH_NUM_SAMPLES_MASK		(0x1f << 24)
+#define	LRADC_CH_NUM_SAMPLES_OFFSET		24
+#define	LRADC_CH_VALUE_MASK			0x3ffff
+#define	LRADC_CH_VALUE_OFFSET			0
+
+#define	LRADC_DELAY(n)				(0xd0 + (0x10 * (n)))
+#define	LRADC_DELAY_TRIGGER_LRADCS_MASK		(0xff << 24)
+#define	LRADC_DELAY_TRIGGER_LRADCS_OFFSET	24
+#define	LRADC_DELAY_KICK			(1 << 20)
+#define	LRADC_DELAY_TRIGGER_DELAYS_MASK		(0xf << 16)
+#define	LRADC_DELAY_TRIGGER_DELAYS_OFFSET	16
+#define	LRADC_DELAY_LOOP_COUNT_MASK		(0x1f << 11)
+#define	LRADC_DELAY_LOOP_COUNT_OFFSET		11
+#define	LRADC_DELAY_DELAY_MASK			0x7ff
+#define	LRADC_DELAY_DELAY_OFFSET		0
+
+#define	LRADC_CTRL4				0x140
+#define	LRADC_CTRL4_LRADCSELECT_MASK(n)		(0xf << ((n) * 4))
+#define	LRADC_CTRL4_LRADCSELECT_OFFSET(n)	((n) * 4)
+
+/*
+ * Raw I/O operations
+ */
+static int mxs_lradc_read_raw(struct iio_dev *iio_dev,
+			const struct iio_chan_spec *chan,
+			int *val, int *val2, long m)
+{
+	struct mxs_lradc *lradc = iio_priv(iio_dev);
+	int ret;
+
+	if (m != IIO_CHAN_INFO_RAW)
+		return -EINVAL;
+
+	/* Check for invalid channel */
+	if (chan->channel > LRADC_MAX_TOTAL_CHANS)
+		return -EINVAL;
+
+	/*
+	 * See if there is no buffered operation in progess. If there is, simply
+	 * bail out. This can be improved to support both buffered and raw IO at
+	 * the same time, yet the code becomes horribly complicated. Therefore I
+	 * applied KISS principle here.
+	 */
+	ret = mutex_trylock(&lradc->lock);
+	if (!ret)
+		return -EBUSY;
+
+	init_completion(&lradc->completion);
+
+	/*
+	 * No buffered operation in progress, map the channel and trigger it.
+	 * Virtual channel 0 is always used here as the others are always not
+	 * used if doing raw sampling.
+	 */
+	writel(LRADC_CTRL1_LRADC_IRQ_EN_MASK,
+		lradc->base + LRADC_CTRL1 + STMP_OFFSET_REG_CLR);
+	writel(0xff, lradc->base + LRADC_CTRL0 + STMP_OFFSET_REG_CLR);
+
+	writel(chan->channel, lradc->base + LRADC_CTRL4);
+	writel(0, lradc->base + LRADC_CH(0));
+
+	/* Enable the IRQ and start sampling the channel. */
+	writel(LRADC_CTRL1_LRADC_IRQ_EN(0),
+		lradc->base + LRADC_CTRL1 + STMP_OFFSET_REG_SET);
+	writel(1 << 0, lradc->base + LRADC_CTRL0 + STMP_OFFSET_REG_SET);
+
+	/* Wait for completion on the channel, 1 second max. */
+	ret = wait_for_completion_killable_timeout(&lradc->completion,
+						msecs_to_jiffies(1000));
+	if (!ret)
+		ret = -ETIMEDOUT;
+	if (ret < 0)
+		goto err;
+
+	/* Read the data. */
+	*val = readl(lradc->base + LRADC_CH(0)) & LRADC_CH_VALUE_MASK;
+	ret = IIO_VAL_INT;
+
+err:
+	writel(LRADC_CTRL1_LRADC_IRQ_EN(0),
+		lradc->base + LRADC_CTRL1 + STMP_OFFSET_REG_CLR);
+
+	mutex_unlock(&lradc->lock);
+
+	return ret;
+}
+
+static const struct iio_info mxs_lradc_iio_info = {
+	.driver_module		= THIS_MODULE,
+	.read_raw		= mxs_lradc_read_raw,
+};
+
+/*
+ * IRQ Handling
+ */
+static irqreturn_t mxs_lradc_handle_irq(int irq, void *data)
+{
+	struct iio_dev *iio = data;
+	struct mxs_lradc *lradc = iio_priv(iio);
+	unsigned long reg = readl(lradc->base + LRADC_CTRL1);
+
+	if (!(reg & LRADC_CTRL1_LRADC_IRQ_MASK))
+		return IRQ_NONE;
+
+	/*
+	 * Touchscreen IRQ handling code shall probably have priority
+	 * and therefore shall be placed here.
+	 */
+
+	if (iio_buffer_enabled(iio))
+		iio_trigger_poll(iio->trig, iio_get_time_ns());
+	else if (reg & LRADC_CTRL1_LRADC_IRQ(0))
+		complete(&lradc->completion);
+
+	writel(reg & LRADC_CTRL1_LRADC_IRQ_MASK,
+		lradc->base + LRADC_CTRL1 + STMP_OFFSET_REG_CLR);
+
+	return IRQ_HANDLED;
+}
+
+/*
+ * Trigger handling
+ */
+static irqreturn_t mxs_lradc_trigger_handler(int irq, void *p)
+{
+	struct iio_poll_func *pf = p;
+	struct iio_dev *iio = pf->indio_dev;
+	struct mxs_lradc *lradc = iio_priv(iio);
+	struct iio_buffer *buffer = iio->buffer;
+	const uint32_t chan_value = LRADC_CH_ACCUMULATE |
+		((LRADC_DELAY_TIMER_LOOP - 1) << LRADC_CH_NUM_SAMPLES_OFFSET);
+	int i, j = 0;
+
+	for_each_set_bit(i, iio->active_scan_mask, iio->masklength) {
+		lradc->buffer[j] = readl(lradc->base + LRADC_CH(j));
+		writel(chan_value, lradc->base + LRADC_CH(j));
+		lradc->buffer[j] &= LRADC_CH_VALUE_MASK;
+		lradc->buffer[j] /= LRADC_DELAY_TIMER_LOOP;
+		j++;
+	}
+
+	if (iio->scan_timestamp) {
+		s64 *timestamp = (s64 *)((u8 *)lradc->buffer +
+					ALIGN(j, sizeof(s64)));
+		*timestamp = pf->timestamp;
+	}
+
+	iio_push_to_buffer(buffer, (u8 *)lradc->buffer, pf->timestamp);
+
+	iio_trigger_notify_done(iio->trig);
+
+	return IRQ_HANDLED;
+}
+
+static int mxs_lradc_configure_trigger(struct iio_trigger *trig, bool state)
+{
+	struct iio_dev *iio = trig->private_data;
+	struct mxs_lradc *lradc = iio_priv(iio);
+	const uint32_t st = state ? STMP_OFFSET_REG_SET : STMP_OFFSET_REG_CLR;
+
+	writel(LRADC_DELAY_KICK, lradc->base + LRADC_DELAY(0) + st);
+
+	return 0;
+}
+
+static const struct iio_trigger_ops mxs_lradc_trigger_ops = {
+	.owner = THIS_MODULE,
+	.set_trigger_state = &mxs_lradc_configure_trigger,
+};
+
+static int mxs_lradc_trigger_init(struct iio_dev *iio)
+{
+	int ret;
+	struct iio_trigger *trig;
+
+	trig = iio_trigger_alloc("%s-dev%i", iio->name, iio->id);
+	if (trig == NULL)
+		return -ENOMEM;
+
+	trig->dev.parent = iio->dev.parent;
+	trig->private_data = iio;
+	trig->ops = &mxs_lradc_trigger_ops;
+
+	ret = iio_trigger_register(trig);
+	if (ret) {
+		iio_trigger_free(trig);
+		return ret;
+	}
+
+	iio->trig = trig;
+
+	return 0;
+}
+
+static void mxs_lradc_trigger_remove(struct iio_dev *iio)
+{
+	iio_trigger_unregister(iio->trig);
+	iio_trigger_free(iio->trig);
+}
+
+static int mxs_lradc_buffer_preenable(struct iio_dev *iio)
+{
+	struct mxs_lradc *lradc = iio_priv(iio);
+	struct iio_buffer *buffer = iio->buffer;
+	int ret = 0, chan, ofs = 0, enable = 0;
+	uint32_t ctrl4 = 0;
+	uint32_t ctrl1_irq = 0;
+	const uint32_t chan_value = LRADC_CH_ACCUMULATE |
+		((LRADC_DELAY_TIMER_LOOP - 1) << LRADC_CH_NUM_SAMPLES_OFFSET);
+	const int len = bitmap_weight(buffer->scan_mask, LRADC_MAX_TOTAL_CHANS);
+
+	if (!len)
+		return -EINVAL;
+
+	/*
+	 * Lock the driver so raw access can not be done during buffered
+	 * operation. This simplifies the code a lot.
+	 */
+	ret = mutex_trylock(&lradc->lock);
+	if (!ret)
+		return -EBUSY;
+
+	lradc->buffer = kmalloc(len * sizeof(*lradc->buffer), GFP_KERNEL);
+	if (!lradc->buffer) {
+		ret = -ENOMEM;
+		goto err_mem;
+	}
+
+	ret = iio_sw_buffer_preenable(iio);
+	if (ret < 0)
+		goto err_buf;
+
+	writel(LRADC_CTRL1_LRADC_IRQ_EN_MASK,
+		lradc->base + LRADC_CTRL1 + STMP_OFFSET_REG_CLR);
+	writel(0xff, lradc->base + LRADC_CTRL0 + STMP_OFFSET_REG_CLR);
+
+	for_each_set_bit(chan, buffer->scan_mask, LRADC_MAX_TOTAL_CHANS) {
+		ctrl4 |= chan << LRADC_CTRL4_LRADCSELECT_OFFSET(ofs);
+		ctrl1_irq |= LRADC_CTRL1_LRADC_IRQ_EN(ofs);
+		writel(chan_value, lradc->base + LRADC_CH(ofs));
+		enable |= 1 << ofs;
+		ofs++;
+	};
+
+	writel(LRADC_DELAY_TRIGGER_LRADCS_MASK | LRADC_DELAY_KICK,
+		lradc->base + LRADC_DELAY(0) + STMP_OFFSET_REG_CLR);
+
+	writel(ctrl4, lradc->base + LRADC_CTRL4);
+	writel(ctrl1_irq, lradc->base + LRADC_CTRL1 + STMP_OFFSET_REG_SET);
+
+	writel(enable << LRADC_DELAY_TRIGGER_LRADCS_OFFSET,
+		lradc->base + LRADC_DELAY(0) + STMP_OFFSET_REG_SET);
+
+	return 0;
+
+err_buf:
+	kfree(lradc->buffer);
+err_mem:
+	mutex_unlock(&lradc->lock);
+	return ret;
+}
+
+static int mxs_lradc_buffer_postdisable(struct iio_dev *iio)
+{
+	struct mxs_lradc *lradc = iio_priv(iio);
+
+	writel(LRADC_DELAY_TRIGGER_LRADCS_MASK | LRADC_DELAY_KICK,
+		lradc->base + LRADC_DELAY(0) + STMP_OFFSET_REG_CLR);
+
+	writel(0xff, lradc->base + LRADC_CTRL0 + STMP_OFFSET_REG_CLR);
+	writel(LRADC_CTRL1_LRADC_IRQ_EN_MASK,
+		lradc->base + LRADC_CTRL1 + STMP_OFFSET_REG_CLR);
+
+	kfree(lradc->buffer);
+	mutex_unlock(&lradc->lock);
+
+	return 0;
+}
+
+static bool mxs_lradc_validate_scan_mask(struct iio_dev *iio,
+					const unsigned long *mask)
+{
+	const int mw = bitmap_weight(mask, iio->masklength);
+
+	return mw <= LRADC_MAX_MAPPED_CHANS;
+}
+
+static const struct iio_buffer_setup_ops mxs_lradc_buffer_ops = {
+	.preenable = &mxs_lradc_buffer_preenable,
+	.postenable = &iio_triggered_buffer_postenable,
+	.predisable = &iio_triggered_buffer_predisable,
+	.postdisable = &mxs_lradc_buffer_postdisable,
+	.validate_scan_mask = &mxs_lradc_validate_scan_mask,
+};
+
+/*
+ * Driver initialization
+ */
+
+#define MXS_ADC_CHAN(idx, chan_type) {				\
+	.type = (chan_type),					\
+	.indexed = 1,						\
+	.scan_index = (idx),					\
+	.info_mask = IIO_CHAN_INFO_RAW_SEPARATE_BIT,		\
+	.channel = (idx),					\
+	.scan_type = {						\
+		.sign = 'u',					\
+		.realbits = 18,					\
+		.storagebits = 32,				\
+	},							\
+}
+
+static const struct iio_chan_spec mxs_lradc_chan_spec[] = {
+	MXS_ADC_CHAN(0, IIO_VOLTAGE),
+	MXS_ADC_CHAN(1, IIO_VOLTAGE),
+	MXS_ADC_CHAN(2, IIO_VOLTAGE),
+	MXS_ADC_CHAN(3, IIO_VOLTAGE),
+	MXS_ADC_CHAN(4, IIO_VOLTAGE),
+	MXS_ADC_CHAN(5, IIO_VOLTAGE),
+	MXS_ADC_CHAN(6, IIO_VOLTAGE),
+	MXS_ADC_CHAN(7, IIO_VOLTAGE),	/* VBATT */
+	MXS_ADC_CHAN(8, IIO_TEMP),	/* Temp sense 0 */
+	MXS_ADC_CHAN(9, IIO_TEMP),	/* Temp sense 1 */
+	MXS_ADC_CHAN(10, IIO_VOLTAGE),	/* VDDIO */
+	MXS_ADC_CHAN(11, IIO_VOLTAGE),	/* VTH */
+	MXS_ADC_CHAN(12, IIO_VOLTAGE),	/* VDDA */
+	MXS_ADC_CHAN(13, IIO_VOLTAGE),	/* VDDD */
+	MXS_ADC_CHAN(14, IIO_VOLTAGE),	/* VBG */
+	MXS_ADC_CHAN(15, IIO_VOLTAGE),	/* VDD5V */
+};
+
+static void mxs_lradc_hw_init(struct mxs_lradc *lradc)
+{
+	int i;
+	const uint32_t cfg =
+		(LRADC_DELAY_TIMER_PER << LRADC_DELAY_DELAY_OFFSET);
+
+	stmp_reset_block(lradc->base);
+
+	for (i = 0; i < LRADC_MAX_DELAY_CHANS; i++)
+		writel(cfg | (1 << (LRADC_DELAY_TRIGGER_DELAYS_OFFSET + i)),
+			lradc->base + LRADC_DELAY(i));
+
+	/* Start internal temperature sensing. */
+	writel(0, lradc->base + LRADC_CTRL2);
+}
+
+static void mxs_lradc_hw_stop(struct mxs_lradc *lradc)
+{
+	int i;
+
+	writel(LRADC_CTRL1_LRADC_IRQ_EN_MASK,
+		lradc->base + LRADC_CTRL1 + STMP_OFFSET_REG_CLR);
+
+	for (i = 0; i < LRADC_MAX_DELAY_CHANS; i++)
+		writel(0, lradc->base + LRADC_DELAY(i));
+}
+
+static int __devinit mxs_lradc_probe(struct platform_device *pdev)
+{
+	struct device *dev = &pdev->dev;
+	struct mxs_lradc *lradc;
+	struct iio_dev *iio;
+	struct resource *iores;
+	int ret = 0;
+	int i;
+
+	/* Allocate the IIO device. */
+	iio = iio_device_alloc(sizeof(*lradc));
+	if (!iio) {
+		dev_err(dev, "Failed to allocate IIO device\n");
+		return -ENOMEM;
+	}
+
+	lradc = iio_priv(iio);
+
+	/* Grab the memory area */
+	iores = platform_get_resource(pdev, IORESOURCE_MEM, 0);
+	lradc->dev = &pdev->dev;
+	lradc->base = devm_request_and_ioremap(dev, iores);
+	if (!lradc->base) {
+		ret = -EADDRNOTAVAIL;
+		goto err_addr;
+	}
+
+	/* Grab all IRQ sources */
+	for (i = 0; i < 13; i++) {
+		lradc->irq[i] = platform_get_irq(pdev, i);
+		if (lradc->irq[i] < 0) {
+			ret = -EINVAL;
+			goto err_addr;
+		}
+
+		ret = devm_request_irq(dev, lradc->irq[i],
+					mxs_lradc_handle_irq, 0,
+					mxs_lradc_irq_name[i], iio);
+		if (ret)
+			goto err_addr;
+	}
+
+	dev_set_drvdata(&pdev->dev, iio);
+
+	init_completion(&lradc->completion);
+	mutex_init(&lradc->lock);
+
+	iio->name = pdev->name;
+	iio->dev.parent = &pdev->dev;
+	iio->info = &mxs_lradc_iio_info;
+	iio->modes = INDIO_DIRECT_MODE;
+	iio->channels = mxs_lradc_chan_spec;
+	iio->num_channels = ARRAY_SIZE(mxs_lradc_chan_spec);
+
+	ret = iio_triggered_buffer_setup(iio, &iio_pollfunc_store_time,
+				&mxs_lradc_trigger_handler,
+				&mxs_lradc_buffer_ops);
+	if (ret)
+		goto err_addr;
+
+	ret = mxs_lradc_trigger_init(iio);
+	if (ret)
+		goto err_trig;
+
+	/* Register IIO device. */
+	ret = iio_device_register(iio);
+	if (ret) {
+		dev_err(dev, "Failed to register IIO device\n");
+		goto err_dev;
+	}
+
+	/* Configure the hardware. */
+	mxs_lradc_hw_init(lradc);
+
+	return 0;
+
+err_dev:
+	mxs_lradc_trigger_remove(iio);
+err_trig:
+	iio_triggered_buffer_cleanup(iio);
+err_addr:
+	iio_device_free(iio);
+	return ret;
+}
+
+static int __devexit mxs_lradc_remove(struct platform_device *pdev)
+{
+	struct iio_dev *iio = dev_get_drvdata(&pdev->dev);
+	struct mxs_lradc *lradc = iio_priv(iio);
+
+	mxs_lradc_hw_stop(lradc);
+
+	iio_device_unregister(iio);
+	iio_triggered_buffer_cleanup(iio);
+	mxs_lradc_trigger_remove(iio);
+	iio_device_free(iio);
+
+	return 0;
+}
+
+static const struct of_device_id mxs_lradc_dt_ids[] = {
+	{ .compatible = "fsl,imx28-lradc", },
+	{ /* sentinel */ }
+};
+MODULE_DEVICE_TABLE(of, mxs_lradc_dt_ids);
+
+static struct platform_driver mxs_lradc_driver = {
+	.driver	= {
+		.name	= DRIVER_NAME,
+		.owner	= THIS_MODULE,
+		.of_match_table = mxs_lradc_dt_ids,
+	},
+	.probe	= mxs_lradc_probe,
+	.remove	= __devexit_p(mxs_lradc_remove),
+};
+
+module_platform_driver(mxs_lradc_driver);
+
+MODULE_AUTHOR("Marek Vasut <marex@denx.de>");
+MODULE_DESCRIPTION("Freescale i.MX23/i.MX28 LRADC driver");
+MODULE_LICENSE("GPL v2");
-- 
1.7.10.4

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

* [PATCH 3/3] IIO: arm: Add LRADC to i.MX28 dts
  2012-08-03 15:28 [PATCH 0/3] i.MX28 LRADC driver Marek Vasut
  2012-08-03 15:28 ` [PATCH 1/3] IIO: Add 4-byte unsigned reads into generic-buffer example Marek Vasut
  2012-08-03 15:28 ` [PATCH 2/3 V2] IIO: Add basic MXS LRADC driver Marek Vasut
@ 2012-08-03 15:28 ` Marek Vasut
  2012-08-06  2:39   ` Shawn Guo
  2012-08-12 14:23 ` [PATCH 0/3] i.MX28 LRADC driver Marek Vasut
  3 siblings, 1 reply; 26+ messages in thread
From: Marek Vasut @ 2012-08-03 15:28 UTC (permalink / raw)
  To: linux-iio
  Cc: linux-arm-kernel, Marek Vasut, Jonathan Cameron, Juergen Beisert,
	Lars-Peter Clausen, Shawn Guo, Wolfgang Denk

Signed-off-by: Marek Vasut <marex@denx.de>
Cc: Jonathan Cameron <jic23@kernel.org>
Cc: Juergen Beisert <jbe@pengutronix.de>
Cc: Lars-Peter Clausen <lars@metafoo.de>
Cc: Shawn Guo <shawn.guo@linaro.org>
Cc: Wolfgang Denk <wd@denx.de>
---
 arch/arm/boot/dts/imx28.dtsi |    3 +++
 1 file changed, 3 insertions(+)

diff --git a/arch/arm/boot/dts/imx28.dtsi b/arch/arm/boot/dts/imx28.dtsi
index 4a0f12c..91752d2 100644
--- a/arch/arm/boot/dts/imx28.dtsi
+++ b/arch/arm/boot/dts/imx28.dtsi
@@ -677,7 +677,10 @@
 			};
 
 			lradc@80050000 {
+				compatible = "fsl,imx28-lradc";
 				reg = <0x80050000 2000>;
+				interrupts = <10 14 15 16 17 18 19
+						20 21 22 23 24 25>;
 				status = "disabled";
 			};
 
-- 
1.7.10.4

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

* Re: [PATCH 2/3 V2] IIO: Add basic MXS LRADC driver
  2012-08-03 15:28 ` [PATCH 2/3 V2] IIO: Add basic MXS LRADC driver Marek Vasut
@ 2012-08-06  2:37   ` Shawn Guo
  2012-08-06  3:53     ` Marek Vasut
  2012-08-06  8:49   ` Lars-Peter Clausen
  1 sibling, 1 reply; 26+ messages in thread
From: Shawn Guo @ 2012-08-06  2:37 UTC (permalink / raw)
  To: Marek Vasut
  Cc: linux-iio, linux-arm-kernel, Jonathan Cameron, Juergen Beisert,
	Lars-Peter Clausen, Wolfgang Denk

On Fri, Aug 03, 2012 at 05:28:40PM +0200, Marek Vasut wrote:
> --- /dev/null
> +++ b/drivers/staging/iio/adc/mxs-lradc.c

<snip>

> +#include <mach/mxs.h>
> +#include <mach/common.h>
> +
Why do you need these two mach headers?

-- 
Regards,
Shawn

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

* Re: [PATCH 3/3] IIO: arm: Add LRADC to i.MX28 dts
  2012-08-03 15:28 ` [PATCH 3/3] IIO: arm: Add LRADC to i.MX28 dts Marek Vasut
@ 2012-08-06  2:39   ` Shawn Guo
  0 siblings, 0 replies; 26+ messages in thread
From: Shawn Guo @ 2012-08-06  2:39 UTC (permalink / raw)
  To: Marek Vasut
  Cc: linux-iio, linux-arm-kernel, Jonathan Cameron, Juergen Beisert,
	Lars-Peter Clausen, Wolfgang Denk

On Fri, Aug 03, 2012 at 05:28:41PM +0200, Marek Vasut wrote:
> Signed-off-by: Marek Vasut <marex@denx.de>
> Cc: Jonathan Cameron <jic23@kernel.org>
> Cc: Juergen Beisert <jbe@pengutronix.de>
> Cc: Lars-Peter Clausen <lars@metafoo.de>
> Cc: Shawn Guo <shawn.guo@linaro.org>
> Cc: Wolfgang Denk <wd@denx.de>
> ---
>  arch/arm/boot/dts/imx28.dtsi |    3 +++
>  1 file changed, 3 insertions(+)
> 
> diff --git a/arch/arm/boot/dts/imx28.dtsi b/arch/arm/boot/dts/imx28.dtsi
> index 4a0f12c..91752d2 100644
> --- a/arch/arm/boot/dts/imx28.dtsi
> +++ b/arch/arm/boot/dts/imx28.dtsi
> @@ -677,7 +677,10 @@
>  			};
>  
>  			lradc@80050000 {
> +				compatible = "fsl,imx28-lradc";
>  				reg = <0x80050000 2000>;
> +				interrupts = <10 14 15 16 17 18 19
> +						20 21 22 23 24 25>;

Is there a binding doc for this?

Regards,
Shawn

>  				status = "disabled";
>  			};
>  
> -- 
> 1.7.10.4
> 

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

* Re: [PATCH 2/3 V2] IIO: Add basic MXS LRADC driver
  2012-08-06  2:37   ` Shawn Guo
@ 2012-08-06  3:53     ` Marek Vasut
  0 siblings, 0 replies; 26+ messages in thread
From: Marek Vasut @ 2012-08-06  3:53 UTC (permalink / raw)
  To: Shawn Guo
  Cc: linux-iio, linux-arm-kernel, Jonathan Cameron, Juergen Beisert,
	Lars-Peter Clausen, Wolfgang Denk

Dear Shawn Guo,

> On Fri, Aug 03, 2012 at 05:28:40PM +0200, Marek Vasut wrote:
> > --- /dev/null
> > +++ b/drivers/staging/iio/adc/mxs-lradc.c
> 
> <snip>
> 
> > +#include <mach/mxs.h>
> > +#include <mach/common.h>
> > +
> 
> Why do you need these two mach headers?

Might be just some remnant ... any further comments please?

Best regards,
Marek Vasut

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

* Re: [PATCH 2/3 V2] IIO: Add basic MXS LRADC driver
  2012-08-03 15:28 ` [PATCH 2/3 V2] IIO: Add basic MXS LRADC driver Marek Vasut
  2012-08-06  2:37   ` Shawn Guo
@ 2012-08-06  8:49   ` Lars-Peter Clausen
  2012-08-11 23:11     ` Marek Vasut
  1 sibling, 1 reply; 26+ messages in thread
From: Lars-Peter Clausen @ 2012-08-06  8:49 UTC (permalink / raw)
  To: Marek Vasut
  Cc: linux-iio, linux-arm-kernel, Jonathan Cameron, Juergen Beisert,
	Shawn Guo, Wolfgang Denk

On 08/03/2012 05:28 PM, Marek Vasut wrote:
> This driver is very basic. It supports userland trigger, buffer and
> raw access to channels. The support for delay channels is missing
> altogether.

Looks mostly good to me. Some comments inline.

I think you need to provide a documentation for the devicetree binding, even
though it's a rather simple binding.

> 
> Signed-off-by: Marek Vasut <marex@denx.de>
> Cc: Jonathan Cameron <jic23@kernel.org>
> Cc: Juergen Beisert <jbe@pengutronix.de>
> Cc: Lars-Peter Clausen <lars@metafoo.de>
> Cc: Shawn Guo <shawn.guo@linaro.org>
> Cc: Wolfgang Denk <wd@denx.de>
> ---
>  drivers/staging/iio/adc/Kconfig     |   12 +
>  drivers/staging/iio/adc/Makefile    |    1 +
>  drivers/staging/iio/adc/mxs-lradc.c |  591 +++++++++++++++++++++++++++++++++++
>  3 files changed, 604 insertions(+)
>  create mode 100644 drivers/staging/iio/adc/mxs-lradc.c
> 
> V2: Use delay channel 0 in case of buffered sampling so the samples are deployed
>     continuously.
>     Disallow RAW sampling while buffered mode is enabled to simplify code.
> 
> diff --git a/drivers/staging/iio/adc/Kconfig b/drivers/staging/iio/adc/Kconfig
> index 67711b7..97ca697 100644
> --- a/drivers/staging/iio/adc/Kconfig
> +++ b/drivers/staging/iio/adc/Kconfig
[...]
> + */
> +static int mxs_lradc_read_raw(struct iio_dev *iio_dev,
> +			const struct iio_chan_spec *chan,
> +			int *val, int *val2, long m)
> +{
> [...]
> +
> +	init_completion(&lradc->completion);

This should rather be INIT_COMPLETION. init_completion should only called
once in probe, since it will reinitialize the spinlock which opens up race
conditions.

> [...]
> +
> +	/* Wait for completion on the channel, 1 second max. */
> +	ret = wait_for_completion_killable_timeout(&lradc->completion,
> +						msecs_to_jiffies(1000));

msecs_to_jiffies(1000) = HZ, but I guess both is OK.

> [...]
> +}
[...]
> +
> +static int __devinit mxs_lradc_probe(struct platform_device *pdev)
> +{
> [...]
> +
> +	/* Grab all IRQ sources */
> +	for (i = 0; i < 13; i++) {
> +		lradc->irq[i] = platform_get_irq(pdev, i);
> +		if (lradc->irq[i] < 0) {
> +			ret = -EINVAL;
> +			goto err_addr;
> +		}
> +
> +		ret = devm_request_irq(dev, lradc->irq[i],
> +					mxs_lradc_handle_irq, 0,
> +					mxs_lradc_irq_name[i], iio);

devm_request_irq is a bit dangerous as long we do not have a
devm_iio_device_alloc. The IRQ will only be freed after the memory for the
IIO device has been freed, which means there is a slight window where the
IRQ could fire although the memory has already been freed.

> +		if (ret)
> +			goto err_addr;
> +	}
> +
> +	dev_set_drvdata(&pdev->dev, iio);

platform_set_drvdata

> +
> +	init_completion(&lradc->completion);
> +	mutex_init(&lradc->lock);
> +

[...]

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

* Re: [PATCH 2/3 V2] IIO: Add basic MXS LRADC driver
  2012-08-06  8:49   ` Lars-Peter Clausen
@ 2012-08-11 23:11     ` Marek Vasut
  2012-08-12  9:27       ` Lars-Peter Clausen
  0 siblings, 1 reply; 26+ messages in thread
From: Marek Vasut @ 2012-08-11 23:11 UTC (permalink / raw)
  To: Lars-Peter Clausen
  Cc: linux-iio, linux-arm-kernel, Jonathan Cameron, Juergen Beisert,
	Shawn Guo, Wolfgang Denk

Dear Lars-Peter Clausen,

> On 08/03/2012 05:28 PM, Marek Vasut wrote:
> > This driver is very basic. It supports userland trigger, buffer and
> > raw access to channels. The support for delay channels is missing
> > altogether.
> 
> Looks mostly good to me. Some comments inline.
> 
> I think you need to provide a documentation for the devicetree binding,
> even though it's a rather simple binding.

Definitelly, will add it.

> > Signed-off-by: Marek Vasut <marex@denx.de>
> > Cc: Jonathan Cameron <jic23@kernel.org>
> > Cc: Juergen Beisert <jbe@pengutronix.de>
> > Cc: Lars-Peter Clausen <lars@metafoo.de>
> > Cc: Shawn Guo <shawn.guo@linaro.org>
> > Cc: Wolfgang Denk <wd@denx.de>
> > ---
> > 
> >  drivers/staging/iio/adc/Kconfig     |   12 +
> >  drivers/staging/iio/adc/Makefile    |    1 +
> >  drivers/staging/iio/adc/mxs-lradc.c |  591
> >  +++++++++++++++++++++++++++++++++++ 3 files changed, 604 insertions(+)
> >  create mode 100644 drivers/staging/iio/adc/mxs-lradc.c
> > 
> > V2: Use delay channel 0 in case of buffered sampling so the samples are
> > deployed
> > 
> >     continuously.
> >     Disallow RAW sampling while buffered mode is enabled to simplify
> >     code.
> > 
> > diff --git a/drivers/staging/iio/adc/Kconfig
> > b/drivers/staging/iio/adc/Kconfig index 67711b7..97ca697 100644
> > --- a/drivers/staging/iio/adc/Kconfig
> > +++ b/drivers/staging/iio/adc/Kconfig
> 
> [...]
> 
> > + */
> > +static int mxs_lradc_read_raw(struct iio_dev *iio_dev,
> > +			const struct iio_chan_spec *chan,
> > +			int *val, int *val2, long m)
> > +{
> > [...]
> > +
> > +	init_completion(&lradc->completion);
> 
> This should rather be INIT_COMPLETION. init_completion should only called
> once in probe, since it will reinitialize the spinlock which opens up race
> conditions.
> 
> > [...]
> > +
> > +	/* Wait for completion on the channel, 1 second max. */
> > +	ret = wait_for_completion_killable_timeout(&lradc->completion,
> > +						msecs_to_jiffies(1000));
> 
> msecs_to_jiffies(1000) = HZ, but I guess both is OK.

Even on NOHZ kernel?

> > [...]
> > +}
> 
> [...]
> 
> > +
> > +static int __devinit mxs_lradc_probe(struct platform_device *pdev)
> > +{
> > [...]
> > +
> > +	/* Grab all IRQ sources */
> > +	for (i = 0; i < 13; i++) {
> > +		lradc->irq[i] = platform_get_irq(pdev, i);
> > +		if (lradc->irq[i] < 0) {
> > +			ret = -EINVAL;
> > +			goto err_addr;
> > +		}
> > +
> > +		ret = devm_request_irq(dev, lradc->irq[i],
> > +					mxs_lradc_handle_irq, 0,
> > +					mxs_lradc_irq_name[i], iio);
> 
> devm_request_irq is a bit dangerous as long we do not have a
> devm_iio_device_alloc. The IRQ will only be freed after the memory for the
> IIO device has been freed, which means there is a slight window where the
> IRQ could fire although the memory has already been freed.

The IRQ is disabled, see mxs_lradc_hw_stop(), so it should be all right.

> > +		if (ret)
> > +			goto err_addr;
> > +	}
> > +
> > +	dev_set_drvdata(&pdev->dev, iio);
> 
> platform_set_drvdata
> 
> > +
> > +	init_completion(&lradc->completion);
> > +	mutex_init(&lradc->lock);
> > +
> 
> [...]

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

* Re: [PATCH 2/3 V2] IIO: Add basic MXS LRADC driver
  2012-08-11 23:11     ` Marek Vasut
@ 2012-08-12  9:27       ` Lars-Peter Clausen
  0 siblings, 0 replies; 26+ messages in thread
From: Lars-Peter Clausen @ 2012-08-12  9:27 UTC (permalink / raw)
  To: Marek Vasut
  Cc: linux-iio, linux-arm-kernel, Jonathan Cameron, Juergen Beisert,
	Shawn Guo, Wolfgang Denk

On 08/12/2012 01:11 AM, Marek Vasut wrote:
> Dear Lars-Peter Clausen,
> 
>> On 08/03/2012 05:28 PM, Marek Vasut wrote:
>>> This driver is very basic. It supports userland trigger, buffer and
>>> raw access to channels. The support for delay channels is missing
>>> altogether.
>>
>> Looks mostly good to me. Some comments inline.
>>
>> I think you need to provide a documentation for the devicetree binding,
>> even though it's a rather simple binding.
> 
> Definitelly, will add it.
> 
>>> Signed-off-by: Marek Vasut <marex@denx.de>
>>> Cc: Jonathan Cameron <jic23@kernel.org>
>>> Cc: Juergen Beisert <jbe@pengutronix.de>
>>> Cc: Lars-Peter Clausen <lars@metafoo.de>
>>> Cc: Shawn Guo <shawn.guo@linaro.org>
>>> Cc: Wolfgang Denk <wd@denx.de>
>>> ---
>>>
>>>  drivers/staging/iio/adc/Kconfig     |   12 +
>>>  drivers/staging/iio/adc/Makefile    |    1 +
>>>  drivers/staging/iio/adc/mxs-lradc.c |  591
>>>  +++++++++++++++++++++++++++++++++++ 3 files changed, 604 insertions(+)
>>>  create mode 100644 drivers/staging/iio/adc/mxs-lradc.c
>>>
>>> V2: Use delay channel 0 in case of buffered sampling so the samples are
>>> deployed
>>>
>>>     continuously.
>>>     Disallow RAW sampling while buffered mode is enabled to simplify
>>>     code.
>>>
>>> diff --git a/drivers/staging/iio/adc/Kconfig
>>> b/drivers/staging/iio/adc/Kconfig index 67711b7..97ca697 100644
>>> --- a/drivers/staging/iio/adc/Kconfig
>>> +++ b/drivers/staging/iio/adc/Kconfig
>>
>> [...]
>>
>>> + */
>>> +static int mxs_lradc_read_raw(struct iio_dev *iio_dev,
>>> +			const struct iio_chan_spec *chan,
>>> +			int *val, int *val2, long m)
>>> +{
>>> [...]
>>> +
>>> +	init_completion(&lradc->completion);
>>
>> This should rather be INIT_COMPLETION. init_completion should only called
>> once in probe, since it will reinitialize the spinlock which opens up race
>> conditions.
>>
>>> [...]
>>> +
>>> +	/* Wait for completion on the channel, 1 second max. */
>>> +	ret = wait_for_completion_killable_timeout(&lradc->completion,
>>> +						msecs_to_jiffies(1000));
>>
>> msecs_to_jiffies(1000) = HZ, but I guess both is OK.
> 
> Even on NOHZ kernel?

Yes HZ is always the number of jiffies per second.

> 
>>> [...]
>>> +}
>>
>> [...]
>>
>>> +
>>> +static int __devinit mxs_lradc_probe(struct platform_device *pdev)
>>> +{
>>> [...]
>>> +
>>> +	/* Grab all IRQ sources */
>>> +	for (i = 0; i < 13; i++) {
>>> +		lradc->irq[i] = platform_get_irq(pdev, i);
>>> +		if (lradc->irq[i] < 0) {
>>> +			ret = -EINVAL;
>>> +			goto err_addr;
>>> +		}
>>> +
>>> +		ret = devm_request_irq(dev, lradc->irq[i],
>>> +					mxs_lradc_handle_irq, 0,
>>> +					mxs_lradc_irq_name[i], iio);
>>
>> devm_request_irq is a bit dangerous as long we do not have a
>> devm_iio_device_alloc. The IRQ will only be freed after the memory for the
>> IIO device has been freed, which means there is a slight window where the
>> IRQ could fire although the memory has already been freed.
> 
> The IRQ is disabled, see mxs_lradc_hw_stop(), so it should be all right.

Ok.

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

* Re: [PATCH 0/3] i.MX28 LRADC driver
  2012-08-03 15:28 [PATCH 0/3] i.MX28 LRADC driver Marek Vasut
                   ` (2 preceding siblings ...)
  2012-08-03 15:28 ` [PATCH 3/3] IIO: arm: Add LRADC to i.MX28 dts Marek Vasut
@ 2012-08-12 14:23 ` Marek Vasut
  3 siblings, 0 replies; 26+ messages in thread
From: Marek Vasut @ 2012-08-12 14:23 UTC (permalink / raw)
  To: linux-iio
  Cc: linux-arm-kernel, Jonathan Cameron, Juergen Beisert,
	Lars-Peter Clausen, Wolfgang Denk

Dear Marek Vasut,

> Introduce the i.MX28 LRADC driver and support tech that comes with it.
> 
> Marek Vasut (3):
>   IIO: Add 4-byte unsigned reads into generic-buffer example
>   IIO: Add basic MXS LRADC driver
>   IIO: arm: Add LRADC to i.MX28 dts

What about 1/3 btw? Can that be applied ?

>  arch/arm/boot/dts/imx28.dtsi                       |    3 +
>  drivers/staging/iio/Documentation/generic_buffer.c |   10 +
>  drivers/staging/iio/adc/Kconfig                    |   12 +
>  drivers/staging/iio/adc/Makefile                   |    1 +
>  drivers/staging/iio/adc/mxs-lradc.c                |  591
> ++++++++++++++++++++ 5 files changed, 617 insertions(+)
>  create mode 100644 drivers/staging/iio/adc/mxs-lradc.c
> 
> Cc: Jonathan Cameron <jic23@kernel.org>
> Cc: Juergen Beisert <jbe@pengutronix.de>
> Cc: Lars-Peter Clausen <lars@metafoo.de>
> Cc: Wolfgang Denk <wd@denx.de>

Best regards,
Marek Vasut

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

* [PATCH 3/3] IIO: arm: Add LRADC to i.MX28 dts
  2012-08-12 15:21 Marek Vasut
@ 2012-08-12 15:21 ` Marek Vasut
  2012-08-14  1:56   ` Shawn Guo
  2012-08-17  2:48   ` Shawn Guo
  0 siblings, 2 replies; 26+ messages in thread
From: Marek Vasut @ 2012-08-12 15:21 UTC (permalink / raw)
  To: linux-iio
  Cc: Marek Vasut, Jonathan Cameron, Juergen Beisert,
	Lars-Peter Clausen, Shawn Guo, Wolfgang Denk

Signed-off-by: Marek Vasut <marex@denx.de>
Cc: Jonathan Cameron <jic23@kernel.org>
Cc: Juergen Beisert <jbe@pengutronix.de>
Cc: Lars-Peter Clausen <lars@metafoo.de>
Cc: Shawn Guo <shawn.guo@linaro.org>
Cc: Wolfgang Denk <wd@denx.de>
---
 arch/arm/boot/dts/imx28.dtsi |    3 +++
 1 file changed, 3 insertions(+)

diff --git a/arch/arm/boot/dts/imx28.dtsi b/arch/arm/boot/dts/imx28.dtsi
index 2a413ed..ad90c59 100644
--- a/arch/arm/boot/dts/imx28.dtsi
+++ b/arch/arm/boot/dts/imx28.dtsi
@@ -677,7 +677,10 @@
 			};
 
 			lradc@80050000 {
+				compatible = "fsl,imx28-lradc";
 				reg = <0x80050000 0x2000>;
+				interrupts = <10 14 15 16 17 18 19
+						20 21 22 23 24 25>;
 				status = "disabled";
 			};
 
-- 
1.7.10.4

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

* Re: [PATCH 3/3] IIO: arm: Add LRADC to i.MX28 dts
  2012-08-12 15:21 ` [PATCH 3/3] IIO: arm: Add LRADC to i.MX28 dts Marek Vasut
@ 2012-08-14  1:56   ` Shawn Guo
  2012-08-14  2:10     ` Marek Vasut
  2012-08-17  2:48   ` Shawn Guo
  1 sibling, 1 reply; 26+ messages in thread
From: Shawn Guo @ 2012-08-14  1:56 UTC (permalink / raw)
  To: Marek Vasut
  Cc: linux-iio, Jonathan Cameron, Juergen Beisert, Lars-Peter Clausen,
	Wolfgang Denk

The patch subject does not look right.

ARM: dts: imx28: ...

Regards,
Shawn

On Sun, Aug 12, 2012 at 05:21:58PM +0200, Marek Vasut wrote:
> Signed-off-by: Marek Vasut <marex@denx.de>
> Cc: Jonathan Cameron <jic23@kernel.org>
> Cc: Juergen Beisert <jbe@pengutronix.de>
> Cc: Lars-Peter Clausen <lars@metafoo.de>
> Cc: Shawn Guo <shawn.guo@linaro.org>
> Cc: Wolfgang Denk <wd@denx.de>
> ---
>  arch/arm/boot/dts/imx28.dtsi |    3 +++
>  1 file changed, 3 insertions(+)
> 
> diff --git a/arch/arm/boot/dts/imx28.dtsi b/arch/arm/boot/dts/imx28.dtsi
> index 2a413ed..ad90c59 100644
> --- a/arch/arm/boot/dts/imx28.dtsi
> +++ b/arch/arm/boot/dts/imx28.dtsi
> @@ -677,7 +677,10 @@
>  			};
>  
>  			lradc@80050000 {
> +				compatible = "fsl,imx28-lradc";
>  				reg = <0x80050000 0x2000>;
> +				interrupts = <10 14 15 16 17 18 19
> +						20 21 22 23 24 25>;
>  				status = "disabled";
>  			};
>  
> -- 
> 1.7.10.4
> 

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

* Re: [PATCH 3/3] IIO: arm: Add LRADC to i.MX28 dts
  2012-08-14  1:56   ` Shawn Guo
@ 2012-08-14  2:10     ` Marek Vasut
  2012-08-14  2:23       ` Shawn Guo
  0 siblings, 1 reply; 26+ messages in thread
From: Marek Vasut @ 2012-08-14  2:10 UTC (permalink / raw)
  To: Shawn Guo
  Cc: linux-iio, Jonathan Cameron, Juergen Beisert, Lars-Peter Clausen,
	Wolfgang Denk

Dear Shawn Guo,

> The patch subject does not look right.

Can you fix by hand when applying please?

> ARM: dts: imx28: ...
> 
> Regards,
> Shawn
> 
> On Sun, Aug 12, 2012 at 05:21:58PM +0200, Marek Vasut wrote:
> > Signed-off-by: Marek Vasut <marex@denx.de>
> > Cc: Jonathan Cameron <jic23@kernel.org>
> > Cc: Juergen Beisert <jbe@pengutronix.de>
> > Cc: Lars-Peter Clausen <lars@metafoo.de>
> > Cc: Shawn Guo <shawn.guo@linaro.org>
> > Cc: Wolfgang Denk <wd@denx.de>
> > ---
> > 
> >  arch/arm/boot/dts/imx28.dtsi |    3 +++
> >  1 file changed, 3 insertions(+)
> > 
> > diff --git a/arch/arm/boot/dts/imx28.dtsi b/arch/arm/boot/dts/imx28.dtsi
> > index 2a413ed..ad90c59 100644
> > --- a/arch/arm/boot/dts/imx28.dtsi
> > +++ b/arch/arm/boot/dts/imx28.dtsi
> > @@ -677,7 +677,10 @@
> > 
> >  			};
> >  			
> >  			lradc@80050000 {
> > 
> > +				compatible = "fsl,imx28-lradc";
> > 
> >  				reg = <0x80050000 0x2000>;
> > 
> > +				interrupts = <10 14 15 16 17 18 19
> > +						20 21 22 23 24 25>;
> > 
> >  				status = "disabled";
> >  			
> >  			};

Best regards,
Marek Vasut

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

* Re: [PATCH 3/3] IIO: arm: Add LRADC to i.MX28 dts
  2012-08-14  2:10     ` Marek Vasut
@ 2012-08-14  2:23       ` Shawn Guo
  2012-08-14 12:33         ` Marek Vasut
  0 siblings, 1 reply; 26+ messages in thread
From: Shawn Guo @ 2012-08-14  2:23 UTC (permalink / raw)
  To: Marek Vasut
  Cc: linux-iio, Jonathan Cameron, Juergen Beisert, Lars-Peter Clausen,
	Wolfgang Denk

On 14 August 2012 10:10, Marek Vasut <marex@denx.de> wrote:
> Dear Shawn Guo,
>
>> The patch subject does not look right.
>
> Can you fix by hand when applying please?
>
I remember I have commented on the similar problem for a couple of
times.  I can do it for this time, but never later.  Also I will not
apply it until the driver patch gets accepted.

Regards,
Shawn

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

* Re: [PATCH 3/3] IIO: arm: Add LRADC to i.MX28 dts
  2012-08-14  2:23       ` Shawn Guo
@ 2012-08-14 12:33         ` Marek Vasut
  2012-08-14 13:15           ` Shawn Guo
  0 siblings, 1 reply; 26+ messages in thread
From: Marek Vasut @ 2012-08-14 12:33 UTC (permalink / raw)
  To: Shawn Guo
  Cc: linux-iio, Jonathan Cameron, Juergen Beisert, Lars-Peter Clausen,
	Wolfgang Denk

Dear Shawn Guo,

> On 14 August 2012 10:10, Marek Vasut <marex@denx.de> wrote:
> > Dear Shawn Guo,
> > 
> >> The patch subject does not look right.
> > 
> > Can you fix by hand when applying please?
> 
> I remember I have commented on the similar problem for a couple of
> times.  I can do it for this time, but never later.  Also I will not
> apply it until the driver patch gets accepted.

Is there any key to those tags ? Or a document ?

> Regards,
> Shawn

Best regards,
Marek Vasut

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

* Re: [PATCH 3/3] IIO: arm: Add LRADC to i.MX28 dts
  2012-08-14 12:33         ` Marek Vasut
@ 2012-08-14 13:15           ` Shawn Guo
  2012-08-14 13:23             ` Marek Vasut
  0 siblings, 1 reply; 26+ messages in thread
From: Shawn Guo @ 2012-08-14 13:15 UTC (permalink / raw)
  To: Marek Vasut
  Cc: linux-iio, Jonathan Cameron, Juergen Beisert, Lars-Peter Clausen,
	Wolfgang Denk

On 14 August 2012 20:33, Marek Vasut <marex@denx.de> wrote:
> Is there any key to those tags ? Or a document ?
>
Is there any better document than git log on the file you are committing?

Regards,
Shawn

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

* Re: [PATCH 3/3] IIO: arm: Add LRADC to i.MX28 dts
  2012-08-14 13:15           ` Shawn Guo
@ 2012-08-14 13:23             ` Marek Vasut
  0 siblings, 0 replies; 26+ messages in thread
From: Marek Vasut @ 2012-08-14 13:23 UTC (permalink / raw)
  To: Shawn Guo
  Cc: linux-iio, Jonathan Cameron, Juergen Beisert, Lars-Peter Clausen,
	Wolfgang Denk

Dear Shawn Guo,

> On 14 August 2012 20:33, Marek Vasut <marex@denx.de> wrote:
> > Is there any key to those tags ? Or a document ?
> 
> Is there any better document than git log on the file you are committing?

Yes, probably ... especially for newly commited files, I'd expect something to 
be there.

> Regards,
> Shawn

Best regards,
Marek Vasut

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

* Re: [PATCH 3/3] IIO: arm: Add LRADC to i.MX28 dts
  2012-08-12 15:21 ` [PATCH 3/3] IIO: arm: Add LRADC to i.MX28 dts Marek Vasut
  2012-08-14  1:56   ` Shawn Guo
@ 2012-08-17  2:48   ` Shawn Guo
  2012-08-17  2:57     ` Marek Vasut
  1 sibling, 1 reply; 26+ messages in thread
From: Shawn Guo @ 2012-08-17  2:48 UTC (permalink / raw)
  To: Marek Vasut
  Cc: linux-iio, Jonathan Cameron, Juergen Beisert, Lars-Peter Clausen,
	Wolfgang Denk

On Sun, Aug 12, 2012 at 05:21:58PM +0200, Marek Vasut wrote:
> Signed-off-by: Marek Vasut <marex@denx.de>
> Cc: Jonathan Cameron <jic23@kernel.org>
> Cc: Juergen Beisert <jbe@pengutronix.de>
> Cc: Lars-Peter Clausen <lars@metafoo.de>
> Cc: Shawn Guo <shawn.guo@linaro.org>
> Cc: Wolfgang Denk <wd@denx.de>
 
Applied with subject reworded as below:

  ARM: dts: imx28: Add compatible and interrupt for LRADC

-- 
Regards,
Shawn

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

* Re: [PATCH 3/3] IIO: arm: Add LRADC to i.MX28 dts
  2012-08-17  2:48   ` Shawn Guo
@ 2012-08-17  2:57     ` Marek Vasut
  2012-08-17  3:02       ` Shawn Guo
  0 siblings, 1 reply; 26+ messages in thread
From: Marek Vasut @ 2012-08-17  2:57 UTC (permalink / raw)
  To: Shawn Guo
  Cc: linux-iio, Jonathan Cameron, Juergen Beisert, Lars-Peter Clausen,
	Wolfgang Denk

Dear Shawn Guo,

> On Sun, Aug 12, 2012 at 05:21:58PM +0200, Marek Vasut wrote:
> > Signed-off-by: Marek Vasut <marex@denx.de>
> > Cc: Jonathan Cameron <jic23@kernel.org>
> > Cc: Juergen Beisert <jbe@pengutronix.de>
> > Cc: Lars-Peter Clausen <lars@metafoo.de>
> > Cc: Shawn Guo <shawn.guo@linaro.org>
> > Cc: Wolfgang Denk <wd@denx.de>
> 
> Applied with subject reworded as below:
> 
>   ARM: dts: imx28: Add compatible and interrupt for LRADC

Thanks ... still, is there some key for those tags? Or do you invent them at 
random and then let people guess what's right? Some git grep on Documentation 
directory gets me nothing.

TIA

Best regards,
Marek Vasut

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

* Re: [PATCH 3/3] IIO: arm: Add LRADC to i.MX28 dts
  2012-08-17  2:57     ` Marek Vasut
@ 2012-08-17  3:02       ` Shawn Guo
  2012-08-19 15:30         ` Marek Vasut
  0 siblings, 1 reply; 26+ messages in thread
From: Shawn Guo @ 2012-08-17  3:02 UTC (permalink / raw)
  To: Marek Vasut
  Cc: linux-iio, Jonathan Cameron, Juergen Beisert, Lars-Peter Clausen,
	Wolfgang Denk

On 17 August 2012 10:57, Marek Vasut <marex@denx.de> wrote:
> Thanks ... still, is there some key for those tags? Or do you invent them at
> random and then let people guess what's right? Some git grep on Documentation
> directory gets me nothing.
>
There is no official document for this.  But generally, each subsystem
has a convention on the subject prefix, so that the output of git
commands like git pull, git shortlog looks consistent on the patch
subject, and more importantly people can easily know subsystem the
patch touches.

The convention for patches touching arch/arm is "ARM: ".

Regards,
Shawn

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

* Re: [PATCH 3/3] IIO: arm: Add LRADC to i.MX28 dts
  2012-08-17  3:02       ` Shawn Guo
@ 2012-08-19 15:30         ` Marek Vasut
  2012-08-20  7:29           ` Jonathan Cameron
  0 siblings, 1 reply; 26+ messages in thread
From: Marek Vasut @ 2012-08-19 15:30 UTC (permalink / raw)
  To: linux-kernel; +Cc: Shawn Guo, linux-iio, Jonathan Cameron, Lars-Peter Clausen

Dear Shawn Guo,

> On 17 August 2012 10:57, Marek Vasut <marex@denx.de> wrote:
> > Thanks ... still, is there some key for those tags? Or do you invent them
> > at random and then let people guess what's right? Some git grep on
> > Documentation directory gets me nothing.
> 
> There is no official document for this.

Hm, maybe such document can be introduced?

> But generally, each subsystem
> has a convention on the subject prefix, so that the output of git
> commands like git pull, git shortlog looks consistent on the patch
> subject, and more importantly people can easily know subsystem the
> patch touches.
> 
> The convention for patches touching arch/arm is "ARM: ".
> 
> Regards,
> Shawn

Best regards,
Marek Vasut

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

* Re: [PATCH 3/3] IIO: arm: Add LRADC to i.MX28 dts
  2012-08-19 15:30         ` Marek Vasut
@ 2012-08-20  7:29           ` Jonathan Cameron
  2012-08-20  7:52             ` Shawn Guo
  0 siblings, 1 reply; 26+ messages in thread
From: Jonathan Cameron @ 2012-08-20  7:29 UTC (permalink / raw)
  To: Marek Vasut
  Cc: linux-kernel, Shawn Guo, linux-iio, Jonathan Cameron,
	Lars-Peter Clausen

On 19/08/12 16:30, Marek Vasut wrote:
> Dear Shawn Guo,
>
>> On 17 August 2012 10:57, Marek Vasut <marex@denx.de> wrote:
>>> Thanks ... still, is there some key for those tags? Or do you invent them
>>> at random and then let people guess what's right? Some git grep on
>>> Documentation directory gets me nothing.
>>
>> There is no official document for this.
>
> Hm, maybe such document can be introduced?
Sounds like a voluteer ;) More seriously I suspect it would never get
updated or be correct in the first place. It would be a pile of grief
for whoever was looking after it.

Mostly these prefixes are an excuse for grumpy maintainers to moan
at people :)
>
>> But generally, each subsystem
>> has a convention on the subject prefix, so that the output of git
>> commands like git pull, git shortlog looks consistent on the patch
>> subject, and more importantly people can easily know subsystem the
>> patch touches.
>>
>> The convention for patches touching arch/arm is "ARM: ".
>>
>> Regards,
>> Shawn
>
> Best regards,
> Marek Vasut
>


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

* Re: [PATCH 3/3] IIO: arm: Add LRADC to i.MX28 dts
  2012-08-20  7:29           ` Jonathan Cameron
@ 2012-08-20  7:52             ` Shawn Guo
  2012-08-20  7:57               ` Jonathan Cameron
  0 siblings, 1 reply; 26+ messages in thread
From: Shawn Guo @ 2012-08-20  7:52 UTC (permalink / raw)
  To: Jonathan Cameron
  Cc: Marek Vasut, linux-kernel, linux-iio, Jonathan Cameron,
	Lars-Peter Clausen

On Mon, Aug 20, 2012 at 08:29:23AM +0100, Jonathan Cameron wrote:
> Mostly these prefixes are an excuse for grumpy maintainers to moan
> at people :)

Yeah, I have to become grumpy when my comment gets ignored and I have
to make it right (for several times) to avoid my upstream moaning at me.

Is it so hard?  You are not creating a new subsystem but just patching
an existing file.  A "git log" on the file simply shows you how to do it.

-- 
Regards,
Shawn

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

* Re: [PATCH 3/3] IIO: arm: Add LRADC to i.MX28 dts
  2012-08-20  7:52             ` Shawn Guo
@ 2012-08-20  7:57               ` Jonathan Cameron
  2012-08-20 13:41                 ` Marek Vasut
  0 siblings, 1 reply; 26+ messages in thread
From: Jonathan Cameron @ 2012-08-20  7:57 UTC (permalink / raw)
  To: Shawn Guo
  Cc: Marek Vasut, linux-kernel, linux-iio, Jonathan Cameron,
	Lars-Peter Clausen

On 20/08/12 08:52, Shawn Guo wrote:
> On Mon, Aug 20, 2012 at 08:29:23AM +0100, Jonathan Cameron wrote:
>> Mostly these prefixes are an excuse for grumpy maintainers to moan
>> at people :)
>
> Yeah, I have to become grumpy when my comment gets ignored and I have
> to make it right (for several times) to avoid my upstream moaning at me.
Not at all. My upstream has never moaned at me about it, but I still 
like to moan about it myself ;)
>
> Is it so hard?  You are not creating a new subsystem but just patching
> an existing file.  A "git log" on the file simply shows you how to do it
>
Indeed. A file listing these would be add just one more piece of largely
pointless horrendous documentation.

Perhaps if Marek feels particularly strongly about this, proposing an
additional line to for the SubmittingPatches document to say get your
title format by looking at the log for what you are patching will do
the job? (I can't immediately spot anything equivalent in there...)

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

* Re: [PATCH 3/3] IIO: arm: Add LRADC to i.MX28 dts
  2012-08-20  7:57               ` Jonathan Cameron
@ 2012-08-20 13:41                 ` Marek Vasut
  0 siblings, 0 replies; 26+ messages in thread
From: Marek Vasut @ 2012-08-20 13:41 UTC (permalink / raw)
  To: Jonathan Cameron
  Cc: Shawn Guo, linux-kernel, linux-iio, Jonathan Cameron,
	Lars-Peter Clausen

Dear Jonathan Cameron,

> On 20/08/12 08:52, Shawn Guo wrote:
> > On Mon, Aug 20, 2012 at 08:29:23AM +0100, Jonathan Cameron wrote:
> >> Mostly these prefixes are an excuse for grumpy maintainers to moan
> >> at people :)
> > 
> > Yeah, I have to become grumpy when my comment gets ignored and I have
> > to make it right (for several times) to avoid my upstream moaning at me.
> 
> Not at all. My upstream has never moaned at me about it, but I still
> like to moan about it myself ;)

Your upstream is enjoyable to work with :)

> > Is it so hard?  You are not creating a new subsystem but just patching
> > an existing file.  A "git log" on the file simply shows you how to do it
> 
> Indeed. A file listing these would be add just one more piece of largely
> pointless horrendous documentation.

I was thinking more like a list of tags ... based on directories or something. 
But giving it a further thought, I see the trouble now.

> Perhaps if Marek feels particularly strongly about this, proposing an
> additional line to for the SubmittingPatches document to say get your
> title format by looking at the log for what you are patching will do
> the job? (I can't immediately spot anything equivalent in there...)

That might just be it ;-)

Thanks

Best regards,
Marek Vasut

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

end of thread, other threads:[~2012-08-20 13:41 UTC | newest]

Thread overview: 26+ messages (download: mbox.gz follow: Atom feed
-- links below jump to the message on this page --
2012-08-03 15:28 [PATCH 0/3] i.MX28 LRADC driver Marek Vasut
2012-08-03 15:28 ` [PATCH 1/3] IIO: Add 4-byte unsigned reads into generic-buffer example Marek Vasut
2012-08-03 15:28 ` [PATCH 2/3 V2] IIO: Add basic MXS LRADC driver Marek Vasut
2012-08-06  2:37   ` Shawn Guo
2012-08-06  3:53     ` Marek Vasut
2012-08-06  8:49   ` Lars-Peter Clausen
2012-08-11 23:11     ` Marek Vasut
2012-08-12  9:27       ` Lars-Peter Clausen
2012-08-03 15:28 ` [PATCH 3/3] IIO: arm: Add LRADC to i.MX28 dts Marek Vasut
2012-08-06  2:39   ` Shawn Guo
2012-08-12 14:23 ` [PATCH 0/3] i.MX28 LRADC driver Marek Vasut
  -- strict thread matches above, loose matches on Subject: below --
2012-08-12 15:21 Marek Vasut
2012-08-12 15:21 ` [PATCH 3/3] IIO: arm: Add LRADC to i.MX28 dts Marek Vasut
2012-08-14  1:56   ` Shawn Guo
2012-08-14  2:10     ` Marek Vasut
2012-08-14  2:23       ` Shawn Guo
2012-08-14 12:33         ` Marek Vasut
2012-08-14 13:15           ` Shawn Guo
2012-08-14 13:23             ` Marek Vasut
2012-08-17  2:48   ` Shawn Guo
2012-08-17  2:57     ` Marek Vasut
2012-08-17  3:02       ` Shawn Guo
2012-08-19 15:30         ` Marek Vasut
2012-08-20  7:29           ` Jonathan Cameron
2012-08-20  7:52             ` Shawn Guo
2012-08-20  7:57               ` Jonathan Cameron
2012-08-20 13:41                 ` Marek Vasut

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