From 5e0db5610808aae42989238e40f0731f009dba8f Mon Sep 17 00:00:00 2001 From: patacongo Date: Tue, 29 May 2012 00:54:22 +0000 Subject: Massive naming fix: STMPE11->STMPE811 git-svn-id: https://nuttx.svn.sourceforge.net/svnroot/nuttx/trunk@4782 7fd9a85b-ad96-42d3-883c-3090e2eb8679 --- nuttx/drivers/input/Make.defs | 20 +- nuttx/drivers/input/stmpe11.h | 245 -------- nuttx/drivers/input/stmpe11_adc.c | 266 -------- nuttx/drivers/input/stmpe11_base.c | 546 ----------------- nuttx/drivers/input/stmpe11_gpio.c | 454 -------------- nuttx/drivers/input/stmpe11_temp.c | 174 ------ nuttx/drivers/input/stmpe11_tsc.c | 1144 ----------------------------------- nuttx/drivers/input/stmpe811.h | 245 ++++++++ nuttx/drivers/input/stmpe811_adc.c | 266 ++++++++ nuttx/drivers/input/stmpe811_base.c | 546 +++++++++++++++++ nuttx/drivers/input/stmpe811_gpio.c | 454 ++++++++++++++ nuttx/drivers/input/stmpe811_temp.c | 174 ++++++ nuttx/drivers/input/stmpe811_tsc.c | 1144 +++++++++++++++++++++++++++++++++++ 13 files changed, 2839 insertions(+), 2839 deletions(-) delete mode 100644 nuttx/drivers/input/stmpe11.h delete mode 100644 nuttx/drivers/input/stmpe11_adc.c delete mode 100644 nuttx/drivers/input/stmpe11_base.c delete mode 100644 nuttx/drivers/input/stmpe11_gpio.c delete mode 100644 nuttx/drivers/input/stmpe11_temp.c delete mode 100644 nuttx/drivers/input/stmpe11_tsc.c create mode 100644 nuttx/drivers/input/stmpe811.h create mode 100644 nuttx/drivers/input/stmpe811_adc.c create mode 100644 nuttx/drivers/input/stmpe811_base.c create mode 100644 nuttx/drivers/input/stmpe811_gpio.c create mode 100644 nuttx/drivers/input/stmpe811_temp.c create mode 100644 nuttx/drivers/input/stmpe811_tsc.c (limited to 'nuttx/drivers') diff --git a/nuttx/drivers/input/Make.defs b/nuttx/drivers/input/Make.defs index c7c715b70..aaf08b827 100644 --- a/nuttx/drivers/input/Make.defs +++ b/nuttx/drivers/input/Make.defs @@ -47,19 +47,19 @@ ifeq ($(CONFIG_INPUT_ADS7843E),y) CSRCS += ads7843e.c endif -ifeq ($(CONFIG_INPUT_STMPE11),y) - CSRCS += stmpe11_base.c -ifneq ($(CONFIG_INPUT_STMPE11_TSC_DISABLE),y) - CSRCS += stmpe11_tsc.c +ifeq ($(CONFIG_INPUT_STMPE811),y) + CSRCS += stmpe811_base.c +ifneq ($(CONFIG_INPUT_STMPE811_TSC_DISABLE),y) + CSRCS += stmpe811_tsc.c endif -ifneq ($(CONFIG_INPUT_STMPE11_GPIO_DISABLE),y) - CSRCS += stmpe11_gpio.c +ifneq ($(CONFIG_INPUT_STMPE811_GPIO_DISABLE),y) + CSRCS += stmpe811_gpio.c endif -ifneq ($(CONFIG_INPUT_STMPE11_ADC_DISABLE),y) - CSRCS += stmpe11_adc.c +ifneq ($(CONFIG_INPUT_STMPE811_ADC_DISABLE),y) + CSRCS += stmpe811_adc.c endif -ifneq ($(CONFIG_INPUT_STMPE11_TEMP_DISABLE),y) - CSRCS += stmpe11_temp.c +ifneq ($(CONFIG_INPUT_STMPE811_TEMP_DISABLE),y) + CSRCS += stmpe811_temp.c endif endif diff --git a/nuttx/drivers/input/stmpe11.h b/nuttx/drivers/input/stmpe11.h deleted file mode 100644 index 05917fc37..000000000 --- a/nuttx/drivers/input/stmpe11.h +++ /dev/null @@ -1,245 +0,0 @@ -/******************************************************************************************** - * drivers/input/stmpe11.h - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * References: - * "STMPE811 S-Touch® advanced resistive touchscreen controller with 8-bit - * GPIO expander," Doc ID 14489 Rev 6, CD00186725, STMicroelectronics" - * - * 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. - * - ********************************************************************************************/ - -#ifndef __DRIVERS_INPUT_STMPE11_H -#define __DRIVERS_INPUT_STMPE11_H - -/******************************************************************************************** - * Included Files - ********************************************************************************************/ - -#include - -#include -#include - -#include -#include -#include - -#if defined(CONFIG_INPUT) && defined(CONFIG_INPUT_STMPE11) - -/******************************************************************************************** - * Pre-Processor Definitions - ********************************************************************************************/ -/* Configuration ****************************************************************************/ -/* Reference counting is partially implemented, but not needed in the current design. - */ - -#undef CONFIG_STMPE11_REFCNT - -/* No support for the SPI interface yet */ - -#ifdef CONFIG_STMPE11_SPI -# error "Only the STMPE11 I2C interface is supported by this driver" -#endif - -/* Driver support ***************************************************************************/ -/* This format is used to construct the /dev/input[n] device driver path. It defined here - * so that it will be used consistently in all places. - */ - -#define DEV_FORMAT "/dev/input%d" -#define DEV_NAMELEN 16 - -/* STMPE11 Resources ************************************************************************/ -#ifndef CONFIG_STMPE11_TSC_DISABLE -# define SMTPE11_ADC_NPINS 4 /* Only pins 0-3 can be used for ADC */ -# define SMTPE11_GPIO_NPINS 4 /* Only pins 0-3 can be used as GPIOs */ -#else -# define SMTPE11_ADC_NPINS 8 /* All pins can be used for ADC */ -# define SMTPE11_GPIO_NPINS 8 /* All pins can be used as GPIOs */ -#endif - -/* Driver flags */ - -#define STMPE11_FLAGS_TSC_INITIALIZED (1 << 0) /* 1: The TSC block has been initialized */ -#define STMPE11_FLAGS_GPIO_INITIALIZED (1 << 1) /* 1: The GIO block has been initialized */ -#define STMPE11_FLAGS_ADC_INITIALIZED (1 << 2) /* 1: The ADC block has been initialized */ -#define STMPE11_FLAGS_TS_INITIALIZED (1 << 3) /* 1: The TS block has been initialized */ - -/* Timeout to detect missing pen up events */ - -#define STMPE11_PENUP_TICKS ((100 + (MSEC_PER_TICK-1)) / MSEC_PER_TICK) - -/******************************************************************************************** - * Public Types - ********************************************************************************************/ -/* This describes the state of one contact */ - -enum stmpe11_contact_3 -{ - CONTACT_NONE = 0, /* No contact */ - CONTACT_DOWN, /* First contact */ - CONTACT_MOVE, /* Same contact, possibly different position */ - CONTACT_UP, /* Contact lost */ -}; - -/* This structure describes the results of one STMPE11 sample */ - -struct stmpe11_sample_s -{ - uint8_t id; /* Sampled touch point ID */ - uint8_t contact; /* Contact state (see enum stmpe11_contact_e) */ - bool valid; /* True: x,y,z contain valid, sampled data */ - uint16_t x; /* Measured X position */ - uint16_t y; /* Measured Y position */ - uint8_t z; /* Measured Z index */ -}; - -/* This structure represents the state of the SMTPE11 driver */ - -struct stmpe11_dev_s -{ -#ifdef CONFIG_STMPE11_MULTIPLE - FAR struct stmpe11_dev_s *flink; /* Supports a singly linked list of drivers */ -#endif - - /* Common fields */ - - FAR struct stmpe11_config_s *config; /* Board configuration data */ - sem_t exclsem; /* Manages exclusive access to this structure */ -#ifdef CONFIG_STMPE11_SPI - FAR struct spi_dev_s *spi; /* Saved SPI driver instance */ -#else - FAR struct i2c_dev_s *i2c; /* Saved I2C driver instance */ -#endif - - uint8_t inuse; /* SMTPE11 pins in use */ - uint8_t flags; /* See SMTPE11_FLAGS_* definitions */ - struct work_s work; /* Supports the interrupt handling "bottom half" */ - - /* Fields that may be disabled to save size if touchscreen support is not used. */ - -#ifndef CONFIG_STMPE11_TSC_DISABLE -#ifdef CONFIG_STMPE11_REFCNT - uint8_t crefs; /* Number of times the device has been opened */ -#endif - uint8_t nwaiters; /* Number of threads waiting for STMPE11 data */ - uint8_t id; /* Current touch point ID */ - uint8_t minor; /* Touchscreen minor device number */ - volatile bool penchange; /* An unreported event is buffered */ - - uint16_t threshx; /* Thresholded X value */ - uint16_t threshy; /* Thresholded Y value */ - sem_t waitsem; /* Used to wait for the availability of data */ - - struct work_s timeout; /* Supports tiemeout work */ - WDOG_ID wdog; /* Timeout to detect missing pen down events */ - struct stmpe11_sample_s sample; /* Last sampled touch point data */ - - /* The following is a list if poll structures of threads waiting for - * driver events. The 'struct pollfd' reference for each open is also - * retained in the f_priv field of the 'struct file'. - */ - -#ifndef CONFIG_DISABLE_POLL - struct pollfd *fds[CONFIG_STMPE11_NPOLLWAITERS]; -#endif -#endif - - /* Fields that may be disabled to save size of GPIO support is not used */ - -#if !defined(CONFIG_STMPE11_GPIO_DISABLE) && !defined(CONFIG_STMPE11_GPIOINT_DISABLE) - stmpe11_handler_t handlers[SMTPE11_GPIO_NPINS]; /* GPIO "interrupt handlers" */ -#endif -}; - -/******************************************************************************************** - * Public Function Prototypes - ********************************************************************************************/ - -/******************************************************************************************** - * Name: stmpe11_getreg8 - * - * Description: - * Read from an 8-bit STMPE11 register - * - ********************************************************************************************/ - -uint8_t stmpe11_getreg8(FAR struct stmpe11_dev_s *priv, uint8_t regaddr); - -/******************************************************************************************** - * Name: stmpe11_putreg8 - * - * Description: - * Write a value to an 8-bit STMPE11 register - * - ********************************************************************************************/ - -void stmpe11_putreg8(FAR struct stmpe11_dev_s *priv, uint8_t regaddr, uint8_t regval); - -/******************************************************************************************** - * Name: stmpe11_getreg16 - * - * Description: - * Read 16-bits of data from an STMPE-11 register - * - ********************************************************************************************/ - -uint16_t stmpe11_getreg16(FAR struct stmpe11_dev_s *priv, uint8_t regaddr); - -/******************************************************************************************** - * Name: stmpe11_tscint - * - * Description: - * Handle touchscreen interrupt events (this function actually executes in the context of - * the worker thread). - * - ********************************************************************************************/ - -#ifndef CONFIG_STMPE11_TSC_DISABLE -void stmpe11_tscworker(FAR struct stmpe11_dev_s *priv, uint8_t intsta) weak_function; -#endif - -/******************************************************************************************** - * Name: stmpe11_gpioworker - * - * Description: - * Handle GPIO interrupt events (this function actually executes in the context of the - * worker thread). - * - ********************************************************************************************/ - -#if !defined(CONFIG_STMPE11_GPIO_DISABLE) && !defined(CONFIG_STMPE11_GPIOINT_DISABLE) -void stmpe11_gpioworker(FAR struct stmpe11_dev_s *priv) weak_function; -#endif - -#endif /* CONFIG_INPUT && CONFIG_INPUT_STMPE11 */ -#endif /* __DRIVERS_INPUT_STMPE11_H */ diff --git a/nuttx/drivers/input/stmpe11_adc.c b/nuttx/drivers/input/stmpe11_adc.c deleted file mode 100644 index 5b9d045c9..000000000 --- a/nuttx/drivers/input/stmpe11_adc.c +++ /dev/null @@ -1,266 +0,0 @@ -/**************************************************************************** - * drivers/input/stmpe11_adc.c - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * References: - * "STMPE811 S-Touch® advanced resistive touchscreen controller with 8-bit - * GPIO expander," Doc ID 14489 Rev 6, CD00186725, STMicroelectronics" - * - * 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 "stmpe11.h" - -#if defined(CONFIG_INPUT) && defined(CONFIG_INPUT_STMPE11) && !defined(CONFIG_STMPE11_ADC_DISABLE) - -/**************************************************************************** - * Private Types - ****************************************************************************/ - -/**************************************************************************** - * Private Data - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: stmpe11_adcinitialize - * - * Description: - * Configure for ADC mode operation. Set overall ADC ADC timing that - * applies to all pins. - * - * Input Parameters: - * handle - The handle previously returned by stmpe11_instantiate - * - * Returned Value: - * Zero is returned on success. Otherwise, a negated errno value is - * returned to indicate the nature of the failure. - * - ****************************************************************************/ - -int stmpe11_adcinitialize(STMPE11_HANDLE handle) -{ - FAR struct stmpe11_dev_s *priv = (FAR struct stmpe11_dev_s *)handle; - uint8_t regval; - int ret; - - DEBUGASSERT(handle); - - /* Get exclusive access to the device structure */ - - ret = sem_wait(&priv->exclsem); - if (ret < 0) - { - int errval = errno; - idbg("sem_wait failed: %d\n", errval); - return -errval; - } - - /* Enable Clocking for ADC */ - - regval = stmpe11_getreg8(priv, STMPE11_SYS_CTRL2); - regval &= ~SYS_CTRL2_ADC_OFF; - stmpe11_putreg8(priv, STMPE11_SYS_CTRL2, regval); - - /* Select Sample Time, bit number and ADC Reference */ - - stmpe11_putreg8(priv, STMPE11_ADC_CTRL1, priv->config->ctrl1); - - /* Wait for 20 ms */ - - up_mdelay(20); - - /* Select the ADC clock speed */ - - stmpe11_putreg8(priv, STMPE11_ADC_CTRL2, priv->config->ctrl2); - - /* Mark ADC initialized */ - - priv->flags |= STMPE11_FLAGS_ADC_INITIALIZED; - sem_post(&priv->exclsem); - return OK; -} - -/**************************************************************************** - * Name: stmpe11_adcconfig - * - * Description: - * Configure a pin for ADC input. - * - * Input Parameters: - * handle - The handle previously returned by stmpe11_instantiate - * pin - The ADC pin number - * - * Returned Value: - * Zero is returned on success. Otherwise, a negated errno value is - * returned to indicate the nature of the failure. - * - ****************************************************************************/ - -int stmpe11_adcconfig(STMPE11_HANDLE handle, int pin) -{ - FAR struct stmpe11_dev_s *priv = (FAR struct stmpe11_dev_s *)handle; - uint8_t pinmask = GPIO_PIN(pin); - uint8_t regval; - int ret; - - DEBUGASSERT(handle && (unsigned)pin < STMPE11_ADC_NPINS); - - /* Get exclusive access to the device structure */ - - ret = sem_wait(&priv->exclsem); - if (ret < 0) - { - int errval = errno; - idbg("sem_wait failed: %d\n", errval); - return -errval; - } - - /* Make sure that the pin is not already in use */ - - if ((priv->inuse & pinmask) != 0) - { - idbg("PIN%d is already in-use\n", pin); - sem_post(&priv->exclsem); - return -EBUSY; - } - - /* Clear the alternate function bit for the pin, making it an ADC input - * (or perhaps an an external reference, depending on the state of the - * ADC_CTRL1_REF_SEL bit). - */ - - regval = stmpe11_getreg8(priv, STMPE11_GPIO_AF); - regval &= ~pinmask; - stmpe11_putreg8(priv, STMPE11_GPIO_AF, regval); - - /* Mark the pin as 'in use' */ - - priv->inuse |= pinmask; - sem_post(&priv->exclsem); - return OK; -} - -/**************************************************************************** - * Name: stmpe11_adcread - * - * Description: - * Read the converted analog input value from the select pin. - * - * Input Parameters: - * handle - The handle previously returned by stmpe11_instantiate - * pin - The ADC pin number - * - * Returned Value: - * The converted value (there is no error reporting mechanism). - * - ****************************************************************************/ - -uint16_t stmpe11_adcread(STMPE11_HANDLE handle, int pin) -{ - FAR struct stmpe11_dev_s *priv = (FAR struct stmpe11_dev_s *)handle; - uint8_t pinmask = GPIO_PIN(pin); - uint8_t regval; - int i; - int ret; - - DEBUGASSERT(handle && (unsigned)pin < 8); - - /* Get exclusive access to the device structure */ - - ret = sem_wait(&priv->exclsem); - if (ret < 0) - { - int errval = errno; - idbg("sem_wait failed: %d\n", errval); - return -errval; - } - - /* Request AD conversion by setting the bit corresponding the pin in the - * ADC CAPT register. - */ - - stmpe11_putreg8(priv, STMPE11_ADC_CAPT, pinmask); - - /* Wait for the conversion to complete. The ADC CAPT register reads '1' - * if conversion is completed. Reads '0' if conversion is in progress. - * Try three times before giving up. - */ - - for (i = 0; i < 3; i++) - { - /* The worst case ADC conversion time is (nominally) 56.4 uS. The - * following usleep() looks nice but in reality, the usleep() - * does not have that kind of precision (it will probably end up - * waiting 10 MS). - */ - - usleep(57); - - /* Check if the conversion is complete */ - - regval = stmpe11_getreg8(priv, STMPE11_ADC_CAPT); - if ((regval & pinmask) != 0) - { - break; - } - } - - /* At the completion of the conversion, return whatever we read from - * from the channel register associated with the pin. - */ - - return stmpe11_getreg16(priv, STMPE11_ADC_DATACH(pin)); -} - -#endif /* CONFIG_INPUT && CONFIG_INPUT_STMPE11 && !CONFIG_STMPE11_ADC_DISABLE */ - diff --git a/nuttx/drivers/input/stmpe11_base.c b/nuttx/drivers/input/stmpe11_base.c deleted file mode 100644 index 8e2900610..000000000 --- a/nuttx/drivers/input/stmpe11_base.c +++ /dev/null @@ -1,546 +0,0 @@ -/**************************************************************************** - * drivers/input/stmpe11_base.c - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * References: - * "STMPE811 S-Touch® advanced resistive touchscreen controller with 8-bit - * GPIO expander," Doc ID 14489 Rev 6, CD00186725, STMicroelectronics" - * - * 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 "stmpe11.h" - -#if defined(CONFIG_INPUT) && defined(CONFIG_INPUT_STMPE11) - -/**************************************************************************** - * Private Types - ****************************************************************************/ - -/**************************************************************************** - * Private Data - ****************************************************************************/ - -/* If only a single STMPE11 device is supported, then the driver state - * structure may as well be pre-allocated. - */ - -#ifndef CONFIG_STMPE11_MULTIPLE -static struct stmpe11_dev_s g_stmpe11; - -/* Otherwise, we will need to maintain allocated driver instances in a list */ - -#else -static struct stmpe11_dev_s *g_stmpe11list; -#endif - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: stmpe11_worker - * - * Description: - * This is the "bottom half" of the STMPE11 interrupt handler - * - ****************************************************************************/ - -static void stmpe11_worker(FAR void *arg) -{ - FAR struct stmpe11_dev_s *priv = (FAR struct stmpe11_dev_s *)arg; - uint8_t regval; - - DEBUGASSERT(priv && priv->config); - - /* Get the global interrupt status */ - - regval = stmpe11_getreg8(priv, STMPE11_INT_STA); - - /* Check for a touchscreen interrupt */ - -#ifndef CONFIG_STMPE11_TSC_DISABLE - if ((regval & (INT_TOUCH_DET|INT_FIFO_TH|INT_FIFO_OFLOW)) != 0) - { - /* Dispatch the touchscreen interrupt if it was brought into the link */ - -#ifdef CONFIG_HAVE_WEAKFUNCTIONS - if (stmpe11_tscworker) -#endif - { - stmpe11_tscworker(priv, regval); - } - - stmpe11_putreg8(priv, STMPE11_INT_STA, (INT_TOUCH_DET|INT_FIFO_TH|INT_FIFO_OFLOW)); - regval &= ~(INT_TOUCH_DET|INT_FIFO_TH|INT_FIFO_OFLOW); - } -#endif - -#if !defined(CONFIG_STMPE11_GPIO_DISABLE) && !defined(CONFIG_STMPE11_GPIOINT_DISABLE) - if ((regval & INT_GPIO) != 0) - { - /* Dispatch the GPIO interrupt if it was brought into the link */ - -#ifdef CONFIG_HAVE_WEAKFUNCTIONS - if (stmpe11_gpioworker) -#endif - { - stmpe11_gpioworker(priv); - } - - stmpe11_putreg8(priv, STMPE11_INT_STA, INT_GPIO); - regval &= ~INT_GPIO; - } -#endif - - /* Clear any other residual, unhandled pending interrupt */ - - if (regval != 0) - { - stmpe11_putreg8(priv, STMPE11_INT_STA, regval); - } - - /* Re-enable the STMPE11 GPIO interrupt */ - - priv->config->enable(priv->config, true); -} - -/**************************************************************************** - * Name: stmpe11_interrupt - * - * Description: - * The STMPE11 interrupt handler - * - ****************************************************************************/ - -static int stmpe11_interrupt(int irq, FAR void *context) -{ - FAR struct stmpe11_dev_s *priv; - FAR struct stmpe11_config_s *config; - int ret; - - /* Which STMPE11 device caused the interrupt? */ - -#ifndef CONFIG_STMPE11_MULTIPLE - priv = &g_stmpe11; -#else - for (priv = g_stmpe11list; - priv && priv->config->irq != irq; - priv = priv->flink); - - ASSERT(priv != NULL); -#endif - - /* Get a pointer the callbacks for convenience (and so the code is not so - * ugly). - */ - - config = priv->config; - DEBUGASSERT(config != NULL); - - /* Disable further interrupts */ - - config->enable(config, false); - - /* Check if interrupt work is already queue. If it is already busy, then - * we already have interrupt processing in the pipeline and we need to do - * nothing more. - */ - - if (work_available(&priv->work)) - { - /* Yes.. Transfer processing to the worker thread. Since STMPE11 - * interrupts are disabled while the work is pending, no special - * action should be required to protect the work queue. - */ - - ret = work_queue(&priv->work, stmpe11_worker, priv, 0); - if (ret != 0) - { - illdbg("Failed to queue work: %d\n", ret); - } - } - - /* Clear any pending interrupts and return success */ - - config->clear(config); - return OK; -} - -/**************************************************************************** - * Name: stmpe11_checkid - * - * Description: - * Read and verify the STMPE11 chip ID - * - ****************************************************************************/ - -static int stmpe11_checkid(FAR struct stmpe11_dev_s *priv) -{ - uint16_t devid = 0; - - /* Read device ID */ - - devid = stmpe11_getreg8(priv, STMPE11_CHIP_ID); - devid = (uint32_t)(devid << 8); - devid |= (uint32_t)stmpe11_getreg8(priv, STMPE11_CHIP_ID+1); - ivdbg("devid: %04x\n", devid); - - if (devid != (uint16_t)CHIP_ID) - { - /* ID is not Correct */ - - return -ENODEV; - } - - return OK; -} - -/**************************************************************************** - * Name: stmpe11_reset - * - * Description: - * Reset the STMPE11 - * - ****************************************************************************/ - -static void stmpe11_reset(FAR struct stmpe11_dev_s *priv) -{ - /* Power Down the STMPE11 */ - - stmpe11_putreg8(priv, STMPE11_SYS_CTRL1, SYS_CTRL1_SOFTRESET); - - /* Wait a bit */ - - usleep(20*1000); - - /* Then power on again. All registers will be in their reset state. */ - - stmpe11_putreg8(priv, STMPE11_SYS_CTRL1, 0); -} - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: stmpe11_instantiate - * - * Description: - * Instantiate and configure the STMPE11 device driver to use the provided - * I2C or SPIdevice instance. - * - * Input Parameters: - * dev - An I2C or SPI driver instance - * config - Persistant board configuration data - * - * Returned Value: - * A non-zero handle is returned on success. This handle may then be used - * to configure the STMPE11 driver as necessary. A NULL handle value is - * returned on failure. - * - ****************************************************************************/ - -#ifdef CONFIG_STMPE11_SPI -STMPE11_HANDLE stmpe11_instantiate(FAR struct spi_dev_s *dev, - FAR struct stmpe11_config_s *config) -#else -STMPE11_HANDLE stmpe11_instantiate(FAR struct i2c_dev_s *dev, - FAR struct stmpe11_config_s *config) -#endif -{ - FAR struct stmpe11_dev_s *priv; - uint8_t regval; - int ret; - - /* Allocate the device state structure */ - -#ifdef CONFIG_STMPE11_MULTIPLE - priv = (FAR struct stmpe11_dev_s *)kzalloc(sizeof(struct stmpe11_dev_s)); - if (!priv) - { - return NULL; - } - - /* And save the device structure in the list of STMPE11 so that we can find it later */ - - priv->flink = g_stmpe11list; - g_stmpe11list = priv; -#else - - /* Use the one-and-only STMPE11 driver instance */ - - priv = &g_stmpe11; -#endif - - /* Initialize the device state structure */ - - sem_init(&priv->exclsem, 0, 1); - priv->config = config; - -#ifdef CONFIG_STMPE11_SPI - priv->spi = dev; -#else - priv->i2c = dev; - - /* Set the I2C address and frequency. REVISIT: This logic would be - * insufficient if we share the I2C bus with any other devices that also - * modify the address and frequency. - */ - - I2C_SETADDRESS(dev, config->address, 7); - I2C_SETFREQUENCY(dev, config->frequency); -#endif - - /* Read and verify the STMPE11 chip ID */ - - ret = stmpe11_checkid(priv); - if (ret < 0) - { -#ifdef CONFIG_STMPE11_MULTIPLE - kfree(priv); -#endif - return NULL; - } - - /* Generate STMPE11 Software reset */ - - stmpe11_reset(priv); - - /* Configure the interrupt output pin to generate interrupts on high or low level. */ - - regval = stmpe11_getreg8(priv, STMPE11_INT_CTRL); -#ifdef CONFIG_STMPE11_ACTIVELOW - regval &= ~INT_CTRL_INT_POLARITY; /* Pin polarity: Active low / falling edge */ -#else - regval |= INT_CTRL_INT_POLARITY; /* Pin polarity: Active high / rising edge */ -#endif -#ifdef CONFIG_STMPE11_EDGE - regval |= INT_CTRL_INT_TYPE; /* Edge interrupt */ -#else - regval &= ~INT_CTRL_INT_TYPE; /* Level interrupt */ -#endif - stmpe11_putreg8(priv, STMPE11_INT_CTRL, regval); - - /* Attach the STMPE11 interrupt handler. */ - - config->attach(config, stmpe11_interrupt); - - /* Clear any pending interrupts */ - - stmpe11_putreg8(priv, STMPE11_INT_STA, INT_ALL); - config->clear(config); - config->enable(config, true); - - /* Enable global interrupts */ - - regval = stmpe11_getreg8(priv, STMPE11_INT_CTRL); - regval |= INT_CTRL_GLOBAL_INT; - stmpe11_putreg8(priv, STMPE11_INT_CTRL, regval); - - /* Return our private data structure as an opaque handle */ - - return (STMPE11_HANDLE)priv; -} - -/**************************************************************************** - * Name: stmpe11_getreg8 - * - * Description: - * Read from an 8-bit STMPE11 register - * - ****************************************************************************/ - -#ifdef CONFIG_STMPE11_I2C -uint8_t stmpe11_getreg8(FAR struct stmpe11_dev_s *priv, uint8_t regaddr) -{ - /* 8-bit data read sequence: - * - * Start - I2C_Write_Address - STMPE11_Reg_Address - - * Repeated_Start - I2C_Read_Address - STMPE11_Read_Data - STOP - */ - - struct i2c_msg_s msg[2]; - uint8_t regval; - int ret; - - /* Setup 8-bit STMPE11 address write message */ - - msg[0].addr = priv->config->address; /* 7-bit address */ - msg[0].flags = 0; /* Write transaction, beginning with START */ - msg[0].buffer = ®addr; /* Transfer from this address */ - msg[0].length = 1; /* Send one byte following the address - * (no STOP) */ - - /* Set up the 8-bit STMPE11 data read message */ - - msg[1].addr = priv->config->address; /* 7-bit address */ - msg[1].flags = I2C_M_READ; /* Read transaction, beginning with Re-START */ - msg[1].buffer = ®val; /* Transfer to this address */ - msg[1].length = 1; /* Receive one byte following the address - * (then STOP) */ - - /* Perform the transfer */ - - ret = I2C_TRANSFER(priv->i2c, msg, 2); - if (ret < 0) - { - idbg("I2C_TRANSFER failed: %d\n", ret); - return 0; - } - -#ifdef CONFIG_STMPE11_REGDEBUG - dbg("%02x->%02x\n", regaddr, regval); -#endif - return regval; -} -#endif - -/**************************************************************************** - * Name: stmpe11_putreg8 - * - * Description: - * Write a value to an 8-bit STMPE11 register - * - ****************************************************************************/ - -#ifdef CONFIG_STMPE11_I2C -void stmpe11_putreg8(FAR struct stmpe11_dev_s *priv, - uint8_t regaddr, uint8_t regval) -{ - /* 8-bit data read sequence: - * - * Start - I2C_Write_Address - STMPE11_Reg_Address - STMPE11_Write_Data - STOP - */ - - struct i2c_msg_s msg; - uint8_t txbuffer[2]; - int ret; - -#ifdef CONFIG_STMPE11_REGDEBUG - dbg("%02x<-%02x\n", regaddr, regval); -#endif - - /* Setup to the data to be transferred. Two bytes: The STMPE11 register - * address followed by one byte of data. - */ - - txbuffer[0] = regaddr; - txbuffer[1] = regval; - - /* Setup 8-bit STMPE11 address write message */ - - msg.addr = priv->config->address; /* 7-bit address */ - msg.flags = 0; /* Write transaction, beginning with START */ - msg.buffer = txbuffer; /* Transfer from this address */ - msg.length = 2; /* Send two byte following the address - * (then STOP) */ - - /* Perform the transfer */ - - ret = I2C_TRANSFER(priv->i2c, &msg, 1); - if (ret < 0) - { - idbg("I2C_TRANSFER failed: %d\n", ret); - } -} -#endif - -/**************************************************************************** - * Name: stmpe11_getreg16 - * - * Description: - * Read 16-bits of data from an STMPE-11 register - * - ****************************************************************************/ - -#ifdef CONFIG_STMPE11_I2C -uint16_t stmpe11_getreg16(FAR struct stmpe11_dev_s *priv, uint8_t regaddr) -{ - /* 16-bit data read sequence: - * - * Start - I2C_Write_Address - STMPE11_Reg_Address - - * Repeated_Start - I2C_Read_Address - STMPE11_Read_Data_1 - - * STMPE11_Read_Data_2 - STOP - */ - - - struct i2c_msg_s msg[2]; - uint8_t rxbuffer[2]; - int ret; - - /* Setup 8-bit STMPE11 address write message */ - - msg[0].addr = priv->config->address; /* 7-bit address */ - msg[0].flags = 0; /* Write transaction, beginning with START */ - msg[0].buffer = ®addr; /* Transfer from this address */ - msg[0].length = 1; /* Send one byte following the address - * (no STOP) */ - - /* Set up the 8-bit STMPE11 data read message */ - - msg[1].addr = priv->config->address; /* 7-bit address */ - msg[1].flags = I2C_M_READ; /* Read transaction, beginning with Re-START */ - msg[1].buffer = rxbuffer; /* Transfer to this address */ - msg[1].length = 2; /* Receive two bytes following the address - * (then STOP) */ - - /* Perform the transfer */ - - ret = I2C_TRANSFER(priv->i2c, msg, 2); - if (ret < 0) - { - idbg("I2C_TRANSFER failed: %d\n", ret); - return 0; - } - -#ifdef CONFIG_STMPE11_REGDEBUG - dbg("%02x->%02x%02x\n", regaddr, rxbuffer[0], rxbuffer[1]); -#endif - return (uint16_t)rxbuffer[0] << 8 | (uint16_t)rxbuffer[1]; -} -#endif - -#endif /* CONFIG_INPUT && CONFIG_INPUT_STMPE11 */ - diff --git a/nuttx/drivers/input/stmpe11_gpio.c b/nuttx/drivers/input/stmpe11_gpio.c deleted file mode 100644 index 82024b4d0..000000000 --- a/nuttx/drivers/input/stmpe11_gpio.c +++ /dev/null @@ -1,454 +0,0 @@ -/**************************************************************************** - * drivers/input/stmpe11_gpio.c - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * References: - * "STMPE811 S-Touch® advanced resistive touchscreen controller with 8-bit - * GPIO expander," Doc ID 14489 Rev 6, CD00186725, STMicroelectronics" - * - * 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 "stmpe11.h" - -#if defined(CONFIG_INPUT) && defined(CONFIG_INPUT_STMPE11) && !defined(CONFIG_STMPE11_GPIO_DISABLE) - -/**************************************************************************** - * Private Types - ****************************************************************************/ - -/**************************************************************************** - * Private Data - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: stmpe11_gpioinit - * - * Description: - * Initialize the GPIO interrupt subsystem - * - * Input Parameters: - * handle - The handle previously returned by stmpe11_instantiate - * - * Returned Value: - * Zero is returned on success. Otherwise, a negated errno value is - * returned to indicate the nature of the failure. - * - ****************************************************************************/ - -static void stmpe11_gpioinit(FAR struct stmpe11_dev_s *priv) -{ - uint8_t regval; - - if ((priv->flags & STMPE11_FLAGS_GPIO_INITIALIZED) == 0) - { - /* Enable Clocking for GPIO */ - - regval = stmpe11_getreg8(priv, STMPE11_SYS_CTRL2); - regval &= ~SYS_CTRL2_GPIO_OFF; - stmpe11_putreg8(priv, STMPE11_SYS_CTRL2, regval); - - /* Disable all GPIO interrupts */ - - stmpe11_putreg8(priv, STMPE11_GPIO_EN, 0); - - /* Enable global GPIO interrupts */ - -#ifndef CONFIG_STMPE11_GPIOINT_DISABLE - regval = stmpe11_getreg8(priv, STMPE11_INT_EN); - regval |= INT_GPIO; - stmpe11_putreg8(priv, STMPE11_INT_EN, regval); -#endif - - priv->flags |= STMPE11_FLAGS_GPIO_INITIALIZED; - } -} - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: stmpe11_gpioconfig - * - * Description: - * Configure an STMPE11 GPIO pin - * - * Input Parameters: - * handle - The handle previously returned by stmpe11_instantiate - * pinconfig - Bit-encoded pin configuration - * - * Returned Value: - * Zero is returned on success. Otherwise, a negated errno value is - * returned to indicate the nature of the failure. - * - ****************************************************************************/ - -int stmpe11_gpioconfig(STMPE11_HANDLE handle, uint8_t pinconfig) -{ - FAR struct stmpe11_dev_s *priv = (FAR struct stmpe11_dev_s *)handle; - int pin = (pinconfig & STMPE11_GPIO_PIN_MASK) >> STMPE11_GPIO_PIN_SHIFT; - uint8_t pinmask = (1 << pin); - uint8_t regval; - int ret; - - DEBUGASSERT(handle && (unsigned)pin < STMPE11_GPIO_NPINS); - - /* Get exclusive access to the device structure */ - - ret = sem_wait(&priv->exclsem); - if (ret < 0) - { - int errval = errno; - idbg("sem_wait failed: %d\n", errval); - return -errval; - } - - /* Make sure that the pin is not already in use */ - - if ((priv->inuse & pinmask) != 0) - { - idbg("PIN%d is already in-use\n", pin); - sem_post(&priv->exclsem); - return -EBUSY; - } - - /* Make sure that the GPIO block has been initialized */ - - stmpe11_gpioinit(priv); - - /* Set the alternate function bit for the pin, making it a GPIO */ - - regval = stmpe11_getreg8(priv, STMPE11_GPIO_AF); - regval |= pinmask; - stmpe11_putreg8(priv, STMPE11_GPIO_AF, regval); - - /* Is the pin an input or an output? */ - - if ((pinconfig & STMPE11_GPIO_DIR) == STMPE11_GPIO_OUTPUT) - { - /* The pin is an output */ - - regval = stmpe11_getreg8(priv, STMPE11_GPIO_DIR); - regval &= ~pinmask; - stmpe11_putreg8(priv, STMPE11_GPIO_DIR, regval); - - /* Set its initial output value */ - - stmpe11_gpiowrite(handle, pinconfig, - (pinconfig & STMPE11_GPIO_VALUE) != STMPE11_GPIO_ZERO); - } - else - { - /* It is an input */ - - regval = stmpe11_getreg8(priv, STMPE11_GPIO_DIR); - regval |= pinmask; - stmpe11_putreg8(priv, STMPE11_GPIO_DIR, regval); - - /* Set up the falling edge detection */ - - regval = stmpe11_getreg8(priv, STMPE11_GPIO_FE); - if ((pinconfig & STMPE11_GPIO_FALLING) != 0) - { - regval |= pinmask; - } - else - { - regval &= pinmask; - } - stmpe11_putreg8(priv, STMPE11_GPIO_FE, regval); - - /* Set up the rising edge detection */ - - regval = stmpe11_getreg8(priv, STMPE11_GPIO_RE); - if ((pinconfig & STMPE11_GPIO_FALLING) != 0) - { - regval |= pinmask; - } - else - { - regval &= pinmask; - } - stmpe11_putreg8(priv, STMPE11_GPIO_RE, regval); - - /* Disable interrupts for now */ - - regval = stmpe11_getreg8(priv, STMPE11_GPIO_EN); - regval &= ~pinmask; - stmpe11_putreg8(priv, STMPE11_GPIO_EN, regval); - } - - /* Mark the pin as 'in use' */ - - priv->inuse |= pinmask; - sem_post(&priv->exclsem); - return OK; -} - -/**************************************************************************** - * Name: stmpe11_gpiowrite - * - * Description: - * Set or clear the GPIO output - * - * Input Parameters: - * handle - The handle previously returned by stmpe11_instantiate - * pinconfig - Bit-encoded pin configuration - * value = true: write logic '1'; false: write logic '0; - * - * Returned Value: - * None - * - ****************************************************************************/ - -void stmpe11_gpiowrite(STMPE11_HANDLE handle, uint8_t pinconfig, bool value) -{ - FAR struct stmpe11_dev_s *priv = (FAR struct stmpe11_dev_s *)handle; - int pin = (pinconfig & STMPE11_GPIO_PIN_MASK) >> STMPE11_GPIO_PIN_SHIFT; - int ret; - - DEBUGASSERT(handle && (unsigned)pin < STMPE11_GPIO_NPINS); - - /* Get exclusive access to the device structure */ - - ret = sem_wait(&priv->exclsem); - if (ret < 0) - { - idbg("sem_wait failed: %d\n", errno); - return; - } - - /* Are we setting or clearing outputs? */ - - if (value) - { - /* Set the output valu(s)e by writing to the SET register */ - - stmpe11_putreg8(priv, STMPE11_GPIO_SETPIN, (1 << pin)); - } - else - { - /* Clear the output value(s) by writing to the CLR register */ - - stmpe11_putreg8(priv, STMPE11_GPIO_CLRPIN, (1 << pin)); - } - - sem_post(&priv->exclsem); -} - -/**************************************************************************** - * Name: stmpe11_gpioread - * - * Description: - * Set or clear the GPIO output - * - * Input Parameters: - * handle - The handle previously returned by stmpe11_instantiate - * pinconfig - Bit-encoded pin configuration - * value - The location to return the state of the GPIO pin - * - * Returned Value: - * Zero is returned on success. Otherwise, a negated errno value is - * returned to indicate the nature of the failure. - * - ****************************************************************************/ - -int stmpe11_gpioread(STMPE11_HANDLE handle, uint8_t pinconfig, bool *value) -{ - FAR struct stmpe11_dev_s *priv = (FAR struct stmpe11_dev_s *)handle; - int pin = (pinconfig & STMPE11_GPIO_PIN_MASK) >> STMPE11_GPIO_PIN_SHIFT; - uint8_t regval; - int ret; - - DEBUGASSERT(handle && (unsigned)pin < STMPE11_GPIO_NPINS); - - /* Get exclusive access to the device structure */ - - ret = sem_wait(&priv->exclsem); - if (ret < 0) - { - int errval = errno; - idbg("sem_wait failed: %d\n", errval); - return -errval; - } - - regval = stmpe11_getreg8(priv, STMPE11_GPIO_MPSTA); - *value = ((regval & GPIO_PIN(pin)) != 0); - sem_post(&priv->exclsem); - return OK; -} - -/*********************************************************************************** - * Name: stmpe11_gpioattach - * - * Description: - * Attach to a GPIO interrupt input pin and enable interrupts on the pin. Using - * the value NULL for the handler address will disable interrupts from the pin and - * detach the handler. - * - * NOTE: Callbacks do not occur from an interrupt handler but rather from the - * context of the worker thread. - * - * Input Parameters: - * handle - The handle previously returned by stmpe11_instantiate - * pinconfig - Bit-encoded pin configuration - * handler - The handler that will be called when the interrupt occurs. - * - * Returned Value: - * Zero is returned on success. Otherwise, a negated errno value is returned - * to indicate the nature of the failure. - * - ************************************************************************************/ - -#ifndef CONFIG_STMPE11_GPIOINT_DISABLE -int stmpe11_gpioattach(STMPE11_HANDLE handle, uint8_t pinconfig, - stmpe11_handler_t handler) -{ - FAR struct stmpe11_dev_s *priv = (FAR struct stmpe11_dev_s *)handle; - int pin = (pinconfig & STMPE11_GPIO_PIN_MASK) >> STMPE11_GPIO_PIN_SHIFT; - uint8_t regval; - int ret; - - DEBUGASSERT(handle && (unsigned)pin < STMPE11_GPIO_NPINS); - - /* Get exclusive access to the device structure */ - - ret = sem_wait(&priv->exclsem); - if (ret < 0) - { - int errval = errno; - idbg("sem_wait failed: %d\n", errval); - return -errval; - } - - /* Make sure that the GPIO interrupt system has been gpioinitialized */ - - stmpe11_gpioinit(priv); - - /* Set/clear the handler */ - - priv->handlers[pin] = handler; - - /* If an handler has provided, then we are enabling interrupts */ - - regval = stmpe11_getreg8(priv, STMPE11_GPIO_EN); - if (handler) - { - /* Enable interrupts for this GPIO */ - - regval &= ~GPIO_PIN(pin); - } - else - { - /* Disable interrupts for this GPIO */ - - regval &= ~GPIO_PIN(pin); - } - stmpe11_putreg8(priv, STMPE11_GPIO_EN, regval); - - sem_post(&priv->exclsem); - return OK; -} -#endif - -/**************************************************************************** - * Name: stmpe11_gpioworker - * - * Description: - * Handle GPIO interrupt events (this function actually executes in the - * context of the worker thread). - * - ****************************************************************************/ - -#ifndef CONFIG_STMPE11_GPIOINT_DISABLE -void stmpe11_gpioworker(FAR struct stmpe11_dev_s *priv) -{ - uint8_t regval; - uint8_t pinmask; - int pin; - - /* Get the set of pending GPIO interrupts */ - - regval = stmpe11_getreg8(priv, STMPE11_GPIO_INTSTA); - - /* Look at each pin */ - - for (pin = 0; pin < SMTPE11_GPIO_NPINS; pin++) - { - pinmask = GPIO_INT(pin); - if ((regval & pinmask) != 0) - { - /* Check if we have a handler for this interrupt (there should - * be one) - */ - - if (priv->handlers[pin]) - { - /* Interrupt is pending... dispatch the interrupt to the - * callback - */ - - priv->handlers[pin](pin); - } - else - { - illdbg("No handler for PIN%d, GPIO_INTSTA: %02x\n", pin, regval); - } - - /* Clear the pending GPIO interrupt by writing a '1' to the - * pin position in the status register. - */ - - stmpe11_putreg8(priv, STMPE11_GPIO_INTSTA, pinmask); - } - } -} -#endif - -#endif /* CONFIG_INPUT && CONFIG_INPUT_STMPE11 && !CONFIG_STMPE11_GPIO_DISABLE */ - diff --git a/nuttx/drivers/input/stmpe11_temp.c b/nuttx/drivers/input/stmpe11_temp.c deleted file mode 100644 index b3eb8f6c5..000000000 --- a/nuttx/drivers/input/stmpe11_temp.c +++ /dev/null @@ -1,174 +0,0 @@ -/**************************************************************************** - * drivers/input/stmpe11_temp.c - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * References: - * "STMPE811 S-Touch® advanced resistive touchscreen controller with 8-bit - * GPIO expander," Doc ID 14489 Rev 6, CD00186725, STMicroelectronics" - * - * 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 "stmpe11.h" - -#if defined(CONFIG_INPUT) && defined(CONFIG_INPUT_STMPE11) && !defined(CONFIG_STMPE11_TEMP_DISABLE) - -/**************************************************************************** - * Private Types - ****************************************************************************/ - -/**************************************************************************** - * Private Data - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: stmpe11_tempinitialize - * - * Description: - * Configure the temperature sensor. - * - * Input Parameters: - * handle - The handle previously returned by stmpe11_instantiate - * - * Returned Value: - * Zero is returned on success. Otherwise, a negated errno value is - * returned to indicate the nature of the failure. - * - ****************************************************************************/ - -int stmpe11_tempinitialize(STMPE11_HANDLE handle) -{ - FAR struct stmpe11_dev_s *priv = (FAR struct stmpe11_dev_s *)handle; - uint8_t regval; - - /* Enable clocking for ADC and the temperature sensor */ - - regval = stmpe11_getreg8(priv, STMPE11_SYS_CTRL2); - regval &= ~(SYS_CTRL2_TS_OFF | SYS_CTRL2_ADC_OFF); - stmpe11_putreg8(priv, STMPE11_SYS_CTRL2, regval); - - /* Enable the temperature sensor */ - - stmpe11_putreg8(priv, STMPE11_TEMP_CTRL, TEMP_CTRL_ENABLE); - - /* Aquire data enable */ - - stmpe11_putreg8(priv, STMPE11_TEMP_CTRL, (TEMP_CTRL_ACQ|TEMP_CTRL_ENABLE)); - - return OK; -} - -/**************************************************************************** - * Name: stmpe11_tempread - * - * Description: - * Configure the temperature sensor. - * - * Input Parameters: - * handle - The handle previously returned by stmpe11_instantiate - * - * Returned Value: - * Zero is returned on success. Otherwise, a negated errno value is - * returned to indicate the nature of the failure. - * - ****************************************************************************/ - -uint16_t stmpe11_tempread(STMPE11_HANDLE handle) -{ - FAR struct stmpe11_dev_s *priv = (FAR struct stmpe11_dev_s *)handle; - uint32_t temp = 0; - uint8_t temp1; - uint8_t temp2; - - /* Acquire data enable */ - - stmpe11_putreg8(priv, STMPE11_TEMP_CTRL, (TEMP_CTRL_ACQ|TEMP_CTRL_ENABLE)); - - /* Read the temperature */ - - temp1 = stmpe11_getreg8(priv, STMPE11_SYS_CTRL2); - temp2 = stmpe11_getreg8(priv, STMPE11_SYS_CTRL2+1); - - /* Scale the temperature (where Vio is assumed to be .33) */ - - temp = ((uint32_t)(temp1 & 3) << 8) | temp2; - temp = (uint32_t)((33 * temp * 100) / 751); - temp = (uint32_t)((temp + 5) / 10); - - return (uint16_t)temp; -} - -/**************************************************************************** - * Name: stmpe11_tempinterrupt - * - * Description: - * Configure the temperature sensor to sample the temperature periodically. - * Set the temperature threshold to generate an interrupt and notify - * to the client using the provide callback function pointer. - * - * Input Parameters: - * handle - The handle previously returned by stmpe11_instantiate - * threshold - The threshold temperature value - * direction - True: Generate an interrupt if the temperate exceeds the - * threshold value; False: Generate an interrupt if the - * temperature falls below the threshold value. - * callback - The client callback function that will be called when - * the termperature crosses the threshold. - * - * Returned Value: - * Zero is returned on success. Otherwise, a negated errno value is - * returned to indicate the nature of the failure. - * - ****************************************************************************/ -/* Not implemented */ - -#endif /* CONFIG_INPUT && CONFIG_INPUT_STMPE11 && !CONFIG_STMPE11_TEMP_DISABLE */ - diff --git a/nuttx/drivers/input/stmpe11_tsc.c b/nuttx/drivers/input/stmpe11_tsc.c deleted file mode 100644 index 03ede7302..000000000 --- a/nuttx/drivers/input/stmpe11_tsc.c +++ /dev/null @@ -1,1144 +0,0 @@ -/**************************************************************************** - * drivers/input/stmpe11_tsc.c - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * References: - * "STMPE811 S-Touch® advanced resistive touchscreen controller with 8-bit - * GPIO expander," Doc ID 14489 Rev 6, CD00186725, STMicroelectronics" - * - * 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 -#include -#include - -#include -#include -#include -#include -#include - -#include -#include -#include - -#include "stmpe11.h" - -#if defined(CONFIG_INPUT) && defined(CONFIG_INPUT_STMPE11) && !defined(CONFIG_STMPE11_TSC_DISABLE) - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -#define Direction_IN 0x00 -#define Direction_OUT 0x01 - -#define Polarity_Low 0x00 -#define Polarity_High 0x04 -#define Type_Level 0x00 -#define Type_Edge 0x02 - -#define IO_IT_0 0x01 -#define IO_IT_1 0x02 -#define IO_IT_2 0x04 -#define IO_IT_3 0x08 -#define IO_IT_4 0x10 -#define IO_IT_5 0x20 -#define IO_IT_6 0x40 -#define IO_IT_7 0x80 -#define ALL_IT 0xFF -#define IOE_JOY_IT (uint8_t)(IO_IT_3 | IO_IT_4 | IO_IT_5 | IO_IT_6 | IO_IT_7) -#define IOE_TS_IT (uint8_t)(IO_IT_0 | IO_IT_1 | IO_IT_2) -#define IOE_INMEMS_IT (uint8_t)(IO_IT_2 | IO_IT_3) - -#define EDGE_FALLING 0x01 -#define EDGE_RISING 0x02 - -#define TIMEOUT_MAX 0x3000 /*nwaiters > 0) - { - /* After posting this semaphore, we need to exit because the STMPE11 - * is no longer available. - */ - - sem_post(&priv->waitsem); - } - - /* If there are threads waiting on poll() for STMPE11 data to become available, - * then wake them up now. NOTE: we wake up all waiting threads because we - * do not know that they are going to do. If they all try to read the data, - * then some make end up blocking after all. - */ - -#ifndef CONFIG_DISABLE_POLL - for (i = 0; i < CONFIG_STMPE11_NPOLLWAITERS; i++) - { - struct pollfd *fds = priv->fds[i]; - if (fds) - { - fds->revents |= POLLIN; - ivdbg("Report events: %02x\n", fds->revents); - sem_post(fds->sem); - } - } -#endif -} - -/**************************************************************************** - * Name: stmpe11_sample - * - * Description: - * Check if touchscreen sample data is available now and, if so, return - * the sample data. This is part of the stmpe11_read logic. - * - * Assumption: - * Pre-emption is disable to prevent the worker thread from running. - * Otherwise, sampled data may continue to change. - * - ****************************************************************************/ - -static int stmpe11_sample(FAR struct stmpe11_dev_s *priv, - FAR struct stmpe11_sample_s *sample) -{ - int ret = -EAGAIN; - - /* Is there new STMPE11 sample data available? */ - - if (priv->penchange) - { - /* Yes.. the state has changed in some way. Return a copy of the - * sampled data. - */ - - memcpy(sample, &priv->sample, sizeof(struct stmpe11_sample_s)); - - /* Now manage state transitions */ - - if (sample->contact == CONTACT_UP) - { - /* The sampling logic has detected pen-up in some condition other - * than CONTACT_NONE. Set the next state to CONTACT_NONE: Further - * pen-down reports will be ignored. Increment the ID so that - * next contact ID will be unique - */ - - priv->sample.contact = CONTACT_NONE; - priv->sample.valid = false; - priv->id++; - } - else if (sample->contact == CONTACT_DOWN) - { - /* The sampling logic has detected pen-up in some condition other - * than CONTACT_MOVE. Set the next state to CONTACT_MOVE: Further - * samples collected while the pen is down will reported as movement - * events. - */ - - priv->sample.contact = CONTACT_MOVE; - } - - priv->penchange = false; - ret = OK; - } - - return ret; -} - -/**************************************************************************** - * Name: stmpe11_waitsample - * - * Description: - * Wait for a sample to become available (this is really part of the - * stmpe11_read logic). - * - ****************************************************************************/ - -static inline int stmpe11_waitsample(FAR struct stmpe11_dev_s *priv, - FAR struct stmpe11_sample_s *sample) -{ - int ret; - - /* Disable pre-emption to prevent the worker thread from running - * asynchronously. - */ - - sched_lock(); - - /* Now release the semaphore that manages mutually exclusive access to - * the device structure. This may cause other tasks to become ready to - * run, but they cannot run yet because pre-emption is disabled. - */ - - sem_post(&priv->exclsem); - - /* Try to get the a sample... if we cannot, then wait on the semaphore - * that is posted when new sample data is availble. - */ - - while (stmpe11_sample(priv, sample) < 0) - { - /* Wait for a change in the STMPE11 state */ - - priv->nwaiters++; - ret = sem_wait(&priv->waitsem); - priv->nwaiters--; - - /* When we are re-awakened, pre-emption will again be disabled */ - - if (ret < 0) - { -#ifdef CONFIG_DEBUG - // Sample the errno (debug output could change it) - - int errval = errno; - - /* If we are awakened by a signal, then we need to return - * the failure now. - */ - - idbg("ERROR: sem_wait failed: %d\n", errval); - DEBUGASSERT(errval == EINTR); -#endif - ret = -EINTR; - goto errout; - } - } - - /* Re-acquire the the semaphore that manages mutually exclusive access to - * the device structure. We may have to wait here. But we have our sample. - * Interrupts and pre-emption will be re-enabled while we wait. - */ - - ret = sem_wait(&priv->exclsem); - -errout: - /* Restore pre-emption. We might get suspended here but that is okay - * because we already have our sample. Note: this means that if there - * were two threads reading from the STMPE11 for some reason, the data - * might be read out of order. - */ - - sched_unlock(); - return ret; -} - -/**************************************************************************** - * Name: stmpe11_open - * - * Description: - * Standard character driver open method. - * - ****************************************************************************/ - -static int stmpe11_open(FAR struct file *filep) -{ -#ifdef CONFIG_STMPE11_REFCNT - FAR struct inode *inode; - FAR struct stmpe11_dev_s *priv; - uint8_t tmp; - int ret; - - DEBUGASSERT(filep); - inode = filep->f_inode; - - DEBUGASSERT(inode && inode->i_private); - priv = (FAR struct stmpe11_dev_s *)inode->i_private; - - /* Get exclusive access to the driver data structure */ - - ret = sem_wait(&priv->exclsem); - if (ret < 0) - { - /* This should only happen if the wait was canceled by an signal */ - - DEBUGASSERT(errno == EINTR); - return -EINTR; - } - - /* Increment the reference count */ - - tmp = priv->crefs + 1; - if (tmp == 0) - { - /* More than 255 opens; uint8_t overflows to zero */ - - ret = -EMFILE; - goto errout_with_sem; - } - - /* When the reference increments to 1, this is the first open event - * on the driver.. and an opportunity to do any one-time initialization. - */ - - /* Save the new open count on success */ - - priv->crefs = tmp; - -errout_with_sem: - sem_post(&priv->exclsem); - return ret; -#else - return OK; -#endif -} - -/**************************************************************************** - * Name: stmpe11_close - * - * Description: - * Standard character driver close method. - * - ****************************************************************************/ - -static int stmpe11_close(FAR struct file *filep) -{ -#ifdef CONFIG_STMPE11_REFCNT - FAR struct inode *inode; - FAR struct stmpe11_dev_s *priv; - int ret; - - DEBUGASSERT(filep); - inode = filep->f_inode; - - DEBUGASSERT(inode && inode->i_private); - priv = (FAR struct stmpe11_dev_s *)inode->i_private; - - /* Get exclusive access to the driver data structure */ - - ret = sem_wait(&priv->exclsem); - if (ret < 0) - { - /* This should only happen if the wait was canceled by an signal */ - - DEBUGASSERT(errno == EINTR); - return -EINTR; - } - - /* Decrement the reference count unless it would decrement a negative - * value. When the count decrements to zero, there are no further - * open references to the driver. - */ - - if (priv->crefs >= 1) - { - priv->crefs--; - } - - sem_post(&priv->exclsem); -#endif - return OK; -} - -/**************************************************************************** - * Name: stmpe11_read - * - * Description: - * Standard character driver read method. - * - ****************************************************************************/ - -static ssize_t stmpe11_read(FAR struct file *filep, FAR char *buffer, size_t len) -{ - FAR struct inode *inode; - FAR struct stmpe11_dev_s *priv; - FAR struct touch_sample_s *report; - struct stmpe11_sample_s sample; - int ret; - - ivdbg("len=%d\n", len); - DEBUGASSERT(filep); - inode = filep->f_inode; - - DEBUGASSERT(inode && inode->i_private); - priv = (FAR struct stmpe11_dev_s *)inode->i_private; - - /* Verify that the caller has provided a buffer large enough to receive - * the touch data. - */ - - if (len < SIZEOF_TOUCH_SAMPLE_S(1)) - { - /* We could provide logic to break up a touch report into segments and - * handle smaller reads... but why? - */ - - return -ENOSYS; - } - - /* Get exclusive access to the driver data structure */ - - ret = sem_wait(&priv->exclsem); - if (ret < 0) - { - /* This should only happen if the wait was canceled by an signal */ - - DEBUGASSERT(errno == EINTR); - return -EINTR; - } - - /* Try to read sample data. */ - - ret = stmpe11_sample(priv, &sample); - if (ret < 0) - { - /* Sample data is not available now. We would ave to wait to get - * receive sample data. If the user has specified the O_NONBLOCK - * option, then just return an error. - */ - - if (filep->f_oflags & O_NONBLOCK) - { - ret = -EAGAIN; - goto errout; - } - - /* Wait for sample data */ - - ret = stmpe11_waitsample(priv, &sample); - if (ret < 0) - { - /* We might have been awakened by a signal */ - - goto errout; - } - } - - /* In any event, we now have sampled STMPE11 data that we can report - * to the caller. - */ - - report = (FAR struct touch_sample_s *)buffer; - memset(report, 0, SIZEOF_TOUCH_SAMPLE_S(1)); - report->npoints = 1; - report->point[0].id = sample.id; - report->point[0].x = sample.x; - report->point[0].y = sample.y; - report->point[0].pressure = sample.z; - - /* Report the appropriate flags */ - - if (sample.contact == CONTACT_UP) - { - /* Pen is now up. Is the positional data valid? This is important to - * know because the release will be sent to the window based on its - * last positional data. - */ - - if (sample.valid) - { - report->point[0].flags = TOUCH_UP | TOUCH_ID_VALID | - TOUCH_POS_VALID | TOUCH_PRESSURE_VALID; - } - else - { - report->point[0].flags = TOUCH_UP | TOUCH_ID_VALID; - } - } - else if (sample.contact == CONTACT_DOWN) - { - /* First contact */ - - report->point[0].flags = TOUCH_DOWN | TOUCH_ID_VALID | - TOUCH_POS_VALID | TOUCH_PRESSURE_VALID; - } - else /* if (sample->contact == CONTACT_MOVE) */ - { - /* Movement of the same contact */ - - report->point[0].flags = TOUCH_MOVE | TOUCH_ID_VALID | - TOUCH_POS_VALID | TOUCH_PRESSURE_VALID; - } - - ret = SIZEOF_TOUCH_SAMPLE_S(1); - -errout: - sem_post(&priv->exclsem); - return ret; -} - -/**************************************************************************** - * Name: stmpe11_ioctl - * - * Description: - * Standard character driver ioctl method. - * -****************************************************************************/ - -static int stmpe11_ioctl(FAR struct file *filep, int cmd, unsigned long arg) -{ - FAR struct inode *inode; - FAR struct stmpe11_dev_s *priv; - int ret; - - ivdbg("cmd: %d arg: %ld\n", cmd, arg); - DEBUGASSERT(filep); - inode = filep->f_inode; - - DEBUGASSERT(inode && inode->i_private); - priv = (FAR struct stmpe11_dev_s *)inode->i_private; - - /* Get exclusive access to the driver data structure */ - - ret = sem_wait(&priv->exclsem); - if (ret < 0) - { - /* This should only happen if the wait was canceled by an signal */ - - DEBUGASSERT(errno == EINTR); - return -EINTR; - } - - /* Process the IOCTL by command */ - - switch (cmd) - { - case TSIOC_SETFREQUENCY: /* arg: Pointer to uint32_t frequency value */ - { - FAR uint32_t *ptr = (FAR uint32_t *)((uintptr_t)arg); - DEBUGASSERT(priv->config != NULL && ptr != NULL); - priv->config->frequency = I2C_SETFREQUENCY(priv->i2c, *ptr); - } - break; - - case TSIOC_GETFREQUENCY: /* arg: Pointer to uint32_t frequency value */ - { - FAR uint32_t *ptr = (FAR uint32_t *)((uintptr_t)arg); - DEBUGASSERT(priv->config != NULL && ptr != NULL); - *ptr = priv->config->frequency; - } - break; - - default: - ret = -ENOTTY; - break; - } - - sem_post(&priv->exclsem); - return ret; -} - -/**************************************************************************** - * Name: stmpe11_poll - * - * Description: - * Standard character driver poll method. - * - ****************************************************************************/ - -#ifndef CONFIG_DISABLE_POLL -static int stmpe11_poll(FAR struct file *filep, FAR struct pollfd *fds, - bool setup) -{ - FAR struct inode *inode; - FAR struct stmpe11_dev_s *priv; - int ret; - int i; - - ivdbg("setup: %d\n", (int)setup); - DEBUGASSERT(filep && fds); - inode = filep->f_inode; - - DEBUGASSERT(inode && inode->i_private); - priv = (FAR struct stmpe11_dev_s *)inode->i_private; - - /* Are we setting up the poll? Or tearing it down? */ - - ret = sem_wait(&priv->exclsem); - if (ret < 0) - { - /* This should only happen if the wait was canceled by an signal */ - - DEBUGASSERT(errno == EINTR); - return -EINTR; - } - - if (setup) - { - /* Ignore waits that do not include POLLIN */ - - if ((fds->events & POLLIN) == 0) - { - idbg("ERROR: Missing POLLIN: revents: %08x\n", fds->revents); - ret = -EDEADLK; - goto errout; - } - - /* This is a request to set up the poll. Find an available - * slot for the poll structure reference - */ - - for (i = 0; i < CONFIG_STMPE11_NPOLLWAITERS; i++) - { - /* Find an available slot */ - - if (!priv->fds[i]) - { - /* Bind the poll structure and this slot */ - - priv->fds[i] = fds; - fds->priv = &priv->fds[i]; - break; - } - } - - if (i >= CONFIG_STMPE11_NPOLLWAITERS) - { - idbg("ERROR: No availabled slot found: %d\n", i); - fds->priv = NULL; - ret = -EBUSY; - goto errout; - } - - /* Should we immediately notify on any of the requested events? */ - - if (priv->penchange) - { - stmpe11_notify(priv); - } - } - else if (fds->priv) - { - /* This is a request to tear down the poll. */ - - struct pollfd **slot = (struct pollfd **)fds->priv; - DEBUGASSERT(slot != NULL); - - /* Remove all memory of the poll setup */ - - *slot = NULL; - fds->priv = NULL; - } - -errout: - sem_post(&priv->exclsem); - return ret; -} -#endif - -/**************************************************************************** - * Name: stmpe11_timeoutworker - * - * Description: - * A timer has expired without receiving a pen up event. Check again. - * - ****************************************************************************/ - -static void stmpe11_timeoutworker(FAR void *arg) -{ - FAR struct stmpe11_dev_s *priv = (FAR struct stmpe11_dev_s *)arg; - - DEBUGASSERT(priv); - - /* Treat the timeout just like an interrupt occurred */ - - stmpe11_tscworker(priv, stmpe11_getreg8(priv, STMPE11_INT_STA)); -} - -/**************************************************************************** - * Name: stmpe11_timeout - * - * Description: - * A timer has expired without receiving a pen up event. Schedule work - * to check again. - * - ****************************************************************************/ - -static void stmpe11_timeout(int argc, uint32_t arg1, ...) -{ - FAR struct stmpe11_dev_s *priv = (FAR struct stmpe11_dev_s *)((uintptr_t)arg1); - int ret; - - /* Are we still stuck in the pen down state? */ - - if (priv->sample.contact == CONTACT_MOVE || - priv->sample.contact == CONTACT_MOVE) - { - /* Yes... is the worker thread available? If not, then apparently - * we have work already pending? - */ - - if (work_available(&priv->timeout)) - { - /* Yes.. Transfer processing to the worker thread. Since STMPE11 - * interrupts are disabled while the work is pending, no special - * action should be required to protect the work queue. - */ - - ret = work_queue(&priv->timeout, stmpe11_timeoutworker, priv, 0); - if (ret != 0) - { - illdbg("Failed to queue work: %d\n", ret); - } - } - } -} - -/**************************************************************************** - * Name: stmpe11_tscinitialize - * - * Description: - * Initialize the touchscreen controller. This is really a part of the - * stmpe11_register logic, - * - ****************************************************************************/ - -static inline void stmpe11_tscinitialize(FAR struct stmpe11_dev_s *priv) -{ - uint8_t regval; - - ivdbg("Initializing touchscreen controller\n"); - - /* Enable TSC and ADC functions */ - - regval = stmpe11_getreg8(priv, STMPE11_SYS_CTRL2); - regval &= ~(SYS_CTRL2_TSC_OFF | SYS_CTRL2_ADC_OFF); - stmpe11_putreg8(priv, STMPE11_SYS_CTRL2, regval); - - /* Enable the TSC global interrupts */ - - regval = stmpe11_getreg8(priv, STMPE11_INT_EN); - regval |= (uint32_t)(INT_TOUCH_DET | INT_FIFO_TH | INT_FIFO_OFLOW); - stmpe11_putreg8(priv, STMPE11_INT_EN, regval); - - /* Select Sample Time, bit number and ADC Reference */ - - stmpe11_putreg8(priv, STMPE11_ADC_CTRL1, priv->config->ctrl1); - - /* Wait for 20 ms */ - - up_mdelay(20); - - /* Select the ADC clock speed */ - - stmpe11_putreg8(priv, STMPE11_ADC_CTRL2, priv->config->ctrl2); - - /* Select TSC pins in non-GPIO mode (AF=0) */ - - regval = stmpe11_getreg8(priv, STMPE11_GPIO_AF); - regval &= ~(uint8_t)TSC_PIN_SET; - stmpe11_putreg8(priv, STMPE11_GPIO_AF, regval); - - /* Select 2 nF filter capacitor */ - - stmpe11_putreg8(priv, STMPE11_TSC_CFG, - (TSC_CFG_AVE_CTRL_4SAMPLES | TSC_CFG_TOUCH_DELAY_500US | TSC_CFG_SETTLING_500US)); - - /* Select single point reading */ - - stmpe11_putreg8(priv, STMPE11_FIFO_TH, 1); - - /* Reset and clear the FIFO. */ - - stmpe11_putreg8(priv, STMPE11_FIFO_STA, FIFO_STA_FIFO_RESET); - stmpe11_putreg8(priv, STMPE11_FIFO_STA, 0); - - /* set the data format for Z value: 7 fractional part and 1 whole part */ - - stmpe11_putreg8(priv, STMPE11_TSC_FRACTIONZ, 0x01); - - /* Set the driving capability of the device for TSC pins: 50mA */ - - stmpe11_putreg8(priv, STMPE11_TSC_IDRIVE, TSC_IDRIVE_50MA); - - /* Enable the TSC. Use no tracking index, touch-screen controller - * operation mode (XYZ). - */ - - stmpe11_putreg8(priv, STMPE11_TSC_CTRL, TSC_CTRL_EN); - - /* Clear all the status pending bits */ - - stmpe11_putreg8(priv, STMPE11_INT_STA, INT_ALL); -} - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: stmpe11_register - * - * Description: - * Enable TSC functionality. GPIO4-7 must be available. This function - * will register the touchsceen driver as /dev/inputN where N is the minor - * device number - * - * Input Parameters: - * handle - The handle previously returned by stmpe11_register - * 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 stmpe11_register(STMPE11_HANDLE handle, int minor) -{ - FAR struct stmpe11_dev_s *priv = (FAR struct stmpe11_dev_s *)handle; - char devname[DEV_NAMELEN]; - int ret; - - ivdbg("handle=%p minor=%d\n", handle, minor); - DEBUGASSERT(priv); - - /* Get exclusive access to the device structure */ - - ret = sem_wait(&priv->exclsem); - if (ret < 0) - { - int errval = errno; - idbg("ERROR: sem_wait failed: %d\n", errval); - return -errval; - } - - /* Make sure that the pins (4-7) need by the TSC are not already in use */ - - if ((priv->inuse & TSC_PIN_SET) != 0) - { - idbg("ERROR: TSC pins is already in-use: %02x\n", priv->inuse); - sem_post(&priv->exclsem); - return -EBUSY; - } - - /* Initialize the TS structure fields to their default values */ - - priv->minor = minor; - priv->penchange = false; - priv->threshx = 0; - priv->threshy = 0; - - /* Create a timer for catching missed pen up conditions */ - - priv->wdog = wd_create(); - if (!priv->wdog) - { - idbg("ERROR: Failed to create a watchdog\n", errno); - sem_post(&priv->exclsem); - return -ENOSPC; - } - - /* Register the character driver */ - - snprintf(devname, DEV_NAMELEN, DEV_FORMAT, minor); - ret = register_driver(devname, &g_stmpe11fops, 0666, priv); - if (ret < 0) - { - idbg("ERROR: Failed to register driver %s: %d\n", devname, ret); - sem_post(&priv->exclsem); - return ret; - } - - /* Initialize the touchscreen controller */ - - stmpe11_tscinitialize(priv); - - /* Inidicate that the touchscreen controller was successfully initialized */ - - priv->inuse |= TSC_PIN_SET; /* Pins 4-7 are now in-use */ - priv->flags |= STMPE11_FLAGS_TSC_INITIALIZED; /* TSC function is initialized */ - sem_post(&priv->exclsem); - return ret; -} - -/**************************************************************************** - * Name: stmpe11_tscworker - * - * Description: - * This function is called to handle a TSC interrupt. It is not really - * an interrupt handle because it is called from the STMPE11 "bottom half" - * logic that runs on the worker thread. - * - ****************************************************************************/ - -void stmpe11_tscworker(FAR struct stmpe11_dev_s *priv, uint8_t intsta) -{ - FAR struct stmpe11_config_s *config; /* Convenience pointer */ - bool pendown; /* true: pend is down */ - uint16_t xdiff; /* X difference used in thresholding */ - uint16_t ydiff; /* Y difference used in thresholding */ - uint16_t x; /* X position */ - uint16_t y; /* Y position */ - - ASSERT(priv != NULL); - - /* Cancel the missing pen up timer */ - - (void)wd_cancel(priv->wdog); - - /* Get a pointer the callbacks for convenience (and so the code is not so - * ugly). - */ - - config = priv->config; - DEBUGASSERT(config != NULL); - - /* Check for pen up or down from the TSC_STA ibit n the STMPE11_TSC_CTRL register. */ - - pendown = (stmpe11_getreg8(priv, STMPE11_TSC_CTRL) & TSC_CTRL_TSC_STA) != 0; - - /* Handle the change from pen down to pen up */ - - if (!pendown) - { - /* The pen is up.. reset thresholding variables. FIFOs will read zero if - * there is no data available (hence the choice of (0,0)) - */ - - priv->threshx = 0; - priv->threshy = 0; - - /* Ignore the interrupt if the pen was already up (CONTACT_NONE == pen up and - * already reported; CONTACT_UP == pen up, but not reported) - */ - - if (priv->sample.contact == CONTACT_NONE || - priv->sample.contact == CONTACT_UP) - { - goto ignored; - } - - /* A pen-down to up transition has been detected. CONTACT_UP indicates the - * initial loss of contzt. The state will be changed to CONTACT_NONE - * after the loss of contact is sampled. - */ - - priv->sample.contact = CONTACT_UP; - } - - /* The pen is down... check for data in the FIFO */ - - else if ((intsta & (INT_FIFO_TH|INT_FIFO_OFLOW)) != 0) - { - /* Read the next x and y positions from the FIFO. */ - -#ifdef CONFIG_STMPE11_SWAPXY - x = stmpe11_getreg16(priv, STMPE11_TSC_DATAX); - y = stmpe11_getreg16(priv, STMPE11_TSC_DATAY); -#else - x = stmpe11_getreg16(priv, STMPE11_TSC_DATAY); - y = stmpe11_getreg16(priv, STMPE11_TSC_DATAX); -#endif - - /* If we have not yet processed the last pen up event, then we - * cannot handle this pen down event. We will have to discard it. That - * should be okay because there will be another FIFO event right behind - * this one. Other kinds of data overruns are not harmful. - * - * Hmm.. a better design might be to disable FIFO interrupts when we - * detect pen up. Then re-enable them when CONTACT_UP is reported. - * That would save processing interrupts just to discard the data. - */ - - if (priv->sample.contact == CONTACT_UP) - { - /* We have not closed the loop on the last touch ... don't report - * anything. - */ - - goto ignored; - } - - /* Perform a thresholding operation so that the results will be more stable. - * If the difference from the last sample is small, then ignore the event. - * REVISIT: Should a large change in pressure also generate a event? - */ - - xdiff = x > priv->threshx ? (x - priv->threshx) : (priv->threshx - x); - ydiff = y > priv->threshy ? (y - priv->threshy) : (priv->threshy - y); - - if (xdiff < CONFIG_STMPE11_THRESHX && ydiff < CONFIG_STMPE11_THRESHY) - { - /* Little or no change in either direction ... don't report anything. */ - - goto ignored; - } - - /* When we see a big difference, snap to the new x/y thresholds */ - - priv->threshx = x; - priv->threshy = y; - - /* Update the x/y position in the sample data */ - - priv->sample.x = priv->threshx; - priv->sample.y = priv->threshy; - - /* Update the Z pressure index */ - - priv->sample.z = stmpe11_getreg8(priv, STMPE11_TSC_DATAZ); - priv->sample.valid = true; - - /* If this is the first (acknowledged) pen down report, then report - * this as the first contact. If contact == CONTACT_DOWN, it will be - * set to set to CONTACT_MOVE after the contact is first sampled. - */ - - if (priv->sample.contact != CONTACT_MOVE) - { - /* First contact */ - - priv->sample.contact = CONTACT_DOWN; - } - } - - /* Pen down, but no data in FIFO */ - - else - { - /* Ignore the interrupt... wait until there is data in the FIFO */ - - goto ignored; - } - - /* We get here if (1) we just went from a pen down to a pen up state OR (2) - * We just get a measurement from the FIFO in a pen down state. Indicate - * the availability of new sample data for this ID. - */ - - priv->sample.id = priv->id; - priv->penchange = true; - - /* Notify any waiters that new STMPE11 data is available */ - - stmpe11_notify(priv); - - /* If we think that the pend is still down, the start/re-start the pen up - * timer. - */ - -ignored: - if (priv->sample.contact == CONTACT_MOVE || - priv->sample.contact == CONTACT_MOVE) - { - (void)wd_start(priv->wdog, STMPE11_PENUP_TICKS, stmpe11_timeout, - 1, (uint32_t)((uintptr_t)priv)); - } - - /* Reset and clear all data in the FIFO */ - - stmpe11_putreg8(priv, STMPE11_FIFO_STA, FIFO_STA_FIFO_RESET); - stmpe11_putreg8(priv, STMPE11_FIFO_STA, 0); -} - -#endif /* CONFIG_INPUT && CONFIG_INPUT_STMPE11 && !CONFIG_STMPE11_TSC_DISABLE */ - diff --git a/nuttx/drivers/input/stmpe811.h b/nuttx/drivers/input/stmpe811.h new file mode 100644 index 000000000..05917fc37 --- /dev/null +++ b/nuttx/drivers/input/stmpe811.h @@ -0,0 +1,245 @@ +/******************************************************************************************** + * drivers/input/stmpe11.h + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * References: + * "STMPE811 S-Touch® advanced resistive touchscreen controller with 8-bit + * GPIO expander," Doc ID 14489 Rev 6, CD00186725, STMicroelectronics" + * + * 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. + * + ********************************************************************************************/ + +#ifndef __DRIVERS_INPUT_STMPE11_H +#define __DRIVERS_INPUT_STMPE11_H + +/******************************************************************************************** + * Included Files + ********************************************************************************************/ + +#include + +#include +#include + +#include +#include +#include + +#if defined(CONFIG_INPUT) && defined(CONFIG_INPUT_STMPE11) + +/******************************************************************************************** + * Pre-Processor Definitions + ********************************************************************************************/ +/* Configuration ****************************************************************************/ +/* Reference counting is partially implemented, but not needed in the current design. + */ + +#undef CONFIG_STMPE11_REFCNT + +/* No support for the SPI interface yet */ + +#ifdef CONFIG_STMPE11_SPI +# error "Only the STMPE11 I2C interface is supported by this driver" +#endif + +/* Driver support ***************************************************************************/ +/* This format is used to construct the /dev/input[n] device driver path. It defined here + * so that it will be used consistently in all places. + */ + +#define DEV_FORMAT "/dev/input%d" +#define DEV_NAMELEN 16 + +/* STMPE11 Resources ************************************************************************/ +#ifndef CONFIG_STMPE11_TSC_DISABLE +# define SMTPE11_ADC_NPINS 4 /* Only pins 0-3 can be used for ADC */ +# define SMTPE11_GPIO_NPINS 4 /* Only pins 0-3 can be used as GPIOs */ +#else +# define SMTPE11_ADC_NPINS 8 /* All pins can be used for ADC */ +# define SMTPE11_GPIO_NPINS 8 /* All pins can be used as GPIOs */ +#endif + +/* Driver flags */ + +#define STMPE11_FLAGS_TSC_INITIALIZED (1 << 0) /* 1: The TSC block has been initialized */ +#define STMPE11_FLAGS_GPIO_INITIALIZED (1 << 1) /* 1: The GIO block has been initialized */ +#define STMPE11_FLAGS_ADC_INITIALIZED (1 << 2) /* 1: The ADC block has been initialized */ +#define STMPE11_FLAGS_TS_INITIALIZED (1 << 3) /* 1: The TS block has been initialized */ + +/* Timeout to detect missing pen up events */ + +#define STMPE11_PENUP_TICKS ((100 + (MSEC_PER_TICK-1)) / MSEC_PER_TICK) + +/******************************************************************************************** + * Public Types + ********************************************************************************************/ +/* This describes the state of one contact */ + +enum stmpe11_contact_3 +{ + CONTACT_NONE = 0, /* No contact */ + CONTACT_DOWN, /* First contact */ + CONTACT_MOVE, /* Same contact, possibly different position */ + CONTACT_UP, /* Contact lost */ +}; + +/* This structure describes the results of one STMPE11 sample */ + +struct stmpe11_sample_s +{ + uint8_t id; /* Sampled touch point ID */ + uint8_t contact; /* Contact state (see enum stmpe11_contact_e) */ + bool valid; /* True: x,y,z contain valid, sampled data */ + uint16_t x; /* Measured X position */ + uint16_t y; /* Measured Y position */ + uint8_t z; /* Measured Z index */ +}; + +/* This structure represents the state of the SMTPE11 driver */ + +struct stmpe11_dev_s +{ +#ifdef CONFIG_STMPE11_MULTIPLE + FAR struct stmpe11_dev_s *flink; /* Supports a singly linked list of drivers */ +#endif + + /* Common fields */ + + FAR struct stmpe11_config_s *config; /* Board configuration data */ + sem_t exclsem; /* Manages exclusive access to this structure */ +#ifdef CONFIG_STMPE11_SPI + FAR struct spi_dev_s *spi; /* Saved SPI driver instance */ +#else + FAR struct i2c_dev_s *i2c; /* Saved I2C driver instance */ +#endif + + uint8_t inuse; /* SMTPE11 pins in use */ + uint8_t flags; /* See SMTPE11_FLAGS_* definitions */ + struct work_s work; /* Supports the interrupt handling "bottom half" */ + + /* Fields that may be disabled to save size if touchscreen support is not used. */ + +#ifndef CONFIG_STMPE11_TSC_DISABLE +#ifdef CONFIG_STMPE11_REFCNT + uint8_t crefs; /* Number of times the device has been opened */ +#endif + uint8_t nwaiters; /* Number of threads waiting for STMPE11 data */ + uint8_t id; /* Current touch point ID */ + uint8_t minor; /* Touchscreen minor device number */ + volatile bool penchange; /* An unreported event is buffered */ + + uint16_t threshx; /* Thresholded X value */ + uint16_t threshy; /* Thresholded Y value */ + sem_t waitsem; /* Used to wait for the availability of data */ + + struct work_s timeout; /* Supports tiemeout work */ + WDOG_ID wdog; /* Timeout to detect missing pen down events */ + struct stmpe11_sample_s sample; /* Last sampled touch point data */ + + /* The following is a list if poll structures of threads waiting for + * driver events. The 'struct pollfd' reference for each open is also + * retained in the f_priv field of the 'struct file'. + */ + +#ifndef CONFIG_DISABLE_POLL + struct pollfd *fds[CONFIG_STMPE11_NPOLLWAITERS]; +#endif +#endif + + /* Fields that may be disabled to save size of GPIO support is not used */ + +#if !defined(CONFIG_STMPE11_GPIO_DISABLE) && !defined(CONFIG_STMPE11_GPIOINT_DISABLE) + stmpe11_handler_t handlers[SMTPE11_GPIO_NPINS]; /* GPIO "interrupt handlers" */ +#endif +}; + +/******************************************************************************************** + * Public Function Prototypes + ********************************************************************************************/ + +/******************************************************************************************** + * Name: stmpe11_getreg8 + * + * Description: + * Read from an 8-bit STMPE11 register + * + ********************************************************************************************/ + +uint8_t stmpe11_getreg8(FAR struct stmpe11_dev_s *priv, uint8_t regaddr); + +/******************************************************************************************** + * Name: stmpe11_putreg8 + * + * Description: + * Write a value to an 8-bit STMPE11 register + * + ********************************************************************************************/ + +void stmpe11_putreg8(FAR struct stmpe11_dev_s *priv, uint8_t regaddr, uint8_t regval); + +/******************************************************************************************** + * Name: stmpe11_getreg16 + * + * Description: + * Read 16-bits of data from an STMPE-11 register + * + ********************************************************************************************/ + +uint16_t stmpe11_getreg16(FAR struct stmpe11_dev_s *priv, uint8_t regaddr); + +/******************************************************************************************** + * Name: stmpe11_tscint + * + * Description: + * Handle touchscreen interrupt events (this function actually executes in the context of + * the worker thread). + * + ********************************************************************************************/ + +#ifndef CONFIG_STMPE11_TSC_DISABLE +void stmpe11_tscworker(FAR struct stmpe11_dev_s *priv, uint8_t intsta) weak_function; +#endif + +/******************************************************************************************** + * Name: stmpe11_gpioworker + * + * Description: + * Handle GPIO interrupt events (this function actually executes in the context of the + * worker thread). + * + ********************************************************************************************/ + +#if !defined(CONFIG_STMPE11_GPIO_DISABLE) && !defined(CONFIG_STMPE11_GPIOINT_DISABLE) +void stmpe11_gpioworker(FAR struct stmpe11_dev_s *priv) weak_function; +#endif + +#endif /* CONFIG_INPUT && CONFIG_INPUT_STMPE11 */ +#endif /* __DRIVERS_INPUT_STMPE11_H */ diff --git a/nuttx/drivers/input/stmpe811_adc.c b/nuttx/drivers/input/stmpe811_adc.c new file mode 100644 index 000000000..5b9d045c9 --- /dev/null +++ b/nuttx/drivers/input/stmpe811_adc.c @@ -0,0 +1,266 @@ +/**************************************************************************** + * drivers/input/stmpe11_adc.c + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * References: + * "STMPE811 S-Touch® advanced resistive touchscreen controller with 8-bit + * GPIO expander," Doc ID 14489 Rev 6, CD00186725, STMicroelectronics" + * + * 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 "stmpe11.h" + +#if defined(CONFIG_INPUT) && defined(CONFIG_INPUT_STMPE11) && !defined(CONFIG_STMPE11_ADC_DISABLE) + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stmpe11_adcinitialize + * + * Description: + * Configure for ADC mode operation. Set overall ADC ADC timing that + * applies to all pins. + * + * Input Parameters: + * handle - The handle previously returned by stmpe11_instantiate + * + * Returned Value: + * Zero is returned on success. Otherwise, a negated errno value is + * returned to indicate the nature of the failure. + * + ****************************************************************************/ + +int stmpe11_adcinitialize(STMPE11_HANDLE handle) +{ + FAR struct stmpe11_dev_s *priv = (FAR struct stmpe11_dev_s *)handle; + uint8_t regval; + int ret; + + DEBUGASSERT(handle); + + /* Get exclusive access to the device structure */ + + ret = sem_wait(&priv->exclsem); + if (ret < 0) + { + int errval = errno; + idbg("sem_wait failed: %d\n", errval); + return -errval; + } + + /* Enable Clocking for ADC */ + + regval = stmpe11_getreg8(priv, STMPE11_SYS_CTRL2); + regval &= ~SYS_CTRL2_ADC_OFF; + stmpe11_putreg8(priv, STMPE11_SYS_CTRL2, regval); + + /* Select Sample Time, bit number and ADC Reference */ + + stmpe11_putreg8(priv, STMPE11_ADC_CTRL1, priv->config->ctrl1); + + /* Wait for 20 ms */ + + up_mdelay(20); + + /* Select the ADC clock speed */ + + stmpe11_putreg8(priv, STMPE11_ADC_CTRL2, priv->config->ctrl2); + + /* Mark ADC initialized */ + + priv->flags |= STMPE11_FLAGS_ADC_INITIALIZED; + sem_post(&priv->exclsem); + return OK; +} + +/**************************************************************************** + * Name: stmpe11_adcconfig + * + * Description: + * Configure a pin for ADC input. + * + * Input Parameters: + * handle - The handle previously returned by stmpe11_instantiate + * pin - The ADC pin number + * + * Returned Value: + * Zero is returned on success. Otherwise, a negated errno value is + * returned to indicate the nature of the failure. + * + ****************************************************************************/ + +int stmpe11_adcconfig(STMPE11_HANDLE handle, int pin) +{ + FAR struct stmpe11_dev_s *priv = (FAR struct stmpe11_dev_s *)handle; + uint8_t pinmask = GPIO_PIN(pin); + uint8_t regval; + int ret; + + DEBUGASSERT(handle && (unsigned)pin < STMPE11_ADC_NPINS); + + /* Get exclusive access to the device structure */ + + ret = sem_wait(&priv->exclsem); + if (ret < 0) + { + int errval = errno; + idbg("sem_wait failed: %d\n", errval); + return -errval; + } + + /* Make sure that the pin is not already in use */ + + if ((priv->inuse & pinmask) != 0) + { + idbg("PIN%d is already in-use\n", pin); + sem_post(&priv->exclsem); + return -EBUSY; + } + + /* Clear the alternate function bit for the pin, making it an ADC input + * (or perhaps an an external reference, depending on the state of the + * ADC_CTRL1_REF_SEL bit). + */ + + regval = stmpe11_getreg8(priv, STMPE11_GPIO_AF); + regval &= ~pinmask; + stmpe11_putreg8(priv, STMPE11_GPIO_AF, regval); + + /* Mark the pin as 'in use' */ + + priv->inuse |= pinmask; + sem_post(&priv->exclsem); + return OK; +} + +/**************************************************************************** + * Name: stmpe11_adcread + * + * Description: + * Read the converted analog input value from the select pin. + * + * Input Parameters: + * handle - The handle previously returned by stmpe11_instantiate + * pin - The ADC pin number + * + * Returned Value: + * The converted value (there is no error reporting mechanism). + * + ****************************************************************************/ + +uint16_t stmpe11_adcread(STMPE11_HANDLE handle, int pin) +{ + FAR struct stmpe11_dev_s *priv = (FAR struct stmpe11_dev_s *)handle; + uint8_t pinmask = GPIO_PIN(pin); + uint8_t regval; + int i; + int ret; + + DEBUGASSERT(handle && (unsigned)pin < 8); + + /* Get exclusive access to the device structure */ + + ret = sem_wait(&priv->exclsem); + if (ret < 0) + { + int errval = errno; + idbg("sem_wait failed: %d\n", errval); + return -errval; + } + + /* Request AD conversion by setting the bit corresponding the pin in the + * ADC CAPT register. + */ + + stmpe11_putreg8(priv, STMPE11_ADC_CAPT, pinmask); + + /* Wait for the conversion to complete. The ADC CAPT register reads '1' + * if conversion is completed. Reads '0' if conversion is in progress. + * Try three times before giving up. + */ + + for (i = 0; i < 3; i++) + { + /* The worst case ADC conversion time is (nominally) 56.4 uS. The + * following usleep() looks nice but in reality, the usleep() + * does not have that kind of precision (it will probably end up + * waiting 10 MS). + */ + + usleep(57); + + /* Check if the conversion is complete */ + + regval = stmpe11_getreg8(priv, STMPE11_ADC_CAPT); + if ((regval & pinmask) != 0) + { + break; + } + } + + /* At the completion of the conversion, return whatever we read from + * from the channel register associated with the pin. + */ + + return stmpe11_getreg16(priv, STMPE11_ADC_DATACH(pin)); +} + +#endif /* CONFIG_INPUT && CONFIG_INPUT_STMPE11 && !CONFIG_STMPE11_ADC_DISABLE */ + diff --git a/nuttx/drivers/input/stmpe811_base.c b/nuttx/drivers/input/stmpe811_base.c new file mode 100644 index 000000000..8e2900610 --- /dev/null +++ b/nuttx/drivers/input/stmpe811_base.c @@ -0,0 +1,546 @@ +/**************************************************************************** + * drivers/input/stmpe11_base.c + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * References: + * "STMPE811 S-Touch® advanced resistive touchscreen controller with 8-bit + * GPIO expander," Doc ID 14489 Rev 6, CD00186725, STMicroelectronics" + * + * 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 "stmpe11.h" + +#if defined(CONFIG_INPUT) && defined(CONFIG_INPUT_STMPE11) + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/* If only a single STMPE11 device is supported, then the driver state + * structure may as well be pre-allocated. + */ + +#ifndef CONFIG_STMPE11_MULTIPLE +static struct stmpe11_dev_s g_stmpe11; + +/* Otherwise, we will need to maintain allocated driver instances in a list */ + +#else +static struct stmpe11_dev_s *g_stmpe11list; +#endif + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stmpe11_worker + * + * Description: + * This is the "bottom half" of the STMPE11 interrupt handler + * + ****************************************************************************/ + +static void stmpe11_worker(FAR void *arg) +{ + FAR struct stmpe11_dev_s *priv = (FAR struct stmpe11_dev_s *)arg; + uint8_t regval; + + DEBUGASSERT(priv && priv->config); + + /* Get the global interrupt status */ + + regval = stmpe11_getreg8(priv, STMPE11_INT_STA); + + /* Check for a touchscreen interrupt */ + +#ifndef CONFIG_STMPE11_TSC_DISABLE + if ((regval & (INT_TOUCH_DET|INT_FIFO_TH|INT_FIFO_OFLOW)) != 0) + { + /* Dispatch the touchscreen interrupt if it was brought into the link */ + +#ifdef CONFIG_HAVE_WEAKFUNCTIONS + if (stmpe11_tscworker) +#endif + { + stmpe11_tscworker(priv, regval); + } + + stmpe11_putreg8(priv, STMPE11_INT_STA, (INT_TOUCH_DET|INT_FIFO_TH|INT_FIFO_OFLOW)); + regval &= ~(INT_TOUCH_DET|INT_FIFO_TH|INT_FIFO_OFLOW); + } +#endif + +#if !defined(CONFIG_STMPE11_GPIO_DISABLE) && !defined(CONFIG_STMPE11_GPIOINT_DISABLE) + if ((regval & INT_GPIO) != 0) + { + /* Dispatch the GPIO interrupt if it was brought into the link */ + +#ifdef CONFIG_HAVE_WEAKFUNCTIONS + if (stmpe11_gpioworker) +#endif + { + stmpe11_gpioworker(priv); + } + + stmpe11_putreg8(priv, STMPE11_INT_STA, INT_GPIO); + regval &= ~INT_GPIO; + } +#endif + + /* Clear any other residual, unhandled pending interrupt */ + + if (regval != 0) + { + stmpe11_putreg8(priv, STMPE11_INT_STA, regval); + } + + /* Re-enable the STMPE11 GPIO interrupt */ + + priv->config->enable(priv->config, true); +} + +/**************************************************************************** + * Name: stmpe11_interrupt + * + * Description: + * The STMPE11 interrupt handler + * + ****************************************************************************/ + +static int stmpe11_interrupt(int irq, FAR void *context) +{ + FAR struct stmpe11_dev_s *priv; + FAR struct stmpe11_config_s *config; + int ret; + + /* Which STMPE11 device caused the interrupt? */ + +#ifndef CONFIG_STMPE11_MULTIPLE + priv = &g_stmpe11; +#else + for (priv = g_stmpe11list; + priv && priv->config->irq != irq; + priv = priv->flink); + + ASSERT(priv != NULL); +#endif + + /* Get a pointer the callbacks for convenience (and so the code is not so + * ugly). + */ + + config = priv->config; + DEBUGASSERT(config != NULL); + + /* Disable further interrupts */ + + config->enable(config, false); + + /* Check if interrupt work is already queue. If it is already busy, then + * we already have interrupt processing in the pipeline and we need to do + * nothing more. + */ + + if (work_available(&priv->work)) + { + /* Yes.. Transfer processing to the worker thread. Since STMPE11 + * interrupts are disabled while the work is pending, no special + * action should be required to protect the work queue. + */ + + ret = work_queue(&priv->work, stmpe11_worker, priv, 0); + if (ret != 0) + { + illdbg("Failed to queue work: %d\n", ret); + } + } + + /* Clear any pending interrupts and return success */ + + config->clear(config); + return OK; +} + +/**************************************************************************** + * Name: stmpe11_checkid + * + * Description: + * Read and verify the STMPE11 chip ID + * + ****************************************************************************/ + +static int stmpe11_checkid(FAR struct stmpe11_dev_s *priv) +{ + uint16_t devid = 0; + + /* Read device ID */ + + devid = stmpe11_getreg8(priv, STMPE11_CHIP_ID); + devid = (uint32_t)(devid << 8); + devid |= (uint32_t)stmpe11_getreg8(priv, STMPE11_CHIP_ID+1); + ivdbg("devid: %04x\n", devid); + + if (devid != (uint16_t)CHIP_ID) + { + /* ID is not Correct */ + + return -ENODEV; + } + + return OK; +} + +/**************************************************************************** + * Name: stmpe11_reset + * + * Description: + * Reset the STMPE11 + * + ****************************************************************************/ + +static void stmpe11_reset(FAR struct stmpe11_dev_s *priv) +{ + /* Power Down the STMPE11 */ + + stmpe11_putreg8(priv, STMPE11_SYS_CTRL1, SYS_CTRL1_SOFTRESET); + + /* Wait a bit */ + + usleep(20*1000); + + /* Then power on again. All registers will be in their reset state. */ + + stmpe11_putreg8(priv, STMPE11_SYS_CTRL1, 0); +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stmpe11_instantiate + * + * Description: + * Instantiate and configure the STMPE11 device driver to use the provided + * I2C or SPIdevice instance. + * + * Input Parameters: + * dev - An I2C or SPI driver instance + * config - Persistant board configuration data + * + * Returned Value: + * A non-zero handle is returned on success. This handle may then be used + * to configure the STMPE11 driver as necessary. A NULL handle value is + * returned on failure. + * + ****************************************************************************/ + +#ifdef CONFIG_STMPE11_SPI +STMPE11_HANDLE stmpe11_instantiate(FAR struct spi_dev_s *dev, + FAR struct stmpe11_config_s *config) +#else +STMPE11_HANDLE stmpe11_instantiate(FAR struct i2c_dev_s *dev, + FAR struct stmpe11_config_s *config) +#endif +{ + FAR struct stmpe11_dev_s *priv; + uint8_t regval; + int ret; + + /* Allocate the device state structure */ + +#ifdef CONFIG_STMPE11_MULTIPLE + priv = (FAR struct stmpe11_dev_s *)kzalloc(sizeof(struct stmpe11_dev_s)); + if (!priv) + { + return NULL; + } + + /* And save the device structure in the list of STMPE11 so that we can find it later */ + + priv->flink = g_stmpe11list; + g_stmpe11list = priv; +#else + + /* Use the one-and-only STMPE11 driver instance */ + + priv = &g_stmpe11; +#endif + + /* Initialize the device state structure */ + + sem_init(&priv->exclsem, 0, 1); + priv->config = config; + +#ifdef CONFIG_STMPE11_SPI + priv->spi = dev; +#else + priv->i2c = dev; + + /* Set the I2C address and frequency. REVISIT: This logic would be + * insufficient if we share the I2C bus with any other devices that also + * modify the address and frequency. + */ + + I2C_SETADDRESS(dev, config->address, 7); + I2C_SETFREQUENCY(dev, config->frequency); +#endif + + /* Read and verify the STMPE11 chip ID */ + + ret = stmpe11_checkid(priv); + if (ret < 0) + { +#ifdef CONFIG_STMPE11_MULTIPLE + kfree(priv); +#endif + return NULL; + } + + /* Generate STMPE11 Software reset */ + + stmpe11_reset(priv); + + /* Configure the interrupt output pin to generate interrupts on high or low level. */ + + regval = stmpe11_getreg8(priv, STMPE11_INT_CTRL); +#ifdef CONFIG_STMPE11_ACTIVELOW + regval &= ~INT_CTRL_INT_POLARITY; /* Pin polarity: Active low / falling edge */ +#else + regval |= INT_CTRL_INT_POLARITY; /* Pin polarity: Active high / rising edge */ +#endif +#ifdef CONFIG_STMPE11_EDGE + regval |= INT_CTRL_INT_TYPE; /* Edge interrupt */ +#else + regval &= ~INT_CTRL_INT_TYPE; /* Level interrupt */ +#endif + stmpe11_putreg8(priv, STMPE11_INT_CTRL, regval); + + /* Attach the STMPE11 interrupt handler. */ + + config->attach(config, stmpe11_interrupt); + + /* Clear any pending interrupts */ + + stmpe11_putreg8(priv, STMPE11_INT_STA, INT_ALL); + config->clear(config); + config->enable(config, true); + + /* Enable global interrupts */ + + regval = stmpe11_getreg8(priv, STMPE11_INT_CTRL); + regval |= INT_CTRL_GLOBAL_INT; + stmpe11_putreg8(priv, STMPE11_INT_CTRL, regval); + + /* Return our private data structure as an opaque handle */ + + return (STMPE11_HANDLE)priv; +} + +/**************************************************************************** + * Name: stmpe11_getreg8 + * + * Description: + * Read from an 8-bit STMPE11 register + * + ****************************************************************************/ + +#ifdef CONFIG_STMPE11_I2C +uint8_t stmpe11_getreg8(FAR struct stmpe11_dev_s *priv, uint8_t regaddr) +{ + /* 8-bit data read sequence: + * + * Start - I2C_Write_Address - STMPE11_Reg_Address - + * Repeated_Start - I2C_Read_Address - STMPE11_Read_Data - STOP + */ + + struct i2c_msg_s msg[2]; + uint8_t regval; + int ret; + + /* Setup 8-bit STMPE11 address write message */ + + msg[0].addr = priv->config->address; /* 7-bit address */ + msg[0].flags = 0; /* Write transaction, beginning with START */ + msg[0].buffer = ®addr; /* Transfer from this address */ + msg[0].length = 1; /* Send one byte following the address + * (no STOP) */ + + /* Set up the 8-bit STMPE11 data read message */ + + msg[1].addr = priv->config->address; /* 7-bit address */ + msg[1].flags = I2C_M_READ; /* Read transaction, beginning with Re-START */ + msg[1].buffer = ®val; /* Transfer to this address */ + msg[1].length = 1; /* Receive one byte following the address + * (then STOP) */ + + /* Perform the transfer */ + + ret = I2C_TRANSFER(priv->i2c, msg, 2); + if (ret < 0) + { + idbg("I2C_TRANSFER failed: %d\n", ret); + return 0; + } + +#ifdef CONFIG_STMPE11_REGDEBUG + dbg("%02x->%02x\n", regaddr, regval); +#endif + return regval; +} +#endif + +/**************************************************************************** + * Name: stmpe11_putreg8 + * + * Description: + * Write a value to an 8-bit STMPE11 register + * + ****************************************************************************/ + +#ifdef CONFIG_STMPE11_I2C +void stmpe11_putreg8(FAR struct stmpe11_dev_s *priv, + uint8_t regaddr, uint8_t regval) +{ + /* 8-bit data read sequence: + * + * Start - I2C_Write_Address - STMPE11_Reg_Address - STMPE11_Write_Data - STOP + */ + + struct i2c_msg_s msg; + uint8_t txbuffer[2]; + int ret; + +#ifdef CONFIG_STMPE11_REGDEBUG + dbg("%02x<-%02x\n", regaddr, regval); +#endif + + /* Setup to the data to be transferred. Two bytes: The STMPE11 register + * address followed by one byte of data. + */ + + txbuffer[0] = regaddr; + txbuffer[1] = regval; + + /* Setup 8-bit STMPE11 address write message */ + + msg.addr = priv->config->address; /* 7-bit address */ + msg.flags = 0; /* Write transaction, beginning with START */ + msg.buffer = txbuffer; /* Transfer from this address */ + msg.length = 2; /* Send two byte following the address + * (then STOP) */ + + /* Perform the transfer */ + + ret = I2C_TRANSFER(priv->i2c, &msg, 1); + if (ret < 0) + { + idbg("I2C_TRANSFER failed: %d\n", ret); + } +} +#endif + +/**************************************************************************** + * Name: stmpe11_getreg16 + * + * Description: + * Read 16-bits of data from an STMPE-11 register + * + ****************************************************************************/ + +#ifdef CONFIG_STMPE11_I2C +uint16_t stmpe11_getreg16(FAR struct stmpe11_dev_s *priv, uint8_t regaddr) +{ + /* 16-bit data read sequence: + * + * Start - I2C_Write_Address - STMPE11_Reg_Address - + * Repeated_Start - I2C_Read_Address - STMPE11_Read_Data_1 - + * STMPE11_Read_Data_2 - STOP + */ + + + struct i2c_msg_s msg[2]; + uint8_t rxbuffer[2]; + int ret; + + /* Setup 8-bit STMPE11 address write message */ + + msg[0].addr = priv->config->address; /* 7-bit address */ + msg[0].flags = 0; /* Write transaction, beginning with START */ + msg[0].buffer = ®addr; /* Transfer from this address */ + msg[0].length = 1; /* Send one byte following the address + * (no STOP) */ + + /* Set up the 8-bit STMPE11 data read message */ + + msg[1].addr = priv->config->address; /* 7-bit address */ + msg[1].flags = I2C_M_READ; /* Read transaction, beginning with Re-START */ + msg[1].buffer = rxbuffer; /* Transfer to this address */ + msg[1].length = 2; /* Receive two bytes following the address + * (then STOP) */ + + /* Perform the transfer */ + + ret = I2C_TRANSFER(priv->i2c, msg, 2); + if (ret < 0) + { + idbg("I2C_TRANSFER failed: %d\n", ret); + return 0; + } + +#ifdef CONFIG_STMPE11_REGDEBUG + dbg("%02x->%02x%02x\n", regaddr, rxbuffer[0], rxbuffer[1]); +#endif + return (uint16_t)rxbuffer[0] << 8 | (uint16_t)rxbuffer[1]; +} +#endif + +#endif /* CONFIG_INPUT && CONFIG_INPUT_STMPE11 */ + diff --git a/nuttx/drivers/input/stmpe811_gpio.c b/nuttx/drivers/input/stmpe811_gpio.c new file mode 100644 index 000000000..82024b4d0 --- /dev/null +++ b/nuttx/drivers/input/stmpe811_gpio.c @@ -0,0 +1,454 @@ +/**************************************************************************** + * drivers/input/stmpe11_gpio.c + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * References: + * "STMPE811 S-Touch® advanced resistive touchscreen controller with 8-bit + * GPIO expander," Doc ID 14489 Rev 6, CD00186725, STMicroelectronics" + * + * 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 "stmpe11.h" + +#if defined(CONFIG_INPUT) && defined(CONFIG_INPUT_STMPE11) && !defined(CONFIG_STMPE11_GPIO_DISABLE) + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stmpe11_gpioinit + * + * Description: + * Initialize the GPIO interrupt subsystem + * + * Input Parameters: + * handle - The handle previously returned by stmpe11_instantiate + * + * Returned Value: + * Zero is returned on success. Otherwise, a negated errno value is + * returned to indicate the nature of the failure. + * + ****************************************************************************/ + +static void stmpe11_gpioinit(FAR struct stmpe11_dev_s *priv) +{ + uint8_t regval; + + if ((priv->flags & STMPE11_FLAGS_GPIO_INITIALIZED) == 0) + { + /* Enable Clocking for GPIO */ + + regval = stmpe11_getreg8(priv, STMPE11_SYS_CTRL2); + regval &= ~SYS_CTRL2_GPIO_OFF; + stmpe11_putreg8(priv, STMPE11_SYS_CTRL2, regval); + + /* Disable all GPIO interrupts */ + + stmpe11_putreg8(priv, STMPE11_GPIO_EN, 0); + + /* Enable global GPIO interrupts */ + +#ifndef CONFIG_STMPE11_GPIOINT_DISABLE + regval = stmpe11_getreg8(priv, STMPE11_INT_EN); + regval |= INT_GPIO; + stmpe11_putreg8(priv, STMPE11_INT_EN, regval); +#endif + + priv->flags |= STMPE11_FLAGS_GPIO_INITIALIZED; + } +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stmpe11_gpioconfig + * + * Description: + * Configure an STMPE11 GPIO pin + * + * Input Parameters: + * handle - The handle previously returned by stmpe11_instantiate + * pinconfig - Bit-encoded pin configuration + * + * Returned Value: + * Zero is returned on success. Otherwise, a negated errno value is + * returned to indicate the nature of the failure. + * + ****************************************************************************/ + +int stmpe11_gpioconfig(STMPE11_HANDLE handle, uint8_t pinconfig) +{ + FAR struct stmpe11_dev_s *priv = (FAR struct stmpe11_dev_s *)handle; + int pin = (pinconfig & STMPE11_GPIO_PIN_MASK) >> STMPE11_GPIO_PIN_SHIFT; + uint8_t pinmask = (1 << pin); + uint8_t regval; + int ret; + + DEBUGASSERT(handle && (unsigned)pin < STMPE11_GPIO_NPINS); + + /* Get exclusive access to the device structure */ + + ret = sem_wait(&priv->exclsem); + if (ret < 0) + { + int errval = errno; + idbg("sem_wait failed: %d\n", errval); + return -errval; + } + + /* Make sure that the pin is not already in use */ + + if ((priv->inuse & pinmask) != 0) + { + idbg("PIN%d is already in-use\n", pin); + sem_post(&priv->exclsem); + return -EBUSY; + } + + /* Make sure that the GPIO block has been initialized */ + + stmpe11_gpioinit(priv); + + /* Set the alternate function bit for the pin, making it a GPIO */ + + regval = stmpe11_getreg8(priv, STMPE11_GPIO_AF); + regval |= pinmask; + stmpe11_putreg8(priv, STMPE11_GPIO_AF, regval); + + /* Is the pin an input or an output? */ + + if ((pinconfig & STMPE11_GPIO_DIR) == STMPE11_GPIO_OUTPUT) + { + /* The pin is an output */ + + regval = stmpe11_getreg8(priv, STMPE11_GPIO_DIR); + regval &= ~pinmask; + stmpe11_putreg8(priv, STMPE11_GPIO_DIR, regval); + + /* Set its initial output value */ + + stmpe11_gpiowrite(handle, pinconfig, + (pinconfig & STMPE11_GPIO_VALUE) != STMPE11_GPIO_ZERO); + } + else + { + /* It is an input */ + + regval = stmpe11_getreg8(priv, STMPE11_GPIO_DIR); + regval |= pinmask; + stmpe11_putreg8(priv, STMPE11_GPIO_DIR, regval); + + /* Set up the falling edge detection */ + + regval = stmpe11_getreg8(priv, STMPE11_GPIO_FE); + if ((pinconfig & STMPE11_GPIO_FALLING) != 0) + { + regval |= pinmask; + } + else + { + regval &= pinmask; + } + stmpe11_putreg8(priv, STMPE11_GPIO_FE, regval); + + /* Set up the rising edge detection */ + + regval = stmpe11_getreg8(priv, STMPE11_GPIO_RE); + if ((pinconfig & STMPE11_GPIO_FALLING) != 0) + { + regval |= pinmask; + } + else + { + regval &= pinmask; + } + stmpe11_putreg8(priv, STMPE11_GPIO_RE, regval); + + /* Disable interrupts for now */ + + regval = stmpe11_getreg8(priv, STMPE11_GPIO_EN); + regval &= ~pinmask; + stmpe11_putreg8(priv, STMPE11_GPIO_EN, regval); + } + + /* Mark the pin as 'in use' */ + + priv->inuse |= pinmask; + sem_post(&priv->exclsem); + return OK; +} + +/**************************************************************************** + * Name: stmpe11_gpiowrite + * + * Description: + * Set or clear the GPIO output + * + * Input Parameters: + * handle - The handle previously returned by stmpe11_instantiate + * pinconfig - Bit-encoded pin configuration + * value = true: write logic '1'; false: write logic '0; + * + * Returned Value: + * None + * + ****************************************************************************/ + +void stmpe11_gpiowrite(STMPE11_HANDLE handle, uint8_t pinconfig, bool value) +{ + FAR struct stmpe11_dev_s *priv = (FAR struct stmpe11_dev_s *)handle; + int pin = (pinconfig & STMPE11_GPIO_PIN_MASK) >> STMPE11_GPIO_PIN_SHIFT; + int ret; + + DEBUGASSERT(handle && (unsigned)pin < STMPE11_GPIO_NPINS); + + /* Get exclusive access to the device structure */ + + ret = sem_wait(&priv->exclsem); + if (ret < 0) + { + idbg("sem_wait failed: %d\n", errno); + return; + } + + /* Are we setting or clearing outputs? */ + + if (value) + { + /* Set the output valu(s)e by writing to the SET register */ + + stmpe11_putreg8(priv, STMPE11_GPIO_SETPIN, (1 << pin)); + } + else + { + /* Clear the output value(s) by writing to the CLR register */ + + stmpe11_putreg8(priv, STMPE11_GPIO_CLRPIN, (1 << pin)); + } + + sem_post(&priv->exclsem); +} + +/**************************************************************************** + * Name: stmpe11_gpioread + * + * Description: + * Set or clear the GPIO output + * + * Input Parameters: + * handle - The handle previously returned by stmpe11_instantiate + * pinconfig - Bit-encoded pin configuration + * value - The location to return the state of the GPIO pin + * + * Returned Value: + * Zero is returned on success. Otherwise, a negated errno value is + * returned to indicate the nature of the failure. + * + ****************************************************************************/ + +int stmpe11_gpioread(STMPE11_HANDLE handle, uint8_t pinconfig, bool *value) +{ + FAR struct stmpe11_dev_s *priv = (FAR struct stmpe11_dev_s *)handle; + int pin = (pinconfig & STMPE11_GPIO_PIN_MASK) >> STMPE11_GPIO_PIN_SHIFT; + uint8_t regval; + int ret; + + DEBUGASSERT(handle && (unsigned)pin < STMPE11_GPIO_NPINS); + + /* Get exclusive access to the device structure */ + + ret = sem_wait(&priv->exclsem); + if (ret < 0) + { + int errval = errno; + idbg("sem_wait failed: %d\n", errval); + return -errval; + } + + regval = stmpe11_getreg8(priv, STMPE11_GPIO_MPSTA); + *value = ((regval & GPIO_PIN(pin)) != 0); + sem_post(&priv->exclsem); + return OK; +} + +/*********************************************************************************** + * Name: stmpe11_gpioattach + * + * Description: + * Attach to a GPIO interrupt input pin and enable interrupts on the pin. Using + * the value NULL for the handler address will disable interrupts from the pin and + * detach the handler. + * + * NOTE: Callbacks do not occur from an interrupt handler but rather from the + * context of the worker thread. + * + * Input Parameters: + * handle - The handle previously returned by stmpe11_instantiate + * pinconfig - Bit-encoded pin configuration + * handler - The handler that will be called when the interrupt occurs. + * + * Returned Value: + * Zero is returned on success. Otherwise, a negated errno value is returned + * to indicate the nature of the failure. + * + ************************************************************************************/ + +#ifndef CONFIG_STMPE11_GPIOINT_DISABLE +int stmpe11_gpioattach(STMPE11_HANDLE handle, uint8_t pinconfig, + stmpe11_handler_t handler) +{ + FAR struct stmpe11_dev_s *priv = (FAR struct stmpe11_dev_s *)handle; + int pin = (pinconfig & STMPE11_GPIO_PIN_MASK) >> STMPE11_GPIO_PIN_SHIFT; + uint8_t regval; + int ret; + + DEBUGASSERT(handle && (unsigned)pin < STMPE11_GPIO_NPINS); + + /* Get exclusive access to the device structure */ + + ret = sem_wait(&priv->exclsem); + if (ret < 0) + { + int errval = errno; + idbg("sem_wait failed: %d\n", errval); + return -errval; + } + + /* Make sure that the GPIO interrupt system has been gpioinitialized */ + + stmpe11_gpioinit(priv); + + /* Set/clear the handler */ + + priv->handlers[pin] = handler; + + /* If an handler has provided, then we are enabling interrupts */ + + regval = stmpe11_getreg8(priv, STMPE11_GPIO_EN); + if (handler) + { + /* Enable interrupts for this GPIO */ + + regval &= ~GPIO_PIN(pin); + } + else + { + /* Disable interrupts for this GPIO */ + + regval &= ~GPIO_PIN(pin); + } + stmpe11_putreg8(priv, STMPE11_GPIO_EN, regval); + + sem_post(&priv->exclsem); + return OK; +} +#endif + +/**************************************************************************** + * Name: stmpe11_gpioworker + * + * Description: + * Handle GPIO interrupt events (this function actually executes in the + * context of the worker thread). + * + ****************************************************************************/ + +#ifndef CONFIG_STMPE11_GPIOINT_DISABLE +void stmpe11_gpioworker(FAR struct stmpe11_dev_s *priv) +{ + uint8_t regval; + uint8_t pinmask; + int pin; + + /* Get the set of pending GPIO interrupts */ + + regval = stmpe11_getreg8(priv, STMPE11_GPIO_INTSTA); + + /* Look at each pin */ + + for (pin = 0; pin < SMTPE11_GPIO_NPINS; pin++) + { + pinmask = GPIO_INT(pin); + if ((regval & pinmask) != 0) + { + /* Check if we have a handler for this interrupt (there should + * be one) + */ + + if (priv->handlers[pin]) + { + /* Interrupt is pending... dispatch the interrupt to the + * callback + */ + + priv->handlers[pin](pin); + } + else + { + illdbg("No handler for PIN%d, GPIO_INTSTA: %02x\n", pin, regval); + } + + /* Clear the pending GPIO interrupt by writing a '1' to the + * pin position in the status register. + */ + + stmpe11_putreg8(priv, STMPE11_GPIO_INTSTA, pinmask); + } + } +} +#endif + +#endif /* CONFIG_INPUT && CONFIG_INPUT_STMPE11 && !CONFIG_STMPE11_GPIO_DISABLE */ + diff --git a/nuttx/drivers/input/stmpe811_temp.c b/nuttx/drivers/input/stmpe811_temp.c new file mode 100644 index 000000000..b3eb8f6c5 --- /dev/null +++ b/nuttx/drivers/input/stmpe811_temp.c @@ -0,0 +1,174 @@ +/**************************************************************************** + * drivers/input/stmpe11_temp.c + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * References: + * "STMPE811 S-Touch® advanced resistive touchscreen controller with 8-bit + * GPIO expander," Doc ID 14489 Rev 6, CD00186725, STMicroelectronics" + * + * 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 "stmpe11.h" + +#if defined(CONFIG_INPUT) && defined(CONFIG_INPUT_STMPE11) && !defined(CONFIG_STMPE11_TEMP_DISABLE) + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stmpe11_tempinitialize + * + * Description: + * Configure the temperature sensor. + * + * Input Parameters: + * handle - The handle previously returned by stmpe11_instantiate + * + * Returned Value: + * Zero is returned on success. Otherwise, a negated errno value is + * returned to indicate the nature of the failure. + * + ****************************************************************************/ + +int stmpe11_tempinitialize(STMPE11_HANDLE handle) +{ + FAR struct stmpe11_dev_s *priv = (FAR struct stmpe11_dev_s *)handle; + uint8_t regval; + + /* Enable clocking for ADC and the temperature sensor */ + + regval = stmpe11_getreg8(priv, STMPE11_SYS_CTRL2); + regval &= ~(SYS_CTRL2_TS_OFF | SYS_CTRL2_ADC_OFF); + stmpe11_putreg8(priv, STMPE11_SYS_CTRL2, regval); + + /* Enable the temperature sensor */ + + stmpe11_putreg8(priv, STMPE11_TEMP_CTRL, TEMP_CTRL_ENABLE); + + /* Aquire data enable */ + + stmpe11_putreg8(priv, STMPE11_TEMP_CTRL, (TEMP_CTRL_ACQ|TEMP_CTRL_ENABLE)); + + return OK; +} + +/**************************************************************************** + * Name: stmpe11_tempread + * + * Description: + * Configure the temperature sensor. + * + * Input Parameters: + * handle - The handle previously returned by stmpe11_instantiate + * + * Returned Value: + * Zero is returned on success. Otherwise, a negated errno value is + * returned to indicate the nature of the failure. + * + ****************************************************************************/ + +uint16_t stmpe11_tempread(STMPE11_HANDLE handle) +{ + FAR struct stmpe11_dev_s *priv = (FAR struct stmpe11_dev_s *)handle; + uint32_t temp = 0; + uint8_t temp1; + uint8_t temp2; + + /* Acquire data enable */ + + stmpe11_putreg8(priv, STMPE11_TEMP_CTRL, (TEMP_CTRL_ACQ|TEMP_CTRL_ENABLE)); + + /* Read the temperature */ + + temp1 = stmpe11_getreg8(priv, STMPE11_SYS_CTRL2); + temp2 = stmpe11_getreg8(priv, STMPE11_SYS_CTRL2+1); + + /* Scale the temperature (where Vio is assumed to be .33) */ + + temp = ((uint32_t)(temp1 & 3) << 8) | temp2; + temp = (uint32_t)((33 * temp * 100) / 751); + temp = (uint32_t)((temp + 5) / 10); + + return (uint16_t)temp; +} + +/**************************************************************************** + * Name: stmpe11_tempinterrupt + * + * Description: + * Configure the temperature sensor to sample the temperature periodically. + * Set the temperature threshold to generate an interrupt and notify + * to the client using the provide callback function pointer. + * + * Input Parameters: + * handle - The handle previously returned by stmpe11_instantiate + * threshold - The threshold temperature value + * direction - True: Generate an interrupt if the temperate exceeds the + * threshold value; False: Generate an interrupt if the + * temperature falls below the threshold value. + * callback - The client callback function that will be called when + * the termperature crosses the threshold. + * + * Returned Value: + * Zero is returned on success. Otherwise, a negated errno value is + * returned to indicate the nature of the failure. + * + ****************************************************************************/ +/* Not implemented */ + +#endif /* CONFIG_INPUT && CONFIG_INPUT_STMPE11 && !CONFIG_STMPE11_TEMP_DISABLE */ + diff --git a/nuttx/drivers/input/stmpe811_tsc.c b/nuttx/drivers/input/stmpe811_tsc.c new file mode 100644 index 000000000..03ede7302 --- /dev/null +++ b/nuttx/drivers/input/stmpe811_tsc.c @@ -0,0 +1,1144 @@ +/**************************************************************************** + * drivers/input/stmpe11_tsc.c + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * References: + * "STMPE811 S-Touch® advanced resistive touchscreen controller with 8-bit + * GPIO expander," Doc ID 14489 Rev 6, CD00186725, STMicroelectronics" + * + * 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 +#include +#include + +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "stmpe11.h" + +#if defined(CONFIG_INPUT) && defined(CONFIG_INPUT_STMPE11) && !defined(CONFIG_STMPE11_TSC_DISABLE) + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#define Direction_IN 0x00 +#define Direction_OUT 0x01 + +#define Polarity_Low 0x00 +#define Polarity_High 0x04 +#define Type_Level 0x00 +#define Type_Edge 0x02 + +#define IO_IT_0 0x01 +#define IO_IT_1 0x02 +#define IO_IT_2 0x04 +#define IO_IT_3 0x08 +#define IO_IT_4 0x10 +#define IO_IT_5 0x20 +#define IO_IT_6 0x40 +#define IO_IT_7 0x80 +#define ALL_IT 0xFF +#define IOE_JOY_IT (uint8_t)(IO_IT_3 | IO_IT_4 | IO_IT_5 | IO_IT_6 | IO_IT_7) +#define IOE_TS_IT (uint8_t)(IO_IT_0 | IO_IT_1 | IO_IT_2) +#define IOE_INMEMS_IT (uint8_t)(IO_IT_2 | IO_IT_3) + +#define EDGE_FALLING 0x01 +#define EDGE_RISING 0x02 + +#define TIMEOUT_MAX 0x3000 /*nwaiters > 0) + { + /* After posting this semaphore, we need to exit because the STMPE11 + * is no longer available. + */ + + sem_post(&priv->waitsem); + } + + /* If there are threads waiting on poll() for STMPE11 data to become available, + * then wake them up now. NOTE: we wake up all waiting threads because we + * do not know that they are going to do. If they all try to read the data, + * then some make end up blocking after all. + */ + +#ifndef CONFIG_DISABLE_POLL + for (i = 0; i < CONFIG_STMPE11_NPOLLWAITERS; i++) + { + struct pollfd *fds = priv->fds[i]; + if (fds) + { + fds->revents |= POLLIN; + ivdbg("Report events: %02x\n", fds->revents); + sem_post(fds->sem); + } + } +#endif +} + +/**************************************************************************** + * Name: stmpe11_sample + * + * Description: + * Check if touchscreen sample data is available now and, if so, return + * the sample data. This is part of the stmpe11_read logic. + * + * Assumption: + * Pre-emption is disable to prevent the worker thread from running. + * Otherwise, sampled data may continue to change. + * + ****************************************************************************/ + +static int stmpe11_sample(FAR struct stmpe11_dev_s *priv, + FAR struct stmpe11_sample_s *sample) +{ + int ret = -EAGAIN; + + /* Is there new STMPE11 sample data available? */ + + if (priv->penchange) + { + /* Yes.. the state has changed in some way. Return a copy of the + * sampled data. + */ + + memcpy(sample, &priv->sample, sizeof(struct stmpe11_sample_s)); + + /* Now manage state transitions */ + + if (sample->contact == CONTACT_UP) + { + /* The sampling logic has detected pen-up in some condition other + * than CONTACT_NONE. Set the next state to CONTACT_NONE: Further + * pen-down reports will be ignored. Increment the ID so that + * next contact ID will be unique + */ + + priv->sample.contact = CONTACT_NONE; + priv->sample.valid = false; + priv->id++; + } + else if (sample->contact == CONTACT_DOWN) + { + /* The sampling logic has detected pen-up in some condition other + * than CONTACT_MOVE. Set the next state to CONTACT_MOVE: Further + * samples collected while the pen is down will reported as movement + * events. + */ + + priv->sample.contact = CONTACT_MOVE; + } + + priv->penchange = false; + ret = OK; + } + + return ret; +} + +/**************************************************************************** + * Name: stmpe11_waitsample + * + * Description: + * Wait for a sample to become available (this is really part of the + * stmpe11_read logic). + * + ****************************************************************************/ + +static inline int stmpe11_waitsample(FAR struct stmpe11_dev_s *priv, + FAR struct stmpe11_sample_s *sample) +{ + int ret; + + /* Disable pre-emption to prevent the worker thread from running + * asynchronously. + */ + + sched_lock(); + + /* Now release the semaphore that manages mutually exclusive access to + * the device structure. This may cause other tasks to become ready to + * run, but they cannot run yet because pre-emption is disabled. + */ + + sem_post(&priv->exclsem); + + /* Try to get the a sample... if we cannot, then wait on the semaphore + * that is posted when new sample data is availble. + */ + + while (stmpe11_sample(priv, sample) < 0) + { + /* Wait for a change in the STMPE11 state */ + + priv->nwaiters++; + ret = sem_wait(&priv->waitsem); + priv->nwaiters--; + + /* When we are re-awakened, pre-emption will again be disabled */ + + if (ret < 0) + { +#ifdef CONFIG_DEBUG + // Sample the errno (debug output could change it) + + int errval = errno; + + /* If we are awakened by a signal, then we need to return + * the failure now. + */ + + idbg("ERROR: sem_wait failed: %d\n", errval); + DEBUGASSERT(errval == EINTR); +#endif + ret = -EINTR; + goto errout; + } + } + + /* Re-acquire the the semaphore that manages mutually exclusive access to + * the device structure. We may have to wait here. But we have our sample. + * Interrupts and pre-emption will be re-enabled while we wait. + */ + + ret = sem_wait(&priv->exclsem); + +errout: + /* Restore pre-emption. We might get suspended here but that is okay + * because we already have our sample. Note: this means that if there + * were two threads reading from the STMPE11 for some reason, the data + * might be read out of order. + */ + + sched_unlock(); + return ret; +} + +/**************************************************************************** + * Name: stmpe11_open + * + * Description: + * Standard character driver open method. + * + ****************************************************************************/ + +static int stmpe11_open(FAR struct file *filep) +{ +#ifdef CONFIG_STMPE11_REFCNT + FAR struct inode *inode; + FAR struct stmpe11_dev_s *priv; + uint8_t tmp; + int ret; + + DEBUGASSERT(filep); + inode = filep->f_inode; + + DEBUGASSERT(inode && inode->i_private); + priv = (FAR struct stmpe11_dev_s *)inode->i_private; + + /* Get exclusive access to the driver data structure */ + + ret = sem_wait(&priv->exclsem); + if (ret < 0) + { + /* This should only happen if the wait was canceled by an signal */ + + DEBUGASSERT(errno == EINTR); + return -EINTR; + } + + /* Increment the reference count */ + + tmp = priv->crefs + 1; + if (tmp == 0) + { + /* More than 255 opens; uint8_t overflows to zero */ + + ret = -EMFILE; + goto errout_with_sem; + } + + /* When the reference increments to 1, this is the first open event + * on the driver.. and an opportunity to do any one-time initialization. + */ + + /* Save the new open count on success */ + + priv->crefs = tmp; + +errout_with_sem: + sem_post(&priv->exclsem); + return ret; +#else + return OK; +#endif +} + +/**************************************************************************** + * Name: stmpe11_close + * + * Description: + * Standard character driver close method. + * + ****************************************************************************/ + +static int stmpe11_close(FAR struct file *filep) +{ +#ifdef CONFIG_STMPE11_REFCNT + FAR struct inode *inode; + FAR struct stmpe11_dev_s *priv; + int ret; + + DEBUGASSERT(filep); + inode = filep->f_inode; + + DEBUGASSERT(inode && inode->i_private); + priv = (FAR struct stmpe11_dev_s *)inode->i_private; + + /* Get exclusive access to the driver data structure */ + + ret = sem_wait(&priv->exclsem); + if (ret < 0) + { + /* This should only happen if the wait was canceled by an signal */ + + DEBUGASSERT(errno == EINTR); + return -EINTR; + } + + /* Decrement the reference count unless it would decrement a negative + * value. When the count decrements to zero, there are no further + * open references to the driver. + */ + + if (priv->crefs >= 1) + { + priv->crefs--; + } + + sem_post(&priv->exclsem); +#endif + return OK; +} + +/**************************************************************************** + * Name: stmpe11_read + * + * Description: + * Standard character driver read method. + * + ****************************************************************************/ + +static ssize_t stmpe11_read(FAR struct file *filep, FAR char *buffer, size_t len) +{ + FAR struct inode *inode; + FAR struct stmpe11_dev_s *priv; + FAR struct touch_sample_s *report; + struct stmpe11_sample_s sample; + int ret; + + ivdbg("len=%d\n", len); + DEBUGASSERT(filep); + inode = filep->f_inode; + + DEBUGASSERT(inode && inode->i_private); + priv = (FAR struct stmpe11_dev_s *)inode->i_private; + + /* Verify that the caller has provided a buffer large enough to receive + * the touch data. + */ + + if (len < SIZEOF_TOUCH_SAMPLE_S(1)) + { + /* We could provide logic to break up a touch report into segments and + * handle smaller reads... but why? + */ + + return -ENOSYS; + } + + /* Get exclusive access to the driver data structure */ + + ret = sem_wait(&priv->exclsem); + if (ret < 0) + { + /* This should only happen if the wait was canceled by an signal */ + + DEBUGASSERT(errno == EINTR); + return -EINTR; + } + + /* Try to read sample data. */ + + ret = stmpe11_sample(priv, &sample); + if (ret < 0) + { + /* Sample data is not available now. We would ave to wait to get + * receive sample data. If the user has specified the O_NONBLOCK + * option, then just return an error. + */ + + if (filep->f_oflags & O_NONBLOCK) + { + ret = -EAGAIN; + goto errout; + } + + /* Wait for sample data */ + + ret = stmpe11_waitsample(priv, &sample); + if (ret < 0) + { + /* We might have been awakened by a signal */ + + goto errout; + } + } + + /* In any event, we now have sampled STMPE11 data that we can report + * to the caller. + */ + + report = (FAR struct touch_sample_s *)buffer; + memset(report, 0, SIZEOF_TOUCH_SAMPLE_S(1)); + report->npoints = 1; + report->point[0].id = sample.id; + report->point[0].x = sample.x; + report->point[0].y = sample.y; + report->point[0].pressure = sample.z; + + /* Report the appropriate flags */ + + if (sample.contact == CONTACT_UP) + { + /* Pen is now up. Is the positional data valid? This is important to + * know because the release will be sent to the window based on its + * last positional data. + */ + + if (sample.valid) + { + report->point[0].flags = TOUCH_UP | TOUCH_ID_VALID | + TOUCH_POS_VALID | TOUCH_PRESSURE_VALID; + } + else + { + report->point[0].flags = TOUCH_UP | TOUCH_ID_VALID; + } + } + else if (sample.contact == CONTACT_DOWN) + { + /* First contact */ + + report->point[0].flags = TOUCH_DOWN | TOUCH_ID_VALID | + TOUCH_POS_VALID | TOUCH_PRESSURE_VALID; + } + else /* if (sample->contact == CONTACT_MOVE) */ + { + /* Movement of the same contact */ + + report->point[0].flags = TOUCH_MOVE | TOUCH_ID_VALID | + TOUCH_POS_VALID | TOUCH_PRESSURE_VALID; + } + + ret = SIZEOF_TOUCH_SAMPLE_S(1); + +errout: + sem_post(&priv->exclsem); + return ret; +} + +/**************************************************************************** + * Name: stmpe11_ioctl + * + * Description: + * Standard character driver ioctl method. + * +****************************************************************************/ + +static int stmpe11_ioctl(FAR struct file *filep, int cmd, unsigned long arg) +{ + FAR struct inode *inode; + FAR struct stmpe11_dev_s *priv; + int ret; + + ivdbg("cmd: %d arg: %ld\n", cmd, arg); + DEBUGASSERT(filep); + inode = filep->f_inode; + + DEBUGASSERT(inode && inode->i_private); + priv = (FAR struct stmpe11_dev_s *)inode->i_private; + + /* Get exclusive access to the driver data structure */ + + ret = sem_wait(&priv->exclsem); + if (ret < 0) + { + /* This should only happen if the wait was canceled by an signal */ + + DEBUGASSERT(errno == EINTR); + return -EINTR; + } + + /* Process the IOCTL by command */ + + switch (cmd) + { + case TSIOC_SETFREQUENCY: /* arg: Pointer to uint32_t frequency value */ + { + FAR uint32_t *ptr = (FAR uint32_t *)((uintptr_t)arg); + DEBUGASSERT(priv->config != NULL && ptr != NULL); + priv->config->frequency = I2C_SETFREQUENCY(priv->i2c, *ptr); + } + break; + + case TSIOC_GETFREQUENCY: /* arg: Pointer to uint32_t frequency value */ + { + FAR uint32_t *ptr = (FAR uint32_t *)((uintptr_t)arg); + DEBUGASSERT(priv->config != NULL && ptr != NULL); + *ptr = priv->config->frequency; + } + break; + + default: + ret = -ENOTTY; + break; + } + + sem_post(&priv->exclsem); + return ret; +} + +/**************************************************************************** + * Name: stmpe11_poll + * + * Description: + * Standard character driver poll method. + * + ****************************************************************************/ + +#ifndef CONFIG_DISABLE_POLL +static int stmpe11_poll(FAR struct file *filep, FAR struct pollfd *fds, + bool setup) +{ + FAR struct inode *inode; + FAR struct stmpe11_dev_s *priv; + int ret; + int i; + + ivdbg("setup: %d\n", (int)setup); + DEBUGASSERT(filep && fds); + inode = filep->f_inode; + + DEBUGASSERT(inode && inode->i_private); + priv = (FAR struct stmpe11_dev_s *)inode->i_private; + + /* Are we setting up the poll? Or tearing it down? */ + + ret = sem_wait(&priv->exclsem); + if (ret < 0) + { + /* This should only happen if the wait was canceled by an signal */ + + DEBUGASSERT(errno == EINTR); + return -EINTR; + } + + if (setup) + { + /* Ignore waits that do not include POLLIN */ + + if ((fds->events & POLLIN) == 0) + { + idbg("ERROR: Missing POLLIN: revents: %08x\n", fds->revents); + ret = -EDEADLK; + goto errout; + } + + /* This is a request to set up the poll. Find an available + * slot for the poll structure reference + */ + + for (i = 0; i < CONFIG_STMPE11_NPOLLWAITERS; i++) + { + /* Find an available slot */ + + if (!priv->fds[i]) + { + /* Bind the poll structure and this slot */ + + priv->fds[i] = fds; + fds->priv = &priv->fds[i]; + break; + } + } + + if (i >= CONFIG_STMPE11_NPOLLWAITERS) + { + idbg("ERROR: No availabled slot found: %d\n", i); + fds->priv = NULL; + ret = -EBUSY; + goto errout; + } + + /* Should we immediately notify on any of the requested events? */ + + if (priv->penchange) + { + stmpe11_notify(priv); + } + } + else if (fds->priv) + { + /* This is a request to tear down the poll. */ + + struct pollfd **slot = (struct pollfd **)fds->priv; + DEBUGASSERT(slot != NULL); + + /* Remove all memory of the poll setup */ + + *slot = NULL; + fds->priv = NULL; + } + +errout: + sem_post(&priv->exclsem); + return ret; +} +#endif + +/**************************************************************************** + * Name: stmpe11_timeoutworker + * + * Description: + * A timer has expired without receiving a pen up event. Check again. + * + ****************************************************************************/ + +static void stmpe11_timeoutworker(FAR void *arg) +{ + FAR struct stmpe11_dev_s *priv = (FAR struct stmpe11_dev_s *)arg; + + DEBUGASSERT(priv); + + /* Treat the timeout just like an interrupt occurred */ + + stmpe11_tscworker(priv, stmpe11_getreg8(priv, STMPE11_INT_STA)); +} + +/**************************************************************************** + * Name: stmpe11_timeout + * + * Description: + * A timer has expired without receiving a pen up event. Schedule work + * to check again. + * + ****************************************************************************/ + +static void stmpe11_timeout(int argc, uint32_t arg1, ...) +{ + FAR struct stmpe11_dev_s *priv = (FAR struct stmpe11_dev_s *)((uintptr_t)arg1); + int ret; + + /* Are we still stuck in the pen down state? */ + + if (priv->sample.contact == CONTACT_MOVE || + priv->sample.contact == CONTACT_MOVE) + { + /* Yes... is the worker thread available? If not, then apparently + * we have work already pending? + */ + + if (work_available(&priv->timeout)) + { + /* Yes.. Transfer processing to the worker thread. Since STMPE11 + * interrupts are disabled while the work is pending, no special + * action should be required to protect the work queue. + */ + + ret = work_queue(&priv->timeout, stmpe11_timeoutworker, priv, 0); + if (ret != 0) + { + illdbg("Failed to queue work: %d\n", ret); + } + } + } +} + +/**************************************************************************** + * Name: stmpe11_tscinitialize + * + * Description: + * Initialize the touchscreen controller. This is really a part of the + * stmpe11_register logic, + * + ****************************************************************************/ + +static inline void stmpe11_tscinitialize(FAR struct stmpe11_dev_s *priv) +{ + uint8_t regval; + + ivdbg("Initializing touchscreen controller\n"); + + /* Enable TSC and ADC functions */ + + regval = stmpe11_getreg8(priv, STMPE11_SYS_CTRL2); + regval &= ~(SYS_CTRL2_TSC_OFF | SYS_CTRL2_ADC_OFF); + stmpe11_putreg8(priv, STMPE11_SYS_CTRL2, regval); + + /* Enable the TSC global interrupts */ + + regval = stmpe11_getreg8(priv, STMPE11_INT_EN); + regval |= (uint32_t)(INT_TOUCH_DET | INT_FIFO_TH | INT_FIFO_OFLOW); + stmpe11_putreg8(priv, STMPE11_INT_EN, regval); + + /* Select Sample Time, bit number and ADC Reference */ + + stmpe11_putreg8(priv, STMPE11_ADC_CTRL1, priv->config->ctrl1); + + /* Wait for 20 ms */ + + up_mdelay(20); + + /* Select the ADC clock speed */ + + stmpe11_putreg8(priv, STMPE11_ADC_CTRL2, priv->config->ctrl2); + + /* Select TSC pins in non-GPIO mode (AF=0) */ + + regval = stmpe11_getreg8(priv, STMPE11_GPIO_AF); + regval &= ~(uint8_t)TSC_PIN_SET; + stmpe11_putreg8(priv, STMPE11_GPIO_AF, regval); + + /* Select 2 nF filter capacitor */ + + stmpe11_putreg8(priv, STMPE11_TSC_CFG, + (TSC_CFG_AVE_CTRL_4SAMPLES | TSC_CFG_TOUCH_DELAY_500US | TSC_CFG_SETTLING_500US)); + + /* Select single point reading */ + + stmpe11_putreg8(priv, STMPE11_FIFO_TH, 1); + + /* Reset and clear the FIFO. */ + + stmpe11_putreg8(priv, STMPE11_FIFO_STA, FIFO_STA_FIFO_RESET); + stmpe11_putreg8(priv, STMPE11_FIFO_STA, 0); + + /* set the data format for Z value: 7 fractional part and 1 whole part */ + + stmpe11_putreg8(priv, STMPE11_TSC_FRACTIONZ, 0x01); + + /* Set the driving capability of the device for TSC pins: 50mA */ + + stmpe11_putreg8(priv, STMPE11_TSC_IDRIVE, TSC_IDRIVE_50MA); + + /* Enable the TSC. Use no tracking index, touch-screen controller + * operation mode (XYZ). + */ + + stmpe11_putreg8(priv, STMPE11_TSC_CTRL, TSC_CTRL_EN); + + /* Clear all the status pending bits */ + + stmpe11_putreg8(priv, STMPE11_INT_STA, INT_ALL); +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stmpe11_register + * + * Description: + * Enable TSC functionality. GPIO4-7 must be available. This function + * will register the touchsceen driver as /dev/inputN where N is the minor + * device number + * + * Input Parameters: + * handle - The handle previously returned by stmpe11_register + * 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 stmpe11_register(STMPE11_HANDLE handle, int minor) +{ + FAR struct stmpe11_dev_s *priv = (FAR struct stmpe11_dev_s *)handle; + char devname[DEV_NAMELEN]; + int ret; + + ivdbg("handle=%p minor=%d\n", handle, minor); + DEBUGASSERT(priv); + + /* Get exclusive access to the device structure */ + + ret = sem_wait(&priv->exclsem); + if (ret < 0) + { + int errval = errno; + idbg("ERROR: sem_wait failed: %d\n", errval); + return -errval; + } + + /* Make sure that the pins (4-7) need by the TSC are not already in use */ + + if ((priv->inuse & TSC_PIN_SET) != 0) + { + idbg("ERROR: TSC pins is already in-use: %02x\n", priv->inuse); + sem_post(&priv->exclsem); + return -EBUSY; + } + + /* Initialize the TS structure fields to their default values */ + + priv->minor = minor; + priv->penchange = false; + priv->threshx = 0; + priv->threshy = 0; + + /* Create a timer for catching missed pen up conditions */ + + priv->wdog = wd_create(); + if (!priv->wdog) + { + idbg("ERROR: Failed to create a watchdog\n", errno); + sem_post(&priv->exclsem); + return -ENOSPC; + } + + /* Register the character driver */ + + snprintf(devname, DEV_NAMELEN, DEV_FORMAT, minor); + ret = register_driver(devname, &g_stmpe11fops, 0666, priv); + if (ret < 0) + { + idbg("ERROR: Failed to register driver %s: %d\n", devname, ret); + sem_post(&priv->exclsem); + return ret; + } + + /* Initialize the touchscreen controller */ + + stmpe11_tscinitialize(priv); + + /* Inidicate that the touchscreen controller was successfully initialized */ + + priv->inuse |= TSC_PIN_SET; /* Pins 4-7 are now in-use */ + priv->flags |= STMPE11_FLAGS_TSC_INITIALIZED; /* TSC function is initialized */ + sem_post(&priv->exclsem); + return ret; +} + +/**************************************************************************** + * Name: stmpe11_tscworker + * + * Description: + * This function is called to handle a TSC interrupt. It is not really + * an interrupt handle because it is called from the STMPE11 "bottom half" + * logic that runs on the worker thread. + * + ****************************************************************************/ + +void stmpe11_tscworker(FAR struct stmpe11_dev_s *priv, uint8_t intsta) +{ + FAR struct stmpe11_config_s *config; /* Convenience pointer */ + bool pendown; /* true: pend is down */ + uint16_t xdiff; /* X difference used in thresholding */ + uint16_t ydiff; /* Y difference used in thresholding */ + uint16_t x; /* X position */ + uint16_t y; /* Y position */ + + ASSERT(priv != NULL); + + /* Cancel the missing pen up timer */ + + (void)wd_cancel(priv->wdog); + + /* Get a pointer the callbacks for convenience (and so the code is not so + * ugly). + */ + + config = priv->config; + DEBUGASSERT(config != NULL); + + /* Check for pen up or down from the TSC_STA ibit n the STMPE11_TSC_CTRL register. */ + + pendown = (stmpe11_getreg8(priv, STMPE11_TSC_CTRL) & TSC_CTRL_TSC_STA) != 0; + + /* Handle the change from pen down to pen up */ + + if (!pendown) + { + /* The pen is up.. reset thresholding variables. FIFOs will read zero if + * there is no data available (hence the choice of (0,0)) + */ + + priv->threshx = 0; + priv->threshy = 0; + + /* Ignore the interrupt if the pen was already up (CONTACT_NONE == pen up and + * already reported; CONTACT_UP == pen up, but not reported) + */ + + if (priv->sample.contact == CONTACT_NONE || + priv->sample.contact == CONTACT_UP) + { + goto ignored; + } + + /* A pen-down to up transition has been detected. CONTACT_UP indicates the + * initial loss of contzt. The state will be changed to CONTACT_NONE + * after the loss of contact is sampled. + */ + + priv->sample.contact = CONTACT_UP; + } + + /* The pen is down... check for data in the FIFO */ + + else if ((intsta & (INT_FIFO_TH|INT_FIFO_OFLOW)) != 0) + { + /* Read the next x and y positions from the FIFO. */ + +#ifdef CONFIG_STMPE11_SWAPXY + x = stmpe11_getreg16(priv, STMPE11_TSC_DATAX); + y = stmpe11_getreg16(priv, STMPE11_TSC_DATAY); +#else + x = stmpe11_getreg16(priv, STMPE11_TSC_DATAY); + y = stmpe11_getreg16(priv, STMPE11_TSC_DATAX); +#endif + + /* If we have not yet processed the last pen up event, then we + * cannot handle this pen down event. We will have to discard it. That + * should be okay because there will be another FIFO event right behind + * this one. Other kinds of data overruns are not harmful. + * + * Hmm.. a better design might be to disable FIFO interrupts when we + * detect pen up. Then re-enable them when CONTACT_UP is reported. + * That would save processing interrupts just to discard the data. + */ + + if (priv->sample.contact == CONTACT_UP) + { + /* We have not closed the loop on the last touch ... don't report + * anything. + */ + + goto ignored; + } + + /* Perform a thresholding operation so that the results will be more stable. + * If the difference from the last sample is small, then ignore the event. + * REVISIT: Should a large change in pressure also generate a event? + */ + + xdiff = x > priv->threshx ? (x - priv->threshx) : (priv->threshx - x); + ydiff = y > priv->threshy ? (y - priv->threshy) : (priv->threshy - y); + + if (xdiff < CONFIG_STMPE11_THRESHX && ydiff < CONFIG_STMPE11_THRESHY) + { + /* Little or no change in either direction ... don't report anything. */ + + goto ignored; + } + + /* When we see a big difference, snap to the new x/y thresholds */ + + priv->threshx = x; + priv->threshy = y; + + /* Update the x/y position in the sample data */ + + priv->sample.x = priv->threshx; + priv->sample.y = priv->threshy; + + /* Update the Z pressure index */ + + priv->sample.z = stmpe11_getreg8(priv, STMPE11_TSC_DATAZ); + priv->sample.valid = true; + + /* If this is the first (acknowledged) pen down report, then report + * this as the first contact. If contact == CONTACT_DOWN, it will be + * set to set to CONTACT_MOVE after the contact is first sampled. + */ + + if (priv->sample.contact != CONTACT_MOVE) + { + /* First contact */ + + priv->sample.contact = CONTACT_DOWN; + } + } + + /* Pen down, but no data in FIFO */ + + else + { + /* Ignore the interrupt... wait until there is data in the FIFO */ + + goto ignored; + } + + /* We get here if (1) we just went from a pen down to a pen up state OR (2) + * We just get a measurement from the FIFO in a pen down state. Indicate + * the availability of new sample data for this ID. + */ + + priv->sample.id = priv->id; + priv->penchange = true; + + /* Notify any waiters that new STMPE11 data is available */ + + stmpe11_notify(priv); + + /* If we think that the pend is still down, the start/re-start the pen up + * timer. + */ + +ignored: + if (priv->sample.contact == CONTACT_MOVE || + priv->sample.contact == CONTACT_MOVE) + { + (void)wd_start(priv->wdog, STMPE11_PENUP_TICKS, stmpe11_timeout, + 1, (uint32_t)((uintptr_t)priv)); + } + + /* Reset and clear all data in the FIFO */ + + stmpe11_putreg8(priv, STMPE11_FIFO_STA, FIFO_STA_FIFO_RESET); + stmpe11_putreg8(priv, STMPE11_FIFO_STA, 0); +} + +#endif /* CONFIG_INPUT && CONFIG_INPUT_STMPE11 && !CONFIG_STMPE11_TSC_DISABLE */ + -- cgit v1.2.3