Add STMPE11 touchscreen logic

git-svn-id: https://nuttx.svn.sourceforge.net/svnroot/nuttx/trunk@4703 7fd9a85b-ad96-42d3-883c-3090e2eb8679
This commit is contained in:
patacongo 2012-05-06 16:00:16 +00:00
parent edf3b4667b
commit db2a671b19
9 changed files with 1171 additions and 56 deletions

View File

@ -12,7 +12,7 @@
<h1><big><font color="#3c34ec">
<i>NuttX RTOS Porting Guide</i>
</font></big></h1>
<p>Last Updated: April 13, 2011</p>
<p>Last Updated: May 6, 2011</p>
</td>
</tr>
</table>
@ -4672,6 +4672,48 @@ build
there are multiple TSC2007 touchscreens, this setting will enable
multiple touchscreens with the same driver.
</li>
<li>
<code>CONFIG_INPUT_STMPE11</code>:
Enables support for the STMPE11 driver (Needs <code>CONFIG_INPUT</code>)
</li>
<li>
<code>CONFIG_STMPE11_SPI</code>:
Enables support for the SPI interface (not currenly supported)
</li>
<li>
<code>CONFIG_STMPE11_I2C</code>:
Enables support for the I2C interface
</li>
<li>
<code>CONFIG_STMPE11_MULTIPLE </code>:
Can be defined to support multiple STMPE11 devices on board.
</li>
<li>
<code>CONFIG_STMPE11_NPOLLWAITERS</code>:
Maximum number of threads that can be waiting on poll() (ignored if
<code>CONFIG_DISABLE_POLL</code> is set).
</li>
<li>
<code>CONFIG_STMPE11_TSC_DISABLE</code>:
Disable driver touchscreen functionality.
</li>
<li>
<code>CONFIG_STMPE11_ADC_DISABLE</code>:
Disable driver ADC functionality.
</li>
<li>
<code>CONFIG_STMPE11_GPIO_DISABLE</code>:
Disable driver GPIO functionlaity.
</li>
<li>
<code>CONFIG_STMPE11_GPIOINT_DISABLE</code>:
Disable driver GPIO interrupt functionlality (ignored if GPIO
functionality is disabled).
</li>
<li>
<code>CONFIG_STMPE11_TS_DISABLE</code>:
Disable driver temperature sensor functionlaity.
</li>
</ul>
<h3>Analog Devices</h3>

View File

@ -775,6 +775,7 @@ defconfig -- This is a configuration file similar to the Linux
CONFIG_INPUT
Enables general support for input devices
CONFIG_INPUT_TSC2007
If CONFIG_INPUT is selected, then this setting will enable building
of the TI TSC2007 touchscreen driver.
@ -783,6 +784,29 @@ defconfig -- This is a configuration file similar to the Linux
there are multiple TSC2007 touchscreens, this setting will enable
multiple touchscreens with the same driver.
CONFIG_INPUT_STMPE11
Enables support for the STMPE11 driver (Needs CONFIG_INPUT)
CONFIG_STMPE11_SPI
Enables support for the SPI interface (not currenly supported)
CONFIG_STMPE11_I2C
Enables support for the I2C interface
CONFIG_STMPE11_MULTIPLE
Can be defined to support multiple STMPE11 devices on board.
CONFIG_STMPE11_NPOLLWAITERS
Maximum number of threads that can be waiting on poll() (ignored if
CONFIG_DISABLE_POLL is set).
CONFIG_STMPE11_TSC_DISABLE
Disable driver touchscreen functionality.
CONFIG_STMPE11_ADC_DISABLE
Disable driver ADC functionality.
CONFIG_STMPE11_GPIO_DISABLE
Disable driver GPIO functionlaity.
CONFIG_STMPE11_GPIOINT_DISABLE
Disable driver GPIO interrupt functionlality (ignored if GPIO
functionality is disabled).
CONFIG_STMPE11_TS_DISABLE
Disable driver temperature sensor functionlaity.
Analog Devices
CONFIG_DAC

View File

@ -49,6 +49,9 @@ endif
ifeq ($(CONFIG_INPUT_STMPE11),y)
CSRCS += stmpe11_base.c
ifneq ($(CONFIG_INPUT_STMPE11_TSC_DISABLE),y)
CSRCS += stmpe11_tsc.c
endif
ifneq ($(CONFIG_INPUT_STMPE11_GPIO_DISABLE),y)
CSRCS += stmpe11_gpio.c
endif

View File

@ -113,7 +113,7 @@ struct stmpe11_sample_s
uint8_t contact; /* Contact state (see enum stmpe11_contact_e) */
uint16_t x; /* Measured X position */
uint16_t y; /* Measured Y position */
uint16_t z; /* Measured Z position */
uint8_t z; /* Measured Z index */
};
/* This structure represents the state of the SMTPE11 driver */
@ -216,11 +216,11 @@ uint16_t stmpe11_getreg16(FAR struct stmpe11_dev_s *priv, uint8_t regaddr);
********************************************************************************************/
#ifndef CONFIG_STMPE11_TSC_DISABLE
void stmpe11_tscint(FAR struct stmpe11_dev_s *priv) weak_function;
void stmpe11_tscworker(FAR struct stmpe11_dev_s *priv) weak_function;
#endif
/********************************************************************************************
* Name: stmpe11_gpioint
* Name: stmpe11_gpioworker
*
* Description:
* Handle GPIO interrupt events (this function actually executes in the context of the
@ -229,7 +229,7 @@ void stmpe11_tscint(FAR struct stmpe11_dev_s *priv) weak_function;
********************************************************************************************/
#if !defined(CONFIG_STMPE11_GPIO_DISABLE) && !defined(CONFIG_STMPE11_GPIOINT_DISABLE)
void stmpe11_gpioint(FAR struct stmpe11_dev_s *priv) weak_function;
void stmpe11_gpioworker(FAR struct stmpe11_dev_s *priv) weak_function;
#endif
#endif /* CONFIG_INPUT && CONFIG_INPUT_STMPE11 */

View File

@ -48,6 +48,7 @@
#include <errno.h>
#include <debug.h>
#include <nuttx/arch.h>
#include <nuttx/input/stmpe11.h>
#include "stmpe11.h"
@ -71,15 +72,14 @@
****************************************************************************/
/****************************************************************************
* Name: stmpe11_adctiming
* Name: stmpe11_adcinitialize
*
* Description:
* Configure overall ADC timing that applies to all pins.
* 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
* ctrl1 - The value of the ADC_CRTL1 register (see above).
* ctrl2 - The value of the ADC_CRTL2 register (see above).
*
* Returned Value:
* Zero is returned on success. Otherwise, a negated errno value is
@ -87,7 +87,7 @@
*
****************************************************************************/
int stmpe11_adctiming(STMPE11_HANDLE handle, uint8_t ctrl1, uint8_t ctrl2)
int stmpe11_adcinitialize(STMPE11_HANDLE handle)
{
FAR struct stmpe11_dev_s *priv = (FAR struct stmpe11_dev_s *)handle;
uint8_t regval;
@ -111,10 +111,17 @@ int stmpe11_adctiming(STMPE11_HANDLE handle, uint8_t ctrl1, uint8_t ctrl2)
regval &= ~SYS_CTRL2_ADC_OFF;
stmpe11_putreg8(priv, STMPE11_SYS_CTRL2, regval);
/* Configure the ADC properties */
/* Select Sample Time, bit number and ADC Reference */
stmpe11_putreg8(priv, STMPE11_ADC_CTRL1, ctrl1);
stmpe11_putreg8(priv, STMPE11_ADC_CTRL2, ctrl2);
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 */

View File

@ -102,9 +102,11 @@ static void stmpe11_worker(FAR void *arg)
{
/* Dispatch the touchscreen interrupt if it was brought into the link */
if (stmpe11_tscint)
#ifdef CONFIG_HAVE_WEAKFUNCTIONS
if (stmpe11_tscworker)
#endif
{
stmpe11_tscint(priv);
stmpe11_tscworker(priv);
}
stmpe11_putreg8(priv, STMPE11_INT_STA, (INT_TOUCH_DET|INT_FIFO_TH|INT_FIFO_OFLOW));
@ -117,9 +119,11 @@ static void stmpe11_worker(FAR void *arg)
{
/* Dispatch the GPIO interrupt if it was brought into the link */
if (stmpe11_gpioint)
#ifdef CONFIG_HAVE_WEAKFUNCTIONS
if (stmpe11_gpioworker)
#endif
{
stmpe11_gpioint(priv);
stmpe11_gpioworker(priv);
}
stmpe11_putreg8(priv, STMPE11_INT_STA, INT_GPIO);

View File

@ -397,7 +397,7 @@ int stmpe11_gpioattach(STMPE11_HANDLE handle, uint8_t pinconfig,
#endif
/****************************************************************************
* Name: stmpe11_gpioint
* Name: stmpe11_gpioworker
*
* Description:
* Handle GPIO interrupt events (this function actually executes in the
@ -406,7 +406,7 @@ int stmpe11_gpioattach(STMPE11_HANDLE handle, uint8_t pinconfig,
****************************************************************************/
#ifndef CONFIG_STMPE11_GPIOINT_DISABLE
void stmpe11_gpioint(FAR struct stmpe11_dev_s *priv)
void stmpe11_gpioworker(FAR struct stmpe11_dev_s *priv)
{
uint8_t regval;
uint8_t pinmask;

File diff suppressed because it is too large Load Diff

View File

@ -57,8 +57,35 @@
* Pre-Processor Definitions
********************************************************************************************/
/* Configuration ****************************************************************************/
/* The STMPE811 interfaces with the host CPU via a I2C or SPI interface. The pin IN_1 allows
* the selection of interface protocol at reset state.
/* Prerequisites: CONFIG_INPUT=y
* Other settings that effect the driver: CONFIG_DISABLE_POLL
*
* CONFIG_INPUT_STMPE11
* Enables support for the STMPE11 driver (Needs CONFIG_INPUT)
* CONFIG_STMPE11_SPI
* Enables support for the SPI interface (not currenly supported)
* CONFIG_STMPE11_I2C
* Enables support for the I2C interface
* CONFIG_STMPE11_MULTIPLE
* Can be defined to support multiple STMPE11 devices on board.
* CONFIG_STMPE11_NPOLLWAITERS
* Maximum number of threads that can be waiting on poll() (ignored if
* CONFIG_DISABLE_POLL is set).
* CONFIG_STMPE11_TSC_DISABLE
* Disable driver touchscreen functionality.
* CONFIG_STMPE11_ADC_DISABLE
* Disable driver ADC functionality.
* CONFIG_STMPE11_GPIO_DISABLE
* Disable driver GPIO functionlaity.
* CONFIG_STMPE11_GPIOINT_DISABLE
* Disable driver GPIO interrupt functionlality (ignored if GPIO functionality is
* disabled).
* CONFIG_STMPE11_TS_DISABLE
* Disable driver temperature sensor functionlaity.
*/
/* The STMPE811 interfaces with the target CPU via a I2C or SPI interface. The pin IN_1
* allows the selection of interface protocol at reset state.
*/
#if !defined(CONFIG_STMPE11_SPI) && !defined(CONFIG_STMPE11_I2C)
@ -235,6 +262,7 @@
/* GPIO set/clear/sta/dir/edge/rising/falling/af registers */
#define GPIO_PIN(n) (1 << (n))
#define TSC_PIN_SET (0xf0) /* Pins 4-7: Used by touchscreen */
/* ADC control */
@ -286,32 +314,32 @@
/* Touchscreen controller configuration */
#define TSWC_CFG_SETTLING_SHIFT (0) /* Bits 0-2: Panel driver settling time */
#define TSWC_CFG_SETTLING_MASK (7 << TSWC_CFG_SETTLING_SHIFT)
# define TSWC_CFG_SETTLING_10US (0 << TSWC_CFG_SETTLING_SHIFT)
# define TSWC_CFG_SETTLING_100US (1 << TSWC_CFG_SETTLING_SHIFT)
# define TSWC_CFG_SETTLING_500US (2 << TSWC_CFG_SETTLING_SHIFT)
# define TSWC_CFG_SETTLING_1MS (3 << TSWC_CFG_SETTLING_SHIFT)
# define TSWC_CFG_SETTLING_5MS (4 << TSWC_CFG_SETTLING_SHIFT)
# define TSWC_CFG_SETTLING_10MS (5 << TSWC_CFG_SETTLING_SHIFT)
# define TSWC_CFG_SETTLING_50MS (6 << TSWC_CFG_SETTLING_SHIFT)
# define TSWC_CFG_SETTLING_100MS (7 << TSWC_CFG_SETTLING_SHIFT)
#define TSWC_CFG_TOUCH_DELAY_SHIFT (1) /* Bits 3-5: Touch detect delay */
#define TSWC_CFG_TOUCH_DELAY_MASK (7 << TSWC_CFG_TOUCH_DELAY_SHIFT)
# define TSWC_CFG_TOUCH_DELAY_10US (0 << TSWC_CFG_TOUCH_DELAY_SHIFT)
# define TSWC_CFG_TOUCH_DELAY_50US (1 << TSWC_CFG_TOUCH_DELAY_SHIFT)
# define TSWC_CFG_TOUCH_DELAY_100US (1 << TSWC_CFG_TOUCH_DELAY_SHIFT)
# define TSWC_CFG_TOUCH_DELAY_500US (2 << TSWC_CFG_TOUCH_DELAY_SHIFT)
# define TSWC_CFG_TOUCH_DELAY_1MS (3 << TSWC_CFG_TOUCH_DELAY_SHIFT)
# define TSWC_CFG_TOUCH_DELAY_5MS (4 << TSWC_CFG_TOUCH_DELAY_SHIFT)
# define TSWC_CFG_TOUCH_DELAY_10MS (5 << TSWC_CFG_TOUCH_DELAY_SHIFT)
# define TSWC_CFG_TOUCH_DELAY_50MS (6 << TSWC_CFG_TOUCH_DELAY_SHIFT)
#define TSWC_CFG_AVE_CTRL_SHIFT (6) /* Bits 6-7: Average control */
#define TSWC_CFG_AVE_CTRL_MASK (3 << TSWC_CFG_AVE_CTRL_SHIFT)
# define TSWC_CFG_AVE_CTRL_1SAMPLE (0 << TSWC_CFG_AVE_CTRL_SHIFT)
# define TSWC_CFG_AVE_CTRL_2SAMPLES (1 << TSWC_CFG_AVE_CTRL_SHIFT)
# define TSWC_CFG_AVE_CTRL_4SAMPLES (2 << TSWC_CFG_AVE_CTRL_SHIFT)
# define TSWC_CFG_AVE_CTRL_8SAMPLES (3 << TSWC_CFG_AVE_CTRL_SHIFT)
#define TSC_CFG_SETTLING_SHIFT (0) /* Bits 0-2: Panel driver settling time */
#define TSC_CFG_SETTLING_MASK (7 << TSC_CFG_SETTLING_SHIFT)
# define TSC_CFG_SETTLING_10US (0 << TSC_CFG_SETTLING_SHIFT)
# define TSC_CFG_SETTLING_100US (1 << TSC_CFG_SETTLING_SHIFT)
# define TSC_CFG_SETTLING_500US (2 << TSC_CFG_SETTLING_SHIFT)
# define TSC_CFG_SETTLING_1MS (3 << TSC_CFG_SETTLING_SHIFT)
# define TSC_CFG_SETTLING_5MS (4 << TSC_CFG_SETTLING_SHIFT)
# define TSC_CFG_SETTLING_10MS (5 << TSC_CFG_SETTLING_SHIFT)
# define TSC_CFG_SETTLING_50MS (6 << TSC_CFG_SETTLING_SHIFT)
# define TSC_CFG_SETTLING_100MS (7 << TSC_CFG_SETTLING_SHIFT)
#define TSC_CFG_TOUCH_DELAY_SHIFT (1) /* Bits 3-5: Touch detect delay */
#define TSC_CFG_TOUCH_DELAY_MASK (7 << TSC_CFG_TOUCH_DELAY_SHIFT)
# define TSC_CFG_TOUCH_DELAY_10US (0 << TSC_CFG_TOUCH_DELAY_SHIFT)
# define TSC_CFG_TOUCH_DELAY_50US (1 << TSC_CFG_TOUCH_DELAY_SHIFT)
# define TSC_CFG_TOUCH_DELAY_100US (2 << TSC_CFG_TOUCH_DELAY_SHIFT)
# define TSC_CFG_TOUCH_DELAY_500US (3 << TSC_CFG_TOUCH_DELAY_SHIFT)
# define TSC_CFG_TOUCH_DELAY_1MS (4 << TSC_CFG_TOUCH_DELAY_SHIFT)
# define TSC_CFG_TOUCH_DELAY_5MS (5 << TSC_CFG_TOUCH_DELAY_SHIFT)
# define TSC_CFG_TOUCH_DELAY_10MS (6 << TSC_CFG_TOUCH_DELAY_SHIFT)
# define TSC_CFG_TOUCH_DELAY_50MS (7 << TSC_CFG_TOUCH_DELAY_SHIFT)
#define TSC_CFG_AVE_CTRL_SHIFT (6) /* Bits 6-7: Average control */
#define TSC_CFG_AVE_CTRL_MASK (3 << TSC_CFG_AVE_CTRL_SHIFT)
# define TSC_CFG_AVE_CTRL_1SAMPLE (0 << TSC_CFG_AVE_CTRL_SHIFT)
# define TSC_CFG_AVE_CTRL_2SAMPLES (1 << TSC_CFG_AVE_CTRL_SHIFT)
# define TSC_CFG_AVE_CTRL_4SAMPLES (2 << TSC_CFG_AVE_CTRL_SHIFT)
# define TSC_CFG_AVE_CTRL_8SAMPLES (3 << TSC_CFG_AVE_CTRL_SHIFT)
/* Current status of FIFO */
@ -328,6 +356,8 @@
/* Touchscreen controller drive I */
#define TSC_IDRIVE (1 << 0) /* Bit 0: MAX current on TSC driving channel */
# define TSC_IDRIVE_20MA (0) /* 20mA typical, 35mA max */
# define TSC_IDRIVE_50MA (1 << 0) /* 50mA typical, 80mA max */
/* Touchscreen controller shield */
@ -427,6 +457,16 @@ struct stmpe11_config_s
int irq; /* IRQ number received by interrupt handler. */
#endif
/* These are the timing valuses for ADC CTRL1 and CTRL2. These values
* are only used if either the TSC or the ADC are enabled. These values
* determine the characteristics of sampling.
*/
#if !defined(CONFIG_STMPE11_ADC_DISABLE) || !defined(CONFIG_STMPE11_TSC_DISABLE)
uint8_t ctrl1; /* Initialization value for ADC CTRL1 */
uint8_t ctrl2; /* Initialization value for ADC CTRL1 */
#endif
/* IRQ/GPIO access callbacks. These operations all hidden behind
* callbacks to isolate the STMPE11 driver from differences in GPIO
* interrupt handling by varying boards and MCUs. If possible,
@ -436,15 +476,11 @@ struct stmpe11_config_s
* attach - Attach the STMPE11 interrupt handler to the GPIO interrupt
* enable - Enable or disable the GPIO interrupt
* clear - Acknowledge/clear any pending GPIO interrupt
* pendown - Return the state of the pen down GPIO input (TSC only)
*/
int (*attach)(FAR struct stmpe11_config_s *state, xcpt_t isr);
void (*enable)(FAR struct stmpe11_config_s *state, bool enable);
void (*clear)(FAR struct stmpe11_config_s *state);
#ifndef CONFIG_STMPE11_TSC_DISABLE
bool (*pendown)(FAR struct stmpe11_config_s *state);
#endif
};
/* Since the STMPE11 is a multi-function device, no functionality is assumed when the device
@ -600,15 +636,13 @@ EXTERN int stmpe11_gpioattach(STMPE11_HANDLE handle, uint8_t pinconfig,
#endif
/********************************************************************************************
* Name: stmpe11_adctiming
* Name: stmpe11_adcinitialize
*
* Description:
* Configure overall ADC timing that applies to all pins.
* 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
* ctrl1 - The value of the ADC_CRTL1 register (see above).
* ctrl2 - The value of the ADC_CRTL2 register (see above).
*
* Returned Value:
* Zero is returned on success. Otherwise, a negated errno value is returned to indicate
@ -617,7 +651,7 @@ EXTERN int stmpe11_gpioattach(STMPE11_HANDLE handle, uint8_t pinconfig,
********************************************************************************************/
#ifndef CONFIG_STMPE11_ADC_DISABLE
EXTERN int stmpe11_adctiming(STMPE11_HANDLE handle, uint8_t ctrl1, uint8_t ctrl2);
EXTERN int stmpe11_adcinitialize(STMPE11_HANDLE handle);
#endif
/********************************************************************************************