* [PATCH 0/2] Atmel AT91SAM9RL Touchscreen Driver
@ 2008-04-25 18:56 Justin Waters
2008-04-25 18:56 ` [PATCH 1/2] atmel_tsadcc: Device driver for AT91SAM9RL Touchscreen Justin Waters
0 siblings, 1 reply; 11+ messages in thread
From: Justin Waters @ 2008-04-25 18:56 UTC (permalink / raw)
To: linux-input, linux-arm-kernel; +Cc: dmitry.torokhov, linux
The following patches are for touchscreen support on the AT91SAM9RL SoC from
Atmel. It contains an integrated touchscreen/adc controller (tsadcc). These
patches initialize it an configure it purely as a touchscreen driver.
The first patch adds the driver to the kernel tree.
The second patch adds board and cpu specific functionality pertaining to the
AT91SAM9RL SoC and AT91SAM9RL-EK board.
These both apply to a mainline 2.6.25 kernel.
-------------------------------------------------------------------
List admin: http://lists.arm.linux.org.uk/mailman/listinfo/linux-arm-kernel
FAQ: http://www.arm.linux.org.uk/mailinglists/faq.php
Etiquette: http://www.arm.linux.org.uk/mailinglists/etiquette.php
^ permalink raw reply [flat|nested] 11+ messages in thread
* [PATCH 1/2] atmel_tsadcc: Device driver for AT91SAM9RL Touchscreen
2008-04-25 18:56 [PATCH 0/2] Atmel AT91SAM9RL Touchscreen Driver Justin Waters
@ 2008-04-25 18:56 ` Justin Waters
2008-04-25 18:56 ` [PATCH 2/2] atmel_tsadcc: Add board specific information for touchscreen driver Justin Waters
` (2 more replies)
0 siblings, 3 replies; 11+ messages in thread
From: Justin Waters @ 2008-04-25 18:56 UTC (permalink / raw)
To: linux-input, linux-arm-kernel; +Cc: dmitry.torokhov, linux
The atmel tsadcc is a touchscreen/adc controller found on the AT91SAM9RL SoC.
This driver provides basic support for this controller for use as a
touchscreen. Some future improvements include suspend/resume capabilities and
debugfs support.
Signed-off-by: Justin Waters <justin.waters@timesys.com>
---
drivers/input/touchscreen/Kconfig | 11 +
drivers/input/touchscreen/Makefile | 1 +
drivers/input/touchscreen/atmel_tsadcc.c | 375 ++++++++++++++++++++++++++++++
include/linux/atmel_tsadcc.h | 89 +++++++
4 files changed, 476 insertions(+), 0 deletions(-)
create mode 100644 drivers/input/touchscreen/atmel_tsadcc.c
create mode 100644 include/linux/atmel_tsadcc.h
diff --git a/drivers/input/touchscreen/Kconfig b/drivers/input/touchscreen/Kconfig
index 90e8e92..6e76eff 100644
--- a/drivers/input/touchscreen/Kconfig
+++ b/drivers/input/touchscreen/Kconfig
@@ -170,6 +170,17 @@ config TOUCHSCREEN_TOUCHWIN
To compile this driver as a module, choose M here: the
module will be called touchwin.
+config TOUCHSCREEN_ATMEL_TSADCC
+ tristate "Atmel Touchscreen Interface"
+ help
+ Say Y here if you have a 4-wire touchscreen connected to the
+ ADC Controller on your Atmel SoC (such as the AT91SAM9RL).
+
+ If unsure, say N.
+
+ To compile this driver as a module, choose M here: the
+ module will be called atmel_tsadcc.
+
config TOUCHSCREEN_UCB1400
tristate "Philips UCB1400 touchscreen"
select AC97_BUS
diff --git a/drivers/input/touchscreen/Makefile b/drivers/input/touchscreen/Makefile
index 35d4097..3302e27 100644
--- a/drivers/input/touchscreen/Makefile
+++ b/drivers/input/touchscreen/Makefile
@@ -18,4 +18,5 @@ obj-$(CONFIG_TOUCHSCREEN_USB_COMPOSITE) += usbtouchscreen.o
obj-$(CONFIG_TOUCHSCREEN_PENMOUNT) += penmount.o
obj-$(CONFIG_TOUCHSCREEN_TOUCHRIGHT) += touchright.o
obj-$(CONFIG_TOUCHSCREEN_TOUCHWIN) += touchwin.o
+obj-$(CONFIG_TOUCHSCREEN_ATMEL_TSADCC) += atmel_tsadcc.o
obj-$(CONFIG_TOUCHSCREEN_UCB1400) += ucb1400_ts.o
diff --git a/drivers/input/touchscreen/atmel_tsadcc.c b/drivers/input/touchscreen/atmel_tsadcc.c
new file mode 100644
index 0000000..b8a0984
--- /dev/null
+++ b/drivers/input/touchscreen/atmel_tsadcc.c
@@ -0,0 +1,375 @@
+/*
+ * Atmel TSADCC touchscreen sensor driver
+ *
+ * Copyright (c) 2008 TimeSys Corporation
+ * Copyright (c) 2008 Justin Waters
+ *
+ * Based on touchscreen code from Atmel Corporation
+ * and on the ads7846 driver by David Brownell.
+ *
+ * This program is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
+ */
+#include <linux/hwmon.h>
+#include <linux/init.h>
+#include <linux/clk.h>
+#include <linux/err.h>
+#include <linux/delay.h>
+#include <linux/input.h>
+#include <linux/interrupt.h>
+#include <linux/slab.h>
+#include <linux/platform_device.h>
+#include <asm/irq.h>
+#include <linux/atmel_tsadcc.h>
+
+/*
+ * This code has been heavily tested on the Atmel at91sam9rl-ek
+ */
+
+/* These values are dependent upon the performance of the ADC. Ideally,
+ * These should be as close to the startup time and debounce time as
+ * possible (without going over). These assume an optimally setup ADC as
+ * per the electrical characteristics of the AT91SAM9RL tsadcc module
+ */
+#define TS_POLL_DELAY (1 * 1000000) /* ns delay before the first sample */
+#define TS_POLL_PERIOD (5 * 1000000) /* ns delay between samples */
+
+/*--------------------------------------------------------------------------*/
+
+static inline void atmel_tsadcc_getevent(struct atmel_tsadcc *ts)
+{
+ unsigned int regbuf;
+
+ /*
+ * Calculate the X Coordinates
+ * x = (ATMEL_TSADCC_CDR3 * 1024) / ATMEL_TSADCC_CDR2
+ */
+ regbuf = atmel_tsadcc_readreg(ATMEL_TSADCC_CDR2);
+ if (regbuf)
+ regbuf = atmel_tsadcc_readreg(ATMEL_TSADCC_CDR3) * 1024 / regbuf;
+ ts->event.x = regbuf;
+
+ /*
+ * Calculate the Y Coordinates
+ * y = (ATMEL_TSADCC_CDR1 * 1024) / ATMEL_TSADCC_CDR0
+ */
+ regbuf = atmel_tsadcc_readreg(ATMEL_TSADCC_CDR0);
+ if (regbuf)
+ regbuf = atmel_tsadcc_readreg(ATMEL_TSADCC_CDR1) * 1024 / regbuf;
+ ts->event.y = regbuf;
+
+ dev_dbg (&ts->pdev->dev, "X=%08X Y=%08X\n", ts->event.x, ts->event.y);
+
+ return;
+}
+
+/*--------------------------------------------------------------------------*/
+/*
+ * Touchscreen Interrupts
+ *
+ * The TSADCC Touchscreen provides a number of hardware interrupts. For this
+ * driver, we enable the PENCNT and NOCNT interrupts, which signal an interrupt
+ * when the pen either makes or breaks contact with the screen. When the pen
+ * is detected, we enable a timer that triggers the ADC periodically and polls
+ * the results. The timer resets itself only as long as the pen is making
+ * contact. Once the pen is lifted, the timer is no longer refreshed and the
+ * button and pressure is reduced to zero.
+ */
+static enum hrtimer_restart atmel_tsadcc_timer(struct hrtimer *handle)
+{
+ struct atmel_tsadcc *ts = container_of(handle, struct atmel_tsadcc, timer);
+ unsigned long flags;
+ unsigned int status;
+
+ spin_lock_irqsave(&ts->lock, flags);
+
+ /* Read the status register */
+ status = atmel_tsadcc_readreg(ATMEL_TSADCC_SR);
+
+ /* If the data is ready, read it! */
+ if(status & 0xF)
+ {
+ /* Read the LCDR Register to clear the DRDY bit */
+ atmel_tsadcc_readreg(ATMEL_TSADCC_LCDR);
+
+ dev_dbg (&ts->pdev->dev,"Status=0x%08X\n",status);
+
+ /* Pen remains down */
+ atmel_tsadcc_getevent(ts);
+
+ input_report_abs(ts->input, ABS_X, ts->event.x);
+ input_report_abs(ts->input, ABS_Y, ts->event.y);
+ input_report_abs(ts->input, ABS_PRESSURE, 7500);
+
+ input_sync(ts->input);
+
+ if(ts->pendown) {
+ /* Make ADC perform another conversion */
+ atmel_tsadcc_writereg(ATMEL_TSADCC_CR,2);
+
+ hrtimer_start(&ts->timer, ktime_set(0, TS_POLL_PERIOD),
+ HRTIMER_MODE_REL);
+ }
+ }
+
+ spin_unlock_irq(&ts->lock);
+ return HRTIMER_NORESTART;
+}
+
+static irqreturn_t atmel_tsadcc_irq(int irq, void *handle)
+{
+ struct atmel_tsadcc *ts = handle;
+ unsigned long flags;
+ unsigned int status;
+
+ spin_lock_irqsave(&ts->lock, flags);
+
+ /* Read the status register */
+ status = atmel_tsadcc_readreg(ATMEL_TSADCC_SR);
+
+ /* Read the LCDR Register to clear the DRDY bit */
+ atmel_tsadcc_readreg(ATMEL_TSADCC_LCDR);
+
+ dev_dbg (&ts->pdev->dev,"Status=0x%08X\n",status);
+
+ if (ts->pendown) {
+ if (status & (1 << 21)) { /* Pen Up Event */
+ dev_dbg (&ts->pdev->dev, "Pen up\n");
+
+ ts->pendown = 0;
+
+ atmel_tsadcc_getevent(ts);
+
+ input_report_key(ts->input, BTN_TOUCH, 0);
+ input_report_abs(ts->input, ABS_PRESSURE, 0);
+ input_sync(ts->input);
+ }
+ } else if (status & (1 << 20)) { /* Pen first down */
+ dev_dbg (&ts->pdev->dev, "Pen down\n");
+
+ ts->pendown = 1;
+
+ atmel_tsadcc_getevent(ts);
+
+ input_report_key(ts->input, BTN_TOUCH, 1);
+ input_report_abs(ts->input, ABS_X, ts->event.x);
+ input_report_abs(ts->input, ABS_Y, ts->event.y);
+ input_report_abs(ts->input, ABS_PRESSURE, 1);
+
+ input_sync(ts->input);
+
+ /* Set up polling timer */
+ hrtimer_start(&ts->timer, ktime_set(0, TS_POLL_DELAY),
+ HRTIMER_MODE_REL);
+ }
+
+ spin_unlock_irqrestore(&ts->lock, flags);
+
+ return IRQ_HANDLED;
+}
+
+/*--------------------------------------------------------------------------*/
+/* TODO: Create power save features */
+static int atmel_tsadcc_suspend(struct platform_device *pdev, pm_message_t message)
+{
+ return 0;
+}
+
+static int atmel_tsadcc_resume(struct platform_device *pdev)
+{
+ return 0;
+}
+
+/*--------------------------------------------------------------------------*/
+
+static int __devinit atmel_tsadcc_probe(struct platform_device *pdev)
+{
+ struct atmel_tsadcc *ts;
+ struct input_dev *input_dev;
+ struct atmel_tsadcc_platform_data *pdata = pdev->dev.platform_data;
+ int err;
+ struct resource *res;
+ unsigned int regbuf;
+
+ dev_dbg(&pdev->dev,"Begin probe\n");
+
+ /* Check Resources */
+ if (pdev->num_resources != 2) {
+ dev_err(&pdev->dev, "resources improperly configured\n");
+ return -ENODEV;
+ }
+
+ if (!pdata) {
+ dev_err(&pdev->dev, "no platform data\n");
+ return -ENODEV;
+ }
+
+ /* Allocate memory for device */
+ ts = kzalloc(sizeof(struct atmel_tsadcc), GFP_KERNEL);
+ input_dev = input_allocate_device();
+ if (!ts || !input_dev) {
+ err = -ENOMEM;
+ goto err_free_mem;
+ }
+ platform_set_drvdata(pdev, ts);
+
+ /* Set up polling timer */
+ hrtimer_init(&ts->timer, CLOCK_MONOTONIC, HRTIMER_MODE_REL);
+ ts->timer.function = atmel_tsadcc_timer;
+
+ /* Touchscreen Information */
+ ts->pdev = pdev;
+ ts->input = input_dev;
+ snprintf(ts->phys, sizeof(ts->phys), "%s/input0", pdev->dev.bus_id);
+ ts->reg_name = "Atmel TSADCC Regs";
+ ts->pendown = 0;
+
+ /* Input Device Information */
+ input_dev->name = "Atmel Touchscreen ADC Controller";
+ input_dev->phys = ts->phys;
+ input_dev->dev.parent = &pdev->dev;
+
+ input_dev->evbit[0] = BIT_MASK(EV_KEY) | BIT_MASK(EV_ABS);
+ input_dev->keybit[BIT_WORD(BTN_TOUCH)] = BIT_MASK(BTN_TOUCH);
+ input_set_abs_params(input_dev, ABS_X, 0, 0x3FF, 0, 0);
+ input_set_abs_params(input_dev, ABS_Y, 0, 0x3FF, 0, 0);
+ input_set_abs_params(input_dev, ABS_PRESSURE, 0, 15000, 0, 0);
+
+ /* Remap Register Memory */
+ res = platform_get_resource(pdev, IORESOURCE_MEM, 0);
+ ts->reg_start = res->start;
+ ts->reg_length = res->end - res->start +1;
+
+ if (!request_mem_region(ts->reg_start, ts->reg_length, ts->reg_name)) {
+ dev_err(&pdev->dev, "resources unavailable\n");
+ err = -EBUSY;
+ goto err_free_mem;
+ }
+
+ ts->reg = ioremap(ts->reg_start, ts->reg_length);
+ if (!ts->reg){
+ dev_err(&pdev->dev, "unable to remap register memory\n");
+ err = -ENOMEM;
+ goto err_release_mem;
+ }
+
+ /* Setup Clock */
+ ts->tsc_clk = clk_get(&pdev->dev,"tsc_clk");
+ if (IS_ERR(ts->tsc_clk)) {
+ dev_err(&pdev->dev, "unable to get clock\n");
+ err = PTR_ERR(ts->tsc_clk);
+ goto err_iounmap;
+ }
+ clk_enable(ts->tsc_clk);
+
+ regbuf = clk_get_rate(ts->tsc_clk);
+ dev_dbg (&pdev->dev,"Master clock is set at: %d Hz\n",regbuf);
+
+ /* Setup IRQ */
+ ts->irq = platform_get_irq(pdev, 0);
+ if (ts->irq < 0) {
+ dev_err(&pdev->dev, "unable to get IRQ\n");
+ err = -EBUSY;
+ goto err_clk_put;
+ }
+
+ /* Fill in initial Register Data */
+ ATMEL_TSADCC_RESET;
+ regbuf = (0x01 & 0x3) | /* TSAMOD */
+ ((0x0 & 0x1) << 5) | /* SLEEP */
+ ((0x1 & 0x1) << 6) | /* PENDET */
+ ((pdata->prescaler & 0x3F) << 8) | /* PRESCAL */
+ ((pdata->startup & 0x7F) << 16) | /* STARTUP */
+ ((pdata->debounce & 0x0F) << 28); /* PENDBC */
+ atmel_tsadcc_writereg(ATMEL_TSADCC_MR,regbuf);
+
+ regbuf = (0x4 & 0x7) | /* TRGMOD */
+ ((0xFFFF & 0xFFFF) << 16); /* TRGPER */
+ atmel_tsadcc_writereg(ATMEL_TSADCC_TRGR,regbuf);
+
+ regbuf = ((pdata->tsshtim & 0xF) << 24); /* TSSHTIM */
+ atmel_tsadcc_writereg(ATMEL_TSADCC_TSR,regbuf);
+
+ regbuf = atmel_tsadcc_readreg(ATMEL_TSADCC_IMR);
+ dev_dbg (&pdev->dev, "Initial IMR = %X\n", regbuf);
+
+ /* Register and enable IRQ */
+ if (request_irq(ts->irq, atmel_tsadcc_irq, IRQF_TRIGGER_LOW,
+ pdev->dev.driver->name, ts)) {
+ dev_dbg(&pdev->dev, "IRQ %d busy!\n", ts->irq);
+ err = -EBUSY;
+ goto err_iounmap;
+ }
+ regbuf = ((0x1 & 0x1) << 20) | /* PENCNT */
+ ((0x1 & 0x1) << 21); /* NOCNT */
+ atmel_tsadcc_writereg(ATMEL_TSADCC_IER,regbuf);
+
+ regbuf = atmel_tsadcc_readreg(ATMEL_TSADCC_IMR);
+ dev_dbg (&pdev->dev, "Post-Enable IMR = %X\n", regbuf);
+
+ /* Register Input Device */
+ err = input_register_device(input_dev);
+ if (err)
+ goto err_free_irq;
+
+ return 0;
+
+ err_free_irq:
+ free_irq(ts->irq, ts);
+ err_clk_put:
+ clk_put(ts->tsc_clk);
+ err_iounmap:
+ iounmap(ts->reg);
+ err_release_mem:
+ release_mem_region(ts->reg_start, ts->reg_length);
+ err_free_mem:
+ dev_dbg(&pdev->dev, "Error occurred: Freeing Memory!\n");
+ input_free_device(input_dev);
+ kfree(ts);
+ return err;
+}
+
+static int __devexit atmel_tsadcc_remove(struct platform_device *pdev)
+{
+ struct atmel_tsadcc *ts = dev_get_drvdata(&pdev->dev);
+
+ input_unregister_device(ts->input);
+
+ free_irq(ts->irq, ts);
+
+ /* Free Memory */
+ iounmap(ts->reg);
+ release_mem_region(ts->reg_start, ts->reg_length);
+ kfree(ts);
+
+ dev_dbg(&pdev->dev, "unregistered touchscreen\n");
+
+ return 0;
+}
+
+static struct platform_driver atmel_tsadcc_driver = {
+ .driver = {
+ .name = "atmel_tsadcc",
+ .owner = THIS_MODULE,
+ },
+ .probe = atmel_tsadcc_probe,
+ .remove = __devexit_p(atmel_tsadcc_remove),
+ .suspend = atmel_tsadcc_suspend,
+ .resume = atmel_tsadcc_resume,
+};
+
+static int __init atmel_tsadcc_init(void)
+{
+ return platform_driver_register(&atmel_tsadcc_driver);
+}
+module_init(atmel_tsadcc_init);
+
+static void __exit atmel_tsadcc_exit(void)
+{
+ platform_driver_unregister(&atmel_tsadcc_driver);
+}
+module_exit(atmel_tsadcc_exit);
+
+MODULE_DESCRIPTION("Atmel TSADCC Touchscreen Driver");
+MODULE_LICENSE("GPL");
diff --git a/include/linux/atmel_tsadcc.h b/include/linux/atmel_tsadcc.h
new file mode 100644
index 0000000..3199622
--- /dev/null
+++ b/include/linux/atmel_tsadcc.h
@@ -0,0 +1,89 @@
+/*
+ * Atmel TSADCC touchscreen sensor driver
+ *
+ * Copyright (c) 2008 TimeSys Corporation
+ * Copyright (c) 2008 Justin Waters
+ *
+ * This program is free software; you can redistribute it and/or modify it
+ * under the terms of the GNU General Public License version 2 as published by
+ * the Free Software Foundation.
+ */
+
+#ifndef _ATMEL_TSADCC_H
+#define _ATMEL_TSADCC_H
+
+/*--------------------------------------------------------------------------
+ * Register Locations
+ *
+ * From AT91SAM9RL64 User Guide, 15-Jan-08, Table 43-2
+ *--------------------------------------------------------------------------*/
+#define ATMEL_TSADCC_CR 0x00 /* Control (wo) */
+#define ATMEL_TSADCC_MR 0x04 /* Mode (rw) */
+#define ATMEL_TSADCC_TRGR 0x08 /* Trigger (rw) */
+#define ATMEL_TSADCC_TSR 0x0C /* Touch Screen (rw) */
+#define ATMEL_TSADCC_CHER 0x10 /* Channel Enable (wo) */
+#define ATMEL_TSADCC_CHDR 0x14 /* Channel Disable (wo) */
+#define ATMEL_TSADCC_CHSR 0x18 /* Channel Status (ro) */
+#define ATMEL_TSADCC_SR 0x1C /* Status (ro) */
+#define ATMEL_TSADCC_LCDR 0x20 /* Last Converted Data (ro) */
+#define ATMEL_TSADCC_IER 0x24 /* Interrupt Enable (wo) */
+#define ATMEL_TSADCC_IDR 0x28 /* Interrupt Disable (wo) */
+#define ATMEL_TSADCC_IMR 0x2C /* Interrupt Mask (ro) */
+#define ATMEL_TSADCC_CDR0 0x30 /* Channel Data 0 (ro) */
+#define ATMEL_TSADCC_CDR1 0x34 /* Channel Data 1 (ro) */
+#define ATMEL_TSADCC_CDR2 0x38 /* Channel Data 2 (ro) */
+#define ATMEL_TSADCC_CDR3 0x3C /* Channel Data 3 (ro) */
+#define ATMEL_TSADCC_CDR4 0x40 /* Channel Data 4 (ro) */
+#define ATMEL_TSADCC_CDR5 0x44 /* Channel Data 5 (ro) */
+
+/*--------------------------------------------------------------------------
+ * I/O Macros
+ *--------------------------------------------------------------------------*/
+#define atmel_tsadcc_readreg(a) ioread32(ts->reg + a)
+#define atmel_tsadcc_writereg(a,v) iowrite32(v,ts->reg + a)
+
+
+/*--------------------------------------------------------------------------
+ * Miscellaneous Macros
+ *--------------------------------------------------------------------------*/
+#define ATMEL_TSADCC_RESET atmel_tsadcc_writereg(ATMEL_TSADCC_CR,0x00000001)
+
+/*--------------------------------------------------------------------------
+ * Touchscreen Structs
+ *--------------------------------------------------------------------------*/
+
+struct ts_event {
+ unsigned int x;
+ unsigned int y;
+};
+
+struct atmel_tsadcc_platform_data {
+ unsigned int prescaler:6; /* ADC Clock Prescaler */
+ unsigned int debounce:4; /* Pen Debounce Period */
+ unsigned int tsshtim:4; /* Touchscreen Sample and Hold Time */
+ unsigned int startup:7; /* Startup time */
+};
+
+struct atmel_tsadcc {
+ struct input_dev *input;
+ char phys[32];
+ struct platform_device *pdev;
+ int irq;
+
+ void __iomem *reg;
+ const char *reg_name;
+ unsigned long reg_start;
+ unsigned long reg_length;
+
+ spinlock_t lock;
+
+ struct clk *tsc_clk;
+ struct hrtimer timer;
+ struct ts_event event;
+
+ unsigned int pendown;
+};
+
+/*--------------------------------------------------------------------------*/
+
+#endif /* _ATMEL_TSADCC_H */
--
1.5.4.3
-------------------------------------------------------------------
List admin: http://lists.arm.linux.org.uk/mailman/listinfo/linux-arm-kernel
FAQ: http://www.arm.linux.org.uk/mailinglists/faq.php
Etiquette: http://www.arm.linux.org.uk/mailinglists/etiquette.php
^ permalink raw reply related [flat|nested] 11+ messages in thread
* [PATCH 2/2] atmel_tsadcc: Add board specific information for touchscreen driver
2008-04-25 18:56 ` [PATCH 1/2] atmel_tsadcc: Device driver for AT91SAM9RL Touchscreen Justin Waters
@ 2008-04-25 18:56 ` Justin Waters
2008-04-25 22:29 ` Andrew Victor
2008-04-25 20:34 ` [PATCH 1/2] atmel_tsadcc: Device driver for AT91SAM9RL Touchscreen Dmitry Torokhov
2008-04-25 21:10 ` Russell King - ARM Linux
2 siblings, 1 reply; 11+ messages in thread
From: Justin Waters @ 2008-04-25 18:56 UTC (permalink / raw)
To: linux-input, linux-arm-kernel; +Cc: dmitry.torokhov, linux
This patch adds board and cpu integration for the atmel_tsadcc driver on the
at91sam9rl-ek board.
Signed-off-by: Justin Waters <justin.waters@timesys.com>
---
arch/arm/configs/at91sam9rlek_defconfig | 1 +
arch/arm/mach-at91/at91sam9rl_devices.c | 56 +++++++++++++++++++++++++++++++
arch/arm/mach-at91/board-sam9rlek.c | 2 +
include/asm-arm/arch-at91/board.h | 3 ++
4 files changed, 62 insertions(+), 0 deletions(-)
diff --git a/arch/arm/configs/at91sam9rlek_defconfig b/arch/arm/configs/at91sam9rlek_defconfig
index fbe8b30..fb273ad 100644
--- a/arch/arm/configs/at91sam9rlek_defconfig
+++ b/arch/arm/configs/at91sam9rlek_defconfig
@@ -520,6 +520,7 @@ CONFIG_INPUT_TOUCHSCREEN=y
# CONFIG_TOUCHSCREEN_PENMOUNT is not set
# CONFIG_TOUCHSCREEN_TOUCHRIGHT is not set
# CONFIG_TOUCHSCREEN_TOUCHWIN is not set
+CONFIG_TOUCHSCREEN_ATMEL_TSADCC=y
# CONFIG_TOUCHSCREEN_UCB1400 is not set
# CONFIG_INPUT_MISC is not set
diff --git a/arch/arm/mach-at91/at91sam9rl_devices.c b/arch/arm/mach-at91/at91sam9rl_devices.c
index f43b5c3..780ea48 100644
--- a/arch/arm/mach-at91/at91sam9rl_devices.c
+++ b/arch/arm/mach-at91/at91sam9rl_devices.c
@@ -15,6 +15,7 @@
#include <linux/fb.h>
#include <video/atmel_lcdc.h>
+#include <linux/atmel_tsadcc.h>
#include <asm/arch/board.h>
#include <asm/arch/gpio.h>
@@ -579,6 +580,61 @@ void __init at91_add_device_ssc(unsigned id, unsigned pins) {}
/* --------------------------------------------------------------------
+ * * Touchscreen (ATMEL_TSADCC)
+ * * -------------------------------------------------------------------- */
+
+#if defined(CONFIG_TOUCHSCREEN_ATMEL_TSADCC) || defined(CONFIG_TOUCHSCREEN_ATMEL_TSADCC_MODULE)
+static u64 atmel_tsadcc_dmamask = 0xffffffffUL;
+
+static struct atmel_tsadcc_platform_data tsadcc_data = {
+ /* These values work with a 100 MHz Master Clock for the ADC */
+ .prescaler = 0xC, /* 3.846 MHz Clock */
+ .debounce = 0xE, /* 4.2 ms debounce */
+ .tsshtim = 0x3, /* 1.04 us Sample Hold time */
+ .startup = 0x13, /* 41 us Startup Time */
+};
+
+static struct resource atmel_tsadcc_resources[] = {
+ [0] = {
+ .start = AT91SAM9RL_BASE_TSC,
+ .end = AT91SAM9RL_BASE_TSC + SZ_16K - 1,
+ .flags = IORESOURCE_MEM,
+ },
+ [1] = {
+ .start = AT91SAM9RL_ID_TSC,
+ .end = AT91SAM9RL_ID_TSC,
+ .flags = IORESOURCE_IRQ,
+ },
+};
+
+static struct platform_device at91_tsadcc_device = {
+ .name = "atmel_tsadcc",
+ .id = 0,
+ .dev = {
+ .dma_mask = &atmel_tsadcc_dmamask,
+ .coherent_dma_mask = 0xffffffff,
+ .platform_data = &tsadcc_data,
+ },
+ .resource = atmel_tsadcc_resources,
+ .num_resources = ARRAY_SIZE(atmel_tsadcc_resources),
+};
+
+void __init at91_add_device_tsadcc(void)
+{
+ at91_set_A_periph(AT91_PIN_PA17, 0); /* AD0_XR */
+ at91_set_A_periph(AT91_PIN_PA18, 0); /* AD1_XL */
+ at91_set_A_periph(AT91_PIN_PA19, 0); /* AD2_YT */
+ at91_set_A_periph(AT91_PIN_PA20, 0); /* AD3_TB */
+
+ platform_device_register(&at91_tsadcc_device);
+}
+#else
+void __init at91_add_device_tsadcc(void) {
+}
+#endif
+
+
+/* --------------------------------------------------------------------
* UART
* -------------------------------------------------------------------- */
diff --git a/arch/arm/mach-at91/board-sam9rlek.c b/arch/arm/mach-at91/board-sam9rlek.c
index bc0546d..1c92793 100644
--- a/arch/arm/mach-at91/board-sam9rlek.c
+++ b/arch/arm/mach-at91/board-sam9rlek.c
@@ -190,6 +190,8 @@ static void __init ek_board_init(void)
at91_add_device_mmc(0, &ek_mmc_data);
/* LCD Controller */
at91_add_device_lcdc(&ek_lcdc_data);
+ /* TSADCC */
+ at91_add_device_tsadcc();
}
MACHINE_START(AT91SAM9RLEK, "Atmel AT91SAM9RL-EK")
diff --git a/include/asm-arm/arch-at91/board.h b/include/asm-arm/arch-at91/board.h
index dc189f0..e59e088 100644
--- a/include/asm-arm/arch-at91/board.h
+++ b/include/asm-arm/arch-at91/board.h
@@ -158,6 +158,9 @@ extern void __init at91_add_device_ac97(struct atmel_ac97_data *data);
/* ISI */
extern void __init at91_add_device_isi(void);
+ /* Touchscreen Controller */
+extern void __init at91_add_device_tsadcc(void);
+
/* LEDs */
extern void __init at91_init_leds(u8 cpu_led, u8 timer_led);
extern void __init at91_gpio_leds(struct gpio_led *leds, int nr);
--
1.5.4.3
-------------------------------------------------------------------
List admin: http://lists.arm.linux.org.uk/mailman/listinfo/linux-arm-kernel
FAQ: http://www.arm.linux.org.uk/mailinglists/faq.php
Etiquette: http://www.arm.linux.org.uk/mailinglists/etiquette.php
^ permalink raw reply related [flat|nested] 11+ messages in thread
* Re: [PATCH 1/2] atmel_tsadcc: Device driver for AT91SAM9RL Touchscreen
2008-04-25 18:56 ` [PATCH 1/2] atmel_tsadcc: Device driver for AT91SAM9RL Touchscreen Justin Waters
2008-04-25 18:56 ` [PATCH 2/2] atmel_tsadcc: Add board specific information for touchscreen driver Justin Waters
@ 2008-04-25 20:34 ` Dmitry Torokhov
2008-04-25 21:10 ` Russell King - ARM Linux
2 siblings, 0 replies; 11+ messages in thread
From: Dmitry Torokhov @ 2008-04-25 20:34 UTC (permalink / raw)
To: Justin Waters; +Cc: linux-input, linux-arm-kernel, linux
Hi Justin,
On Fri, Apr 25, 2008 at 02:56:37PM -0400, Justin Waters wrote:
> The atmel tsadcc is a touchscreen/adc controller found on the AT91SAM9RL SoC.
> This driver provides basic support for this controller for use as a
> touchscreen. Some future improvements include suspend/resume capabilities and
> debugfs support.
>
> Signed-off-by: Justin Waters <justin.waters@timesys.com>
Thank you for the patch. Some comments:
> diff --git a/drivers/input/touchscreen/Makefile b/drivers/input/touchscreen/Makefile
> index 35d4097..3302e27 100644
> --- a/drivers/input/touchscreen/Makefile
> +++ b/drivers/input/touchscreen/Makefile
> @@ -18,4 +18,5 @@ obj-$(CONFIG_TOUCHSCREEN_USB_COMPOSITE) += usbtouchscreen.o
> obj-$(CONFIG_TOUCHSCREEN_PENMOUNT) += penmount.o
> obj-$(CONFIG_TOUCHSCREEN_TOUCHRIGHT) += touchright.o
> obj-$(CONFIG_TOUCHSCREEN_TOUCHWIN) += touchwin.o
> +obj-$(CONFIG_TOUCHSCREEN_ATMEL_TSADCC) += atmel_tsadcc.o
If it was sorted alphabetically it would help me.
> +
> + /* Pen remains down */
> + atmel_tsadcc_getevent(ts);
> +
> + input_report_abs(ts->input, ABS_X, ts->event.x);
> + input_report_abs(ts->input, ABS_Y, ts->event.y);
> + input_report_abs(ts->input, ABS_PRESSURE, 7500);
> +
The device does not really support pressure reading, please don't try
to provide fake reports. Signal touch with BTN_TOUCH.
> +static int __devexit atmel_tsadcc_remove(struct platform_device *pdev)
> +{
> + struct atmel_tsadcc *ts = dev_get_drvdata(&pdev->dev);
> +
> + input_unregister_device(ts->input);
> +
> + free_irq(ts->irq, ts);
You should free IRQ first, otherwise IRQ may fire just was device is
unregistered and bad things may happed.
Also please run checkpatch on the driver since there are some
formatting and whitespace issues (note that I dont particularly care
about 80 column limit as long as code is readable).
Thank you.
--
Dmitry
^ permalink raw reply [flat|nested] 11+ messages in thread
* Re: [PATCH 1/2] atmel_tsadcc: Device driver for AT91SAM9RL Touchscreen
2008-04-25 18:56 ` [PATCH 1/2] atmel_tsadcc: Device driver for AT91SAM9RL Touchscreen Justin Waters
2008-04-25 18:56 ` [PATCH 2/2] atmel_tsadcc: Add board specific information for touchscreen driver Justin Waters
2008-04-25 20:34 ` [PATCH 1/2] atmel_tsadcc: Device driver for AT91SAM9RL Touchscreen Dmitry Torokhov
@ 2008-04-25 21:10 ` Russell King - ARM Linux
2008-04-25 21:37 ` Justin Waters
` (2 more replies)
2 siblings, 3 replies; 11+ messages in thread
From: Russell King - ARM Linux @ 2008-04-25 21:10 UTC (permalink / raw)
To: Justin Waters; +Cc: linux-input, linux-arm-kernel, dmitry.torokhov, linux
On Fri, Apr 25, 2008 at 02:56:37PM -0400, Justin Waters wrote:
> The atmel tsadcc is a touchscreen/adc controller found on the AT91SAM9RL
> SoC. This driver provides basic support for this controller for use as a
> touchscreen. Some future improvements include suspend/resume capabilities
> and debugfs support.
>...
> +config TOUCHSCREEN_ATMEL_TSADCC
> + tristate "Atmel Touchscreen Interface"
No dependencies. So does this mean this'll build and link on an
x86 platform?
> +/* These values are dependent upon the performance of the ADC. Ideally,
> + * These should be as close to the startup time and debounce time as
> + * possible (without going over). These assume an optimally setup ADC as
> + * per the electrical characteristics of the AT91SAM9RL tsadcc module
> + */
> +#define TS_POLL_DELAY (1 * 1000000) /* ns delay before the first sample */
> +#define TS_POLL_PERIOD (5 * 1000000) /* ns delay between samples */
So 1ms and 5ms... Not particularly high resolution...
> +static enum hrtimer_restart atmel_tsadcc_timer(struct hrtimer *handle)
So this uses the highres timer infrastructure. Does this build if
CONFIG_HIGH_RES_TIMERS is not set?
> +static int __devinit atmel_tsadcc_probe(struct platform_device *pdev)
> +{
> + struct atmel_tsadcc *ts;
> + struct input_dev *input_dev;
> + struct atmel_tsadcc_platform_data *pdata = pdev->dev.platform_data;
> + int err;
> + struct resource *res;
> + unsigned int regbuf;
This looks haphazard.
> + /* Touchscreen Information */
> + ts->pdev = pdev;
> + ts->input = input_dev;
Weird indentation.
> + /* Remap Register Memory */
> + res = platform_get_resource(pdev, IORESOURCE_MEM, 0);
> + ts->reg_start = res->start;
> + ts->reg_length = res->end - res->start +1;
So if no memory resources were passed, this oopses.
> + /* Setup Clock */
> + ts->tsc_clk = clk_get(&pdev->dev,"tsc_clk");
> + if (IS_ERR(ts->tsc_clk)) {
Great, nice to see a driver using the clock API properly.
> + dev_err(&pdev->dev, "unable to get clock\n");
> + err = PTR_ERR(ts->tsc_clk);
> + goto err_iounmap;
> + }
Odd indentation on the last line above.
> + clk_enable(ts->tsc_clk);
> +
> + regbuf = clk_get_rate(ts->tsc_clk);
> + dev_dbg (&pdev->dev,"Master clock is set at: %d Hz\n",regbuf);
> +
> + /* Setup IRQ */
> + ts->irq = platform_get_irq(pdev, 0);
> + if (ts->irq < 0) {
> + dev_err(&pdev->dev, "unable to get IRQ\n");
> + err = -EBUSY;
> + goto err_clk_put;
> + }
Ditto.
> +
> + /* Fill in initial Register Data */
> + ATMEL_TSADCC_RESET;
> + regbuf = (0x01 & 0x3) | /* TSAMOD */
> + ((0x0 & 0x1) << 5) | /* SLEEP */
(0 & 1) << 5 ? How about using a #define for bit 5 and simply
omitting it?
> + ((0x1 & 0x1) << 6) | /* PENDET */
And a #define for bit 6 as well?
> + ((pdata->prescaler & 0x3F) << 8) | /* PRESCAL */
> + ((pdata->startup & 0x7F) << 16) | /* STARTUP */
> + ((pdata->debounce & 0x0F) << 28); /* PENDBC */
> + atmel_tsadcc_writereg(ATMEL_TSADCC_MR,regbuf);
> +
> + regbuf = (0x4 & 0x7) | /* TRGMOD */
> + ((0xFFFF & 0xFFFF) << 16); /* TRGPER */
> + atmel_tsadcc_writereg(ATMEL_TSADCC_TRGR,regbuf);
> +
> + regbuf = ((pdata->tsshtim & 0xF) << 24); /* TSSHTIM */
> + atmel_tsadcc_writereg(ATMEL_TSADCC_TSR,regbuf);
> +
> + regbuf = atmel_tsadcc_readreg(ATMEL_TSADCC_IMR);
> + dev_dbg (&pdev->dev, "Initial IMR = %X\n", regbuf);
> +
> + /* Register and enable IRQ */
> + if (request_irq(ts->irq, atmel_tsadcc_irq, IRQF_TRIGGER_LOW,
> + pdev->dev.driver->name, ts)) {
> + dev_dbg(&pdev->dev, "IRQ %d busy!\n", ts->irq);
> + err = -EBUSY;
> + goto err_iounmap;
> + }
Ditto.
> + regbuf = ((0x1 & 0x1) << 20) | /* PENCNT */
> + ((0x1 & 0x1) << 21); /* NOCNT */
#defines... even more so then the comments become entirely unnecessary.
^ permalink raw reply [flat|nested] 11+ messages in thread
* Re: [PATCH 1/2] atmel_tsadcc: Device driver for AT91SAM9RL Touchscreen
2008-04-25 21:10 ` Russell King - ARM Linux
@ 2008-04-25 21:37 ` Justin Waters
2008-04-25 22:52 ` David Brownell
2008-06-05 13:49 ` Haavard Skinnemoen
2008-04-25 22:16 ` Andrew Victor
2008-04-28 5:55 ` Uwe Kleine-König
2 siblings, 2 replies; 11+ messages in thread
From: Justin Waters @ 2008-04-25 21:37 UTC (permalink / raw)
To: Russell King - ARM Linux
Cc: linux-input@vger.kernel.org,
linux-arm-kernel@lists.arm.linux.org.uk,
dmitry.torokhov@gmail.com, linux@maxim.org.za
Thank you for the comments. I've inlined responses below:
On Fri, 2008-04-25 at 17:10 -0400, Russell King - ARM Linux wrote:
> > +config TOUCHSCREEN_ATMEL_TSADCC
> > + tristate "Atmel Touchscreen Interface"
>
> No dependencies. So does this mean this'll build and link on an
> x86 platform?
>
I was actually thinking that this IP will end up on an AVR32 platform as
well, so I intentionally tried to avoid making the driver too ARM
specific. However, I definitely see the point of specifying
ARCH_AT91SAM9RL and worrying about adding additional support for new
platforms later, so I'll add that in.
> > +/* These values are dependent upon the performance of the ADC. Ideally,
> > + * These should be as close to the startup time and debounce time as
> > + * possible (without going over). These assume an optimally setup ADC as
> > + * per the electrical characteristics of the AT91SAM9RL tsadcc module
> > + */
> > +#define TS_POLL_DELAY (1 * 1000000) /* ns delay before the first sample */
> > +#define TS_POLL_PERIOD (5 * 1000000) /* ns delay between samples */
>
> So 1ms and 5ms... Not particularly high resolution...
>
> > +static enum hrtimer_restart atmel_tsadcc_timer(struct hrtimer *handle)
>
> So this uses the highres timer infrastructure. Does this build if
> CONFIG_HIGH_RES_TIMERS is not set?
>
Thank you for catching this. I'll definitely revisit this. Since HRT
support is not mainline for the SAM9 platforms, I'm going to remove all
references to it and worry about high resolution timer support at a
later time.
> > + /* Remap Register Memory */
> > + res = platform_get_resource(pdev, IORESOURCE_MEM, 0);
> > + ts->reg_start = res->start;
> > + ts->reg_length = res->end - res->start +1;
>
> So if no memory resources were passed, this oopses.
Ouch, sorry about that. I'll get a check in there.
I'll also take care of the whitespace issues and #defines as well.
-Justin Waters
^ permalink raw reply [flat|nested] 11+ messages in thread
* Re: [PATCH 1/2] atmel_tsadcc: Device driver for AT91SAM9RL Touchscreen
2008-04-25 21:10 ` Russell King - ARM Linux
2008-04-25 21:37 ` Justin Waters
@ 2008-04-25 22:16 ` Andrew Victor
2008-04-28 5:55 ` Uwe Kleine-König
2 siblings, 0 replies; 11+ messages in thread
From: Andrew Victor @ 2008-04-25 22:16 UTC (permalink / raw)
To: Justin Waters
Cc: Russell King - ARM Linux, linux-input, linux-arm-kernel,
dmitry.torokhov
hi Justin,
> > + regbuf = (0x01 & 0x3) | /* TSAMOD */
> > + ((0x0 & 0x1) << 5) | /* SLEEP */
>
> (0 & 1) << 5 ? How about using a #define for bit 5 and simply
> omitting it?
>
> > + ((0x1 & 0x1) << 6) | /* PENDET */
>
> And a #define for bit 6 as well?
Maybe this header file will be useful to you...
/*
* include/asm-arm/arch-at91/at91_tsc.h
*
* Touch Screen ADC Controller (TSC)
* Based on AT91SAM9RL64 preliminary draft datasheet.
*
* This program is free software; you can redistribute it and/or modify it
* under the terms of the GNU General Public License as published by the
* Free Software Foundation; either version 2 of the License, or (at your
* option) any later version.
*/
#ifndef AT91_TSC_H
#define AT91_TSC_H
#define AT91_TSADCC_CR 0x00 /* Control register */
#define AT91_TSADCC_SWRST (1 << 0) /* Software Reset*/
#define AT91_TSADCC_START (1 << 1) /* Start conversion */
#define AT91_TSADCC_MR 0x04 /* Mode register */
#define AT91_TSADCC_TSAMOD (3 << 0) /* ADC mode */
#define AT91_TSADCC_LOWRES (1 << 4) /* Resolution selection */
#define AT91_TSADCC_SLEEP (1 << 5) /* Sleep mode */
#define AT91_TSADCC_PENDET (1 << 6) /* Pen Detect selection */
#define AT91_TSADCC_PRESCAL (0x3f << 8) /* Prescalar Rate Selection */
#define AT91_TSADCC_STARTUP (0x7f << 16) /* Start Up time */
#define AT91_TSADCC_SHTIM (0xf << 24) /* Sample & Hold time */
#define AT91_TSADCC_PENDBC (0xf << 28) /* Pen Detect debouncing time */
#define AT91_TSADCC_TRGR 0x08 /* Trigger register */
#define AT91_TSADCC_TRGMOD (7 << 0) /* Trigger mode */
#define AT91_TSADCC_TRGMOD_NONE (0 << 0)
#define AT91_TSADCC_TRGMOD_EXT_RISING (1 << 0)
#define AT91_TSADCC_TRGMOD_EXT_FALLING (2 << 0)
#define AT91_TSADCC_TRGMOD_EXT_ANY (3 << 0)
#define AT91_TSADCC_TRGMOD_PENDET (4 << 0)
#define AT91_TSADCC_TRGMOD_PERIOD (5 << 0)
#define AT91_TSADCC_TRGMOD_CONTINUOUS (6 << 0)
#define AT91_TSADCC_TRGPER (0xffff << 16) /* Trigger period */
#define AT91_TSADCC_TSR 0x0C /* Touch Screen register */
#define AT91_TSADCC_TSFREQ (0xf << 0) /* TS Frequency in Interleaved mode */
#define AT91_TSADCC_TSSHTIM (0xf << 24) /* Sample & Hold time */
#define AT91_TSADCC_CHER 0x10 /* Channel Enable register */
#define AT91_TSADCC_CHDR 0x14 /* Channel Disable register */
#define AT91_TSADCC_CHSR 0x18 /* Channel Status register */
#define AT91_TSADCC_CH(n) (1 << (n)) /* Channel number */
#define AT91_TSADCC_SR 0x1C /* Status register */
#define AT91_TSADCC_EOC(n) (1 << ((n)+0)) /* End of conversion for channel N */
#define AT91_TSADCC_OVRE(n) (1 << ((n)+8)) /* Overrun error for channel N */
#define AT91_TSADCC_DRDY (1 << 16) /* Data Ready */
#define AT91_TSADCC_GOVRE (1 << 17) /* General Overrun Error */
#define AT91_TSADCC_ENDRX (1 << 18) /* End of RX Buffer */
#define AT91_TSADCC_RXBUFF (1 << 19) /* TX Buffer full */
#define AT91_TSADCC_PENCNT (1 << 20) /* Pen contact */
#define AT91_TSADCC_NOCNT (1 << 21) /* No contact */
#define AT91_TSADCC_LCDR 0x20 /* Last Converted Data register */
#define AT91_TSADCC_DATA (0x3ff << 0) /* Channel data */
#define AT91_TSADCC_IER 0x24 /* Interrupt Enable register */
#define AT91_TSADCC_IDR 0x28 /* Interrupt Disable register */
#define AT91_TSADCC_IMR 0x2C /* Interrupt Mask register */
#define AT91_TSADCC_CDR0 0x30 /* Channel Data 0 */
#define AT91_TSADCC_CDR1 0x34 /* Channel Data 1 */
#define AT91_TSADCC_CDR2 0x38 /* Channel Data 2 */
#define AT91_TSADCC_CDR3 0x3C /* Channel Data 3 */
#define AT91_TSADCC_CDR4 0x40 /* Channel Data 4 */
#define AT91_TSADCC_CDR5 0x44 /* Channel Data 5 */
#endif
Regards,
Andrew Victor
^ permalink raw reply [flat|nested] 11+ messages in thread
* Re: [PATCH 2/2] atmel_tsadcc: Add board specific information for touchscreen driver
2008-04-25 18:56 ` [PATCH 2/2] atmel_tsadcc: Add board specific information for touchscreen driver Justin Waters
@ 2008-04-25 22:29 ` Andrew Victor
0 siblings, 0 replies; 11+ messages in thread
From: Andrew Victor @ 2008-04-25 22:29 UTC (permalink / raw)
To: Justin Waters; +Cc: linux-input, linux-arm-kernel, dmitry.torokhov, linux
hi Justin,
> +static u64 atmel_tsadcc_dmamask = 0xffffffffUL;
Rather use DMA_BIT_MASK(32).
> + /* These values work with a 100 MHz Master Clock for the ADC */
> + .prescaler = 0xC, /* 3.846 MHz Clock */
> + .debounce = 0xE, /* 4.2 ms debounce */
> + .tsshtim = 0x3, /* 1.04 us Sample Hold time */
> + .startup = 0x13, /* 41 us Startup Time */
What is the impact of a different Master Clock rate? This devices.c
file is intended to be board-independent.
Wouldn't it be better for the driver to call clk_get_rate() and
calculate "good" values for these?
> + .coherent_dma_mask = 0xffffffff,
Similarly, DMA_BIT_MASK(32).
Regards,
Andrew Victor
^ permalink raw reply [flat|nested] 11+ messages in thread
* Re: [PATCH 1/2] atmel_tsadcc: Device driver for AT91SAM9RL Touchscreen
2008-04-25 21:37 ` Justin Waters
@ 2008-04-25 22:52 ` David Brownell
2008-06-05 13:49 ` Haavard Skinnemoen
1 sibling, 0 replies; 11+ messages in thread
From: David Brownell @ 2008-04-25 22:52 UTC (permalink / raw)
To: Justin Waters
Cc: linux-arm-kernel, Russell King - ARM Linux,
dmitry.torokhov@gmail.com, linux@maxim.org.za,
linux-input@vger.kernel.org
On Friday 25 April 2008, Justin Waters wrote:
>
> Since HRT
> support is not mainline for the SAM9 platforms,
It's not? I though that all got merged. PIT supports clocksource
and periodic clockevents, and the TC modules support oneshot timers
sufficient for HRT and NO_HZ. Merged for 2.6.26-rc1 ...
- Dave
> I'm going to remove all
> references to it and worry about high resolution timer support at a
> later time.
>
--
To unsubscribe from this list: send the line "unsubscribe linux-input" 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] 11+ messages in thread
* Re: [PATCH 1/2] atmel_tsadcc: Device driver for AT91SAM9RL Touchscreen
2008-04-25 21:10 ` Russell King - ARM Linux
2008-04-25 21:37 ` Justin Waters
2008-04-25 22:16 ` Andrew Victor
@ 2008-04-28 5:55 ` Uwe Kleine-König
2 siblings, 0 replies; 11+ messages in thread
From: Uwe Kleine-König @ 2008-04-28 5:55 UTC (permalink / raw)
To: Russell King - ARM Linux
Cc: Justin Waters, dmitry.torokhov, linux-arm-kernel, linux,
linux-input
Hello,
> > + /* Setup Clock */
> > + ts->tsc_clk = clk_get(&pdev->dev,"tsc_clk");
> > + if (IS_ERR(ts->tsc_clk)) {
>
> Great, nice to see a driver using the clock API properly.
>
> > + dev_err(&pdev->dev, "unable to get clock\n");
> > + err = PTR_ERR(ts->tsc_clk);
> > + goto err_iounmap;
> > + }
>
> Odd indentation on the last line above.
>
> > + clk_enable(ts->tsc_clk);
To use the clock API properly you should check the return value of
clk_enable, too :-)
Uwe
--
Uwe Kleine-König, Software Engineer
Digi International GmbH Branch Breisach, Küferstrasse 8, 79206 Breisach, Germany
Tax: 315/5781/0242 / VAT: DE153662976 / Reg. Amtsgericht Dortmund HRB 13962
--
To unsubscribe from this list: send the line "unsubscribe linux-input" 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] 11+ messages in thread
* Re: [PATCH 1/2] atmel_tsadcc: Device driver for AT91SAM9RL Touchscreen
2008-04-25 21:37 ` Justin Waters
2008-04-25 22:52 ` David Brownell
@ 2008-06-05 13:49 ` Haavard Skinnemoen
1 sibling, 0 replies; 11+ messages in thread
From: Haavard Skinnemoen @ 2008-06-05 13:49 UTC (permalink / raw)
To: Justin Waters
Cc: linux-input@vger.kernel.org, dmitry.torokhov@gmail.com,
Russell King - ARM Linux, linux-arm-kernel@lists.arm.linux.org.uk,
linux@maxim.org.za
Justin Waters <justin.waters@timesys.com> wrote:
> On Fri, 2008-04-25 at 17:10 -0400, Russell King - ARM Linux wrote:
> > > +config TOUCHSCREEN_ATMEL_TSADCC
> > > + tristate "Atmel Touchscreen Interface"
> >
> > No dependencies. So does this mean this'll build and link on an
> > x86 platform?
> >
> I was actually thinking that this IP will end up on an AVR32 platform as
> well, so I intentionally tried to avoid making the driver too ARM
> specific. However, I definitely see the point of specifying
> ARCH_AT91SAM9RL and worrying about adding additional support for new
> platforms later, so I'll add that in.
Thanks for thinking about AVR32 as well :-)
I think adding a dependency on AT91 is the right thing to do for now. We
can always patch in "|| AVR32" later if/when this IP finds its way into
an AVR32 chip.
Though it looks like the only thing this driver uses that isn't
available on x86 is the clk API, so perhaps it would be best to depend
on HAVE_CLK assuming this patch gets merged:
http://lkml.org/lkml/2008/5/29/367
This would give the driver much better compile-testing coverage by
people who do allyesconfig builds and such on different platforms.
Haavard
-------------------------------------------------------------------
List admin: http://lists.arm.linux.org.uk/mailman/listinfo/linux-arm-kernel
FAQ: http://www.arm.linux.org.uk/mailinglists/faq.php
Etiquette: http://www.arm.linux.org.uk/mailinglists/etiquette.php
^ permalink raw reply [flat|nested] 11+ messages in thread
end of thread, other threads:[~2008-06-05 13:49 UTC | newest]
Thread overview: 11+ messages (download: mbox.gz follow: Atom feed
-- links below jump to the message on this page --
2008-04-25 18:56 [PATCH 0/2] Atmel AT91SAM9RL Touchscreen Driver Justin Waters
2008-04-25 18:56 ` [PATCH 1/2] atmel_tsadcc: Device driver for AT91SAM9RL Touchscreen Justin Waters
2008-04-25 18:56 ` [PATCH 2/2] atmel_tsadcc: Add board specific information for touchscreen driver Justin Waters
2008-04-25 22:29 ` Andrew Victor
2008-04-25 20:34 ` [PATCH 1/2] atmel_tsadcc: Device driver for AT91SAM9RL Touchscreen Dmitry Torokhov
2008-04-25 21:10 ` Russell King - ARM Linux
2008-04-25 21:37 ` Justin Waters
2008-04-25 22:52 ` David Brownell
2008-06-05 13:49 ` Haavard Skinnemoen
2008-04-25 22:16 ` Andrew Victor
2008-04-28 5:55 ` Uwe Kleine-König
This is a public inbox, see mirroring instructions
for how to clone and mirror all data and code used for this inbox;
as well as URLs for NNTP newsgroup(s).