From 2a2f7f98b1a10c62e64bd0cc56219175cd709243 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 5 Jul 2014 17:12:14 -0600 Subject: SAMA5D4-EK: Add board support for the maXTouch --- nuttx/configs/sama5d4-ek/Kconfig | 12 ++ nuttx/configs/sama5d4-ek/README.txt | 31 +++ nuttx/configs/sama5d4-ek/src/Makefile | 4 + nuttx/configs/sama5d4-ek/src/sam_maxtouch.c | 315 ++++++++++++++++++++++++++++ nuttx/configs/sama5d4-ek/src/sama5d4-ek.h | 56 +++++ 5 files changed, 418 insertions(+) create mode 100644 nuttx/configs/sama5d4-ek/src/sam_maxtouch.c diff --git a/nuttx/configs/sama5d4-ek/Kconfig b/nuttx/configs/sama5d4-ek/Kconfig index 5c4ae21d8..ea53972c4 100644 --- a/nuttx/configs/sama5d4-ek/Kconfig +++ b/nuttx/configs/sama5d4-ek/Kconfig @@ -174,6 +174,18 @@ config SAMA5D4EK_AT25_NXFFS endchoice # AT25 serial FLASH configuration +if INPUT_MXT + +config SAMA5D4EK_MXT_I2CFREQUENCY + int "maXTouch I2C frequency" + default 100000 + +config SAMA5D4EK_MXT_DEVMINOR + int "/dev/input minor number" + default 0 + +endif # INPUT_MXT + config SAMA5D4EK_CHANNEL int "PWM channel number" default 0 if SAMA5_PWM_CHAN0 diff --git a/nuttx/configs/sama5d4-ek/README.txt b/nuttx/configs/sama5d4-ek/README.txt index 463e38e4e..157675094 100644 --- a/nuttx/configs/sama5d4-ek/README.txt +++ b/nuttx/configs/sama5d4-ek/README.txt @@ -92,6 +92,7 @@ Contents - Watchdog Timer - TRNG and /dev/random - I2S Audio Support + - TM7000 LCD/Touchscreen - SAMA4D4-EK Configuration Options - Configurations - To-Do List @@ -2771,6 +2772,36 @@ I2S Audio Support Library Routines CONFIG_SCHED_WORKQUEUE=y : Driver needs work queue support +TM7000 LCD/Touchscreen +====================== + + The TM7000 LCD is available for the SAMA5D4-EK. See documentation + available on the Precision Design Associates website: + http://www.pdaatl.com/doc/tm7000.pdf + + The TM7000 features an touchscreen controol + + - 7 inch LCD at 800x480 18-bit RGB resolution and white backlight + - Projected Capacitive Multi-Touch Controller based on the Atmel + MXT768E maXTouch™ IC + - 4 Capacitive “Navigation” Keys available via an Atmel AT42QT1070 + QTouch™ Button Sensor IC + - 200 bytes of non-volatile serial EEPROM + + Both the MXT768E and the AT42QT1070 are I2C devices with interrupting + PIO pins: + + ------------------------ ----------------- + SAMA5D4-EK TM7000 + ------------------------ ----------------- + J9 pin 5 LCD_PE24 J4 pin 5 ~CHG_mxt + J9 pin 6 LCD_PE25 J4 pin 6 ~CHG_QT + J9 pin 7 LCD_TWCK0_PA31 J4 pin 7 SCL_0 + J9 pin 8 LCD_TWD0_PA30 J4 pin 8 SDA_0 + ------------------------ ----------------- + + The schematic indicates the the MXT468E address is 0x4c/0x4d. + SAMA4D4-EK Configuration Options ================================= diff --git a/nuttx/configs/sama5d4-ek/src/Makefile b/nuttx/configs/sama5d4-ek/src/Makefile index 7d2521405..484fab0b0 100644 --- a/nuttx/configs/sama5d4-ek/src/Makefile +++ b/nuttx/configs/sama5d4-ek/src/Makefile @@ -96,6 +96,10 @@ ifeq ($(CONFIG_SAMA5_EMACB),y) CSRCS += sam_ethernet.c endif +ifeq ($(CONFIG_INPUT_MXT),y) +CSRCS += sam_maxtouch.c +endif + ifeq ($(CONFIG_NSH_ARCHINIT),y) CSRCS += sam_nsh.c endif diff --git a/nuttx/configs/sama5d4-ek/src/sam_maxtouch.c b/nuttx/configs/sama5d4-ek/src/sam_maxtouch.c new file mode 100644 index 000000000..ec3348d05 --- /dev/null +++ b/nuttx/configs/sama5d4-ek/src/sam_maxtouch.c @@ -0,0 +1,315 @@ +/************************************************************************************ + * configs/sama5d4-ek/src/sam_maxtouch.c + * + * Copyright (C) 2014 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ************************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "up_arch.h" +#include "sam_pio.h" +#include "sam_twi.h" + +#include "sama5d4-ek.h" + +#ifdef HAVE_MAXTOUCH + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ +/* Configuration ************************************************************/ + +#ifndef CONFIG_SAMA5D4EK_MXT_I2CFREQUENCY +# define CONFIG_SAMA5D4EK_MXT_I2CFREQUENCY 500000 +#endif + +#ifndef CONFIG_SAMA5D4EK_MXT_DEVMINOR +# define CONFIG_SAMA5D4EK_MXT_DEVMINOR 0 +#endif + +/* The touchscreen communicates on TWI0 */ + +#define MXT_BUSNUM 0 + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +struct sama5d4ek_tscinfo_s +{ + /* Standard maXTouch interface */ + + struct mxt_lower_s lower; + + /* Extensions for the sama5d4ek board */ + + mxt_handler_t handler; + FAR void *arg; +}; + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/* IRQ/GPIO access callbacks. These operations all hidden behind + * callbacks to isolate the maXTouch driver from differences in GPIO + * interrupt handling by varying boards and MCUs. If possible, + * interrupts should be configured on both rising and falling edges + * so that contact and loss-of-contact events can be detected. + * + * attach - Attach the maXTouch interrupt handler to the GPIO interrupt + * enable - Enable or disable the GPIO interrupt + * clear - Acknowledge/clear any pending GPIO interrupt + */ + +static int mxt_attach(FAR const struct mxt_lower_s *lower, mxt_handler_t isr, + FAR void *arg); +static void mxt_enable(FAR const struct mxt_lower_s *lower, bool enable); +static void mxt_clear(FAR const struct mxt_lower_s *lower); + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/* A reference to a structure of this type must be passed to the maXTouch + * driver. This structure provides information about the configuration + * of the maXTouch and provides some board-specific hooks. + * + * Memory for this structure is provided by the caller. It is not copied + * by the driver and is presumed to persist while the driver is active. The + * memory must be writable because, under certain circumstances, the driver + * may modify certain values. + */ + +static struct sama5d4ek_tscinfo_s g_mxtinfo = +{ + .lower = + { + .frequency = CONFIG_SAMA5D4EK_MXT_I2CFREQUENCY, + + .attach = mxt_attach, + .enable = mxt_enable, + .clear = mxt_clear, + }, +}; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * IRQ/GPIO access callbacks. These operations all hidden behind + * callbacks to isolate the maXTouch driver from differences in GPIO + * interrupt handling by varying boards and MCUs. If possible, + * interrupts should be configured on both rising and falling edges + * so that contact and loss-of-contact events can be detected. + * + * attach - Attach the maXTouch interrupt handler to the GPIO interrupt + * enable - Enable or disable the GPIO interrupt + * clear - Acknowledge/clear any pending GPIO interrupt + * + ****************************************************************************/ + +static int mxt_attach(FAR const struct mxt_lower_s *lower, mxt_handler_t isr, + FAR void *arg) +{ + if (isr) + { + /* Just save the address of the handler for now. The new handler will + * be attached when the interrupt is next enabled. + */ + + ivdbg("Attaching %p\n", isr); + g_mxtinfo.handler = isr; + g_mxtinfo.arg = arg; + } + else + { + ivdbg("Detaching %p\n", g_mxtinfo.handler); + mxt_enable(lower, false); + g_mxtinfo.handler = NULL; + g_mxtinfo.arg = NULL; + } + + return OK; +} + +static void mxt_enable(FAR const struct mxt_lower_s *lower, bool enable) +{ + /* Enable or disable interrupts */ + + if (enable && g_mxtinfo.handler) + { + sam_pioirqenable(IRQ_CHG_MXT); + } + else + { + sam_pioirqdisable(IRQ_CHG_MXT); + } +} + +static void mxt_clear(FAR const struct mxt_lower_s *lower) +{ + /* Does nothing */ +} + +static int mxt_interrupt(int irq, FAR void *context) +{ + /* Just forward the interrupt to the maXTouch driver */ + + if (g_mxtinfo.handler) + { + return g_mxtinfo.handler(&g_mxtinfo.lower, g_mxtinfo.arg); + } + + /* We got an interrupt with no handler. This should not + * happen. + */ + + sam_pioirqdisable(IRQ_CHG_MXT); + return OK; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: arch_tcinitialize + * + * Description: + * Each board that supports a touchscreen device must provide this function. + * This function is called by application-specific, setup logic to + * configure the touchscreen device. This function will register the driver + * as /dev/inputN where N is the minor device number. + * + * Input Parameters: + * minor - The input device minor number + * + * Returned Value: + * Zero is returned on success. Otherwise, a negated errno value is + * returned to indicate the nature of the failure. + * + ****************************************************************************/ + +int arch_tcinitialize(int minor) +{ + FAR struct i2c_dev_s *i2c; + static bool initialized = false; + int ret; + + idbg("minor %d\n", minor); + DEBUGASSERT(minor == 0); + + /* Have we already initialized? Since we never uninitialize we must prevent + * multiple initializations. This is necessary, for example, when the + * touchscreen example is used as a built-in application in NSH and can be + * called numerous time. It will attempt to initialize each time. + */ + + if (!initialized) + { + /* Configure the maXTouch CHG interrupt pin */ + + (void)sam_configpio(PIO_CHG_MXT); + + /* Get an instance of the I2C interface for the touchscreen chip select */ + + i2c = up_i2cinitialize(MXT_BUSNUM); + if (!i2c) + { + idbg("Failed to initialize I2C%d\n", MXT_BUSNUM); + return -ENODEV; + } + + /* Configure maXTouch CHG interrupts */ + + sam_pioirq(IRQ_CHG_MXT); + (void)irq_attach(IRQ_CHG_MXT, mxt_interrupt); + + /* Initialize and register the I2C touchscreen device */ + + ret = mxt_register(i2c, &g_mxtinfo.lower, CONFIG_SAMA5D4EK_MXT_DEVMINOR); + if (ret < 0) + { + idbg("ERROR: Failed to register touchscreen device\n"); + irq_detach(IRQ_CHG_MXT); + /* up_i2cuninitialize(i2c); */ + return -ENODEV; + } + + /* Now we are initialized */ + + initialized = true; + } + + return OK; +} + +/**************************************************************************** + * Name: arch_tcuninitialize + * + * Description: + * Each board that supports a touchscreen device must provide this function. + * This function is called by application-specific, setup logic to + * uninitialize the touchscreen device. + * + * Input Parameters: + * None + * + * Returned Value: + * None + * + ****************************************************************************/ + +void arch_tcuninitialize(void) +{ + /* No support for un-initializing the touchscreen maXTouch device. It will + * continue to run and process touch interrupts in the background. + */ +} + +#endif /* HAVE_MAXTOUCH */ diff --git a/nuttx/configs/sama5d4-ek/src/sama5d4-ek.h b/nuttx/configs/sama5d4-ek/src/sama5d4-ek.h index b4a9040bb..e0506eea4 100644 --- a/nuttx/configs/sama5d4-ek/src/sama5d4-ek.h +++ b/nuttx/configs/sama5d4-ek/src/sama5d4-ek.h @@ -63,6 +63,7 @@ #define HAVE_USBOVCUR 1 #define HAVE_USBMONITOR 1 #define HAVE_NETWORK 1 +#define HAVE_MAXTOUCH 1 /* HSMCI */ /* Can't support MMC/SD if the card interface(s) are not enable */ @@ -296,6 +297,24 @@ # undef HAVE_NETWORK #endif +/* maXTouch controller */ + +#ifndef CONFIG_INPUT_MXT +# undef HAVE_MAXTOUCH +#endif + +#ifdef HAVE_MAXTOUCH +# ifndef CONFIG_SAMA5_TWI0 +# warning CONFIG_SAMA5_TWI0 is required for touchscreen support +# undef HAVE_MAXTOUCH +# endif + +# ifndef CONFIG_SAMA5_PIOE_IRQ +# warning PIOE interrupts not enabled. No touchsreen support. +# undef HAVE_MAXTOUCH +# endif +#endif + /* LEDs *****************************************************************************/ /* There are 3 LEDs on the SAMA5D4-EK: * @@ -338,6 +357,43 @@ PIO_INT_BOTHEDGES | PIO_PORT_PIOE | PIO_PIN13) #define IRQ_BTN_USER SAM_IRQ_PE13 +/* TM7000 LCD/Touchscreen ***********************************************************/ +/* The TM7000 LCD is available for the SAMA5D4-EK. See documentation + * available on the Precision Design Associates website: + * http://www.pdaatl.com/doc/tm7000.pdf + * + * The TM7000 features an touchscreen controol + * + * - 7 inch LCD at 800x480 18-bit RGB resolution and white backlight + * - Projected Capacitive Multi-Touch Controller based on the Atmel + * MXT768E maXTouch™ IC + * - 4 Capacitive “Navigation” Keys available via an Atmel AT42QT1070 + * QTouch™ Button Sensor IC + * - 200 bytes of non-volatile serial EEPROM + * + * Both the MXT768E and the AT42QT1070 are I2C devices with interrupting + * PIO pins: + * + * ------------------------ ----------------- + * SAMA5D4-EK TM7000 + * ------------------------ ----------------- + * J9 pin 5 LCD_PE24 J4 pin 5 ~CHG_mxt + * J9 pin 6 LCD_PE25 J4 pin 6 ~CHG_QT + * J9 pin 7 LCD_TWCK0_PA31 J4 pin 7 SCL_0 + * J9 pin 8 LCD_TWD0_PA30 J4 pin 8 SDA_0 + * ------------------------ ----------------- + * + * The schematic indicates the the MXT468E address is 0x4c/0x4d. + */ + +#define PIO_CHG_MXT (PIO_INPUT | PIO_CFG_PULLUP | PIO_CFG_DEGLITCH | \ + PIO_INT_BOTHEDGES | PIO_PORT_PIOE | PIO_PIN24) +#define IRQ_CHG_MXT SAM_IRQ_PE24 + +#define PIO_CHG_QT (PIO_INPUT | PIO_CFG_PULLUP | PIO_CFG_DEGLITCH | \ + PIO_INT_BOTHEDGES | PIO_PORT_PIOE | PIO_PIN25) +#define IRQ_CHG_QT SAM_IRQ_PE25 + /* HSMCI Card Slots *****************************************************************/ /* The SAMA4D4-EK provides a two SD memory card slots: (1) a full size SD * card slot (J10), and (2) a microSD memory card slot (J11). -- cgit v1.2.3