* [PATCH 1/6] ARM: AT91: Add platform data for the ADCs
2011-12-07 18:25 [RFC v2] IIO: Add hardware triggers support to the AT91 ADC driver Maxime Ripard
@ 2011-12-07 18:25 ` Maxime Ripard
2011-12-07 18:25 ` [PATCH 2/6] ARM: AT91: IIO: Add AT91 ADC driver Maxime Ripard
` (5 subsequent siblings)
6 siblings, 0 replies; 19+ messages in thread
From: Maxime Ripard @ 2011-12-07 18:25 UTC (permalink / raw)
To: linux-iio; +Cc: Patrice Vilchez, Nicolas Ferre, Thomas Petazzoni
Signed-off-by: Maxime Ripard <maxime.ripard@free-electrons.com>
Cc: Patrice Vilchez <patrice.vilchez@atmel.com>
Cc: Nicolas Ferre <nicolas.ferre@atmel.com>
Cc: Thomas Petazzoni <thomas.petazzoni@free-electrons.com>
---
include/linux/platform_data/at91_adc.h | 36 ++++++++++++++++++++++++++++++++
1 files changed, 36 insertions(+), 0 deletions(-)
create mode 100644 include/linux/platform_data/at91_adc.h
diff --git a/include/linux/platform_data/at91_adc.h b/include/linux/platform_data/at91_adc.h
new file mode 100644
index 0000000..1e1813d
--- /dev/null
+++ b/include/linux/platform_data/at91_adc.h
@@ -0,0 +1,36 @@
+/*
+ * Copyright (C) 2011 Free Electrons
+ *
+ * This software is licensed under the terms of the GNU General Public
+ * License version 2, as published by the Free Software Foundation, and
+ * may be copied, distributed, and modified under those terms.
+ *
+ * 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.
+ *
+ */
+
+#ifndef _AT91_ADC_H_
+#define _AT91_ADC_H_
+
+struct at91_adc_data {
+ /* ADC Clock as specified by the datasheet, in Hz. */
+ unsigned int adc_clock;
+ /*
+ * Global number of channels available (to specify which channels are
+ * indeed used on the board, see the channels_used bitmask).
+ */
+ u8 num_channels;
+ /* Channels in use on the board as a bitmask */
+ unsigned long channels_used;
+ /* Startup time of the ADC, in microseconds. */
+ u8 startup_time;
+ /* Reference voltage for the ADC in millivolts */
+ unsigned short vref;
+};
+
+extern void __init at91_add_device_adc(struct at91_adc_data *data);
+
+#endif
--
1.7.4.1
^ permalink raw reply related [flat|nested] 19+ messages in thread* [PATCH 2/6] ARM: AT91: IIO: Add AT91 ADC driver.
2011-12-07 18:25 [RFC v2] IIO: Add hardware triggers support to the AT91 ADC driver Maxime Ripard
2011-12-07 18:25 ` [PATCH 1/6] ARM: AT91: Add platform data for the ADCs Maxime Ripard
@ 2011-12-07 18:25 ` Maxime Ripard
2011-12-07 18:25 ` [PATCH 3/6] ARM: AT91: Add the ADC to the sam9g20ek board Maxime Ripard
` (4 subsequent siblings)
6 siblings, 0 replies; 19+ messages in thread
From: Maxime Ripard @ 2011-12-07 18:25 UTC (permalink / raw)
To: linux-iio; +Cc: Patrice Vilchez, Nicolas Ferre, Thomas Petazzoni
Signed-off-by: Maxime Ripard <maxime.ripard@free-electrons.com>
Cc: Patrice Vilchez <patrice.vilchez@atmel.com>
Cc: Nicolas Ferre <nicolas.ferre@atmel.com>
Cc: Thomas Petazzoni <thomas.petazzoni@free-electrons.com>
---
drivers/staging/iio/adc/Kconfig | 6 +
drivers/staging/iio/adc/Makefile | 1 +
drivers/staging/iio/adc/at91_adc.c | 335 ++++++++++++++++++++++++++++++++++++
3 files changed, 342 insertions(+), 0 deletions(-)
create mode 100644 drivers/staging/iio/adc/at91_adc.c
diff --git a/drivers/staging/iio/adc/Kconfig b/drivers/staging/iio/adc/Kconfig
index d9decea..93de64d 100644
--- a/drivers/staging/iio/adc/Kconfig
+++ b/drivers/staging/iio/adc/Kconfig
@@ -169,6 +169,12 @@ config AD7280
To compile this driver as a module, choose M here: the
module will be called ad7280a
+config AT91_ADC
+ tristate "Atmel AT91 ADC"
+ depends on SYSFS && ARCH_AT91
+ help
+ Say yes here to build support for Atmel AT91 ADC
+
config MAX1363
tristate "Maxim max1363 ADC driver"
depends on I2C
diff --git a/drivers/staging/iio/adc/Makefile b/drivers/staging/iio/adc/Makefile
index ceee7f3..6ef78fb 100644
--- a/drivers/staging/iio/adc/Makefile
+++ b/drivers/staging/iio/adc/Makefile
@@ -37,3 +37,4 @@ obj-$(CONFIG_AD7192) += ad7192.o
obj-$(CONFIG_ADT7310) += adt7310.o
obj-$(CONFIG_ADT7410) += adt7410.o
obj-$(CONFIG_AD7280) += ad7280a.o
+obj-$(CONFIG_AT91_ADC) += at91_adc.o
diff --git a/drivers/staging/iio/adc/at91_adc.c b/drivers/staging/iio/adc/at91_adc.c
new file mode 100644
index 0000000..d10df7a
--- /dev/null
+++ b/drivers/staging/iio/adc/at91_adc.c
@@ -0,0 +1,335 @@
+/*
+ * Driver for the ADC present in the Atmel AT91 evaluation boards.
+ *
+ * Copyright 2011 Free Electrons
+ *
+ * Licensed under the GPLv2 or later.
+ */
+
+#include <linux/bitmap.h>
+#include <linux/bitops.h>
+#include <linux/clk.h>
+#include <linux/err.h>
+#include <linux/io.h>
+#include <linux/interrupt.h>
+#include <linux/jiffies.h>
+#include <linux/kernel.h>
+#include <linux/module.h>
+#include <linux/platform_device.h>
+#include <linux/sched.h>
+#include <linux/slab.h>
+#include <linux/wait.h>
+
+#include "../iio.h"
+#include <linux/platform_data/at91_adc.h>
+
+#include <mach/at91_adc.h>
+
+struct at91_adc_state {
+ struct clk *clk;
+ bool done;
+ struct mutex lock;
+ int irq;
+ wait_queue_head_t wq_data_avail;
+ u16 last_value;
+ void __iomem *reg_base;
+ unsigned int vref_mv;
+ unsigned long channels_mask;
+};
+
+static inline u32 at91_adc_reg_read(struct at91_adc_state *st,
+ u8 reg)
+{
+ return readl_relaxed(st->reg_base + reg);
+}
+
+static inline void at91_adc_reg_write(struct at91_adc_state *st,
+ u8 reg,
+ u32 val)
+{
+ writel_relaxed(val, st->reg_base + reg);
+}
+
+static irqreturn_t at91_adc_eoc_trigger(int irq, void *private)
+{
+ struct iio_dev *idev = private;
+ struct at91_adc_state *st = iio_priv(idev);
+ unsigned int status = at91_adc_reg_read(st, AT91_ADC_SR);
+
+ if (!(status & AT91_ADC_DRDY))
+ return IRQ_HANDLED;
+
+ if (status & st->channels_mask) {
+ st->done = true;
+ st->last_value = at91_adc_reg_read(st, AT91_ADC_LCDR);
+ }
+
+ wake_up_interruptible(&st->wq_data_avail);
+
+ return IRQ_HANDLED;
+}
+
+static int at91_adc_channel_init(struct iio_dev *idev,
+ struct at91_adc_data *pdata)
+{
+ struct iio_chan_spec *chan_array;
+ int bit, idx = 0;
+
+ idev->num_channels = bitmap_weight(&pdata->channels_used,
+ pdata->num_channels);
+ chan_array = kcalloc(idev->num_channels, sizeof(struct iio_chan_spec),
+ GFP_KERNEL);
+
+ if (chan_array == NULL)
+ return -ENOMEM;
+
+ for_each_set_bit(bit, &pdata->channels_used, pdata->num_channels) {
+ struct iio_chan_spec *chan = chan_array + idx;
+ chan->type = IIO_VOLTAGE;
+ chan->indexed = 1;
+ chan->channel = bit;
+ chan->scan_type.sign = 'u';
+ chan->scan_type.realbits = 10;
+ chan->scan_type.storagebits = 16;
+ chan->info_mask = IIO_CHAN_INFO_SCALE_SHARED_BIT;
+ idx++;
+ }
+
+ idev->channels = chan_array;
+ return idev->num_channels;
+}
+
+static void at91_adc_channel_remove(struct iio_dev *idev)
+{
+ kfree(idev->channels);
+}
+
+static int at91_adc_read_raw(struct iio_dev *idev,
+ struct iio_chan_spec const *chan,
+ int *val, int *val2, long mask)
+{
+ struct at91_adc_state *st = iio_priv(idev);
+ int ret;
+
+ switch (mask) {
+ case 0:
+ mutex_lock(&st->lock);
+
+ at91_adc_reg_write(st, AT91_ADC_CHER,
+ AT91_ADC_CH(chan->channel));
+ at91_adc_reg_write(st, AT91_ADC_IER,
+ AT91_ADC_EOC(chan->channel));
+ at91_adc_reg_write(st, AT91_ADC_CR, AT91_ADC_START);
+
+ ret = wait_event_interruptible_timeout(st->wq_data_avail,
+ st->done,
+ msecs_to_jiffies(1000));
+ if (ret == 0)
+ return -ETIMEDOUT;
+ else if (ret < 0)
+ return ret;
+
+ *val = st->last_value;
+
+ at91_adc_reg_write(st, AT91_ADC_CHDR,
+ AT91_ADC_CH(chan->channel));
+ at91_adc_reg_write(st, AT91_ADC_IDR,
+ AT91_ADC_EOC(chan->channel));
+
+ st->last_value = 0;
+ st->done = false;
+ mutex_unlock(&st->lock);
+ return IIO_VAL_INT;
+
+ case IIO_CHAN_INFO_SCALE:
+ *val = (st->vref_mv * 1000) >> chan->scan_type.realbits;
+ *val2 = 0;
+ return IIO_VAL_INT_PLUS_MICRO;
+ default:
+ break;
+ }
+ return -EINVAL;
+}
+
+static const struct iio_info at91_adc_info = {
+ .driver_module = THIS_MODULE,
+ .read_raw = &at91_adc_read_raw,
+};
+
+static int __devinit at91_adc_probe(struct platform_device *pdev)
+{
+ unsigned int prsc, mstrclk, ticks;
+ int ret;
+ struct iio_dev *idev;
+ struct at91_adc_state *st;
+ struct resource *res;
+ struct at91_adc_data *pdata = pdev->dev.platform_data;
+
+ res = platform_get_resource(pdev, IORESOURCE_MEM, 0);
+ if (!res) {
+ dev_err(&pdev->dev, "No resource defined\n");
+ ret = -ENXIO;
+ goto error_ret;
+ }
+
+ idev = iio_allocate_device(sizeof(struct at91_adc_state));
+ if (idev == NULL) {
+ ret = -ENOMEM;
+ goto error_ret;
+ }
+
+ platform_set_drvdata(pdev, idev);
+
+ idev->dev.parent = &pdev->dev;
+ idev->name = dev_name(&pdev->dev);
+ idev->modes = INDIO_DIRECT_MODE;
+ idev->info = &at91_adc_info;
+
+ st = iio_priv(idev);
+ st->irq = platform_get_irq(pdev, 0);
+ if (st->irq < 0) {
+ dev_err(&pdev->dev, "No IRQ ID is designated\n");
+ ret = -ENODEV;
+ goto error_free_device;
+ }
+
+ if (!request_mem_region(res->start, resource_size(res),
+ "AT91 adc registers")) {
+ dev_err(&pdev->dev, "Resources are unavailable.\n");
+ ret = -EBUSY;
+ goto error_free_device;
+ }
+
+ st->reg_base = ioremap(res->start, resource_size(res));
+ if (!st->reg_base) {
+ dev_err(&pdev->dev, "Failed to map registers.\n");
+ ret = -ENOMEM;
+ goto error_release_mem;
+ }
+
+ /*
+ * Disable all IRQs before setting up the handler
+ */
+ at91_adc_reg_write(st, AT91_ADC_CR, AT91_ADC_SWRST);
+ at91_adc_reg_write(st, AT91_ADC_IDR, 0xFFFFFFFF);
+ ret = request_irq(st->irq,
+ at91_adc_eoc_trigger,
+ 0,
+ pdev->dev.driver->name,
+ idev);
+ if (ret) {
+ dev_err(&pdev->dev, "Failed to allocate IRQ.\n");
+ goto error_unmap_reg;
+ }
+
+ st->clk = clk_get(&pdev->dev, "adc_clk");
+ if (IS_ERR(st->clk)) {
+ dev_err(&pdev->dev, "Failed to get the clock.\n");
+ ret = PTR_ERR(st->clk);
+ goto error_free_irq;
+ }
+
+ clk_enable(st->clk);
+ mstrclk = clk_get_rate(st->clk);
+
+ if (!pdata) {
+ dev_err(&pdev->dev, "No platform data available.\n");
+ ret = -EINVAL;
+ goto error_free_clk;
+ }
+
+ if (!pdata->adc_clock) {
+ dev_err(&pdev->dev, "No ADCClock available.\n");
+ ret = -EINVAL;
+ goto error_free_clk;
+ }
+
+ /*
+ * Prescaler rate computation using the formula from the Atmel's
+ * datasheet : ADC Clock = MCK / ((Prescaler + 1) * 2), ADC Clock being
+ * specified by the electrical characteristics of the board.
+ */
+ prsc = (mstrclk / (2 * pdata->adc_clock)) - 1;
+
+ if (!pdata->startup_time) {
+ dev_err(&pdev->dev, "No startup time available.\n");
+ ret = -EINVAL;
+ goto error_free_clk;
+ }
+
+ /*
+ * Number of ticks needed to cover the startup time of the ADC as
+ * defined in the electrical characteristics of the board, divided by 8.
+ * The formula thus is : Startup Time = (ticks + 1) * 8 / ADC Clock
+ */
+ ticks = round_up((pdata->startup_time * pdata->adc_clock /
+ 1000000) - 1, 8) / 8;
+ at91_adc_reg_write(st, AT91_ADC_MR,
+ (AT91_ADC_PRESCAL_(prsc) & AT91_ADC_PRESCAL) |
+ (AT91_ADC_STARTUP_(ticks) & AT91_ADC_STARTUP));
+
+ /* Setup the ADC channels available on the board */
+ ret = at91_adc_channel_init(idev, pdata);
+ if (ret < 0)
+ goto error_free_clk;
+
+ init_waitqueue_head(&st->wq_data_avail);
+ mutex_init(&st->lock);
+
+ st->vref_mv = pdata->vref;
+ st->channels_mask = pdata->channels_used;
+
+ ret = iio_device_register(idev);
+ if (ret < 0)
+ goto error_free_channels;
+
+ return 0;
+
+error_free_channels:
+ at91_adc_channel_remove(idev);
+error_free_clk:
+ clk_disable(st->clk);
+ clk_put(st->clk);
+error_free_irq:
+ free_irq(st->irq, idev);
+error_unmap_reg:
+ iounmap(st->reg_base);
+error_release_mem:
+ release_mem_region(res->start, resource_size(res));
+error_free_device:
+ iio_free_device(idev);
+error_ret:
+ return ret;
+}
+
+static int __devexit at91_adc_remove(struct platform_device *pdev)
+{
+ struct iio_dev *idev = platform_get_drvdata(pdev);
+ struct resource *res = platform_get_resource(pdev, IORESOURCE_MEM, 0);
+ struct at91_adc_state *st = iio_priv(idev);
+
+ iio_device_unregister(idev);
+ at91_adc_channel_remove(idev);
+ clk_disable(st->clk);
+ clk_put(st->clk);
+ free_irq(st->irq, idev);
+ iounmap(st->reg_base);
+ release_mem_region(res->start, resource_size(res));
+ iio_free_device(idev);
+
+ return 0;
+}
+
+static struct platform_driver at91_adc_driver = {
+ .probe = at91_adc_probe,
+ .remove = __devexit_p(at91_adc_remove),
+ .driver = {
+ .name = "at91_adc",
+ },
+};
+
+module_platform_driver(at91_adc_driver);
+
+MODULE_LICENSE("GPL");
+MODULE_DESCRIPTION("Atmel AT91 ADC Driver");
+MODULE_AUTHOR("Maxime Ripard <maxime.ripard@free-electrons.com>");
--
1.7.4.1
^ permalink raw reply related [flat|nested] 19+ messages in thread* [PATCH 3/6] ARM: AT91: Add the ADC to the sam9g20ek board
2011-12-07 18:25 [RFC v2] IIO: Add hardware triggers support to the AT91 ADC driver Maxime Ripard
2011-12-07 18:25 ` [PATCH 1/6] ARM: AT91: Add platform data for the ADCs Maxime Ripard
2011-12-07 18:25 ` [PATCH 2/6] ARM: AT91: IIO: Add AT91 ADC driver Maxime Ripard
@ 2011-12-07 18:25 ` Maxime Ripard
2011-12-07 18:25 ` [PATCH 4/6] AT91: IIO: Move the SoC specific informations to the ADC driver Maxime Ripard
` (3 subsequent siblings)
6 siblings, 0 replies; 19+ messages in thread
From: Maxime Ripard @ 2011-12-07 18:25 UTC (permalink / raw)
To: linux-iio; +Cc: Patrice Vilchez, Nicolas Ferre, Thomas Petazzoni
Signed-off-by: Maxime Ripard <maxime.ripard@free-electrons.com>
Cc: Patrice Vilchez <patrice.vilchez@atmel.com>
Cc: Nicolas Ferre <nicolas.ferre@atmel.com>
Cc: Thomas Petazzoni <thomas.petazzoni@free-electrons.com>
---
arch/arm/mach-at91/at91sam9260_devices.c | 62 ++++++++++++++++++++++++++++++
arch/arm/mach-at91/board-sam9g20ek.c | 13 ++++++
2 files changed, 75 insertions(+), 0 deletions(-)
diff --git a/arch/arm/mach-at91/at91sam9260_devices.c b/arch/arm/mach-at91/at91sam9260_devices.c
index 25e3464..eb914c1 100644
--- a/arch/arm/mach-at91/at91sam9260_devices.c
+++ b/arch/arm/mach-at91/at91sam9260_devices.c
@@ -17,6 +17,8 @@
#include <linux/platform_device.h>
#include <linux/i2c-gpio.h>
+#include <linux/platform_data/at91_adc.h>
+
#include <mach/board.h>
#include <mach/cpu.h>
#include <mach/at91sam9260.h>
@@ -1319,6 +1321,66 @@ void __init at91_add_device_cf(struct at91_cf_data *data)
void __init at91_add_device_cf(struct at91_cf_data * data) {}
#endif
+/* --------------------------------------------------------------------
+ * ADCs
+ * -------------------------------------------------------------------- */
+
+#if defined(CONFIG_AT91_ADC) || defined(CONFIG_AT91_ADC_MODULE)
+static struct at91_adc_data adc_data;
+
+static struct resource adc_resources[] = {
+ [0] = {
+ .start = AT91SAM9260_BASE_ADC,
+ .end = AT91SAM9260_BASE_ADC + SZ_16K - 1,
+ .flags = IORESOURCE_MEM,
+ },
+ [1] = {
+ .start = AT91SAM9260_ID_ADC,
+ .end = AT91SAM9260_ID_ADC,
+ .flags = IORESOURCE_IRQ,
+ },
+};
+
+static struct platform_device at91_adc_device = {
+ .name = "at91_adc",
+ .id = -1,
+ .dev = {
+ .platform_data = &adc_data,
+ },
+ .resource = adc_resources,
+ .num_resources = ARRAY_SIZE(adc_resources),
+};
+
+void __init at91_add_device_adc(struct at91_adc_data *data)
+{
+ if (!data)
+ return;
+
+ if (test_bit(0, &data->channels_used))
+ at91_set_A_periph(AT91_PIN_PC0, 0);
+ if (test_bit(1, &data->channels_used))
+ at91_set_A_periph(AT91_PIN_PC1, 0);
+ if (test_bit(2, &data->channels_used))
+ at91_set_A_periph(AT91_PIN_PC2, 0);
+ if (test_bit(3, &data->channels_used))
+ at91_set_A_periph(AT91_PIN_PC3, 0);
+
+ /*
+ * The electrical characteristics part of the AT91SAM9G20 datasheet
+ * sets the ADC clock to 5MHz.
+ */
+ data->adc_clock = 5000000;
+
+ data->num_channels = 4;
+ data->startup_time = 10;
+
+ adc_data = *data;
+ platform_device_register(&at91_adc_device);
+}
+#else
+void __init at91_add_device_adc(struct at91_adc_data *data) {}
+#endif
+
/* -------------------------------------------------------------------- */
/*
* These devices are always present and don't need any board-specific
diff --git a/arch/arm/mach-at91/board-sam9g20ek.c b/arch/arm/mach-at91/board-sam9g20ek.c
index 64fc75c..7758f34 100644
--- a/arch/arm/mach-at91/board-sam9g20ek.c
+++ b/arch/arm/mach-at91/board-sam9g20ek.c
@@ -32,6 +32,8 @@
#include <linux/regulator/fixed.h>
#include <linux/regulator/consumer.h>
+#include <linux/platform_data/at91_adc.h>
+
#include <mach/hardware.h>
#include <asm/setup.h>
#include <asm/mach-types.h>
@@ -309,6 +311,15 @@ static void __init ek_add_device_buttons(void)
static void __init ek_add_device_buttons(void) {}
#endif
+/*
+ * ADCs
+ */
+
+static struct at91_adc_data ek_adc_data = {
+ .channels_used = BIT(0) | BIT(1) | BIT(2) | BIT(3),
+ .vref = 3300,
+};
+
#if defined(CONFIG_REGULATOR_FIXED_VOLTAGE) || defined(CONFIG_REGULATOR_FIXED_VOLTAGE_MODULE)
static struct regulator_consumer_supply ek_audio_consumer_supplies[] = {
REGULATOR_SUPPLY("AVDD", "0-001b"),
@@ -384,6 +395,8 @@ static void __init ek_board_init(void)
ek_add_device_gpio_leds();
/* Push Buttons */
ek_add_device_buttons();
+ /* ADCs */
+ at91_add_device_adc(&ek_adc_data);
/* PCK0 provides MCLK to the WM8731 */
at91_set_B_periph(AT91_PIN_PC1, 0);
/* SSC (for WM8731) */
--
1.7.4.1
^ permalink raw reply related [flat|nested] 19+ messages in thread* [PATCH 4/6] AT91: IIO: Move the SoC specific informations to the ADC driver
2011-12-07 18:25 [RFC v2] IIO: Add hardware triggers support to the AT91 ADC driver Maxime Ripard
` (2 preceding siblings ...)
2011-12-07 18:25 ` [PATCH 3/6] ARM: AT91: Add the ADC to the sam9g20ek board Maxime Ripard
@ 2011-12-07 18:25 ` Maxime Ripard
2011-12-07 18:25 ` [PATCH 5/6] AT91: IIO: cosmetic fixes, better error messages Maxime Ripard
` (2 subsequent siblings)
6 siblings, 0 replies; 19+ messages in thread
From: Maxime Ripard @ 2011-12-07 18:25 UTC (permalink / raw)
To: linux-iio; +Cc: Patrice Vilchez, Nicolas Ferre, Thomas Petazzoni
Signed-off-by: Maxime Ripard <maxime.ripard@free-electrons.com>
Cc: Patrice Vilchez <patrice.vilchez@atmel.com>
Cc: Nicolas Ferre <nicolas.ferre@atmel.com>
Cc: Thomas Petazzoni <thomas.petazzoni@free-electrons.com>
---
arch/arm/mach-at91/at91sam9260_devices.c | 9 -----
drivers/staging/iio/adc/at91_adc.c | 52 ++++++++++++++++++++++++++---
include/linux/platform_data/at91_adc.h | 20 ++++-------
3 files changed, 53 insertions(+), 28 deletions(-)
diff --git a/arch/arm/mach-at91/at91sam9260_devices.c b/arch/arm/mach-at91/at91sam9260_devices.c
index eb914c1..67dad94 100644
--- a/arch/arm/mach-at91/at91sam9260_devices.c
+++ b/arch/arm/mach-at91/at91sam9260_devices.c
@@ -1365,15 +1365,6 @@ void __init at91_add_device_adc(struct at91_adc_data *data)
if (test_bit(3, &data->channels_used))
at91_set_A_periph(AT91_PIN_PC3, 0);
- /*
- * The electrical characteristics part of the AT91SAM9G20 datasheet
- * sets the ADC clock to 5MHz.
- */
- data->adc_clock = 5000000;
-
- data->num_channels = 4;
- data->startup_time = 10;
-
adc_data = *data;
platform_device_register(&at91_adc_device);
}
diff --git a/drivers/staging/iio/adc/at91_adc.c b/drivers/staging/iio/adc/at91_adc.c
index d10df7a..4a0421e 100644
--- a/drivers/staging/iio/adc/at91_adc.c
+++ b/drivers/staging/iio/adc/at91_adc.c
@@ -24,6 +24,22 @@
#include <linux/platform_data/at91_adc.h>
#include <mach/at91_adc.h>
+#include <mach/cpu.h>
+
+/**
+ * struct at91_adc_desc - description of the ADC on the board
+ * @clock: ADC clock as specified by the datasheet, in Hz.
+ * @num_channels: global number of channels available on the board (to
+ specify which channels are indeed in use on the
+ board, see the channels_used bitmask in the platform
+ data)
+ * @startup_time: startup time of the ADC in microseconds
+ */
+struct at91_adc_desc {
+ u32 clock;
+ u8 num_channels;
+ u8 startup_time;
+};
struct at91_adc_state {
struct clk *clk;
@@ -35,8 +51,25 @@ struct at91_adc_state {
void __iomem *reg_base;
unsigned int vref_mv;
unsigned long channels_mask;
+ struct at91_adc_desc *desc;
+};
+
+static struct at91_adc_desc at91_adc_desc_sam9g20 = {
+ .clock = 5000000,
+ .num_channels = 4,
+ .startup_time = 10,
};
+static int at91_adc_select_soc(struct at91_adc_state *st)
+{
+ if (cpu_is_at91sam9g20()) {
+ st->desc = &at91_adc_desc_sam9g20;
+ return 0;
+ }
+
+ return -ENODEV;
+}
+
static inline u32 at91_adc_reg_read(struct at91_adc_state *st,
u8 reg)
{
@@ -72,18 +105,19 @@ static irqreturn_t at91_adc_eoc_trigger(int irq, void *private)
static int at91_adc_channel_init(struct iio_dev *idev,
struct at91_adc_data *pdata)
{
+ struct at91_adc_state *st = iio_priv(idev);
struct iio_chan_spec *chan_array;
int bit, idx = 0;
idev->num_channels = bitmap_weight(&pdata->channels_used,
- pdata->num_channels);
+ st->desc->num_channels);
chan_array = kcalloc(idev->num_channels, sizeof(struct iio_chan_spec),
GFP_KERNEL);
if (chan_array == NULL)
return -ENOMEM;
- for_each_set_bit(bit, &pdata->channels_used, pdata->num_channels) {
+ for_each_set_bit(bit, &pdata->channels_used, st->desc->num_channels) {
struct iio_chan_spec *chan = chan_array + idx;
chan->type = IIO_VOLTAGE;
chan->indexed = 1;
@@ -186,6 +220,12 @@ static int __devinit at91_adc_probe(struct platform_device *pdev)
idev->info = &at91_adc_info;
st = iio_priv(idev);
+ ret = at91_adc_select_soc(st);
+ if (ret) {
+ dev_err(&pdev->dev, "SoC unknown\n");
+ goto error_free_device;
+ }
+
st->irq = platform_get_irq(pdev, 0);
if (st->irq < 0) {
dev_err(&pdev->dev, "No IRQ ID is designated\n");
@@ -238,7 +278,7 @@ static int __devinit at91_adc_probe(struct platform_device *pdev)
goto error_free_clk;
}
- if (!pdata->adc_clock) {
+ if (!st->desc->clock) {
dev_err(&pdev->dev, "No ADCClock available.\n");
ret = -EINVAL;
goto error_free_clk;
@@ -249,9 +289,9 @@ static int __devinit at91_adc_probe(struct platform_device *pdev)
* datasheet : ADC Clock = MCK / ((Prescaler + 1) * 2), ADC Clock being
* specified by the electrical characteristics of the board.
*/
- prsc = (mstrclk / (2 * pdata->adc_clock)) - 1;
+ prsc = (mstrclk / (2 * st->desc->clock)) - 1;
- if (!pdata->startup_time) {
+ if (!st->desc->startup_time) {
dev_err(&pdev->dev, "No startup time available.\n");
ret = -EINVAL;
goto error_free_clk;
@@ -262,7 +302,7 @@ static int __devinit at91_adc_probe(struct platform_device *pdev)
* defined in the electrical characteristics of the board, divided by 8.
* The formula thus is : Startup Time = (ticks + 1) * 8 / ADC Clock
*/
- ticks = round_up((pdata->startup_time * pdata->adc_clock /
+ ticks = round_up((st->desc->startup_time * st->desc->clock /
1000000) - 1, 8) / 8;
at91_adc_reg_write(st, AT91_ADC_MR,
(AT91_ADC_PRESCAL_(prsc) & AT91_ADC_PRESCAL) |
diff --git a/include/linux/platform_data/at91_adc.h b/include/linux/platform_data/at91_adc.h
index 1e1813d..ab43de8 100644
--- a/include/linux/platform_data/at91_adc.h
+++ b/include/linux/platform_data/at91_adc.h
@@ -15,20 +15,14 @@
#ifndef _AT91_ADC_H_
#define _AT91_ADC_H_
+/**
+ * struct at91_adc_data - platform data for ADC driver
+ * @channels_use: channels in use on the board as a bitmask
+ * @vref: Reference voltage for the ADC in millvolts
+ */
struct at91_adc_data {
- /* ADC Clock as specified by the datasheet, in Hz. */
- unsigned int adc_clock;
- /*
- * Global number of channels available (to specify which channels are
- * indeed used on the board, see the channels_used bitmask).
- */
- u8 num_channels;
- /* Channels in use on the board as a bitmask */
- unsigned long channels_used;
- /* Startup time of the ADC, in microseconds. */
- u8 startup_time;
- /* Reference voltage for the ADC in millivolts */
- unsigned short vref;
+ u32 channels_used;
+ u16 vref;
};
extern void __init at91_add_device_adc(struct at91_adc_data *data);
--
1.7.4.1
^ permalink raw reply related [flat|nested] 19+ messages in thread* [PATCH 5/6] AT91: IIO: cosmetic fixes, better error messages
2011-12-07 18:25 [RFC v2] IIO: Add hardware triggers support to the AT91 ADC driver Maxime Ripard
` (3 preceding siblings ...)
2011-12-07 18:25 ` [PATCH 4/6] AT91: IIO: Move the SoC specific informations to the ADC driver Maxime Ripard
@ 2011-12-07 18:25 ` Maxime Ripard
2011-12-10 14:44 ` Jonathan Cameron
2011-12-07 18:25 ` [PATCH 6/6] AT91: IIO: Add support for hardware triggers for the ADC Maxime Ripard
2011-12-07 18:28 ` [RFC v2] IIO: Add hardware triggers support to the AT91 ADC driver Maxime Ripard
6 siblings, 1 reply; 19+ messages in thread
From: Maxime Ripard @ 2011-12-07 18:25 UTC (permalink / raw)
To: linux-iio; +Cc: Patrice Vilchez, Nicolas Ferre, Thomas Petazzoni
Signed-off-by: Maxime Ripard <maxime.ripard@free-electrons.com>
Cc: Patrice Vilchez <patrice.vilchez@atmel.com>
Cc: Nicolas Ferre <nicolas.ferre@atmel.com>
Cc: Thomas Petazzoni <thomas.petazzoni@free-electrons.com>
---
drivers/staging/iio/adc/at91_adc.c | 34 +++++++++++++++++++---------------
1 files changed, 19 insertions(+), 15 deletions(-)
diff --git a/drivers/staging/iio/adc/at91_adc.c b/drivers/staging/iio/adc/at91_adc.c
index 4a0421e..9d6e351 100644
--- a/drivers/staging/iio/adc/at91_adc.c
+++ b/drivers/staging/iio/adc/at91_adc.c
@@ -42,16 +42,16 @@ struct at91_adc_desc {
};
struct at91_adc_state {
- struct clk *clk;
- bool done;
- struct mutex lock;
- int irq;
- wait_queue_head_t wq_data_avail;
- u16 last_value;
- void __iomem *reg_base;
- unsigned int vref_mv;
- unsigned long channels_mask;
- struct at91_adc_desc *desc;
+ u32 channels_mask;
+ struct clk *clk;
+ bool done;
+ struct at91_adc_desc *desc;
+ int irq;
+ u16 last_value;
+ struct mutex lock;
+ void __iomem *reg_base;
+ u32 vref_mv;
+ wait_queue_head_t wq_data_avail;
};
static struct at91_adc_desc at91_adc_desc_sam9g20 = {
@@ -103,7 +103,7 @@ static irqreturn_t at91_adc_eoc_trigger(int irq, void *private)
}
static int at91_adc_channel_init(struct iio_dev *idev,
- struct at91_adc_data *pdata)
+ struct at91_adc_data *pdata)
{
struct at91_adc_state *st = iio_priv(idev);
struct iio_chan_spec *chan_array;
@@ -139,8 +139,8 @@ static void at91_adc_channel_remove(struct iio_dev *idev)
}
static int at91_adc_read_raw(struct iio_dev *idev,
- struct iio_chan_spec const *chan,
- int *val, int *val2, long mask)
+ struct iio_chan_spec const *chan,
+ int *val, int *val2, long mask)
{
struct at91_adc_state *st = iio_priv(idev);
int ret;
@@ -310,8 +310,10 @@ static int __devinit at91_adc_probe(struct platform_device *pdev)
/* Setup the ADC channels available on the board */
ret = at91_adc_channel_init(idev, pdata);
- if (ret < 0)
+ if (ret < 0) {
+ dev_err(&pdev->dev, "Couldn't initialize the channels.\n");
goto error_free_clk;
+ }
init_waitqueue_head(&st->wq_data_avail);
mutex_init(&st->lock);
@@ -320,8 +322,10 @@ static int __devinit at91_adc_probe(struct platform_device *pdev)
st->channels_mask = pdata->channels_used;
ret = iio_device_register(idev);
- if (ret < 0)
+ if (ret < 0) {
+ dev_err(&pdev->dev, "Couldn't register the device.\n");
goto error_free_channels;
+ }
return 0;
--
1.7.4.1
^ permalink raw reply related [flat|nested] 19+ messages in thread* Re: [PATCH 5/6] AT91: IIO: cosmetic fixes, better error messages
2011-12-07 18:25 ` [PATCH 5/6] AT91: IIO: cosmetic fixes, better error messages Maxime Ripard
@ 2011-12-10 14:44 ` Jonathan Cameron
2011-12-12 11:09 ` Maxime Ripard
0 siblings, 1 reply; 19+ messages in thread
From: Jonathan Cameron @ 2011-12-10 14:44 UTC (permalink / raw)
To: Maxime Ripard; +Cc: linux-iio, Patrice Vilchez, Nicolas Ferre, Thomas Petazzoni
All sensible but given I haven't merged anything (as being slow with
both trees just now), I'd rather see these pushed down into the
various places they were first created...
Jonathan
On 12/07/2011 06:25 PM, Maxime Ripard wrote:
> Signed-off-by: Maxime Ripard <maxime.ripard@free-electrons.com>
>
> Cc: Patrice Vilchez <patrice.vilchez@atmel.com>
> Cc: Nicolas Ferre <nicolas.ferre@atmel.com>
> Cc: Thomas Petazzoni <thomas.petazzoni@free-electrons.com>
> ---
> drivers/staging/iio/adc/at91_adc.c | 34 +++++++++++++++++++---------------
> 1 files changed, 19 insertions(+), 15 deletions(-)
>
> diff --git a/drivers/staging/iio/adc/at91_adc.c b/drivers/staging/iio/adc/at91_adc.c
> index 4a0421e..9d6e351 100644
> --- a/drivers/staging/iio/adc/at91_adc.c
> +++ b/drivers/staging/iio/adc/at91_adc.c
> @@ -42,16 +42,16 @@ struct at91_adc_desc {
> };
>
> struct at91_adc_state {
> - struct clk *clk;
> - bool done;
> - struct mutex lock;
> - int irq;
> - wait_queue_head_t wq_data_avail;
> - u16 last_value;
> - void __iomem *reg_base;
> - unsigned int vref_mv;
> - unsigned long channels_mask;
> - struct at91_adc_desc *desc;
> + u32 channels_mask;
> + struct clk *clk;
> + bool done;
> + struct at91_adc_desc *desc;
> + int irq;
> + u16 last_value;
> + struct mutex lock;
> + void __iomem *reg_base;
> + u32 vref_mv;
> + wait_queue_head_t wq_data_avail;
> };
>
> static struct at91_adc_desc at91_adc_desc_sam9g20 = {
> @@ -103,7 +103,7 @@ static irqreturn_t at91_adc_eoc_trigger(int irq, void *private)
> }
>
> static int at91_adc_channel_init(struct iio_dev *idev,
> - struct at91_adc_data *pdata)
> + struct at91_adc_data *pdata)
> {
> struct at91_adc_state *st = iio_priv(idev);
> struct iio_chan_spec *chan_array;
> @@ -139,8 +139,8 @@ static void at91_adc_channel_remove(struct iio_dev *idev)
> }
>
> static int at91_adc_read_raw(struct iio_dev *idev,
> - struct iio_chan_spec const *chan,
> - int *val, int *val2, long mask)
> + struct iio_chan_spec const *chan,
> + int *val, int *val2, long mask)
> {
> struct at91_adc_state *st = iio_priv(idev);
> int ret;
> @@ -310,8 +310,10 @@ static int __devinit at91_adc_probe(struct platform_device *pdev)
>
> /* Setup the ADC channels available on the board */
> ret = at91_adc_channel_init(idev, pdata);
> - if (ret < 0)
> + if (ret < 0) {
> + dev_err(&pdev->dev, "Couldn't initialize the channels.\n");
> goto error_free_clk;
> + }
>
> init_waitqueue_head(&st->wq_data_avail);
> mutex_init(&st->lock);
> @@ -320,8 +322,10 @@ static int __devinit at91_adc_probe(struct platform_device *pdev)
> st->channels_mask = pdata->channels_used;
>
> ret = iio_device_register(idev);
> - if (ret < 0)
> + if (ret < 0) {
> + dev_err(&pdev->dev, "Couldn't register the device.\n");
> goto error_free_channels;
> + }
>
> return 0;
>
^ permalink raw reply [flat|nested] 19+ messages in thread* Re: [PATCH 5/6] AT91: IIO: cosmetic fixes, better error messages
2011-12-10 14:44 ` Jonathan Cameron
@ 2011-12-12 11:09 ` Maxime Ripard
2011-12-12 21:30 ` Jonathan Cameron
0 siblings, 1 reply; 19+ messages in thread
From: Maxime Ripard @ 2011-12-12 11:09 UTC (permalink / raw)
To: Jonathan Cameron
Cc: linux-iio, Patrice Vilchez, Nicolas Ferre, Thomas Petazzoni
Hi Jonathan,
Ok, I will merge this patch with the other patchset and resend a version
of the other patchset.
I suppose you also want the fourth patch merged ?
Maxime
On 10/12/2011 15:44, Jonathan Cameron wrote:
> All sensible but given I haven't merged anything (as being slow with
> both trees just now), I'd rather see these pushed down into the
> various places they were first created...
>
> Jonathan
>
> On 12/07/2011 06:25 PM, Maxime Ripard wrote:
>> Signed-off-by: Maxime Ripard <maxime.ripard@free-electrons.com>
>>
>> Cc: Patrice Vilchez <patrice.vilchez@atmel.com>
>> Cc: Nicolas Ferre <nicolas.ferre@atmel.com>
>> Cc: Thomas Petazzoni <thomas.petazzoni@free-electrons.com>
>> ---
>> drivers/staging/iio/adc/at91_adc.c | 34 +++++++++++++++++++---------------
>> 1 files changed, 19 insertions(+), 15 deletions(-)
>>
>> diff --git a/drivers/staging/iio/adc/at91_adc.c b/drivers/staging/iio/adc/at91_adc.c
>> index 4a0421e..9d6e351 100644
>> --- a/drivers/staging/iio/adc/at91_adc.c
>> +++ b/drivers/staging/iio/adc/at91_adc.c
>> @@ -42,16 +42,16 @@ struct at91_adc_desc {
>> };
>>
>> struct at91_adc_state {
>> - struct clk *clk;
>> - bool done;
>> - struct mutex lock;
>> - int irq;
>> - wait_queue_head_t wq_data_avail;
>> - u16 last_value;
>> - void __iomem *reg_base;
>> - unsigned int vref_mv;
>> - unsigned long channels_mask;
>> - struct at91_adc_desc *desc;
>> + u32 channels_mask;
>> + struct clk *clk;
>> + bool done;
>> + struct at91_adc_desc *desc;
>> + int irq;
>> + u16 last_value;
>> + struct mutex lock;
>> + void __iomem *reg_base;
>> + u32 vref_mv;
>> + wait_queue_head_t wq_data_avail;
>> };
>>
>> static struct at91_adc_desc at91_adc_desc_sam9g20 = {
>> @@ -103,7 +103,7 @@ static irqreturn_t at91_adc_eoc_trigger(int irq, void *private)
>> }
>>
>> static int at91_adc_channel_init(struct iio_dev *idev,
>> - struct at91_adc_data *pdata)
>> + struct at91_adc_data *pdata)
>> {
>> struct at91_adc_state *st = iio_priv(idev);
>> struct iio_chan_spec *chan_array;
>> @@ -139,8 +139,8 @@ static void at91_adc_channel_remove(struct iio_dev *idev)
>> }
>>
>> static int at91_adc_read_raw(struct iio_dev *idev,
>> - struct iio_chan_spec const *chan,
>> - int *val, int *val2, long mask)
>> + struct iio_chan_spec const *chan,
>> + int *val, int *val2, long mask)
>> {
>> struct at91_adc_state *st = iio_priv(idev);
>> int ret;
>> @@ -310,8 +310,10 @@ static int __devinit at91_adc_probe(struct platform_device *pdev)
>>
>> /* Setup the ADC channels available on the board */
>> ret = at91_adc_channel_init(idev, pdata);
>> - if (ret < 0)
>> + if (ret < 0) {
>> + dev_err(&pdev->dev, "Couldn't initialize the channels.\n");
>> goto error_free_clk;
>> + }
>>
>> init_waitqueue_head(&st->wq_data_avail);
>> mutex_init(&st->lock);
>> @@ -320,8 +322,10 @@ static int __devinit at91_adc_probe(struct platform_device *pdev)
>> st->channels_mask = pdata->channels_used;
>>
>> ret = iio_device_register(idev);
>> - if (ret < 0)
>> + if (ret < 0) {
>> + dev_err(&pdev->dev, "Couldn't register the device.\n");
>> goto error_free_channels;
>> + }
>>
>> return 0;
>>
>
--
Maxime Ripard, Free Electrons
Kernel, drivers, real-time and embedded Linux
development, consulting, training and support.
http://free-electrons.com
^ permalink raw reply [flat|nested] 19+ messages in thread* Re: [PATCH 5/6] AT91: IIO: cosmetic fixes, better error messages
2011-12-12 11:09 ` Maxime Ripard
@ 2011-12-12 21:30 ` Jonathan Cameron
0 siblings, 0 replies; 19+ messages in thread
From: Jonathan Cameron @ 2011-12-12 21:30 UTC (permalink / raw)
To: Maxime Ripard; +Cc: linux-iio, Patrice Vilchez, Nicolas Ferre, Thomas Petazzoni
On 12/12/2011 11:09 AM, Maxime Ripard wrote:
> Hi Jonathan,
>
> Ok, I will merge this patch with the other patchset and resend a version
> of the other patchset.
>
> I suppose you also want the fourth patch merged ?
If they aren't how you would have written it from scratch, then yes
please (the answer that saves me reading that patch - daughter doing 30
second count down for a story ;)
>
> Maxime
>
> On 10/12/2011 15:44, Jonathan Cameron wrote:
>> All sensible but given I haven't merged anything (as being slow with
>> both trees just now), I'd rather see these pushed down into the
>> various places they were first created...
>>
>> Jonathan
>>
>> On 12/07/2011 06:25 PM, Maxime Ripard wrote:
>>> Signed-off-by: Maxime Ripard <maxime.ripard@free-electrons.com>
>>>
>>> Cc: Patrice Vilchez <patrice.vilchez@atmel.com>
>>> Cc: Nicolas Ferre <nicolas.ferre@atmel.com>
>>> Cc: Thomas Petazzoni <thomas.petazzoni@free-electrons.com>
>>> ---
>>> drivers/staging/iio/adc/at91_adc.c | 34 +++++++++++++++++++---------------
>>> 1 files changed, 19 insertions(+), 15 deletions(-)
>>>
>>> diff --git a/drivers/staging/iio/adc/at91_adc.c b/drivers/staging/iio/adc/at91_adc.c
>>> index 4a0421e..9d6e351 100644
>>> --- a/drivers/staging/iio/adc/at91_adc.c
>>> +++ b/drivers/staging/iio/adc/at91_adc.c
>>> @@ -42,16 +42,16 @@ struct at91_adc_desc {
>>> };
>>>
>>> struct at91_adc_state {
>>> - struct clk *clk;
>>> - bool done;
>>> - struct mutex lock;
>>> - int irq;
>>> - wait_queue_head_t wq_data_avail;
>>> - u16 last_value;
>>> - void __iomem *reg_base;
>>> - unsigned int vref_mv;
>>> - unsigned long channels_mask;
>>> - struct at91_adc_desc *desc;
>>> + u32 channels_mask;
>>> + struct clk *clk;
>>> + bool done;
>>> + struct at91_adc_desc *desc;
>>> + int irq;
>>> + u16 last_value;
>>> + struct mutex lock;
>>> + void __iomem *reg_base;
>>> + u32 vref_mv;
>>> + wait_queue_head_t wq_data_avail;
>>> };
>>>
>>> static struct at91_adc_desc at91_adc_desc_sam9g20 = {
>>> @@ -103,7 +103,7 @@ static irqreturn_t at91_adc_eoc_trigger(int irq, void *private)
>>> }
>>>
>>> static int at91_adc_channel_init(struct iio_dev *idev,
>>> - struct at91_adc_data *pdata)
>>> + struct at91_adc_data *pdata)
>>> {
>>> struct at91_adc_state *st = iio_priv(idev);
>>> struct iio_chan_spec *chan_array;
>>> @@ -139,8 +139,8 @@ static void at91_adc_channel_remove(struct iio_dev *idev)
>>> }
>>>
>>> static int at91_adc_read_raw(struct iio_dev *idev,
>>> - struct iio_chan_spec const *chan,
>>> - int *val, int *val2, long mask)
>>> + struct iio_chan_spec const *chan,
>>> + int *val, int *val2, long mask)
>>> {
>>> struct at91_adc_state *st = iio_priv(idev);
>>> int ret;
>>> @@ -310,8 +310,10 @@ static int __devinit at91_adc_probe(struct platform_device *pdev)
>>>
>>> /* Setup the ADC channels available on the board */
>>> ret = at91_adc_channel_init(idev, pdata);
>>> - if (ret < 0)
>>> + if (ret < 0) {
>>> + dev_err(&pdev->dev, "Couldn't initialize the channels.\n");
>>> goto error_free_clk;
>>> + }
>>>
>>> init_waitqueue_head(&st->wq_data_avail);
>>> mutex_init(&st->lock);
>>> @@ -320,8 +322,10 @@ static int __devinit at91_adc_probe(struct platform_device *pdev)
>>> st->channels_mask = pdata->channels_used;
>>>
>>> ret = iio_device_register(idev);
>>> - if (ret < 0)
>>> + if (ret < 0) {
>>> + dev_err(&pdev->dev, "Couldn't register the device.\n");
>>> goto error_free_channels;
>>> + }
>>>
>>> return 0;
>>>
>>
>
>
^ permalink raw reply [flat|nested] 19+ messages in thread
* [PATCH 6/6] AT91: IIO: Add support for hardware triggers for the ADC
2011-12-07 18:25 [RFC v2] IIO: Add hardware triggers support to the AT91 ADC driver Maxime Ripard
` (4 preceding siblings ...)
2011-12-07 18:25 ` [PATCH 5/6] AT91: IIO: cosmetic fixes, better error messages Maxime Ripard
@ 2011-12-07 18:25 ` Maxime Ripard
2011-12-10 15:24 ` Jonathan Cameron
2011-12-07 18:28 ` [RFC v2] IIO: Add hardware triggers support to the AT91 ADC driver Maxime Ripard
6 siblings, 1 reply; 19+ messages in thread
From: Maxime Ripard @ 2011-12-07 18:25 UTC (permalink / raw)
To: linux-iio; +Cc: Patrice Vilchez, Thomas Petazzoni, Nicolas Ferre
Signed-off-by: Maxime Ripard <maxime.ripard@free-electrons.com>
Cc: Patrice Vilchez <patrice.vilchez@atmel.com>
Cc: Thomas Petazzoni <thomas.petazzoni@free-electrons.com>
Cc: Nicolas Ferre <nicolas.ferre@atmel.com>
---
arch/arm/mach-at91/at91sam9260_devices.c | 3 +
arch/arm/mach-at91/board-sam9g20ek.c | 1 +
drivers/staging/iio/adc/Kconfig | 11 +-
drivers/staging/iio/adc/at91_adc.c | 286 +++++++++++++++++++++++++++++-
include/linux/platform_data/at91_adc.h | 2 +
5 files changed, 292 insertions(+), 11 deletions(-)
diff --git a/arch/arm/mach-at91/at91sam9260_devices.c b/arch/arm/mach-at91/at91sam9260_devices.c
index 67dad94..d30c9b8 100644
--- a/arch/arm/mach-at91/at91sam9260_devices.c
+++ b/arch/arm/mach-at91/at91sam9260_devices.c
@@ -1365,6 +1365,9 @@ void __init at91_add_device_adc(struct at91_adc_data *data)
if (test_bit(3, &data->channels_used))
at91_set_A_periph(AT91_PIN_PC3, 0);
+ if (data->use_external)
+ at91_set_A_periph(AT91_PIN_PA22, 0);
+
adc_data = *data;
platform_device_register(&at91_adc_device);
}
diff --git a/arch/arm/mach-at91/board-sam9g20ek.c b/arch/arm/mach-at91/board-sam9g20ek.c
index 7758f34..f18f6f2 100644
--- a/arch/arm/mach-at91/board-sam9g20ek.c
+++ b/arch/arm/mach-at91/board-sam9g20ek.c
@@ -317,6 +317,7 @@ static void __init ek_add_device_buttons(void) {}
static struct at91_adc_data ek_adc_data = {
.channels_used = BIT(0) | BIT(1) | BIT(2) | BIT(3),
+ .use_external = true,
.vref = 3300,
};
diff --git a/drivers/staging/iio/adc/Kconfig b/drivers/staging/iio/adc/Kconfig
index 93de64d..9d87c75 100644
--- a/drivers/staging/iio/adc/Kconfig
+++ b/drivers/staging/iio/adc/Kconfig
@@ -170,10 +170,13 @@ config AD7280
module will be called ad7280a
config AT91_ADC
- tristate "Atmel AT91 ADC"
- depends on SYSFS && ARCH_AT91
- help
- Say yes here to build support for Atmel AT91 ADC
+ tristate "Atmel AT91 ADC"
+ depends on SYSFS && ARCH_AT91
+ select IIO_BUFFER
+ select IIO_SW_RING
+ select IIO_TRIGGER
+ help
+ Say yes here to build support for Atmel AT91 ADC.
config MAX1363
tristate "Maxim max1363 ADC driver"
diff --git a/drivers/staging/iio/adc/at91_adc.c b/drivers/staging/iio/adc/at91_adc.c
index 9d6e351..fe31109 100644
--- a/drivers/staging/iio/adc/at91_adc.c
+++ b/drivers/staging/iio/adc/at91_adc.c
@@ -23,10 +23,28 @@
#include "../iio.h"
#include <linux/platform_data/at91_adc.h>
+#include "../buffer.h"
+#include "../ring_sw.h"
+#include "../trigger.h"
+#include "../trigger_consumer.h"
+
#include <mach/at91_adc.h>
#include <mach/cpu.h>
/**
+ * struct at91_adc_trigger - description of triggers
+ * @name: name of the trigger advertised to the user
+ * @value: value to set in the ADC's mode register to enable
+ the trigger
+ * @is_external: is the trigger relies on an external pin ?
+ */
+struct at91_adc_trigger {
+ char *name;
+ u8 value;
+ bool is_external;
+};
+
+/**
* struct at91_adc_desc - description of the ADC on the board
* @clock: ADC clock as specified by the datasheet, in Hz.
* @num_channels: global number of channels available on the board (to
@@ -34,30 +52,62 @@
board, see the channels_used bitmask in the platform
data)
* @startup_time: startup time of the ADC in microseconds
+ * @triggers: array of the triggers available on the board
*/
struct at91_adc_desc {
u32 clock;
u8 num_channels;
u8 startup_time;
+ struct at91_adc_trigger *triggers;
};
struct at91_adc_state {
+ u16 *buffer;
u32 channels_mask;
struct clk *clk;
bool done;
struct at91_adc_desc *desc;
int irq;
+ bool irq_enabled;
u16 last_value;
struct mutex lock;
void __iomem *reg_base;
+ struct iio_trigger **trig;
u32 vref_mv;
wait_queue_head_t wq_data_avail;
};
+static struct at91_adc_trigger at91_adc_trigger_sam9g20[] = {
+ [0] = {
+ .name = "timer-counter-0",
+ .value = AT91_ADC_TRGSEL_TC0 | AT91_ADC_TRGEN,
+ .is_external = false,
+ },
+ [1] = {
+ .name = "timer-counter-1",
+ .value = AT91_ADC_TRGSEL_TC1 | AT91_ADC_TRGEN,
+ .is_external = false,
+ },
+ [2] = {
+ .name = "timer-counter-2",
+ .value = AT91_ADC_TRGSEL_TC2 | AT91_ADC_TRGEN,
+ .is_external = false,
+ },
+ [3] = {
+ .name = "external",
+ .value = AT91_ADC_TRGSEL_EXTERNAL | AT91_ADC_TRGEN,
+ .is_external = true,
+ },
+ [4] = {
+ .name = NULL,
+ },
+};
+
static struct at91_adc_desc at91_adc_desc_sam9g20 = {
.clock = 5000000,
.num_channels = 4,
.startup_time = 10,
+ .triggers = at91_adc_trigger_sam9g20,
};
static int at91_adc_select_soc(struct at91_adc_state *st)
@@ -83,6 +133,48 @@ static inline void at91_adc_reg_write(struct at91_adc_state *st,
writel_relaxed(val, st->reg_base + reg);
}
+static irqreturn_t at91_adc_trigger_handler(int irq, void *p)
+{
+ struct iio_poll_func *pf = p;
+ struct iio_dev *idev = pf->indio_dev;
+ struct at91_adc_state *st = iio_priv(idev);
+ struct iio_buffer *buffer = idev->buffer;
+ int len = 0;
+
+ if (!bitmap_empty(idev->active_scan_mask, idev->masklength)) {
+ int i, j;
+ for (i = 0, j = 0;
+ i < bitmap_weight(idev->active_scan_mask,
+ idev->masklength);
+ i++) {
+ j = find_next_bit(buffer->scan_mask,
+ idev->masklength,
+ j);
+ st->buffer[i] = at91_adc_reg_read(st, AT91_ADC_CHR(j));
+ j++;
+ len += 2;
+ }
+ }
+
+ if (buffer->scan_timestamp) {
+ s64 *timestamp = (s64 *)((u8 *)st->buffer + ALIGN(len,
+ sizeof(s64)));
+ *timestamp = pf->timestamp;
+ }
+
+ buffer_store_to(buffer, (u8 *)st->buffer, pf->timestamp);
+
+ iio_trigger_notify_done(idev->trig);
+ st->irq_enabled = true;
+
+ /* Needed to ACK the DRDY interruption */
+ at91_adc_reg_read(st, AT91_ADC_LCDR);
+
+ enable_irq(st->irq);
+
+ return IRQ_HANDLED;
+}
+
static irqreturn_t at91_adc_eoc_trigger(int irq, void *private)
{
struct iio_dev *idev = private;
@@ -92,13 +184,16 @@ static irqreturn_t at91_adc_eoc_trigger(int irq, void *private)
if (!(status & AT91_ADC_DRDY))
return IRQ_HANDLED;
- if (status & st->channels_mask) {
- st->done = true;
+ if (iio_buffer_enabled(idev)) {
+ disable_irq_nosync(irq);
+ st->irq_enabled = false;
+ iio_trigger_poll(idev->trig, iio_get_time_ns());
+ } else {
st->last_value = at91_adc_reg_read(st, AT91_ADC_LCDR);
+ st->done = true;
+ wake_up_interruptible(&st->wq_data_avail);
}
- wake_up_interruptible(&st->wq_data_avail);
-
return IRQ_HANDLED;
}
@@ -110,8 +205,9 @@ static int at91_adc_channel_init(struct iio_dev *idev,
int bit, idx = 0;
idev->num_channels = bitmap_weight(&pdata->channels_used,
- st->desc->num_channels);
- chan_array = kcalloc(idev->num_channels, sizeof(struct iio_chan_spec),
+ st->desc->num_channels) + 1;
+ chan_array = kcalloc(idev->num_channels + 1,
+ sizeof(struct iio_chan_spec),
GFP_KERNEL);
if (chan_array == NULL)
@@ -122,6 +218,7 @@ static int at91_adc_channel_init(struct iio_dev *idev,
chan->type = IIO_VOLTAGE;
chan->indexed = 1;
chan->channel = bit;
+ chan->scan_index = idx;
chan->scan_type.sign = 'u';
chan->scan_type.realbits = 10;
chan->scan_type.storagebits = 16;
@@ -129,6 +226,13 @@ static int at91_adc_channel_init(struct iio_dev *idev,
idx++;
}
+ (chan_array + idx)->type = IIO_TIMESTAMP;
+ (chan_array + idx)->channel = -1;
+ (chan_array + idx)->scan_index = idx;
+ (chan_array + idx)->scan_type.sign = 's';
+ (chan_array + idx)->scan_type.realbits = 64;
+ (chan_array + idx)->scan_type.storagebits = 64;
+
idev->channels = chan_array;
return idev->num_channels;
}
@@ -138,6 +242,152 @@ static void at91_adc_channel_remove(struct iio_dev *idev)
kfree(idev->channels);
}
+static int at91_adc_configure_trigger(struct iio_trigger *trig, bool state)
+{
+ struct iio_dev *idev = trig->private_data;
+ struct at91_adc_state *st = iio_priv(idev);
+ struct iio_buffer *buffer = idev->buffer;
+ u32 status = at91_adc_reg_read(st, AT91_ADC_MR);
+ u8 bit;
+
+ if (state) {
+ size_t datasize = buffer_get_bytes_per_datum(buffer);
+ int i;
+
+ st->buffer = kmalloc(datasize, GFP_KERNEL);
+ if (st->buffer == NULL)
+ return -ENOMEM;
+
+ for (i = 0; (st->desc->triggers + i) != NULL; i++) {
+ char *name = kasprintf(GFP_KERNEL,
+ "%s-dev%d-%s",
+ idev->name,
+ idev->id,
+ st->desc->triggers[i].name);
+ if (name == NULL)
+ return -ENOMEM;
+
+ if (strcmp(idev->trig->name, name) == 0) {
+ status |= st->desc->triggers[i].value;
+ kfree(name);
+ break;
+ }
+
+ kfree(name);
+ }
+
+ if ((st->desc->triggers + i) == NULL)
+ return -EINVAL;
+
+ at91_adc_reg_write(st, AT91_ADC_MR, status);
+
+ for_each_set_bit(bit, buffer->scan_mask,
+ st->desc->num_channels) {
+ struct iio_chan_spec const *chan = idev->channels + bit;
+ at91_adc_reg_write(st, AT91_ADC_CHER,
+ AT91_ADC_CH(chan->channel));
+ }
+
+ at91_adc_reg_write(st, AT91_ADC_IER, AT91_ADC_DRDY);
+
+ } else {
+ at91_adc_reg_write(st, AT91_ADC_IDR, AT91_ADC_DRDY);
+ at91_adc_reg_write(st, AT91_ADC_MR,
+ status & ~AT91_ADC_TRGEN);
+
+ for_each_set_bit(bit, buffer->scan_mask,
+ st->desc->num_channels) {
+ at91_adc_reg_write(st, AT91_ADC_CHDR,
+ AT91_ADC_CH(bit));
+ }
+ kfree(st->buffer);
+ }
+
+ return 0;
+}
+
+static const struct iio_trigger_ops at91_adc_trigger_ops = {
+ .owner = THIS_MODULE,
+ .set_trigger_state = &at91_adc_configure_trigger,
+};
+
+
+static struct iio_trigger *at91_adc_allocate_trigger(struct iio_dev *idev,
+ struct at91_adc_trigger *trigger)
+{
+ struct iio_trigger *trig = iio_allocate_trigger("%s-dev%d-%s",
+ idev->name,
+ idev->id,
+ trigger->name);
+ int ret;
+
+ if (trig == NULL)
+ return NULL;
+
+ trig->dev.parent = idev->dev.parent;
+ trig->owner = THIS_MODULE;
+ trig->private_data = idev;
+ trig->ops = &at91_adc_trigger_ops;
+
+ ret = iio_trigger_register(trig);
+ if (ret < 0)
+ return NULL;
+
+ return trig;
+}
+
+static int at91_adc_trigger_init(struct iio_dev *idev,
+ struct at91_adc_data *pdata)
+{
+ struct at91_adc_state *st = iio_priv(idev);
+ int i, ret;
+
+ st->trig = kcalloc(sizeof(st->desc->triggers),
+ sizeof(struct iio_trigger *),
+ GFP_KERNEL);
+
+ if (st->trig == NULL) {
+ ret = -ENOMEM;
+ goto error_ret;
+ }
+
+ for (i = 0; st->desc->triggers[i].name != NULL; i++) {
+ if (st->desc->triggers[i].is_external && !(pdata->use_external))
+ continue;
+
+ st->trig[i] = at91_adc_allocate_trigger(idev,
+ st->desc->triggers + i);
+ if (st->trig[i] == NULL) {
+ ret = -ENOMEM;
+ goto error_trigger;
+ }
+ }
+
+ return 0;
+
+error_trigger:
+ for (; i >= 0; i--) {
+ iio_trigger_unregister(st->trig[i]);
+ iio_free_trigger(st->trig[i]);
+ }
+ kfree(st->trig);
+error_ret:
+ return ret;
+}
+
+static void at91_adc_trigger_remove(struct iio_dev *idev)
+{
+ struct at91_adc_state *st = iio_priv(idev);
+ int i;
+
+ for (i = 0; st->desc->triggers[i].name != NULL; i++) {
+ iio_trigger_unregister(st->trig[i]);
+ iio_free_trigger(st->trig[i]);
+ }
+
+ kfree(st->trig);
+}
+
static int at91_adc_read_raw(struct iio_dev *idev,
struct iio_chan_spec const *chan,
int *val, int *val2, long mask)
@@ -321,14 +571,34 @@ static int __devinit at91_adc_probe(struct platform_device *pdev)
st->vref_mv = pdata->vref;
st->channels_mask = pdata->channels_used;
+ ret = iio_sw_rb_simple_setup(idev,
+ &iio_pollfunc_store_time,
+ &at91_adc_trigger_handler);
+ if (ret < 0) {
+ dev_err(&pdev->dev, "Couldn't initialize the buffer.\n");
+ goto error_free_channels;
+ }
+
+ idev->buffer->scan_timestamp = true;
+
+ ret = at91_adc_trigger_init(idev, pdata);
+ if (ret < 0) {
+ dev_err(&pdev->dev, "Couldn't setup the triggers.\n");
+ goto error_unregister_buffer;
+ }
+
ret = iio_device_register(idev);
if (ret < 0) {
dev_err(&pdev->dev, "Couldn't register the device.\n");
- goto error_free_channels;
+ goto error_remove_triggers;
}
return 0;
+error_remove_triggers:
+ at91_adc_trigger_remove(idev);
+error_unregister_buffer:
+ iio_sw_rb_simple_cleanup(idev);
error_free_channels:
at91_adc_channel_remove(idev);
error_free_clk:
@@ -353,6 +623,8 @@ static int __devexit at91_adc_remove(struct platform_device *pdev)
struct at91_adc_state *st = iio_priv(idev);
iio_device_unregister(idev);
+ at91_adc_trigger_remove(idev);
+ iio_sw_rb_simple_cleanup(idev);
at91_adc_channel_remove(idev);
clk_disable(st->clk);
clk_put(st->clk);
diff --git a/include/linux/platform_data/at91_adc.h b/include/linux/platform_data/at91_adc.h
index ab43de8..b1d3a6d 100644
--- a/include/linux/platform_data/at91_adc.h
+++ b/include/linux/platform_data/at91_adc.h
@@ -18,10 +18,12 @@
/**
* struct at91_adc_data - platform data for ADC driver
* @channels_use: channels in use on the board as a bitmask
+ * @use_external: does the board has external triggers availables
* @vref: Reference voltage for the ADC in millvolts
*/
struct at91_adc_data {
u32 channels_used;
+ bool use_external;
u16 vref;
};
--
1.7.4.1
^ permalink raw reply related [flat|nested] 19+ messages in thread* Re: [PATCH 6/6] AT91: IIO: Add support for hardware triggers for the ADC
2011-12-07 18:25 ` [PATCH 6/6] AT91: IIO: Add support for hardware triggers for the ADC Maxime Ripard
@ 2011-12-10 15:24 ` Jonathan Cameron
2011-12-12 13:55 ` Maxime Ripard
0 siblings, 1 reply; 19+ messages in thread
From: Jonathan Cameron @ 2011-12-10 15:24 UTC (permalink / raw)
To: Maxime Ripard; +Cc: linux-iio, Patrice Vilchez, Thomas Petazzoni, Nicolas Ferre
On 12/07/2011 06:25 PM, Maxime Ripard wrote:
> Signed-off-by: Maxime Ripard <maxime.ripard@free-electrons.com>
>
Few bits and bobs inline...
> Cc: Patrice Vilchez <patrice.vilchez@atmel.com>
> Cc: Thomas Petazzoni <thomas.petazzoni@free-electrons.com>
> Cc: Nicolas Ferre <nicolas.ferre@atmel.com>
> ---
> arch/arm/mach-at91/at91sam9260_devices.c | 3 +
> arch/arm/mach-at91/board-sam9g20ek.c | 1 +
> drivers/staging/iio/adc/Kconfig | 11 +-
> drivers/staging/iio/adc/at91_adc.c | 286 +++++++++++++++++++++++++++++-
> include/linux/platform_data/at91_adc.h | 2 +
> 5 files changed, 292 insertions(+), 11 deletions(-)
>
> diff --git a/arch/arm/mach-at91/at91sam9260_devices.c b/arch/arm/mach-at91/at91sam9260_devices.c
> index 67dad94..d30c9b8 100644
> --- a/arch/arm/mach-at91/at91sam9260_devices.c
> +++ b/arch/arm/mach-at91/at91sam9260_devices.c
> @@ -1365,6 +1365,9 @@ void __init at91_add_device_adc(struct at91_adc_data *data)
> if (test_bit(3, &data->channels_used))
> at91_set_A_periph(AT91_PIN_PC3, 0);
>
> + if (data->use_external)
> + at91_set_A_periph(AT91_PIN_PA22, 0);
> +
> adc_data = *data;
> platform_device_register(&at91_adc_device);
> }
> diff --git a/arch/arm/mach-at91/board-sam9g20ek.c b/arch/arm/mach-at91/board-sam9g20ek.c
> index 7758f34..f18f6f2 100644
> --- a/arch/arm/mach-at91/board-sam9g20ek.c
> +++ b/arch/arm/mach-at91/board-sam9g20ek.c
> @@ -317,6 +317,7 @@ static void __init ek_add_device_buttons(void) {}
>
> static struct at91_adc_data ek_adc_data = {
> .channels_used = BIT(0) | BIT(1) | BIT(2) | BIT(3),
> + .use_external = true,
> .vref = 3300,
> };
>
> diff --git a/drivers/staging/iio/adc/Kconfig b/drivers/staging/iio/adc/Kconfig
> index 93de64d..9d87c75 100644
> --- a/drivers/staging/iio/adc/Kconfig
> +++ b/drivers/staging/iio/adc/Kconfig
> @@ -170,10 +170,13 @@ config AD7280
> module will be called ad7280a
>
> config AT91_ADC
> - tristate "Atmel AT91 ADC"
> - depends on SYSFS && ARCH_AT91
> - help
> - Say yes here to build support for Atmel AT91 ADC
> + tristate "Atmel AT91 ADC"
> + depends on SYSFS && ARCH_AT91
> + select IIO_BUFFER
> + select IIO_SW_RING
> + select IIO_TRIGGER
> + help
> + Say yes here to build support for Atmel AT91 ADC.
>
> config MAX1363
> tristate "Maxim max1363 ADC driver"
> diff --git a/drivers/staging/iio/adc/at91_adc.c b/drivers/staging/iio/adc/at91_adc.c
> index 9d6e351..fe31109 100644
> --- a/drivers/staging/iio/adc/at91_adc.c
> +++ b/drivers/staging/iio/adc/at91_adc.c
> @@ -23,10 +23,28 @@
> #include "../iio.h"
> #include <linux/platform_data/at91_adc.h>
>
> +#include "../buffer.h"
> +#include "../ring_sw.h"
> +#include "../trigger.h"
> +#include "../trigger_consumer.h"
> +
> #include <mach/at91_adc.h>
> #include <mach/cpu.h>
>
> /**
> + * struct at91_adc_trigger - description of triggers
> + * @name: name of the trigger advertised to the user
> + * @value: value to set in the ADC's mode register to enable
> + the trigger
> + * @is_external: is the trigger relies on an external pin ?
> + */
> +struct at91_adc_trigger {
> + char *name;
> + u8 value;
> + bool is_external;
> +};
> +
> +/**
> * struct at91_adc_desc - description of the ADC on the board
> * @clock: ADC clock as specified by the datasheet, in Hz.
> * @num_channels: global number of channels available on the board (to
> @@ -34,30 +52,62 @@
> board, see the channels_used bitmask in the platform
> data)
> * @startup_time: startup time of the ADC in microseconds
> + * @triggers: array of the triggers available on the board
> */
> struct at91_adc_desc {
> u32 clock;
> u8 num_channels;
> u8 startup_time;
> + struct at91_adc_trigger *triggers;
> };
>
> struct at91_adc_state {
> + u16 *buffer;
> u32 channels_mask;
> struct clk *clk;
> bool done;
> struct at91_adc_desc *desc;
> int irq;
> + bool irq_enabled;
> u16 last_value;
> struct mutex lock;
> void __iomem *reg_base;
> + struct iio_trigger **trig;
> u32 vref_mv;
> wait_queue_head_t wq_data_avail;
> };
>
> +static struct at91_adc_trigger at91_adc_trigger_sam9g20[] = {
> + [0] = {
> + .name = "timer-counter-0",
> + .value = AT91_ADC_TRGSEL_TC0 | AT91_ADC_TRGEN,
> + .is_external = false,
> + },
> + [1] = {
> + .name = "timer-counter-1",
> + .value = AT91_ADC_TRGSEL_TC1 | AT91_ADC_TRGEN,
> + .is_external = false,
> + },
> + [2] = {
> + .name = "timer-counter-2",
> + .value = AT91_ADC_TRGSEL_TC2 | AT91_ADC_TRGEN,
> + .is_external = false,
> + },
> + [3] = {
> + .name = "external",
> + .value = AT91_ADC_TRGSEL_EXTERNAL | AT91_ADC_TRGEN,
> + .is_external = true,
> + },
> + [4] = {
> + .name = NULL,
> + },
> +};
> +
> static struct at91_adc_desc at91_adc_desc_sam9g20 = {
> .clock = 5000000,
> .num_channels = 4,
> .startup_time = 10,
> + .triggers = at91_adc_trigger_sam9g20,
> };
>
> static int at91_adc_select_soc(struct at91_adc_state *st)
> @@ -83,6 +133,48 @@ static inline void at91_adc_reg_write(struct at91_adc_state *st,
> writel_relaxed(val, st->reg_base + reg);
> }
>
> +static irqreturn_t at91_adc_trigger_handler(int irq, void *p)
> +{
> + struct iio_poll_func *pf = p;
> + struct iio_dev *idev = pf->indio_dev;
> + struct at91_adc_state *st = iio_priv(idev);
> + struct iio_buffer *buffer = idev->buffer;
> + int len = 0;
> +
This doesn't look like stuff that should be in the fast patch.
Could you cache the register to be read in the update_scan_mask
callback then just run over them here? Feels like that might
be cleaner and lead to reads occuring faster.
> + if (!bitmap_empty(idev->active_scan_mask, idev->masklength)) {
> + int i, j;
> + for (i = 0, j = 0;
> + i < bitmap_weight(idev->active_scan_mask,
> + idev->masklength);
> + i++) {
> + j = find_next_bit(buffer->scan_mask,
> + idev->masklength,
> + j);
> + st->buffer[i] = at91_adc_reg_read(st, AT91_ADC_CHR(j));
> + j++;
> + len += 2;
> + }
> + }
> +
> + if (buffer->scan_timestamp) {
> + s64 *timestamp = (s64 *)((u8 *)st->buffer + ALIGN(len,
> + sizeof(s64)));
> + *timestamp = pf->timestamp;
> + }
> +
> + buffer_store_to(buffer, (u8 *)st->buffer, pf->timestamp);
> +
> + iio_trigger_notify_done(idev->trig);
> + st->irq_enabled = true;
> +
> + /* Needed to ACK the DRDY interruption */
> + at91_adc_reg_read(st, AT91_ADC_LCDR);
Still unsure why not threaded_irq and IRQF_ONESHOT.
+ I'd prefer to see that ack in try_reenable callback.
Also, if we need to ack, then why do we need to disable
the irq at all? Surely it won't reoccur until we have
acked?
> +
> + enable_irq(st->irq);
> +
> + return IRQ_HANDLED;
> +}
> +
> static irqreturn_t at91_adc_eoc_trigger(int irq, void *private)
> {
> struct iio_dev *idev = private;
> @@ -92,13 +184,16 @@ static irqreturn_t at91_adc_eoc_trigger(int irq, void *private)
> if (!(status & AT91_ADC_DRDY))
> return IRQ_HANDLED;
>
> - if (status & st->channels_mask) {
> - st->done = true;
> + if (iio_buffer_enabled(idev)) {
> + disable_irq_nosync(irq);
> + st->irq_enabled = false;
> + iio_trigger_poll(idev->trig, iio_get_time_ns());
> + } else {
> st->last_value = at91_adc_reg_read(st, AT91_ADC_LCDR);
> + st->done = true;
> + wake_up_interruptible(&st->wq_data_avail);
> }
>
> - wake_up_interruptible(&st->wq_data_avail);
> -
> return IRQ_HANDLED;
> }
>
> @@ -110,8 +205,9 @@ static int at91_adc_channel_init(struct iio_dev *idev,
> int bit, idx = 0;
>
> idev->num_channels = bitmap_weight(&pdata->channels_used,
> - st->desc->num_channels);
> - chan_array = kcalloc(idev->num_channels, sizeof(struct iio_chan_spec),
> + st->desc->num_channels) + 1;
> + chan_array = kcalloc(idev->num_channels + 1,
> + sizeof(struct iio_chan_spec),
> GFP_KERNEL);
Cosmetic change that should not be in this patch...
>
> if (chan_array == NULL)
> @@ -122,6 +218,7 @@ static int at91_adc_channel_init(struct iio_dev *idev,
> chan->type = IIO_VOLTAGE;
> chan->indexed = 1;
> chan->channel = bit;
> + chan->scan_index = idx;
> chan->scan_type.sign = 'u';
> chan->scan_type.realbits = 10;
> chan->scan_type.storagebits = 16;
> @@ -129,6 +226,13 @@ static int at91_adc_channel_init(struct iio_dev *idev,
> idx++;
> }
>
> + (chan_array + idx)->type = IIO_TIMESTAMP;
> + (chan_array + idx)->channel = -1;
> + (chan_array + idx)->scan_index = idx;
> + (chan_array + idx)->scan_type.sign = 's';
> + (chan_array + idx)->scan_type.realbits = 64;
> + (chan_array + idx)->scan_type.storagebits = 64;
> +
> idev->channels = chan_array;
> return idev->num_channels;
> }
> @@ -138,6 +242,152 @@ static void at91_adc_channel_remove(struct iio_dev *idev)
> kfree(idev->channels);
> }
>
> +static int at91_adc_configure_trigger(struct iio_trigger *trig, bool state)
> +{
> + struct iio_dev *idev = trig->private_data;
> + struct at91_adc_state *st = iio_priv(idev);
> + struct iio_buffer *buffer = idev->buffer;
> + u32 status = at91_adc_reg_read(st, AT91_ADC_MR);
> + u8 bit;
> +
> + if (state) {
> + size_t datasize = buffer_get_bytes_per_datum(buffer);
> + int i;
> +
> + st->buffer = kmalloc(datasize, GFP_KERNEL);
> + if (st->buffer == NULL)
> + return -ENOMEM;
> +
> + for (i = 0; (st->desc->triggers + i) != NULL; i++) {
I kind of feels here like we ought to be able to do better than matching
by name. After all, both ends of this match are controlled by this driver.
Perhaps embed the iio_trigger structure in a device specific one and
store some sort of reference in that? Just feels a little odd as it
currently stands...
> + char *name = kasprintf(GFP_KERNEL,
> + "%s-dev%d-%s",
> + idev->name,
> + idev->id,
> + st->desc->triggers[i].name);
> + if (name == NULL)
> + return -ENOMEM;
> +
> + if (strcmp(idev->trig->name, name) == 0) {
> + status |= st->desc->triggers[i].value;
> + kfree(name);
> + break;
> + }
> +
> + kfree(name);
> + }
> +
> + if ((st->desc->triggers + i) == NULL)
> + return -EINVAL;
> +
> + at91_adc_reg_write(st, AT91_ADC_MR, status);
> +
> + for_each_set_bit(bit, buffer->scan_mask,
> + st->desc->num_channels) {
> + struct iio_chan_spec const *chan = idev->channels + bit;
> + at91_adc_reg_write(st, AT91_ADC_CHER,
> + AT91_ADC_CH(chan->channel));
> + }
> +
> + at91_adc_reg_write(st, AT91_ADC_IER, AT91_ADC_DRDY);
> +
> + } else {
> + at91_adc_reg_write(st, AT91_ADC_IDR, AT91_ADC_DRDY);
> + at91_adc_reg_write(st, AT91_ADC_MR,
> + status & ~AT91_ADC_TRGEN);
> +
> + for_each_set_bit(bit, buffer->scan_mask,
> + st->desc->num_channels) {
> + at91_adc_reg_write(st, AT91_ADC_CHDR,
> + AT91_ADC_CH(bit));
Why do we need to look up the channel to turn it on, and not
to turn it off? Looks suspicious!
beware that things may well go wrong when we introduce multiple
buffers. I'm not sure that the scan configuration (which is
what is actually happening here) should be in the trigger
enable disable at all. Is this just to get us back to a
consistent state when not in triggered mode or is it
needed to stop triggers occuring?
> + }
> + kfree(st->buffer);
> + }
> +
> + return 0;
> +}
> +
> +static const struct iio_trigger_ops at91_adc_trigger_ops = {
> + .owner = THIS_MODULE,
> + .set_trigger_state = &at91_adc_configure_trigger,
> +};
> +
only one blank line please. (yup, i'm in a fussy mood ;)
> +
> +static struct iio_trigger *at91_adc_allocate_trigger(struct iio_dev *idev,
> + struct at91_adc_trigger *trigger)
> +{
> + struct iio_trigger *trig = iio_allocate_trigger("%s-dev%d-%s",
> + idev->name,
> + idev->id,
> + trigger->name);
> + int ret;
> +
> + if (trig == NULL)
> + return NULL;
> +
> + trig->dev.parent = idev->dev.parent;
> + trig->owner = THIS_MODULE;
Clearly my bug, but don't bother setting trig->owner as I'm
going to clear it out shortly... Actually you have led
me to what looks like a nasty issue for any driver that don't
have a trigger->ops (given that get and put trigger don't
bother to check). For the interested, ad7793 and ad7192 are
effected by this mess up. Will post patches after this review.
> + trig->private_data = idev;
> + trig->ops = &at91_adc_trigger_ops;
> +
> + ret = iio_trigger_register(trig);
> + if (ret < 0)
> + return NULL;
> +
> + return trig;
> +}
> +
> +static int at91_adc_trigger_init(struct iio_dev *idev,
> + struct at91_adc_data *pdata)
> +{
> + struct at91_adc_state *st = iio_priv(idev);
> + int i, ret;
> +
> + st->trig = kcalloc(sizeof(st->desc->triggers),
sizeof(st->trig),
makes things a tiny little bit more obvious...
(utter nitpick!)
> + sizeof(struct iio_trigger *),
> + GFP_KERNEL);
> +
> + if (st->trig == NULL) {
> + ret = -ENOMEM;
> + goto error_ret;
> + }
> +
> + for (i = 0; st->desc->triggers[i].name != NULL; i++) {
> + if (st->desc->triggers[i].is_external && !(pdata->use_external))
> + continue;
> +
> + st->trig[i] = at91_adc_allocate_trigger(idev,
> + st->desc->triggers + i);
> + if (st->trig[i] == NULL) {
> + ret = -ENOMEM;
> + goto error_trigger;
> + }
> + }
> +
> + return 0;
> +
> +error_trigger:
> + for (; i >= 0; i--) {
> + iio_trigger_unregister(st->trig[i]);
> + iio_free_trigger(st->trig[i]);
> + }
> + kfree(st->trig);
> +error_ret:
> + return ret;
> +}
> +
> +static void at91_adc_trigger_remove(struct iio_dev *idev)
> +{
> + struct at91_adc_state *st = iio_priv(idev);
> + int i;
> +
> + for (i = 0; st->desc->triggers[i].name != NULL; i++) {
> + iio_trigger_unregister(st->trig[i]);
> + iio_free_trigger(st->trig[i]);
> + }
> +
> + kfree(st->trig);
> +}
> +
> static int at91_adc_read_raw(struct iio_dev *idev,
> struct iio_chan_spec const *chan,
> int *val, int *val2, long mask)
> @@ -321,14 +571,34 @@ static int __devinit at91_adc_probe(struct platform_device *pdev)
> st->vref_mv = pdata->vref;
> st->channels_mask = pdata->channels_used;
>
> + ret = iio_sw_rb_simple_setup(idev,
> + &iio_pollfunc_store_time,
> + &at91_adc_trigger_handler);
> + if (ret < 0) {
> + dev_err(&pdev->dev, "Couldn't initialize the buffer.\n");
> + goto error_free_channels;
> + }
> +
> + idev->buffer->scan_timestamp = true;
I've just been moaning at others about this. Is there a good reason why
this wants to be on by default? I'd much rather decisions on this were
left to userspace. Hence lets assume no one wants any data unless they
tell us otherwise. (note I'm not sure this will play well with the
in kernel push interface stuff so I may well be killing off all
remaining cases where this occurs anyway...
> +
> + ret = at91_adc_trigger_init(idev, pdata);
> + if (ret < 0) {
> + dev_err(&pdev->dev, "Couldn't setup the triggers.\n");
> + goto error_unregister_buffer;
> + }
> +
> ret = iio_device_register(idev);
> if (ret < 0) {
> dev_err(&pdev->dev, "Couldn't register the device.\n");
> - goto error_free_channels;
> + goto error_remove_triggers;
> }
>
> return 0;
>
> +error_remove_triggers:
> + at91_adc_trigger_remove(idev);
> +error_unregister_buffer:
> + iio_sw_rb_simple_cleanup(idev);
> error_free_channels:
> at91_adc_channel_remove(idev);
> error_free_clk:
> @@ -353,6 +623,8 @@ static int __devexit at91_adc_remove(struct platform_device *pdev)
> struct at91_adc_state *st = iio_priv(idev);
>
> iio_device_unregister(idev);
> + at91_adc_trigger_remove(idev);
> + iio_sw_rb_simple_cleanup(idev);
> at91_adc_channel_remove(idev);
> clk_disable(st->clk);
> clk_put(st->clk);
> diff --git a/include/linux/platform_data/at91_adc.h b/include/linux/platform_data/at91_adc.h
> index ab43de8..b1d3a6d 100644
> --- a/include/linux/platform_data/at91_adc.h
> +++ b/include/linux/platform_data/at91_adc.h
> @@ -18,10 +18,12 @@
> /**
> * struct at91_adc_data - platform data for ADC driver
> * @channels_use: channels in use on the board as a bitmask
> + * @use_external: does the board has external triggers availables
> * @vref: Reference voltage for the ADC in millvolts
> */
> struct at91_adc_data {
> u32 channels_used;
> + bool use_external;
> u16 vref;
> };
>
^ permalink raw reply [flat|nested] 19+ messages in thread* Re: [PATCH 6/6] AT91: IIO: Add support for hardware triggers for the ADC
2011-12-10 15:24 ` Jonathan Cameron
@ 2011-12-12 13:55 ` Maxime Ripard
2011-12-12 21:29 ` Jonathan Cameron
0 siblings, 1 reply; 19+ messages in thread
From: Maxime Ripard @ 2011-12-12 13:55 UTC (permalink / raw)
To: Jonathan Cameron
Cc: linux-iio, Patrice Vilchez, Thomas Petazzoni, Nicolas Ferre
Hi,
On 10/12/2011 16:24, Jonathan Cameron wrote:
> On 12/07/2011 06:25 PM, Maxime Ripard wrote:
>> Signed-off-by: Maxime Ripard <maxime.ripard@free-electrons.com>
>>
> Few bits and bobs inline...
>
>> Cc: Patrice Vilchez <patrice.vilchez@atmel.com>
>> Cc: Thomas Petazzoni <thomas.petazzoni@free-electrons.com>
>> Cc: Nicolas Ferre <nicolas.ferre@atmel.com>
>> ---
>> arch/arm/mach-at91/at91sam9260_devices.c | 3 +
>> arch/arm/mach-at91/board-sam9g20ek.c | 1 +
>> drivers/staging/iio/adc/Kconfig | 11 +-
>> drivers/staging/iio/adc/at91_adc.c | 286 +++++++++++++++++++++++++++++-
>> include/linux/platform_data/at91_adc.h | 2 +
>> 5 files changed, 292 insertions(+), 11 deletions(-)
>>
>> diff --git a/arch/arm/mach-at91/at91sam9260_devices.c b/arch/arm/mach-at91/at91sam9260_devices.c
>> index 67dad94..d30c9b8 100644
>> --- a/arch/arm/mach-at91/at91sam9260_devices.c
>> +++ b/arch/arm/mach-at91/at91sam9260_devices.c
>> @@ -1365,6 +1365,9 @@ void __init at91_add_device_adc(struct at91_adc_data *data)
>> if (test_bit(3, &data->channels_used))
>> at91_set_A_periph(AT91_PIN_PC3, 0);
>>
>> + if (data->use_external)
>> + at91_set_A_periph(AT91_PIN_PA22, 0);
>> +
>> adc_data = *data;
>> platform_device_register(&at91_adc_device);
>> }
>> diff --git a/arch/arm/mach-at91/board-sam9g20ek.c b/arch/arm/mach-at91/board-sam9g20ek.c
>> index 7758f34..f18f6f2 100644
>> --- a/arch/arm/mach-at91/board-sam9g20ek.c
>> +++ b/arch/arm/mach-at91/board-sam9g20ek.c
>> @@ -317,6 +317,7 @@ static void __init ek_add_device_buttons(void) {}
>>
>> static struct at91_adc_data ek_adc_data = {
>> .channels_used = BIT(0) | BIT(1) | BIT(2) | BIT(3),
>> + .use_external = true,
>> .vref = 3300,
>> };
>>
>> diff --git a/drivers/staging/iio/adc/Kconfig b/drivers/staging/iio/adc/Kconfig
>> index 93de64d..9d87c75 100644
>> --- a/drivers/staging/iio/adc/Kconfig
>> +++ b/drivers/staging/iio/adc/Kconfig
>> @@ -170,10 +170,13 @@ config AD7280
>> module will be called ad7280a
>>
>> config AT91_ADC
>> - tristate "Atmel AT91 ADC"
>> - depends on SYSFS && ARCH_AT91
>> - help
>> - Say yes here to build support for Atmel AT91 ADC
>> + tristate "Atmel AT91 ADC"
>> + depends on SYSFS && ARCH_AT91
>> + select IIO_BUFFER
>> + select IIO_SW_RING
>> + select IIO_TRIGGER
>> + help
>> + Say yes here to build support for Atmel AT91 ADC.
>>
>> config MAX1363
>> tristate "Maxim max1363 ADC driver"
>> diff --git a/drivers/staging/iio/adc/at91_adc.c b/drivers/staging/iio/adc/at91_adc.c
>> index 9d6e351..fe31109 100644
>> --- a/drivers/staging/iio/adc/at91_adc.c
>> +++ b/drivers/staging/iio/adc/at91_adc.c
>> @@ -23,10 +23,28 @@
>> #include "../iio.h"
>> #include <linux/platform_data/at91_adc.h>
>>
>> +#include "../buffer.h"
>> +#include "../ring_sw.h"
>> +#include "../trigger.h"
>> +#include "../trigger_consumer.h"
>> +
>> #include <mach/at91_adc.h>
>> #include <mach/cpu.h>
>>
>> /**
>> + * struct at91_adc_trigger - description of triggers
>> + * @name: name of the trigger advertised to the user
>> + * @value: value to set in the ADC's mode register to enable
>> + the trigger
>> + * @is_external: is the trigger relies on an external pin ?
>> + */
>> +struct at91_adc_trigger {
>> + char *name;
>> + u8 value;
>> + bool is_external;
>> +};
>> +
>> +/**
>> * struct at91_adc_desc - description of the ADC on the board
>> * @clock: ADC clock as specified by the datasheet, in Hz.
>> * @num_channels: global number of channels available on the board (to
>> @@ -34,30 +52,62 @@
>> board, see the channels_used bitmask in the platform
>> data)
>> * @startup_time: startup time of the ADC in microseconds
>> + * @triggers: array of the triggers available on the board
>> */
>> struct at91_adc_desc {
>> u32 clock;
>> u8 num_channels;
>> u8 startup_time;
>> + struct at91_adc_trigger *triggers;
>> };
>>
>> struct at91_adc_state {
>> + u16 *buffer;
>> u32 channels_mask;
>> struct clk *clk;
>> bool done;
>> struct at91_adc_desc *desc;
>> int irq;
>> + bool irq_enabled;
>> u16 last_value;
>> struct mutex lock;
>> void __iomem *reg_base;
>> + struct iio_trigger **trig;
>> u32 vref_mv;
>> wait_queue_head_t wq_data_avail;
>> };
>>
>> +static struct at91_adc_trigger at91_adc_trigger_sam9g20[] = {
>> + [0] = {
>> + .name = "timer-counter-0",
>> + .value = AT91_ADC_TRGSEL_TC0 | AT91_ADC_TRGEN,
>> + .is_external = false,
>> + },
>> + [1] = {
>> + .name = "timer-counter-1",
>> + .value = AT91_ADC_TRGSEL_TC1 | AT91_ADC_TRGEN,
>> + .is_external = false,
>> + },
>> + [2] = {
>> + .name = "timer-counter-2",
>> + .value = AT91_ADC_TRGSEL_TC2 | AT91_ADC_TRGEN,
>> + .is_external = false,
>> + },
>> + [3] = {
>> + .name = "external",
>> + .value = AT91_ADC_TRGSEL_EXTERNAL | AT91_ADC_TRGEN,
>> + .is_external = true,
>> + },
>> + [4] = {
>> + .name = NULL,
>> + },
>> +};
>> +
>> static struct at91_adc_desc at91_adc_desc_sam9g20 = {
>> .clock = 5000000,
>> .num_channels = 4,
>> .startup_time = 10,
>> + .triggers = at91_adc_trigger_sam9g20,
>> };
>>
>> static int at91_adc_select_soc(struct at91_adc_state *st)
>> @@ -83,6 +133,48 @@ static inline void at91_adc_reg_write(struct at91_adc_state *st,
>> writel_relaxed(val, st->reg_base + reg);
>> }
>>
>> +static irqreturn_t at91_adc_trigger_handler(int irq, void *p)
>> +{
>> + struct iio_poll_func *pf = p;
>> + struct iio_dev *idev = pf->indio_dev;
>> + struct at91_adc_state *st = iio_priv(idev);
>> + struct iio_buffer *buffer = idev->buffer;
>> + int len = 0;
>> +
> This doesn't look like stuff that should be in the fast patch.
> Could you cache the register to be read in the update_scan_mask
> callback then just run over them here? Feels like that might
> be cleaner and lead to reads occuring faster.
Hmm, I don't see any update_scan_mask callback neither in the code nor
in the patches sent to the ml, am I missing something ?
>> + if (!bitmap_empty(idev->active_scan_mask, idev->masklength)) {
>> + int i, j;
>> + for (i = 0, j = 0;
>> + i < bitmap_weight(idev->active_scan_mask,
>> + idev->masklength);
>> + i++) {
>> + j = find_next_bit(buffer->scan_mask,
>> + idev->masklength,
>> + j);
>> + st->buffer[i] = at91_adc_reg_read(st, AT91_ADC_CHR(j));
>> + j++;
>> + len += 2;
>> + }
>> + }
>> +
>> + if (buffer->scan_timestamp) {
>> + s64 *timestamp = (s64 *)((u8 *)st->buffer + ALIGN(len,
>> + sizeof(s64)));
>> + *timestamp = pf->timestamp;
>> + }
>> +
>> + buffer_store_to(buffer, (u8 *)st->buffer, pf->timestamp);
>> +
>> + iio_trigger_notify_done(idev->trig);
>> + st->irq_enabled = true;
>> +
>> + /* Needed to ACK the DRDY interruption */
>> + at91_adc_reg_read(st, AT91_ADC_LCDR);
> Still unsure why not threaded_irq and IRQF_ONESHOT.
Oops, forgot to change it, sorry.
> + I'd prefer to see that ack in try_reenable callback.
> Also, if we need to ack, then why do we need to disable
> the irq at all? Surely it won't reoccur until we have
> acked?
If we don't ACK the interrupt, it will be replayed again and again.
Moreover, if we don't disable the interrupt, as we have no guarantee
about when the reading will actually occur, won't this screw things up
if the triggers keeps firing and we never enter in the handler that
store data in the buffer ?
>> +
>> + enable_irq(st->irq);
>> +
>> + return IRQ_HANDLED;
>> +}
>> +
>> static irqreturn_t at91_adc_eoc_trigger(int irq, void *private)
>> {
>> struct iio_dev *idev = private;
>> @@ -92,13 +184,16 @@ static irqreturn_t at91_adc_eoc_trigger(int irq, void *private)
>> if (!(status & AT91_ADC_DRDY))
>> return IRQ_HANDLED;
>>
>> - if (status & st->channels_mask) {
>> - st->done = true;
>> + if (iio_buffer_enabled(idev)) {
>> + disable_irq_nosync(irq);
>> + st->irq_enabled = false;
>> + iio_trigger_poll(idev->trig, iio_get_time_ns());
>> + } else {
>> st->last_value = at91_adc_reg_read(st, AT91_ADC_LCDR);
>> + st->done = true;
>> + wake_up_interruptible(&st->wq_data_avail);
>> }
>>
>> - wake_up_interruptible(&st->wq_data_avail);
>> -
>> return IRQ_HANDLED;
>> }
>>
>> @@ -110,8 +205,9 @@ static int at91_adc_channel_init(struct iio_dev *idev,
>> int bit, idx = 0;
>>
>> idev->num_channels = bitmap_weight(&pdata->channels_used,
>> - st->desc->num_channels);
>> - chan_array = kcalloc(idev->num_channels, sizeof(struct iio_chan_spec),
>> + st->desc->num_channels) + 1;
>> + chan_array = kcalloc(idev->num_channels + 1,
>> + sizeof(struct iio_chan_spec),
>> GFP_KERNEL);
> Cosmetic change that should not be in this patch...
Well, the number of allocated channels has been incremented by 1 for the
timestamp in the process, and while the diff makes it look that way, I
don't see any cosmetic change here.
>>
>> if (chan_array == NULL)
>> @@ -122,6 +218,7 @@ static int at91_adc_channel_init(struct iio_dev *idev,
>> chan->type = IIO_VOLTAGE;
>> chan->indexed = 1;
>> chan->channel = bit;
>> + chan->scan_index = idx;
>> chan->scan_type.sign = 'u';
>> chan->scan_type.realbits = 10;
>> chan->scan_type.storagebits = 16;
>> @@ -129,6 +226,13 @@ static int at91_adc_channel_init(struct iio_dev *idev,
>> idx++;
>> }
>>
>> + (chan_array + idx)->type = IIO_TIMESTAMP;
>> + (chan_array + idx)->channel = -1;
>> + (chan_array + idx)->scan_index = idx;
>> + (chan_array + idx)->scan_type.sign = 's';
>> + (chan_array + idx)->scan_type.realbits = 64;
>> + (chan_array + idx)->scan_type.storagebits = 64;
>> +
>> idev->channels = chan_array;
>> return idev->num_channels;
>> }
>> @@ -138,6 +242,152 @@ static void at91_adc_channel_remove(struct iio_dev *idev)
>> kfree(idev->channels);
>> }
>>
>> +static int at91_adc_configure_trigger(struct iio_trigger *trig, bool state)
>> +{
>> + struct iio_dev *idev = trig->private_data;
>> + struct at91_adc_state *st = iio_priv(idev);
>> + struct iio_buffer *buffer = idev->buffer;
>> + u32 status = at91_adc_reg_read(st, AT91_ADC_MR);
>> + u8 bit;
>> +
>> + if (state) {
>> + size_t datasize = buffer_get_bytes_per_datum(buffer);
>> + int i;
>> +
>> + st->buffer = kmalloc(datasize, GFP_KERNEL);
>> + if (st->buffer == NULL)
>> + return -ENOMEM;
>> +
>> + for (i = 0; (st->desc->triggers + i) != NULL; i++) {
> I kind of feels here like we ought to be able to do better than matching
> by name. After all, both ends of this match are controlled by this driver.
> Perhaps embed the iio_trigger structure in a device specific one and
> store some sort of reference in that? Just feels a little odd as it
> currently stands...
I agree on having a better dispatch mechanism, but maybe we could just
add a integer ID in the iio_trigger structure directly instead of
relying on some "heavy" structure manipulation. Of course, this ID would
have to be set in stone by the driver, juste like the channel part in
iio_chan_spec.
>> + char *name = kasprintf(GFP_KERNEL,
>> + "%s-dev%d-%s",
>> + idev->name,
>> + idev->id,
>> + st->desc->triggers[i].name);
>> + if (name == NULL)
>> + return -ENOMEM;
>> +
>> + if (strcmp(idev->trig->name, name) == 0) {
>> + status |= st->desc->triggers[i].value;
>> + kfree(name);
>> + break;
>> + }
>> +
>> + kfree(name);
>> + }
>> +
>> + if ((st->desc->triggers + i) == NULL)
>> + return -EINVAL;
>> +
>> + at91_adc_reg_write(st, AT91_ADC_MR, status);
>> +
>> + for_each_set_bit(bit, buffer->scan_mask,
>> + st->desc->num_channels) {
>> + struct iio_chan_spec const *chan = idev->channels + bit;
>> + at91_adc_reg_write(st, AT91_ADC_CHER,
>> + AT91_ADC_CH(chan->channel));
>> + }
>> +
>> + at91_adc_reg_write(st, AT91_ADC_IER, AT91_ADC_DRDY);
>> +
>> + } else {
>> + at91_adc_reg_write(st, AT91_ADC_IDR, AT91_ADC_DRDY);
>> + at91_adc_reg_write(st, AT91_ADC_MR,
>> + status & ~AT91_ADC_TRGEN);
>> +
>> + for_each_set_bit(bit, buffer->scan_mask,
>> + st->desc->num_channels) {
>> + at91_adc_reg_write(st, AT91_ADC_CHDR,
>> + AT91_ADC_CH(bit));
> Why do we need to look up the channel to turn it on, and not
> to turn it off? Looks suspicious!
Oh, right.
> beware that things may well go wrong when we introduce multiple
> buffers. I'm not sure that the scan configuration (which is
> what is actually happening here) should be in the trigger
> enable disable at all. Is this just to get us back to a
> consistent state when not in triggered mode or is it
> needed to stop triggers occuring?
Both actually. It sets us back into a state were we can safely either
use software triggers or setup a new capture. If we remove the setup of
the channels from here and put it into some callback, I'm quite certain
we will reach some corner cases when we come back from triggered mode,
with channels still enabled in IIO (and presumably in the hardware too)
and read into in_voltageX_raw...
>> + }
>> + kfree(st->buffer);
>> + }
>> +
>> + return 0;
>> +}
>> +
>> +static const struct iio_trigger_ops at91_adc_trigger_ops = {
>> + .owner = THIS_MODULE,
>> + .set_trigger_state = &at91_adc_configure_trigger,
>> +};
>> +
> only one blank line please. (yup, i'm in a fussy mood ;)
Ok :)
>> +
>> +static struct iio_trigger *at91_adc_allocate_trigger(struct iio_dev *idev,
>> + struct at91_adc_trigger *trigger)
>> +{
>> + struct iio_trigger *trig = iio_allocate_trigger("%s-dev%d-%s",
>> + idev->name,
>> + idev->id,
>> + trigger->name);
>> + int ret;
>> +
>> + if (trig == NULL)
>> + return NULL;
>> +
>> + trig->dev.parent = idev->dev.parent;
>> + trig->owner = THIS_MODULE;
> Clearly my bug, but don't bother setting trig->owner as I'm
> going to clear it out shortly... Actually you have led
> me to what looks like a nasty issue for any driver that don't
> have a trigger->ops (given that get and put trigger don't
> bother to check). For the interested, ad7793 and ad7192 are
> effected by this mess up. Will post patches after this review.
I'm glad I can help :)
>> + trig->private_data = idev;
>> + trig->ops = &at91_adc_trigger_ops;
>> +
>> + ret = iio_trigger_register(trig);
>> + if (ret < 0)
>> + return NULL;
>> +
>> + return trig;
>> +}
>> +
>> +static int at91_adc_trigger_init(struct iio_dev *idev,
>> + struct at91_adc_data *pdata)
>> +{
>> + struct at91_adc_state *st = iio_priv(idev);
>> + int i, ret;
>> +
>> + st->trig = kcalloc(sizeof(st->desc->triggers),
> sizeof(st->trig),
> makes things a tiny little bit more obvious...
> (utter nitpick!)
Ok
>> + sizeof(struct iio_trigger *),
>> + GFP_KERNEL);
>> +
>> + if (st->trig == NULL) {
>> + ret = -ENOMEM;
>> + goto error_ret;
>> + }
>> +
>> + for (i = 0; st->desc->triggers[i].name != NULL; i++) {
>> + if (st->desc->triggers[i].is_external && !(pdata->use_external))
>> + continue;
>> +
>> + st->trig[i] = at91_adc_allocate_trigger(idev,
>> + st->desc->triggers + i);
>> + if (st->trig[i] == NULL) {
>> + ret = -ENOMEM;
>> + goto error_trigger;
>> + }
>> + }
>> +
>> + return 0;
>> +
>> +error_trigger:
>> + for (; i >= 0; i--) {
>> + iio_trigger_unregister(st->trig[i]);
>> + iio_free_trigger(st->trig[i]);
>> + }
>> + kfree(st->trig);
>> +error_ret:
>> + return ret;
>> +}
>> +
>> +static void at91_adc_trigger_remove(struct iio_dev *idev)
>> +{
>> + struct at91_adc_state *st = iio_priv(idev);
>> + int i;
>> +
>> + for (i = 0; st->desc->triggers[i].name != NULL; i++) {
>> + iio_trigger_unregister(st->trig[i]);
>> + iio_free_trigger(st->trig[i]);
>> + }
>> +
>> + kfree(st->trig);
>> +}
>> +
>> static int at91_adc_read_raw(struct iio_dev *idev,
>> struct iio_chan_spec const *chan,
>> int *val, int *val2, long mask)
>> @@ -321,14 +571,34 @@ static int __devinit at91_adc_probe(struct platform_device *pdev)
>> st->vref_mv = pdata->vref;
>> st->channels_mask = pdata->channels_used;
>>
>> + ret = iio_sw_rb_simple_setup(idev,
>> + &iio_pollfunc_store_time,
>> + &at91_adc_trigger_handler);
>> + if (ret < 0) {
>> + dev_err(&pdev->dev, "Couldn't initialize the buffer.\n");
>> + goto error_free_channels;
>> + }
>> +
>> + idev->buffer->scan_timestamp = true;
> I've just been moaning at others about this. Is there a good reason why
> this wants to be on by default? I'd much rather decisions on this were
> left to userspace. Hence lets assume no one wants any data unless they
> tell us otherwise. (note I'm not sure this will play well with the
> in kernel push interface stuff so I may well be killing off all
> remaining cases where this occurs anyway...
It makes sense indeed.
>> +
>> + ret = at91_adc_trigger_init(idev, pdata);
>> + if (ret < 0) {
>> + dev_err(&pdev->dev, "Couldn't setup the triggers.\n");
>> + goto error_unregister_buffer;
>> + }
>> +
>> ret = iio_device_register(idev);
>> if (ret < 0) {
>> dev_err(&pdev->dev, "Couldn't register the device.\n");
>> - goto error_free_channels;
>> + goto error_remove_triggers;
>> }
>>
>> return 0;
>>
>> +error_remove_triggers:
>> + at91_adc_trigger_remove(idev);
>> +error_unregister_buffer:
>> + iio_sw_rb_simple_cleanup(idev);
>> error_free_channels:
>> at91_adc_channel_remove(idev);
>> error_free_clk:
>> @@ -353,6 +623,8 @@ static int __devexit at91_adc_remove(struct platform_device *pdev)
>> struct at91_adc_state *st = iio_priv(idev);
>>
>> iio_device_unregister(idev);
>> + at91_adc_trigger_remove(idev);
>> + iio_sw_rb_simple_cleanup(idev);
>> at91_adc_channel_remove(idev);
>> clk_disable(st->clk);
>> clk_put(st->clk);
>> diff --git a/include/linux/platform_data/at91_adc.h b/include/linux/platform_data/at91_adc.h
>> index ab43de8..b1d3a6d 100644
>> --- a/include/linux/platform_data/at91_adc.h
>> +++ b/include/linux/platform_data/at91_adc.h
>> @@ -18,10 +18,12 @@
>> /**
>> * struct at91_adc_data - platform data for ADC driver
>> * @channels_use: channels in use on the board as a bitmask
>> + * @use_external: does the board has external triggers availables
>> * @vref: Reference voltage for the ADC in millvolts
>> */
>> struct at91_adc_data {
>> u32 channels_used;
>> + bool use_external;
>> u16 vref;
>> };
>>
>
--
Maxime Ripard, Free Electrons
Kernel, drivers, real-time and embedded Linux
development, consulting, training and support.
http://free-electrons.com
^ permalink raw reply [flat|nested] 19+ messages in thread* Re: [PATCH 6/6] AT91: IIO: Add support for hardware triggers for the ADC
2011-12-12 13:55 ` Maxime Ripard
@ 2011-12-12 21:29 ` Jonathan Cameron
2011-12-13 13:33 ` Maxime Ripard
0 siblings, 1 reply; 19+ messages in thread
From: Jonathan Cameron @ 2011-12-12 21:29 UTC (permalink / raw)
To: Maxime Ripard; +Cc: linux-iio, Patrice Vilchez, Thomas Petazzoni, Nicolas Ferre
>>> +static irqreturn_t at91_adc_trigger_handler(int irq, void *p)
>>> +{
>>> + struct iio_poll_func *pf = p;
>>> + struct iio_dev *idev = pf->indio_dev;
>>> + struct at91_adc_state *st = iio_priv(idev);
>>> + struct iio_buffer *buffer = idev->buffer;
>>> + int len = 0;
>>> +
>> This doesn't look like stuff that should be in the fast patch.
>> Could you cache the register to be read in the update_scan_mask
>> callback then just run over them here? Feels like that might
>> be cleaner and lead to reads occuring faster.
>
> Hmm, I don't see any update_scan_mask callback neither in the code nor
> in the patches sent to the ml, am I missing something ?
sorry, update_scan_mode... Went in with a patch called
staging:iio: add hook to allow core to perform scan related config.
I think that merged a couple of days back..
>
>>> + if (!bitmap_empty(idev->active_scan_mask, idev->masklength)) {
>>> + int i, j;
>>> + for (i = 0, j = 0;
>>> + i < bitmap_weight(idev->active_scan_mask,
>>> + idev->masklength);
>>> + i++) {
>>> + j = find_next_bit(buffer->scan_mask,
>>> + idev->masklength,
>>> + j);
>>> + st->buffer[i] = at91_adc_reg_read(st, AT91_ADC_CHR(j));
>>> + j++;
>>> + len += 2;
>>> + }
>>> + }
>>> +
>>> + if (buffer->scan_timestamp) {
>>> + s64 *timestamp = (s64 *)((u8 *)st->buffer + ALIGN(len,
>>> + sizeof(s64)));
>>> + *timestamp = pf->timestamp;
>>> + }
>>> +
>>> + buffer_store_to(buffer, (u8 *)st->buffer, pf->timestamp);
>>> +
>>> + iio_trigger_notify_done(idev->trig);
>>> + st->irq_enabled = true;
>>> +
>>> + /* Needed to ACK the DRDY interruption */
>>> + at91_adc_reg_read(st, AT91_ADC_LCDR);
>> Still unsure why not threaded_irq and IRQF_ONESHOT.
>
> Oops, forgot to change it, sorry.
>
>> + I'd prefer to see that ack in try_reenable callback.
>> Also, if we need to ack, then why do we need to disable
>> the irq at all? Surely it won't reoccur until we have
>> acked?
>
> If we don't ACK the interrupt, it will be replayed again and again.
Level interrupt? May be some issues as it will occur prior to ack then...
> Moreover, if we don't disable the interrupt, as we have no guarantee
> about when the reading will actually occur, won't this screw things up
> if the triggers keeps firing and we never enter in the handler that
> store data in the buffer ?
The irqf_oneshot stuff handles this fine. Means only one instance is
running at a time (done by masking the interrupt). Also ensures you
don't miss any.
>
>>> +
>>> + enable_irq(st->irq);
>>> +
>>> + return IRQ_HANDLED;
>>> +}
>>> +
>>> static irqreturn_t at91_adc_eoc_trigger(int irq, void *private)
>>> {
>>> struct iio_dev *idev = private;
>>> @@ -92,13 +184,16 @@ static irqreturn_t at91_adc_eoc_trigger(int irq, void *private)
>>> if (!(status & AT91_ADC_DRDY))
>>> return IRQ_HANDLED;
>>>
>>> - if (status & st->channels_mask) {
>>> - st->done = true;
>>> + if (iio_buffer_enabled(idev)) {
>>> + disable_irq_nosync(irq);
>>> + st->irq_enabled = false;
>>> + iio_trigger_poll(idev->trig, iio_get_time_ns());
>>> + } else {
>>> st->last_value = at91_adc_reg_read(st, AT91_ADC_LCDR);
>>> + st->done = true;
>>> + wake_up_interruptible(&st->wq_data_avail);
>>> }
>>>
>>> - wake_up_interruptible(&st->wq_data_avail);
>>> -
>>> return IRQ_HANDLED;
>>> }
>>>
>>> @@ -110,8 +205,9 @@ static int at91_adc_channel_init(struct iio_dev *idev,
>>> int bit, idx = 0;
>>>
>>> idev->num_channels = bitmap_weight(&pdata->channels_used,
>>> - st->desc->num_channels);
>>> - chan_array = kcalloc(idev->num_channels, sizeof(struct iio_chan_spec),
>>> + st->desc->num_channels) + 1;
>>> + chan_array = kcalloc(idev->num_channels + 1,
>>> + sizeof(struct iio_chan_spec),
>>> GFP_KERNEL);
>> Cosmetic change that should not be in this patch...
>
> Well, the number of allocated channels has been incremented by 1 for the
> timestamp in the process, and while the diff makes it look that way, I
> don't see any cosmetic change here.
Ooops, missed that change in there. Sorry!
>
>>>
>>> if (chan_array == NULL)
>>> @@ -122,6 +218,7 @@ static int at91_adc_channel_init(struct iio_dev *idev,
>>> chan->type = IIO_VOLTAGE;
>>> chan->indexed = 1;
>>> chan->channel = bit;
>>> + chan->scan_index = idx;
>>> chan->scan_type.sign = 'u';
>>> chan->scan_type.realbits = 10;
>>> chan->scan_type.storagebits = 16;
>>> @@ -129,6 +226,13 @@ static int at91_adc_channel_init(struct iio_dev *idev,
>>> idx++;
>>> }
>>>
>>> + (chan_array + idx)->type = IIO_TIMESTAMP;
>>> + (chan_array + idx)->channel = -1;
>>> + (chan_array + idx)->scan_index = idx;
>>> + (chan_array + idx)->scan_type.sign = 's';
>>> + (chan_array + idx)->scan_type.realbits = 64;
>>> + (chan_array + idx)->scan_type.storagebits = 64;
>>> +
>>> idev->channels = chan_array;
>>> return idev->num_channels;
>>> }
>>> @@ -138,6 +242,152 @@ static void at91_adc_channel_remove(struct iio_dev *idev)
>>> kfree(idev->channels);
>>> }
>>>
>>> +static int at91_adc_configure_trigger(struct iio_trigger *trig, bool state)
>>> +{
>>> + struct iio_dev *idev = trig->private_data;
>>> + struct at91_adc_state *st = iio_priv(idev);
>>> + struct iio_buffer *buffer = idev->buffer;
>>> + u32 status = at91_adc_reg_read(st, AT91_ADC_MR);
>>> + u8 bit;
>>> +
>>> + if (state) {
>>> + size_t datasize = buffer_get_bytes_per_datum(buffer);
>>> + int i;
>>> +
>>> + st->buffer = kmalloc(datasize, GFP_KERNEL);
>>> + if (st->buffer == NULL)
>>> + return -ENOMEM;
>>> +
>>> + for (i = 0; (st->desc->triggers + i) != NULL; i++) {
>> I kind of feels here like we ought to be able to do better than matching
>> by name. After all, both ends of this match are controlled by this driver.
>> Perhaps embed the iio_trigger structure in a device specific one and
>> store some sort of reference in that? Just feels a little odd as it
>> currently stands...
>
> I agree on having a better dispatch mechanism, but maybe we could just
> add a integer ID in the iio_trigger structure directly instead of
> relying on some "heavy" structure manipulation. Of course, this ID would
> have to be set in stone by the driver, juste like the channel part in
> iio_chan_spec.
Maybe... I'd prefer a containing structure for now just because I don't
have a feel for how common. In other cases where we have a single
driver with multiple triggers (the userspace one, rtc etc) we handle
this by having the private pointer point at the trigger rather than a
containing structure. I can see why you haven't done this here though...
>
>>> + char *name = kasprintf(GFP_KERNEL,
>>> + "%s-dev%d-%s",
>>> + idev->name,
>>> + idev->id,
>>> + st->desc->triggers[i].name);
>>> + if (name == NULL)
>>> + return -ENOMEM;
>>> +
>>> + if (strcmp(idev->trig->name, name) == 0) {
>>> + status |= st->desc->triggers[i].value;
>>> + kfree(name);
>>> + break;
>>> + }
>>> +
>>> + kfree(name);
>>> + }
>>> +
>>> + if ((st->desc->triggers + i) == NULL)
>>> + return -EINVAL;
>>> +
>>> + at91_adc_reg_write(st, AT91_ADC_MR, status);
>>> +
>>> + for_each_set_bit(bit, buffer->scan_mask,
>>> + st->desc->num_channels) {
>>> + struct iio_chan_spec const *chan = idev->channels + bit;
>>> + at91_adc_reg_write(st, AT91_ADC_CHER,
>>> + AT91_ADC_CH(chan->channel));
>>> + }
>>> +
>>> + at91_adc_reg_write(st, AT91_ADC_IER, AT91_ADC_DRDY);
>>> +
>>> + } else {
>>> + at91_adc_reg_write(st, AT91_ADC_IDR, AT91_ADC_DRDY);
>>> + at91_adc_reg_write(st, AT91_ADC_MR,
>>> + status & ~AT91_ADC_TRGEN);
>>> +
>>> + for_each_set_bit(bit, buffer->scan_mask,
>>> + st->desc->num_channels) {
>>> + at91_adc_reg_write(st, AT91_ADC_CHDR,
>>> + AT91_ADC_CH(bit));
>> Why do we need to look up the channel to turn it on, and not
>> to turn it off? Looks suspicious!
>
> Oh, right.
>
>> beware that things may well go wrong when we introduce multiple
>> buffers. I'm not sure that the scan configuration (which is
>> what is actually happening here) should be in the trigger
>> enable disable at all. Is this just to get us back to a
>> consistent state when not in triggered mode or is it
>> needed to stop triggers occuring?
>
> Both actually. It sets us back into a state were we can safely either
> use software triggers or setup a new capture. If we remove the setup of
> the channels from here and put it into some callback, I'm quite certain
> we will reach some corner cases when we come back from triggered mode,
> with channels still enabled in IIO (and presumably in the hardware too)
> and read into in_voltageX_raw...
Then you make the in_voltageX_raw call do the channel setup rather than
the other way around. Lots of drivers doing precisely that...
That way no corner cases matter as we sanity check that the setup is
correct for whatever we want to do. Tends to lead to simpler code as
well overall.
^ permalink raw reply [flat|nested] 19+ messages in thread* Re: [PATCH 6/6] AT91: IIO: Add support for hardware triggers for the ADC
2011-12-12 21:29 ` Jonathan Cameron
@ 2011-12-13 13:33 ` Maxime Ripard
0 siblings, 0 replies; 19+ messages in thread
From: Maxime Ripard @ 2011-12-13 13:33 UTC (permalink / raw)
To: Jonathan Cameron
Cc: linux-iio, Patrice Vilchez, Thomas Petazzoni, Nicolas Ferre
Hi,
On 12/12/2011 22:29, Jonathan Cameron wrote:
>>>> +static irqreturn_t at91_adc_trigger_handler(int irq, void *p)
>>>> +{
>>>> + struct iio_poll_func *pf = p;
>>>> + struct iio_dev *idev = pf->indio_dev;
>>>> + struct at91_adc_state *st = iio_priv(idev);
>>>> + struct iio_buffer *buffer = idev->buffer;
>>>> + int len = 0;
>>>> +
>>> This doesn't look like stuff that should be in the fast patch.
>>> Could you cache the register to be read in the update_scan_mask
>>> callback then just run over them here? Feels like that might
>>> be cleaner and lead to reads occuring faster.
>>
>> Hmm, I don't see any update_scan_mask callback neither in the code nor
>> in the patches sent to the ml, am I missing something ?
> sorry, update_scan_mode... Went in with a patch called
>
> staging:iio: add hook to allow core to perform scan related config.
>
> I think that merged a couple of days back..
Oh, right.
>>
>>>> + if (!bitmap_empty(idev->active_scan_mask, idev->masklength)) {
>>>> + int i, j;
>>>> + for (i = 0, j = 0;
>>>> + i < bitmap_weight(idev->active_scan_mask,
>>>> + idev->masklength);
>>>> + i++) {
>>>> + j = find_next_bit(buffer->scan_mask,
>>>> + idev->masklength,
>>>> + j);
>>>> + st->buffer[i] = at91_adc_reg_read(st, AT91_ADC_CHR(j));
>>>> + j++;
>>>> + len += 2;
>>>> + }
>>>> + }
>>>> +
>>>> + if (buffer->scan_timestamp) {
>>>> + s64 *timestamp = (s64 *)((u8 *)st->buffer + ALIGN(len,
>>>> + sizeof(s64)));
>>>> + *timestamp = pf->timestamp;
>>>> + }
>>>> +
>>>> + buffer_store_to(buffer, (u8 *)st->buffer, pf->timestamp);
>>>> +
>>>> + iio_trigger_notify_done(idev->trig);
>>>> + st->irq_enabled = true;
>>>> +
>>>> + /* Needed to ACK the DRDY interruption */
>>>> + at91_adc_reg_read(st, AT91_ADC_LCDR);
>>> Still unsure why not threaded_irq and IRQF_ONESHOT.
>>
>> Oops, forgot to change it, sorry.
>>
>>> + I'd prefer to see that ack in try_reenable callback.
>>> Also, if we need to ack, then why do we need to disable
>>> the irq at all? Surely it won't reoccur until we have
>>> acked?
>>
>> If we don't ACK the interrupt, it will be replayed again and again.
> Level interrupt? May be some issues as it will occur prior to ack then...
Well, since the interrupt is disabled, I don't really see why it would
occur before the ACK.
>> Moreover, if we don't disable the interrupt, as we have no guarantee
>> about when the reading will actually occur, won't this screw things up
>> if the triggers keeps firing and we never enter in the handler that
>> store data in the buffer ?
> The irqf_oneshot stuff handles this fine. Means only one instance is
> running at a time (done by masking the interrupt). Also ensures you
> don't miss any.
I don't really get how this would work with threaded irqs, except with a
major rework of the handlers.
Obviously, you want the DRDY handler to be the thread here. So the
interrupts will be disabled until the end of the at91_adc_eoc_trigger
handler, which in turn generates an interrupt for the poll functions.
But here, the interrupts will keep coming as we have not yet ACKd
anything, the interrupt being level triggered (because reads are in the
bottom half of the poll function).
So the solution here might be to run iio_trigger_poll_chained instead,
as we would run the iio thread function in the same context, with
disabled interrupts. But as iio_trigger_poll_chained is calling directly
the iio thread function, we would lose the call to
iio_pollfunc_store_time (which is our hard IRQ handler).
So a solution would be to:
1) Get the timestamp in the hard IRQ handler for the ADC interrupt, the
closest to the end of conversion IRQ
2) Move at91_adc_eoc_trigger to the threaded IRQ handler for the ADC
interrupt
3) In the latter handler, call iio_trigger_poll_chained, so that the
thread function of pollfunc is run with the ADC IRQ line disabled.
>>>> +
>>>> + enable_irq(st->irq);
>>>> +
>>>> + return IRQ_HANDLED;
>>>> +}
>>>> +
>>>> static irqreturn_t at91_adc_eoc_trigger(int irq, void *private)
>>>> {
>>>> struct iio_dev *idev = private;
>>>> @@ -92,13 +184,16 @@ static irqreturn_t at91_adc_eoc_trigger(int irq, void *private)
>>>> if (!(status & AT91_ADC_DRDY))
>>>> return IRQ_HANDLED;
>>>>
>>>> - if (status & st->channels_mask) {
>>>> - st->done = true;
>>>> + if (iio_buffer_enabled(idev)) {
>>>> + disable_irq_nosync(irq);
>>>> + st->irq_enabled = false;
>>>> + iio_trigger_poll(idev->trig, iio_get_time_ns());
>>>> + } else {
>>>> st->last_value = at91_adc_reg_read(st, AT91_ADC_LCDR);
>>>> + st->done = true;
>>>> + wake_up_interruptible(&st->wq_data_avail);
>>>> }
>>>>
>>>> - wake_up_interruptible(&st->wq_data_avail);
>>>> -
>>>> return IRQ_HANDLED;
>>>> }
>>>>
>>>> @@ -110,8 +205,9 @@ static int at91_adc_channel_init(struct iio_dev *idev,
>>>> int bit, idx = 0;
>>>>
>>>> idev->num_channels = bitmap_weight(&pdata->channels_used,
>>>> - st->desc->num_channels);
>>>> - chan_array = kcalloc(idev->num_channels, sizeof(struct iio_chan_spec),
>>>> + st->desc->num_channels) + 1;
>>>> + chan_array = kcalloc(idev->num_channels + 1,
>>>> + sizeof(struct iio_chan_spec),
>>>> GFP_KERNEL);
>>> Cosmetic change that should not be in this patch...
>>
>> Well, the number of allocated channels has been incremented by 1 for the
>> timestamp in the process, and while the diff makes it look that way, I
>> don't see any cosmetic change here.
> Ooops, missed that change in there. Sorry!
>>
>>>>
>>>> if (chan_array == NULL)
>>>> @@ -122,6 +218,7 @@ static int at91_adc_channel_init(struct iio_dev *idev,
>>>> chan->type = IIO_VOLTAGE;
>>>> chan->indexed = 1;
>>>> chan->channel = bit;
>>>> + chan->scan_index = idx;
>>>> chan->scan_type.sign = 'u';
>>>> chan->scan_type.realbits = 10;
>>>> chan->scan_type.storagebits = 16;
>>>> @@ -129,6 +226,13 @@ static int at91_adc_channel_init(struct iio_dev *idev,
>>>> idx++;
>>>> }
>>>>
>>>> + (chan_array + idx)->type = IIO_TIMESTAMP;
>>>> + (chan_array + idx)->channel = -1;
>>>> + (chan_array + idx)->scan_index = idx;
>>>> + (chan_array + idx)->scan_type.sign = 's';
>>>> + (chan_array + idx)->scan_type.realbits = 64;
>>>> + (chan_array + idx)->scan_type.storagebits = 64;
>>>> +
>>>> idev->channels = chan_array;
>>>> return idev->num_channels;
>>>> }
>>>> @@ -138,6 +242,152 @@ static void at91_adc_channel_remove(struct iio_dev *idev)
>>>> kfree(idev->channels);
>>>> }
>>>>
>>>> +static int at91_adc_configure_trigger(struct iio_trigger *trig, bool state)
>>>> +{
>>>> + struct iio_dev *idev = trig->private_data;
>>>> + struct at91_adc_state *st = iio_priv(idev);
>>>> + struct iio_buffer *buffer = idev->buffer;
>>>> + u32 status = at91_adc_reg_read(st, AT91_ADC_MR);
>>>> + u8 bit;
>>>> +
>>>> + if (state) {
>>>> + size_t datasize = buffer_get_bytes_per_datum(buffer);
>>>> + int i;
>>>> +
>>>> + st->buffer = kmalloc(datasize, GFP_KERNEL);
>>>> + if (st->buffer == NULL)
>>>> + return -ENOMEM;
>>>> +
>>>> + for (i = 0; (st->desc->triggers + i) != NULL; i++) {
>>> I kind of feels here like we ought to be able to do better than matching
>>> by name. After all, both ends of this match are controlled by this driver.
>>> Perhaps embed the iio_trigger structure in a device specific one and
>>> store some sort of reference in that? Just feels a little odd as it
>>> currently stands...
>>
>> I agree on having a better dispatch mechanism, but maybe we could just
>> add a integer ID in the iio_trigger structure directly instead of
>> relying on some "heavy" structure manipulation. Of course, this ID would
>> have to be set in stone by the driver, juste like the channel part in
>> iio_chan_spec.
> Maybe... I'd prefer a containing structure for now just because I don't
> have a feel for how common. In other cases where we have a single
> driver with multiple triggers (the userspace one, rtc etc) we handle
> this by having the private pointer point at the trigger rather than a
> containing structure. I can see why you haven't done this here though...
>
>>
>>>> + char *name = kasprintf(GFP_KERNEL,
>>>> + "%s-dev%d-%s",
>>>> + idev->name,
>>>> + idev->id,
>>>> + st->desc->triggers[i].name);
>>>> + if (name == NULL)
>>>> + return -ENOMEM;
>>>> +
>>>> + if (strcmp(idev->trig->name, name) == 0) {
>>>> + status |= st->desc->triggers[i].value;
>>>> + kfree(name);
>>>> + break;
>>>> + }
>>>> +
>>>> + kfree(name);
>>>> + }
>>>> +
>>>> + if ((st->desc->triggers + i) == NULL)
>>>> + return -EINVAL;
>>>> +
>>>> + at91_adc_reg_write(st, AT91_ADC_MR, status);
>>>> +
>>>> + for_each_set_bit(bit, buffer->scan_mask,
>>>> + st->desc->num_channels) {
>>>> + struct iio_chan_spec const *chan = idev->channels + bit;
>>>> + at91_adc_reg_write(st, AT91_ADC_CHER,
>>>> + AT91_ADC_CH(chan->channel));
>>>> + }
>>>> +
>>>> + at91_adc_reg_write(st, AT91_ADC_IER, AT91_ADC_DRDY);
>>>> +
>>>> + } else {
>>>> + at91_adc_reg_write(st, AT91_ADC_IDR, AT91_ADC_DRDY);
>>>> + at91_adc_reg_write(st, AT91_ADC_MR,
>>>> + status & ~AT91_ADC_TRGEN);
>>>> +
>>>> + for_each_set_bit(bit, buffer->scan_mask,
>>>> + st->desc->num_channels) {
>>>> + at91_adc_reg_write(st, AT91_ADC_CHDR,
>>>> + AT91_ADC_CH(bit));
>>> Why do we need to look up the channel to turn it on, and not
>>> to turn it off? Looks suspicious!
>>
>> Oh, right.
>>
>>> beware that things may well go wrong when we introduce multiple
>>> buffers. I'm not sure that the scan configuration (which is
>>> what is actually happening here) should be in the trigger
>>> enable disable at all. Is this just to get us back to a
>>> consistent state when not in triggered mode or is it
>>> needed to stop triggers occuring?
>>
>> Both actually. It sets us back into a state were we can safely either
>> use software triggers or setup a new capture. If we remove the setup of
>> the channels from here and put it into some callback, I'm quite certain
>> we will reach some corner cases when we come back from triggered mode,
>> with channels still enabled in IIO (and presumably in the hardware too)
>> and read into in_voltageX_raw...
> Then you make the in_voltageX_raw call do the channel setup rather than
> the other way around. Lots of drivers doing precisely that...
> That way no corner cases matter as we sanity check that the setup is
> correct for whatever we want to do. Tends to lead to simpler code as
> well overall.
But still, let's say I enable the ADC channels in the update_scan_mode
callback. If we setup a triggered capture, with, for example channels 1
and 3 enabled. After a while, we stop the capture, and perform a
software trigger on channel 3. The read_raw function enables the channel
(which is already enabled), wait for the conversion, and then disables
the channel. From the ADC point of view, only the channel 1 would be
enabled, while from the IIO point of view, channels 1 and 3 would be
enabled. This is the kind of corner case I was talking about.
Maxime
--
Maxime Ripard, Free Electrons
Kernel, drivers, real-time and embedded Linux
development, consulting, training and support.
http://free-electrons.com
^ permalink raw reply [flat|nested] 19+ messages in thread
* Re: [RFC v2] IIO: Add hardware triggers support to the AT91 ADC driver
2011-12-07 18:25 [RFC v2] IIO: Add hardware triggers support to the AT91 ADC driver Maxime Ripard
` (5 preceding siblings ...)
2011-12-07 18:25 ` [PATCH 6/6] AT91: IIO: Add support for hardware triggers for the ADC Maxime Ripard
@ 2011-12-07 18:28 ` Maxime Ripard
2011-12-12 15:09 ` Maxime Ripard
6 siblings, 1 reply; 19+ messages in thread
From: Maxime Ripard @ 2011-12-07 18:28 UTC (permalink / raw)
To: linux-iio; +Cc: Patrice Vilchez, Nicolas Ferre, Thomas Petazzoni
HI,
I also have a question related to that.
The SAM9G20 has timer counters as trigger sources for the ADC. Is there
some kind of integration for them in IIO, or should we do the setup of
these counters outside of IIO ?
Thanks,
Maxime
On 07/12/2011 19:25, Maxime Ripard wrote:
> Hi all,
>
> This is a follow-up of the previous patchset about hardware triggers for the
> ADC on AT91.
>
> This is still not for inclusion, as it relies on a duplication of !staging code.
> But basically, I'm submitting it for review and be sure I do everything right.
> Moreover, it will save some iterations when the time for it to be included will
> come.
>
> I should have addressed all the points made by Jonathan in the v1, but here is
> what changed:
> - Fix the timestamp declaration. scan_timestamp was set to true, but no
> channel was declared for it. It is obviously wrong.
> - Rebased on brand new patches, instead of outdated branch. This patch now
> requires the buffer clean ups and scan demux unit patchsets from Jonathan and
> the brand new wrapper functions introduced by Lars Peter.
> - Renamed the triggers to be more explicit
> - Lot of small fixes and improvements: use ALIGN, change the location of
> IRQ acknowledgements, etc.
> - Added comments, switched to kernel doc for the structure declarations
> - split the cosmetic changes into a new commit
>
> Thanks,
> Maxime
>
> Cc: Patrice Vilchez <patrice.vilchez@atmel.com>
> Cc: Nicolas Ferre <nicolas.ferre@atmel.com>
> Cc: Thomas Petazzoni <thomas.petazzoni@free-electrons.com>
>
>
> --
> To unsubscribe from this list: send the line "unsubscribe linux-iio" in
> the body of a message to majordomo@vger.kernel.org
> More majordomo info at http://vger.kernel.org/majordomo-info.html
--
Maxime Ripard, Free Electrons
Kernel, drivers, real-time and embedded Linux
development, consulting, training and support.
http://free-electrons.com
^ permalink raw reply [flat|nested] 19+ messages in thread* Re: [RFC v2] IIO: Add hardware triggers support to the AT91 ADC driver
2011-12-07 18:28 ` [RFC v2] IIO: Add hardware triggers support to the AT91 ADC driver Maxime Ripard
@ 2011-12-12 15:09 ` Maxime Ripard
2011-12-12 21:14 ` Jonathan Cameron
0 siblings, 1 reply; 19+ messages in thread
From: Maxime Ripard @ 2011-12-12 15:09 UTC (permalink / raw)
To: linux-iio, Jonathan Cameron
Cc: Patrice Vilchez, Nicolas Ferre, Thomas Petazzoni
Hi Jonathan,
I think this is really something we should worry about if this is not
already here.
Even though on the G20, the timer counters come from an external IP, so
we can safely say it is not our job to setup these, on the later Atmel
SoCs, the timer counters are embedded into the ADC, so we would
definitely need to setup at least the period of these counters through IIO.
Maxime
On 07/12/2011 19:28, Maxime Ripard wrote:
> I also have a question related to that.
>
> The SAM9G20 has timer counters as trigger sources for the ADC. Is there
> some kind of integration for them in IIO, or should we do the setup of
> these counters outside of IIO ?
>
> Thanks,
> Maxime
>
> On 07/12/2011 19:25, Maxime Ripard wrote:
>> Hi all,
>>
>> This is a follow-up of the previous patchset about hardware triggers for the
>> ADC on AT91.
>>
>> This is still not for inclusion, as it relies on a duplication of !staging code.
>> But basically, I'm submitting it for review and be sure I do everything right.
>> Moreover, it will save some iterations when the time for it to be included will
>> come.
>>
>> I should have addressed all the points made by Jonathan in the v1, but here is
>> what changed:
>> - Fix the timestamp declaration. scan_timestamp was set to true, but no
>> channel was declared for it. It is obviously wrong.
>> - Rebased on brand new patches, instead of outdated branch. This patch now
>> requires the buffer clean ups and scan demux unit patchsets from Jonathan and
>> the brand new wrapper functions introduced by Lars Peter.
>> - Renamed the triggers to be more explicit
>> - Lot of small fixes and improvements: use ALIGN, change the location of
>> IRQ acknowledgements, etc.
>> - Added comments, switched to kernel doc for the structure declarations
>> - split the cosmetic changes into a new commit
>>
>> Thanks,
>> Maxime
>>
>> Cc: Patrice Vilchez <patrice.vilchez@atmel.com>
>> Cc: Nicolas Ferre <nicolas.ferre@atmel.com>
>> Cc: Thomas Petazzoni <thomas.petazzoni@free-electrons.com>
>>
>>
>> --
>> To unsubscribe from this list: send the line "unsubscribe linux-iio" in
>> the body of a message to majordomo@vger.kernel.org
>> More majordomo info at http://vger.kernel.org/majordomo-info.html
>
>
--
Maxime Ripard, Free Electrons
Kernel, drivers, real-time and embedded Linux
development, consulting, training and support.
http://free-electrons.com
^ permalink raw reply [flat|nested] 19+ messages in thread
* Re: [RFC v2] IIO: Add hardware triggers support to the AT91 ADC driver
2011-12-12 15:09 ` Maxime Ripard
@ 2011-12-12 21:14 ` Jonathan Cameron
2011-12-16 17:49 ` Maxime Ripard
0 siblings, 1 reply; 19+ messages in thread
From: Jonathan Cameron @ 2011-12-12 21:14 UTC (permalink / raw)
To: Maxime Ripard; +Cc: linux-iio, Patrice Vilchez, Nicolas Ferre, Thomas Petazzoni
Firstly, sorry I didn't reply when you first raised this. Read it,
thought I'll answer that later and then forgot!
> Hi Jonathan,
>
> I think this is really something we should worry about if this is not
> already here.
I am unclear how this should be supported by the core? Do we have any
real business getting involved. We already have an explicit trigger
driver for timers on the blackfin. Would something like that make
sense here?
>From the point of view of interfaces we also have the rtc driver
(which exits because I was using this as a dubious route to the
various timers on the pxa27x.. There have been various discussions
about generic support for these more general purpose timers but
no one has ever had the time to do anything about it.
>
> Even though on the G20, the timer counters come from an external IP, so
> we can safely say it is not our job to setup these, on the later Atmel
> SoCs, the timer counters are embedded into the ADC, so we would
> definitely need to setup at least the period of these counters through IIO.
Right now we have as stated about a number of drivers doing this, but no
inkernel interfaces. There have been various discussions about taking
the frequency control (that many chips that do data ready triggers have)
into the iio core more directly (to make them available
to in kernel users). Perhaps that fits more with what you are after?
Jonathan
>
> Maxime
>
> On 07/12/2011 19:28, Maxime Ripard wrote:
>> I also have a question related to that.
>>
>> The SAM9G20 has timer counters as trigger sources for the ADC. Is there
>> some kind of integration for them in IIO, or should we do the setup of
>> these counters outside of IIO ?
>>
>> Thanks,
>> Maxime
>>
>> On 07/12/2011 19:25, Maxime Ripard wrote:
>>> Hi all,
>>>
>>> This is a follow-up of the previous patchset about hardware triggers for the
>>> ADC on AT91.
>>>
>>> This is still not for inclusion, as it relies on a duplication of !staging code.
>>> But basically, I'm submitting it for review and be sure I do everything right.
>>> Moreover, it will save some iterations when the time for it to be included will
>>> come.
>>>
>>> I should have addressed all the points made by Jonathan in the v1, but here is
>>> what changed:
>>> - Fix the timestamp declaration. scan_timestamp was set to true, but no
>>> channel was declared for it. It is obviously wrong.
>>> - Rebased on brand new patches, instead of outdated branch. This patch now
>>> requires the buffer clean ups and scan demux unit patchsets from Jonathan and
>>> the brand new wrapper functions introduced by Lars Peter.
>>> - Renamed the triggers to be more explicit
>>> - Lot of small fixes and improvements: use ALIGN, change the location of
>>> IRQ acknowledgements, etc.
>>> - Added comments, switched to kernel doc for the structure declarations
>>> - split the cosmetic changes into a new commit
>>>
>>> Thanks,
>>> Maxime
>>>
>>> Cc: Patrice Vilchez <patrice.vilchez@atmel.com>
>>> Cc: Nicolas Ferre <nicolas.ferre@atmel.com>
>>> Cc: Thomas Petazzoni <thomas.petazzoni@free-electrons.com>
>>>
>>>
>>> --
>>> To unsubscribe from this list: send the line "unsubscribe linux-iio" in
>>> the body of a message to majordomo@vger.kernel.org
>>> More majordomo info at http://vger.kernel.org/majordomo-info.html
>>
>>
>
>
^ permalink raw reply [flat|nested] 19+ messages in thread
* Re: [RFC v2] IIO: Add hardware triggers support to the AT91 ADC driver
2011-12-12 21:14 ` Jonathan Cameron
@ 2011-12-16 17:49 ` Maxime Ripard
2011-12-19 8:41 ` archive
0 siblings, 1 reply; 19+ messages in thread
From: Maxime Ripard @ 2011-12-16 17:49 UTC (permalink / raw)
To: Jonathan Cameron
Cc: linux-iio, Patrice Vilchez, Nicolas Ferre, Thomas Petazzoni
Hi Jonathan,
On 12/12/2011 22:14, Jonathan Cameron wrote:
> Firstly, sorry I didn't reply when you first raised this. Read it,
> thought I'll answer that later and then forgot!
That's ok, I do that all the time :)
>> I think this is really something we should worry about if this is not
>> already here.
>
> I am unclear how this should be supported by the core? Do we have any
> real business getting involved. We already have an explicit trigger
> driver for timers on the blackfin. Would something like that make
> sense here?
I find it odd to have an external driver when you have to write in the
exact same registers of the exact same peripheral. On the G20, it would
make sense, on the later boards, you just have to put the period in the
appropriate field of one of the ADC's register, the same one you use to
setup triggered conversions.
> From the point of view of interfaces we also have the rtc driver
> (which exits because I was using this as a dubious route to the
> various timers on the pxa27x.. There have been various discussions
> about generic support for these more general purpose timers but
> no one has ever had the time to do anything about it.
Well, for my usecase, I guess just a triggerX/frequency file, that fills
the iio_trigger structure would be just fine, and it would be the
responsibility of the set_trigger_state callback to do what it has to do
with it. Of course, I don't know precisely the other drivers' usecases,
so this is probably not generic/extendable enough for IIO, but I'm
really curious about this. Can you point me to these discussions you're
mentionning ? I'm afraid I didn't saw them.
>> Even though on the G20, the timer counters come from an external IP, so
>> we can safely say it is not our job to setup these, on the later Atmel
>> SoCs, the timer counters are embedded into the ADC, so we would
>> definitely need to setup at least the period of these counters through IIO.
> Right now we have as stated about a number of drivers doing this, but no
> inkernel interfaces. There have been various discussions about taking
> the frequency control (that many chips that do data ready triggers have)
> into the iio core more directly (to make them available
> to in kernel users). Perhaps that fits more with what you are after?
Definitely.
Maxime
>> On 07/12/2011 19:28, Maxime Ripard wrote:
>>> I also have a question related to that.
>>>
>>> The SAM9G20 has timer counters as trigger sources for the ADC. Is there
>>> some kind of integration for them in IIO, or should we do the setup of
>>> these counters outside of IIO ?
>>>
>>> Thanks,
>>> Maxime
>>>
>>> On 07/12/2011 19:25, Maxime Ripard wrote:
>>>> Hi all,
>>>>
>>>> This is a follow-up of the previous patchset about hardware triggers for the
>>>> ADC on AT91.
>>>>
>>>> This is still not for inclusion, as it relies on a duplication of !staging code.
>>>> But basically, I'm submitting it for review and be sure I do everything right.
>>>> Moreover, it will save some iterations when the time for it to be included will
>>>> come.
>>>>
>>>> I should have addressed all the points made by Jonathan in the v1, but here is
>>>> what changed:
>>>> - Fix the timestamp declaration. scan_timestamp was set to true, but no
>>>> channel was declared for it. It is obviously wrong.
>>>> - Rebased on brand new patches, instead of outdated branch. This patch now
>>>> requires the buffer clean ups and scan demux unit patchsets from Jonathan and
>>>> the brand new wrapper functions introduced by Lars Peter.
>>>> - Renamed the triggers to be more explicit
>>>> - Lot of small fixes and improvements: use ALIGN, change the location of
>>>> IRQ acknowledgements, etc.
>>>> - Added comments, switched to kernel doc for the structure declarations
>>>> - split the cosmetic changes into a new commit
>>>>
>>>> Thanks,
>>>> Maxime
>>>>
>>>> Cc: Patrice Vilchez <patrice.vilchez@atmel.com>
>>>> Cc: Nicolas Ferre <nicolas.ferre@atmel.com>
>>>> Cc: Thomas Petazzoni <thomas.petazzoni@free-electrons.com>
>>>>
>>>>
>>>> --
>>>> To unsubscribe from this list: send the line "unsubscribe linux-iio" in
>>>> the body of a message to majordomo@vger.kernel.org
>>>> More majordomo info at http://vger.kernel.org/majordomo-info.html
>>>
>>>
>>
>>
>
--
Maxime Ripard, Free Electrons
Kernel, drivers, real-time and embedded Linux
development, consulting, training and support.
http://free-electrons.com
^ permalink raw reply [flat|nested] 19+ messages in thread
* Re: [RFC v2] IIO: Add hardware triggers support to the AT91 ADC driver
2011-12-16 17:49 ` Maxime Ripard
@ 2011-12-19 8:41 ` archive
0 siblings, 0 replies; 19+ messages in thread
From: archive @ 2011-12-19 8:41 UTC (permalink / raw)
To: Maxime Ripard
Cc: Jonathan Cameron, linux-iio, Patrice Vilchez, Nicolas Ferre,
Thomas Petazzoni
Maxime Ripard writes:
> Hi Jonathan,
>
> On 12/12/2011 22:14, Jonathan Cameron wrote:
>> Firstly, sorry I didn't reply when you first raised this. Read it,
>> thought I'll answer that later and then forgot!
>
> That's ok, I do that all the time :)
>
>>> I think this is really something we should worry about if this is not
>>> already here.
>>
>> I am unclear how this should be supported by the core? Do we have any
>> real business getting involved. We already have an explicit trigger
>> driver for timers on the blackfin. Would something like that make
>> sense here?
>
> I find it odd to have an external driver when you have to write in the
> exact same registers of the exact same peripheral.
Then don't make it external - just set everything up in the adc driver.
Numerous devices effectively do this.
> On the G20, it would
> make sense, on the later boards, you just have to put the period in the
> appropriate field of one of the ADC's register, the same one you use to
> setup triggered conversions.
Exactly like many other parts - see imu/adis16400 for example. Almost
anything with a dataready trigger is doing exactly this.
>
>> From the point of view of interfaces we also have the rtc driver
>> (which exits because I was using this as a dubious route to the
>> various timers on the pxa27x.. There have been various discussions
>> about generic support for these more general purpose timers but
>> no one has ever had the time to do anything about it.
>
> Well, for my usecase, I guess just a triggerX/frequency file, that fills
> the iio_trigger structure would be just fine, and it would be the
> responsibility of the set_trigger_state callback to do what it has to do
> with it. Of course, I don't know precisely the other drivers' usecases,
> so this is probably not generic/extendable enough for IIO,
It's all we have needed so far. Trigger interfaces are a lot less defined
than other parts of IIO, precisely because you can get some weird and
wonderful controls in here. This simple case turns up dozens of times
though.
> but I'm
> really curious about this. Can you point me to these discussions you're
> mentionning ? I'm afraid I didn't saw them.
Err. Was a long time ago and in a fairly obscure corner... I can only
find cryptic references to the discussion right now unfortunately...
From what I recall, everyone agreed it would be useful to have a generic
way of using the extra periodic timers found on some SoCs but no one had
enough interest in it to spend time actually doing it...
>
>>> Even though on the G20, the timer counters come from an external IP, so
>>> we can safely say it is not our job to setup these, on the later Atmel
>>> SoCs, the timer counters are embedded into the ADC, so we would
>>> definitely need to setup at least the period of these counters through IIO.
>> Right now we have as stated about a number of drivers doing this, but no
>> inkernel interfaces. There have been various discussions about taking
>> the frequency control (that many chips that do data ready triggers have)
>> into the iio core more directly (to make them available
>> to in kernel users). Perhaps that fits more with what you are after?
>
> Definitely.
We'll get to that one - or feel free to propose something yourself
if you have the time!
>
> Maxime
>
>>> On 07/12/2011 19:28, Maxime Ripard wrote:
>>>> I also have a question related to that.
>>>>
>>>> The SAM9G20 has timer counters as trigger sources for the ADC. Is there
>>>> some kind of integration for them in IIO, or should we do the setup of
>>>> these counters outside of IIO ?
>>>>
>>>> Thanks,
>>>> Maxime
>>>>
>>>> On 07/12/2011 19:25, Maxime Ripard wrote:
>>>>> Hi all,
>>>>>
>>>>> This is a follow-up of the previous patchset about hardware triggers for the
>>>>> ADC on AT91.
>>>>>
>>>>> This is still not for inclusion, as it relies on a duplication of !staging code.
>>>>> But basically, I'm submitting it for review and be sure I do everything right.
>>>>> Moreover, it will save some iterations when the time for it to be included will
>>>>> come.
>>>>>
>>>>> I should have addressed all the points made by Jonathan in the v1, but here is
>>>>> what changed:
>>>>> - Fix the timestamp declaration. scan_timestamp was set to true, but no
>>>>> channel was declared for it. It is obviously wrong.
>>>>> - Rebased on brand new patches, instead of outdated branch. This patch now
>>>>> requires the buffer clean ups and scan demux unit patchsets from Jonathan and
>>>>> the brand new wrapper functions introduced by Lars Peter.
>>>>> - Renamed the triggers to be more explicit
>>>>> - Lot of small fixes and improvements: use ALIGN, change the location of
>>>>> IRQ acknowledgements, etc.
>>>>> - Added comments, switched to kernel doc for the structure declarations
>>>>> - split the cosmetic changes into a new commit
>>>>>
>>>>> Thanks,
>>>>> Maxime
>>>>>
>>>>> Cc: Patrice Vilchez <patrice.vilchez@atmel.com>
>>>>> Cc: Nicolas Ferre <nicolas.ferre@atmel.com>
>>>>> Cc: Thomas Petazzoni <thomas.petazzoni@free-electrons.com>
>>>>>
>>>>>
>>>>> --
>>>>> To unsubscribe from this list: send the line "unsubscribe linux-iio" in
>>>>> the body of a message to majordomo@vger.kernel.org
>>>>> More majordomo info at http://vger.kernel.org/majordomo-info.html
>>>>
>>>>
>>>
>>>
>>
>
>
> --
> Maxime Ripard, Free Electrons
> Kernel, drivers, real-time and embedded Linux
> development, consulting, training and support.
> http://free-electrons.com
> --
> To unsubscribe from this list: send the line "unsubscribe linux-iio" in
> the body of a message to majordomo@vger.kernel.org
> More majordomo info at http://vger.kernel.org/majordomo-info.html
^ permalink raw reply [flat|nested] 19+ messages in thread