From b6f9680b714b4579dcbe0e4bc71c6fa4724bf899 Mon Sep 17 00:00:00 2001 From: patacongo Date: Tue, 8 May 2012 15:07:53 +0000 Subject: Integrate the STMPE11 driver into the STM3240G-EVAL board logic git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@4714 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/configs/sam3u-ek/touchscreen/appconfig | 2 +- nuttx/configs/stm3240g-eval/README.txt | 32 +++ nuttx/configs/stm3240g-eval/nsh/appconfig | 4 + nuttx/configs/stm3240g-eval/nsh/defconfig | 71 ++++- nuttx/configs/stm3240g-eval/nxwm/defconfig | 5 +- nuttx/configs/stm3240g-eval/src/Makefile | 4 + .../configs/stm3240g-eval/src/stm3240g-internal.h | 41 ++- nuttx/configs/stm3240g-eval/src/up_stmpe11.c | 320 +++++++++++++++++++++ nuttx/drivers/input/stmpe11_base.c | 5 +- nuttx/include/nuttx/input/stmpe11.h | 6 +- 10 files changed, 477 insertions(+), 13 deletions(-) create mode 100644 nuttx/configs/stm3240g-eval/src/up_stmpe11.c (limited to 'nuttx') diff --git a/nuttx/configs/sam3u-ek/touchscreen/appconfig b/nuttx/configs/sam3u-ek/touchscreen/appconfig index 34cab1247..ccbdaeb28 100644 --- a/nuttx/configs/sam3u-ek/touchscreen/appconfig +++ b/nuttx/configs/sam3u-ek/touchscreen/appconfig @@ -37,7 +37,7 @@ CONFIGURED_APPS += examples/nsh -# The NSH applicatin library +# The NSH application library CONFIGURED_APPS += system/readline CONFIGURED_APPS += nshlib diff --git a/nuttx/configs/stm3240g-eval/README.txt b/nuttx/configs/stm3240g-eval/README.txt index bf5959871..0717f51c7 100755 --- a/nuttx/configs/stm3240g-eval/README.txt +++ b/nuttx/configs/stm3240g-eval/README.txt @@ -18,6 +18,7 @@ Contents - CAN - FPU - FSMC SRAM + - I/O Exanders - STM3240G-EVAL-specific Configuration Options - Configurations @@ -496,6 +497,37 @@ There are 4 possible SRAM configurations: CONFIG_MM_REGIONS == 3 CONFIG_STM32_FSMC_SRAM defined CONFIG_STM32_CCMEXCLUDE NOT defined +I/O Exanders +============ + +The STM3240G-EVAL has two STMPE11QTR I/O expanders on board both connected to +the STM32 via I2C1. They share a common interrupt line: PI2. + +STMPE11 U24, I2C address 0x41 (7-bit) +------ ---- ---------------- -------------------------------------------- +STPE11 PIN BOARD SIGNAL BOARD CONNECTION +------ ---- ---------------- -------------------------------------------- + Y- TouchScreen_Y- LCD Connector XL + X- TouchScreen_X- LCD Connector XR + Y+ TouchScreen_Y+ LCD Connector XD + X+ TouchScreen_X+ LCD Connector XU + IN3 EXP_IO9 + IN2 EXP_IO10 + IN1 EXP_IO11 + IN0 EXP_IO12 + +STMPE11 U29, I2C address 0x44 (7-bit) +------ ---- ---------------- -------------------------------------------- +STPE11 PIN BOARD SIGNAL BOARD CONNECTION +------ ---- ---------------- -------------------------------------------- + Y- EXP_IO1 + X- EXP_IO2 + Y+ EXP_IO3 + X+ EXP_IO4 + IN3 EXP_IO5 + IN2 EXP_IO6 + IN1 EXP_IO7 + IN0 EXP_IO8 STM3240G-EVAL-specific Configuration Options ============================================ diff --git a/nuttx/configs/stm3240g-eval/nsh/appconfig b/nuttx/configs/stm3240g-eval/nsh/appconfig index 6fe75e7ee..f126b0d80 100644 --- a/nuttx/configs/stm3240g-eval/nsh/appconfig +++ b/nuttx/configs/stm3240g-eval/nsh/appconfig @@ -80,6 +80,10 @@ ifeq ($(CONFIG_WATCHDOG),y) CONFIGURED_APPS += examples/watchdog endif +ifeq ($(CONFIG_INPUT_STMPE11),y) +CONFIGURED_APPS += examples/touchscreen +endif + # Uncomment examples/ftpc to include the FTP client example # Uncomment examples/ftpd to include the FTP daemon example diff --git a/nuttx/configs/stm3240g-eval/nsh/defconfig b/nuttx/configs/stm3240g-eval/nsh/defconfig index 667bc19cf..fc3d1a955 100644 --- a/nuttx/configs/stm3240g-eval/nsh/defconfig +++ b/nuttx/configs/stm3240g-eval/nsh/defconfig @@ -527,6 +527,7 @@ CONFIG_DEBUG_ANALOG=n CONFIG_DEBUG_PWM=n CONFIG_DEBUG_CAN=n CONFIG_DEBUG_I2C=n +CONFIG_DEBUG_INPUT=n CONFIG_HAVE_CXX=y CONFIG_HAVE_CXXINITIALIZE=y @@ -552,7 +553,7 @@ CONFIG_SDCLONE_DISABLE=y CONFIG_SCHED_WORKQUEUE=n CONFIG_SCHED_WORKPRIORITY=192 CONFIG_SCHED_WORKPERIOD=(50*1000) -CONFIG_SCHED_WORKSTACKSIZE=1024 +CONFIG_SCHED_WORKSTACKSIZE=2048 CONFIG_SIG_SIGWORK=4 CONFIG_SCHED_WAITPID=y CONFIG_SCHED_ATEXIT=n @@ -946,6 +947,52 @@ CONFIG_RTC_HIRES=n CONFIG_RTC_FREQUENCY=n CONFIG_RTC_ALARM=n +# +# Input device configuration +# +CONFIG_INPUT=n +CONFIG_INPUT_TSC2007=n + +# +# STMPE11 input device configuration +# +# Prerequisites: CONFIG_INPUT=y +# Other settings that effect the driver: CONFIG_DISABLE_POLL +# +# CONFIG_INPUT_STMPE11 +# Enables support for the STMPE11 driver (Needs CONFIG_INPUT) +# CONFIG_STMPE11_SPI +# Enables support for the SPI interface (not currenly supported) +# CONFIG_STMPE11_I2C +# Enables support for the I2C interface +# CONFIG_STMPE11_MULTIPLE +# Can be defined to support multiple STMPE11 devices on board. +# CONFIG_STMPE11_NPOLLWAITERS +# Maximum number of threads that can be waiting on poll() (ignored if +# CONFIG_DISABLE_POLL is set). +# CONFIG_STMPE11_TSC_DISABLE +# Disable driver touchscreen functionality. +# CONFIG_STMPE11_ADC_DISABLE +# Disable driver ADC functionality. +# CONFIG_STMPE11_GPIO_DISABLE +# Disable driver GPIO functionlaity. +# CONFIG_STMPE11_GPIOINT_DISABLE +# Disable driver GPIO interrupt functionlality (ignored if GPIO functionality is +# disabled). +# CONFIG_STMPE11_TEMP_DISABLE +# Disable driver temperature sensor functionlaity. +# +CONFIG_INPUT_STMPE11=n +CONFIG_STMPE11_SPI=n +CONFIG_STMPE11_I2C=y +CONFIG_STMPE11_MULTIPLE=y +#CONFIG_STMPE11_NPOLLWAITERS +CONFIG_STMPE11_TSC_DISABLE=n +CONFIG_STMPE11_ADC_DISABLE=y +CONFIG_STMPE11_GPIO_DISABLE=y +CONFIG_STMPE11_GPIOINT_DISABLE=y +CONFIG_STMPE11_TEMP_DISABLE=y + # # USB Device Configuration # @@ -1599,6 +1646,28 @@ CONFIG_EXAMPLES_NXLINES_CIRCLECOLOR=0xf7bb CONFIG_EXAMPLES_NXLINES_BPP=16 CONFIG_EXAMPLES_NXLINES_EXTERNINIT=n +# +# Settings for examples/touchscreen +# +# CONFIG_EXAMPLES_TOUCHSCREEN_BUILTIN - Build the touchscreen test as +# an NSH built-in function. Default: Built as a standalone problem +# CONFIG_EXAMPLES_TOUCHSCREEN_MINOR - The minor device number. Minor=N +# correspnds to touchscreen device /dev/input0. Note this value must +# with CONFIG_EXAMPLES_TOUCHSCREEN_DEVPATH. Default 0. +# CONFIG_EXAMPLES_TOUCHSCREEN_DEVPATH - The path to the touchscreen +# device. This must be consistent with CONFIG_EXAMPLES_TOUCHSCREEN_MINOR. +# Default: "/dev/input0" +# CONFIG_EXAMPLES_TOUCHSCREEN_NSAMPLES - If CONFIG_EXAMPLES_TOUCHSCREEN_BUILTIN +# is defined, then the number of samples is provided on the command line +# and this value is ignored. Otherwise, this number of samples is +# collected and the program terminates. Default: Samples are collected +# indefinitely. +# +CONFIG_EXAMPLES_TOUCHSCREEN_BUILTIN=y +CONFIG_EXAMPLES_TOUCHSCREEN_MINOR=0 +CONFIG_EXAMPLES_TOUCHSCREEN_DEVPATH="/dev/input0" +CONFIG_EXAMPLES_TOUCHSCREEN_NSAMPLES=25 + # # Settings for examples/usbstorage # diff --git a/nuttx/configs/stm3240g-eval/nxwm/defconfig b/nuttx/configs/stm3240g-eval/nxwm/defconfig index 73686f67f..72fcaace0 100644 --- a/nuttx/configs/stm3240g-eval/nxwm/defconfig +++ b/nuttx/configs/stm3240g-eval/nxwm/defconfig @@ -527,6 +527,7 @@ CONFIG_DEBUG_ANALOG=n CONFIG_DEBUG_PWM=n CONFIG_DEBUG_CAN=n CONFIG_DEBUG_I2C=n +CONFIG_DEBUG_INPUT=n CONFIG_HAVE_CXX=y CONFIG_HAVE_CXXINITIALIZE=y @@ -949,8 +950,8 @@ CONFIG_RTC_ALARM=n # # Input device configuration # -CONFIG_INPUT=y -CONFIG_INPUT_TSC2007=y +CONFIG_INPUT=n +CONFIG_INPUT_TSC2007=n # # STMPE11 input device configuration diff --git a/nuttx/configs/stm3240g-eval/src/Makefile b/nuttx/configs/stm3240g-eval/src/Makefile index 9ac3cfa53..548c1c8c0 100644 --- a/nuttx/configs/stm3240g-eval/src/Makefile +++ b/nuttx/configs/stm3240g-eval/src/Makefile @@ -88,6 +88,10 @@ ifeq ($(CONFIG_WATCHDOG),y) CSRCS += up_watchdog.c endif +ifeq ($(CONFIG_INPUT_STMPE11),y) +CSRCS += up_stmpe11.c +endif + COBJS = $(CSRCS:.c=$(OBJEXT)) SRCS = $(ASRCS) $(CSRCS) diff --git a/nuttx/configs/stm3240g-eval/src/stm3240g-internal.h b/nuttx/configs/stm3240g-eval/src/stm3240g-internal.h index eb73b3e33..70f3f6079 100644 --- a/nuttx/configs/stm3240g-eval/src/stm3240g-internal.h +++ b/nuttx/configs/stm3240g-eval/src/stm3240g-internal.h @@ -138,9 +138,40 @@ #define GPIO_OTGFS_PWRON (GPIO_OUTPUT|GPIO_FLOAT|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTH|GPIO_PIN5) #define GPIO_OTGFS_OVER (GPIO_INPUT|GPIO_FLOAT|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTF|GPIO_PIN11) -/**************************************************************************************************** - * Public Types - ****************************************************************************************************/ +/* The STM3240G-EVAL has two STMPE11QTR I/O expanders on board both connected + * to the STM32 via I2C1. They share a common interrupt line: PI2. + * + * STMPE11 U24, I2C address 0x41 (7-bit) + * ------ ---- ---------------- -------------------------------------------- + * STPE11 PIN BOARD SIGNAL BOARD CONNECTION + * ------ ---- ---------------- -------------------------------------------- + * Y- TouchScreen_Y- LCD Connector XL + * X- TouchScreen_X- LCD Connector XR + * Y+ TouchScreen_Y+ LCD Connector XD + * X+ TouchScreen_X+ LCD Connector XU + * IN3 EXP_IO9 + * IN2 EXP_IO10 + * IN1 EXP_IO11 + * IN0 EXP_IO12 + * + * STMPE11 U29, I2C address 0x44 (7-bit) + * ------ ---- ---------------- -------------------------------------------- + * STPE11 PIN BOARD SIGNAL BOARD CONNECTION + * ------ ---- ---------------- -------------------------------------------- + * Y- EXP_IO1 + * X- EXP_IO2 + * Y+ EXP_IO3 + * X+ EXP_IO4 + * IN3 EXP_IO5 + * IN2 EXP_IO6 + * IN1 EXP_IO7 + * IN0 EXP_IO8 + */ + +#define STMPE11_ADDR1 0x41 +#define STMPE11_ADDR2 0x44 + +#define GPIO_IO_EXPANDER (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTI|GPIO_PIN2) /* GPIO settings that will be altered when external memory is selected: * @@ -157,6 +188,10 @@ * PD14-15: FSMC D0-D1 */ +/**************************************************************************************************** + * Public Types + ****************************************************************************************************/ + /**************************************************************************************************** * Public data ****************************************************************************************************/ diff --git a/nuttx/configs/stm3240g-eval/src/up_stmpe11.c b/nuttx/configs/stm3240g-eval/src/up_stmpe11.c new file mode 100644 index 000000000..66e844c01 --- /dev/null +++ b/nuttx/configs/stm3240g-eval/src/up_stmpe11.c @@ -0,0 +1,320 @@ +/************************************************************************************ + * configs/stm3240g-eval/src/up_touchscreen.c + * arch/arm/src/board/up_touchscreen.c + * + * Copyright (C) 2012 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 "stm32_internal.h" +#include "stm3240g-internal.h" + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ +/* Configuration ************************************************************/ + +#ifdef CONFIG_INPUT_STMPE11 +#ifndef CONFIG_INPUT +# error "STMPE11 support requires CONFIG_INPUT" +#endif + +#ifndef CONFIG_STM32_I2C1 +# error "STMPE11 support requires CONFIG_STM32_I2C1" +#endif + +#ifndef CONFIG_STMPE11_I2C +# error "Only the STMPE11 I2C interface is supported" +#endif + +#ifdef CONFIG_STMPE11_SPI +# error "Only the STMPE11 SPI interface is supported" +#endif + +#ifndef CONFIG_STMPE11_FREQUENCY +# define CONFIG_STMPE11_FREQUENCY 100000 +#endif + +#ifndef CONFIG_STMPE11_I2CDEV +# define CONFIG_STMPE11_I2CDEV 1 +#endif + +#if CONFIG_STMPE11_I2CDEV != 1 +# error "CONFIG_STMPE11_I2CDEV must be one" +#endif + +#ifndef CONFIG_STMPE11_DEVMINOR +# define CONFIG_STMPE11_DEVMINOR 0 +#endif + +/* Board definitions ********************************************************/ +/* The STM3240G-EVAL has two STMPE11QTR I/O expanders on board both connected + * to the STM32 via I2C1. They share a common interrupt line: PI2. + * + * STMPE11 U24, I2C address 0x41 (7-bit) + * ------ ---- ---------------- -------------------------------------------- + * STPE11 PIN BOARD SIGNAL BOARD CONNECTION + * ------ ---- ---------------- -------------------------------------------- + * Y- TouchScreen_Y- LCD Connector XL + * X- TouchScreen_X- LCD Connector XR + * Y+ TouchScreen_Y+ LCD Connector XD + * X+ TouchScreen_X+ LCD Connector XU + * IN3 EXP_IO9 + * IN2 EXP_IO10 + * IN1 EXP_IO11 + * IN0 EXP_IO12 + * + * STMPE11 U29, I2C address 0x44 (7-bit) + * ------ ---- ---------------- -------------------------------------------- + * STPE11 PIN BOARD SIGNAL BOARD CONNECTION + * ------ ---- ---------------- -------------------------------------------- + * Y- EXP_IO1 + * X- EXP_IO2 + * Y+ EXP_IO3 + * X+ EXP_IO4 + * IN3 EXP_IO5 + * IN2 EXP_IO6 + * IN1 EXP_IO7 + * IN0 EXP_IO8 + */ + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +struct stm32_stmpe11config_s +{ + /* Configuration structure as seen by the STMPE11 driver */ + + struct stmpe11_config_s config; + + /* Additional private definitions only known to this driver */ + + STMPE11_HANDLE handle; /* The STMPE11 driver handle */ + xcpt_t handler; /* The STMPE11 interrupt handler */ +}; + +/**************************************************************************** + * Static Function Prototypes + ****************************************************************************/ + +/* IRQ/GPIO access callbacks. These operations all hidden behind callbacks + * to isolate the STMPE11 driver from differences in GPIO + * interrupt handling by varying boards and MCUs.* so that contact and loss-of-contact events can be detected. + * + * attach - Attach the STMPE11 interrupt handler to the GPIO interrupt + * enable - Enable or disable the GPIO interrupt + * clear - Acknowledge/clear any pending GPIO interrupt + */ + +static int stmpe11_attach(FAR struct stmpe11_config_s *state, xcpt_t isr); +static void stmpe11_enable(FAR struct stmpe11_config_s *state, bool enable); +static void stmpe11_clear(FAR struct stmpe11_config_s *state); + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/* A reference to a structure of this type must be passed to the STMPE11 + * driver. This structure provides information about the configuration + * of the STMPE11 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 frequency or X plate resistance values. + */ + +#ifndef CONFIG_STMPE11_TSC_DISABLE +static struct stm32_stmpe11config_s g_stmpe11config = +{ + .config = + { +#ifdef CONFIG_STMPE11_I2C + .address = STMPE11_ADDR1, +#endif + .frequency = CONFIG_STMPE11_FREQUENCY, + +#ifdef CONFIG_STMPE11_MULTIPLE + .irq = STM32_IRQ_EXTI2, +#endif + .ctrl1 = (ADC_CTRL1_SAMPLE_TIME_80|ADC_CTRL1_MOD_12B|ADC_CTRL1_REF_SEL), + .ctrl2 = ADC_CTRL2_ADC_FREQ_3p25, + + .attach = stmpe11_attach, + .enable = stmpe11_enable, + .clear = stmpe11_clear, + }, + .handler = NULL, +}; +#endif + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/* IRQ/GPIO access callbacks. These operations all hidden behind + * callbacks to isolate the STMPE11 driver from differences in GPIO + * interrupt handling by varying boards and MCUs. + * + * attach - Attach the STMPE11 interrupt handler to the GPIO interrupt + * enable - Enable or disable the GPIO interrupt + * clear - Acknowledge/clear any pending GPIO interrupt + */ + +static int stmpe11_attach(FAR struct stmpe11_config_s *state, xcpt_t isr) +{ + FAR struct stm32_stmpe11config_s *priv = (FAR struct stm32_stmpe11config_s *)state; + + ivdbg("Saving handler %p\n", isr); + DEBUGASSERT(priv); + + /* Just save the handler. We will use it when EXTI interruptsare enabled */ + + priv->handler = isr; + return OK; +} + +static void stmpe11_enable(FAR struct stmpe11_config_s *state, bool enable) +{ + FAR struct stm32_stmpe11config_s *priv = (FAR struct stm32_stmpe11config_s *)state; + + /* Attach and enable, or detach and disable */ + + ivdbg("IRQ:%d enable:%d\n", STM32_IRQ_EXTI2, enable); + if (enable) + { + /* Configure the EXTI interrupt using the SAVED handler */ + + (void)stm32_gpiosetevent(GPIO_IO_EXPANDER, true, true, true, priv->handler); + } + else + { + /* Configure the EXTI interrupt with a NULL handler to disable it */ + + (void)stm32_gpiosetevent(GPIO_IO_EXPANDER, false, false, false, NULL); + } +} + +static void stmpe11_clear(FAR struct stmpe11_config_s *state) +{ + /* Does nothing */ +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: arch_tcinitialize + * + * Description: + * Initialize the touchscreen device + * + ****************************************************************************/ + +int arch_tcinitialize(void) +{ +#ifndef CONFIG_STMPE11_TSC_DISABLE + FAR struct i2c_dev_s *dev; + int ret; + + ivdbg("Initializing\n"); + + /* Configure and enable the STMPE11 interrupt pin as an input */ + + (void)stm32_configgpio(GPIO_IO_EXPANDER); + + /* Get an instance of the I2C interface */ + + dev = up_i2cinitialize(CONFIG_STMPE11_I2CDEV); + if (!dev) + { + idbg("Failed to initialize I2C bus %d\n", CONFIG_STMPE11_I2CDEV); + return -ENODEV; + } + + /* Instantiate the STMPE11 driver */ + + g_stmpe11config.handle = + stmpe11_instantiate(dev, (FAR struct stmpe11_config_s *)&g_stmpe11config); + if (!g_stmpe11config.handle) + { + idbg("Failed to instantiate the STMPE11 driver\n"); + return -ENODEV; + } + + /* Initialize and register the I2C touschscreen device */ + + ret = stmpe11_register(dev, CONFIG_STMPE11_DEVMINOR); + if (ret < 0) + { + idbg("Failed to register STMPE driver: %d\n", ret); + /* up_i2cuninitialize(dev); */ + return -ENODEV; + } + + return OK; +#else + return -ENOSYS; +#endif +} + +/**************************************************************************** + * Name: arch_tcuninitialize + * + * Description: + * Un-initialize the touchscreen device + * + ****************************************************************************/ + +void arch_tcuninitialize(void) +{ + /* No support for un-initializing the touchscreen STMPE11 device yet */ +} + +#endif /* CONFIG_INPUT_STMPE11 */ + diff --git a/nuttx/drivers/input/stmpe11_base.c b/nuttx/drivers/input/stmpe11_base.c index 1e8c7d58a..cabd33db2 100644 --- a/nuttx/drivers/input/stmpe11_base.c +++ b/nuttx/drivers/input/stmpe11_base.c @@ -47,6 +47,7 @@ #include #include +#include #include #include "stmpe11.h" @@ -163,7 +164,7 @@ static int stmpe11_interrupt(int irq, FAR void *context) priv = &g_stmpe11; #else for (priv = g_stmpe11list; - priv && priv->configs->irq != irq; + priv && priv->config->irq != irq; priv = priv->flink); ASSERT(priv != NULL); @@ -296,7 +297,7 @@ STMPE11_HANDLE stmpe11_instantiate(FAR struct i2c_dev_s *dev, priv = (FAR struct stmpe11_dev_s *)kzalloc(sizeof(struct stmpe11_dev_s)); if (!priv) { - return -ENOMEM; + return NULL; } /* And save the device structure in the list of STMPE11 so that we can find it later */ diff --git a/nuttx/include/nuttx/input/stmpe11.h b/nuttx/include/nuttx/input/stmpe11.h index bee90abfb..27eef46ee 100644 --- a/nuttx/include/nuttx/input/stmpe11.h +++ b/nuttx/include/nuttx/input/stmpe11.h @@ -453,7 +453,7 @@ struct stmpe11_config_s * be provided for each so that their interrupts can be distinguished. */ -#ifndef CONFIG_STMPE11_MULTIPLE +#ifdef CONFIG_STMPE11_MULTIPLE int irq; /* IRQ number received by interrupt handler. */ #endif @@ -469,9 +469,7 @@ struct stmpe11_config_s /* IRQ/GPIO access callbacks. These operations all hidden behind * callbacks to isolate the STMPE11 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. + * interrupt handling by varying boards and MCUs. * * attach - Attach the STMPE11 interrupt handler to the GPIO interrupt * enable - Enable or disable the GPIO interrupt -- cgit v1.2.3