A little more cleanup after the big STMPE11->811 name change

git-svn-id: https://nuttx.svn.sourceforge.net/svnroot/nuttx/trunk@4783 7fd9a85b-ad96-42d3-883c-3090e2eb8679
This commit is contained in:
patacongo 2012-05-29 01:43:51 +00:00
parent 5e0db56108
commit 5a87fd158b
10 changed files with 421 additions and 421 deletions

View File

@ -157,7 +157,7 @@ clean:
@rm -f $(BIN) *~ .*.swp *.o
$(call CLEAN)
distclean: clean
distclean: # clean
@for dir in $(SUBDIRS) ; do \
$(MAKE) -C $$dir distclean TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)"; \
done

View File

@ -136,7 +136,7 @@ struct stm32_stmpe811config_s
/* Additional private definitions only known to this driver */
STMPE811_HANDLE handle; /* The STMPE811 driver handle */
xcpt_t handler; /* The STMPE811 interrupt handler */
xcpt_t handler; /* The STMPE811 interrupt handler */
};
/****************************************************************************

View File

@ -136,7 +136,7 @@ struct stm32_stmpe811config_s
/* Additional private definitions only known to this driver */
STMPE811_HANDLE handle; /* The STMPE811 driver handle */
xcpt_t handler; /* The STMPE811 interrupt handler */
xcpt_t handler; /* The STMPE811 interrupt handler */
};
/****************************************************************************

View File

@ -1,5 +1,5 @@
/********************************************************************************************
* drivers/input/stmpe11.h
* drivers/input/stmpe811.h
*
* Copyright (C) 2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
@ -37,8 +37,8 @@
*
********************************************************************************************/
#ifndef __DRIVERS_INPUT_STMPE11_H
#define __DRIVERS_INPUT_STMPE11_H
#ifndef __DRIVERS_INPUT_STMPE811_H
#define __DRIVERS_INPUT_STMPE811_H
/********************************************************************************************
* Included Files
@ -51,9 +51,9 @@
#include <nuttx/clock.h>
#include <nuttx/wqueue.h>
#include <nuttx/input/stmpe11.h>
#include <nuttx/input/stmpe811.h>
#if defined(CONFIG_INPUT) && defined(CONFIG_INPUT_STMPE11)
#if defined(CONFIG_INPUT) && defined(CONFIG_INPUT_STMPE811)
/********************************************************************************************
* Pre-Processor Definitions
@ -62,12 +62,12 @@
/* Reference counting is partially implemented, but not needed in the current design.
*/
#undef CONFIG_STMPE11_REFCNT
#undef CONFIG_STMPE811_REFCNT
/* No support for the SPI interface yet */
#ifdef CONFIG_STMPE11_SPI
# error "Only the STMPE11 I2C interface is supported by this driver"
#ifdef CONFIG_STMPE811_SPI
# error "Only the STMPE811 I2C interface is supported by this driver"
#endif
/* Driver support ***************************************************************************/
@ -78,32 +78,32 @@
#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 */
/* STMPE811 Resources ************************************************************************/
#ifndef CONFIG_STMPE811_TSC_DISABLE
# define STMPE811_ADC_NPINS 4 /* Only pins 0-3 can be used for ADC */
# define STMPE811_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 */
# define STMPE811_ADC_NPINS 8 /* All pins can be used for ADC */
# define STMPE811_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 */
#define STMPE811_FLAGS_TSC_INITIALIZED (1 << 0) /* 1: The TSC block has been initialized */
#define STMPE811_FLAGS_GPIO_INITIALIZED (1 << 1) /* 1: The GIO block has been initialized */
#define STMPE811_FLAGS_ADC_INITIALIZED (1 << 2) /* 1: The ADC block has been initialized */
#define STMPE811_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)
#define STMPE811_PENUP_TICKS ((100 + (MSEC_PER_TICK-1)) / MSEC_PER_TICK)
/********************************************************************************************
* Public Types
********************************************************************************************/
/* This describes the state of one contact */
enum stmpe11_contact_3
enum stmpe811_contact_3
{
CONTACT_NONE = 0, /* No contact */
CONTACT_DOWN, /* First contact */
@ -111,47 +111,47 @@ enum stmpe11_contact_3
CONTACT_UP, /* Contact lost */
};
/* This structure describes the results of one STMPE11 sample */
/* This structure describes the results of one STMPE811 sample */
struct stmpe11_sample_s
struct stmpe811_sample_s
{
uint8_t id; /* Sampled touch point ID */
uint8_t contact; /* Contact state (see enum stmpe11_contact_e) */
uint8_t contact; /* Contact state (see enum stmpe811_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 */
/* This structure represents the state of the STMPE811 driver */
struct stmpe11_dev_s
struct stmpe811_dev_s
{
#ifdef CONFIG_STMPE11_MULTIPLE
FAR struct stmpe11_dev_s *flink; /* Supports a singly linked list of drivers */
#ifdef CONFIG_STMPE811_MULTIPLE
FAR struct stmpe811_dev_s *flink; /* Supports a singly linked list of drivers */
#endif
/* Common fields */
FAR struct stmpe11_config_s *config; /* Board configuration data */
FAR struct stmpe811_config_s *config; /* Board configuration data */
sem_t exclsem; /* Manages exclusive access to this structure */
#ifdef CONFIG_STMPE11_SPI
#ifdef CONFIG_STMPE811_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 */
uint8_t inuse; /* STMPE811 pins in use */
uint8_t flags; /* See STMPE811_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
#ifndef CONFIG_STMPE811_TSC_DISABLE
#ifdef CONFIG_STMPE811_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 nwaiters; /* Number of threads waiting for STMPE811 data */
uint8_t id; /* Current touch point ID */
uint8_t minor; /* Touchscreen minor device number */
volatile bool penchange; /* An unreported event is buffered */
@ -162,7 +162,7 @@ struct stmpe11_dev_s
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 */
struct stmpe811_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
@ -170,14 +170,14 @@ struct stmpe11_dev_s
*/
#ifndef CONFIG_DISABLE_POLL
struct pollfd *fds[CONFIG_STMPE11_NPOLLWAITERS];
struct pollfd *fds[CONFIG_STMPE811_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" */
#if !defined(CONFIG_STMPE811_GPIO_DISABLE) && !defined(CONFIG_STMPE811_GPIOINT_DISABLE)
stmpe811_handler_t handlers[STMPE811_GPIO_NPINS]; /* GPIO "interrupt handlers" */
#endif
};
@ -186,37 +186,37 @@ struct stmpe11_dev_s
********************************************************************************************/
/********************************************************************************************
* Name: stmpe11_getreg8
* Name: stmpe811_getreg8
*
* Description:
* Read from an 8-bit STMPE11 register
* Read from an 8-bit STMPE811 register
*
********************************************************************************************/
uint8_t stmpe11_getreg8(FAR struct stmpe11_dev_s *priv, uint8_t regaddr);
uint8_t stmpe811_getreg8(FAR struct stmpe811_dev_s *priv, uint8_t regaddr);
/********************************************************************************************
* Name: stmpe11_putreg8
* Name: stmpe811_putreg8
*
* Description:
* Write a value to an 8-bit STMPE11 register
* Write a value to an 8-bit STMPE811 register
*
********************************************************************************************/
void stmpe11_putreg8(FAR struct stmpe11_dev_s *priv, uint8_t regaddr, uint8_t regval);
void stmpe811_putreg8(FAR struct stmpe811_dev_s *priv, uint8_t regaddr, uint8_t regval);
/********************************************************************************************
* Name: stmpe11_getreg16
* Name: stmpe811_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);
uint16_t stmpe811_getreg16(FAR struct stmpe811_dev_s *priv, uint8_t regaddr);
/********************************************************************************************
* Name: stmpe11_tscint
* Name: stmpe811_tscint
*
* Description:
* Handle touchscreen interrupt events (this function actually executes in the context of
@ -224,12 +224,12 @@ uint16_t stmpe11_getreg16(FAR struct stmpe11_dev_s *priv, uint8_t regaddr);
*
********************************************************************************************/
#ifndef CONFIG_STMPE11_TSC_DISABLE
void stmpe11_tscworker(FAR struct stmpe11_dev_s *priv, uint8_t intsta) weak_function;
#ifndef CONFIG_STMPE811_TSC_DISABLE
void stmpe811_tscworker(FAR struct stmpe811_dev_s *priv, uint8_t intsta) weak_function;
#endif
/********************************************************************************************
* Name: stmpe11_gpioworker
* Name: stmpe811_gpioworker
*
* Description:
* Handle GPIO interrupt events (this function actually executes in the context of the
@ -237,9 +237,9 @@ void stmpe11_tscworker(FAR struct stmpe11_dev_s *priv, uint8_t intsta) weak_func
*
********************************************************************************************/
#if !defined(CONFIG_STMPE11_GPIO_DISABLE) && !defined(CONFIG_STMPE11_GPIOINT_DISABLE)
void stmpe11_gpioworker(FAR struct stmpe11_dev_s *priv) weak_function;
#if !defined(CONFIG_STMPE811_GPIO_DISABLE) && !defined(CONFIG_STMPE811_GPIOINT_DISABLE)
void stmpe811_gpioworker(FAR struct stmpe811_dev_s *priv) weak_function;
#endif
#endif /* CONFIG_INPUT && CONFIG_INPUT_STMPE11 */
#endif /* __DRIVERS_INPUT_STMPE11_H */
#endif /* CONFIG_INPUT && CONFIG_INPUT_STMPE811 */
#endif /* __DRIVERS_INPUT_STMPE811_H */

View File

@ -1,5 +1,5 @@
/****************************************************************************
* drivers/input/stmpe11_adc.c
* drivers/input/stmpe811_adc.c
*
* Copyright (C) 2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
@ -49,11 +49,11 @@
#include <debug.h>
#include <nuttx/arch.h>
#include <nuttx/input/stmpe11.h>
#include <nuttx/input/stmpe811.h>
#include "stmpe11.h"
#include "stmpe811.h"
#if defined(CONFIG_INPUT) && defined(CONFIG_INPUT_STMPE11) && !defined(CONFIG_STMPE11_ADC_DISABLE)
#if defined(CONFIG_INPUT) && defined(CONFIG_INPUT_STMPE811) && !defined(CONFIG_STMPE811_ADC_DISABLE)
/****************************************************************************
* Private Types
@ -72,14 +72,14 @@
****************************************************************************/
/****************************************************************************
* Name: stmpe11_adcinitialize
* Name: stmpe811_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
* handle - The handle previously returned by stmpe811_instantiate
*
* Returned Value:
* Zero is returned on success. Otherwise, a negated errno value is
@ -87,9 +87,9 @@
*
****************************************************************************/
int stmpe11_adcinitialize(STMPE11_HANDLE handle)
int stmpe811_adcinitialize(STMPE811_HANDLE handle)
{
FAR struct stmpe11_dev_s *priv = (FAR struct stmpe11_dev_s *)handle;
FAR struct stmpe811_dev_s *priv = (FAR struct stmpe811_dev_s *)handle;
uint8_t regval;
int ret;
@ -107,13 +107,13 @@ int stmpe11_adcinitialize(STMPE11_HANDLE handle)
/* Enable Clocking for ADC */
regval = stmpe11_getreg8(priv, STMPE11_SYS_CTRL2);
regval = stmpe811_getreg8(priv, STMPE811_SYS_CTRL2);
regval &= ~SYS_CTRL2_ADC_OFF;
stmpe11_putreg8(priv, STMPE11_SYS_CTRL2, regval);
stmpe811_putreg8(priv, STMPE811_SYS_CTRL2, regval);
/* Select Sample Time, bit number and ADC Reference */
stmpe11_putreg8(priv, STMPE11_ADC_CTRL1, priv->config->ctrl1);
stmpe811_putreg8(priv, STMPE811_ADC_CTRL1, priv->config->ctrl1);
/* Wait for 20 ms */
@ -121,23 +121,23 @@ int stmpe11_adcinitialize(STMPE11_HANDLE handle)
/* Select the ADC clock speed */
stmpe11_putreg8(priv, STMPE11_ADC_CTRL2, priv->config->ctrl2);
stmpe811_putreg8(priv, STMPE811_ADC_CTRL2, priv->config->ctrl2);
/* Mark ADC initialized */
priv->flags |= STMPE11_FLAGS_ADC_INITIALIZED;
priv->flags |= STMPE811_FLAGS_ADC_INITIALIZED;
sem_post(&priv->exclsem);
return OK;
}
/****************************************************************************
* Name: stmpe11_adcconfig
* Name: stmpe811_adcconfig
*
* Description:
* Configure a pin for ADC input.
*
* Input Parameters:
* handle - The handle previously returned by stmpe11_instantiate
* handle - The handle previously returned by stmpe811_instantiate
* pin - The ADC pin number
*
* Returned Value:
@ -146,14 +146,14 @@ int stmpe11_adcinitialize(STMPE11_HANDLE handle)
*
****************************************************************************/
int stmpe11_adcconfig(STMPE11_HANDLE handle, int pin)
int stmpe811_adcconfig(STMPE811_HANDLE handle, int pin)
{
FAR struct stmpe11_dev_s *priv = (FAR struct stmpe11_dev_s *)handle;
FAR struct stmpe811_dev_s *priv = (FAR struct stmpe811_dev_s *)handle;
uint8_t pinmask = GPIO_PIN(pin);
uint8_t regval;
int ret;
DEBUGASSERT(handle && (unsigned)pin < STMPE11_ADC_NPINS);
DEBUGASSERT(handle && (unsigned)pin < STMPE811_ADC_NPINS);
/* Get exclusive access to the device structure */
@ -179,9 +179,9 @@ int stmpe11_adcconfig(STMPE11_HANDLE handle, int pin)
* ADC_CTRL1_REF_SEL bit).
*/
regval = stmpe11_getreg8(priv, STMPE11_GPIO_AF);
regval = stmpe811_getreg8(priv, STMPE811_GPIO_AF);
regval &= ~pinmask;
stmpe11_putreg8(priv, STMPE11_GPIO_AF, regval);
stmpe811_putreg8(priv, STMPE811_GPIO_AF, regval);
/* Mark the pin as 'in use' */
@ -191,13 +191,13 @@ int stmpe11_adcconfig(STMPE11_HANDLE handle, int pin)
}
/****************************************************************************
* Name: stmpe11_adcread
* Name: stmpe811_adcread
*
* Description:
* Read the converted analog input value from the select pin.
*
* Input Parameters:
* handle - The handle previously returned by stmpe11_instantiate
* handle - The handle previously returned by stmpe811_instantiate
* pin - The ADC pin number
*
* Returned Value:
@ -205,9 +205,9 @@ int stmpe11_adcconfig(STMPE11_HANDLE handle, int pin)
*
****************************************************************************/
uint16_t stmpe11_adcread(STMPE11_HANDLE handle, int pin)
uint16_t stmpe811_adcread(STMPE811_HANDLE handle, int pin)
{
FAR struct stmpe11_dev_s *priv = (FAR struct stmpe11_dev_s *)handle;
FAR struct stmpe811_dev_s *priv = (FAR struct stmpe811_dev_s *)handle;
uint8_t pinmask = GPIO_PIN(pin);
uint8_t regval;
int i;
@ -229,7 +229,7 @@ uint16_t stmpe11_adcread(STMPE11_HANDLE handle, int pin)
* ADC CAPT register.
*/
stmpe11_putreg8(priv, STMPE11_ADC_CAPT, pinmask);
stmpe811_putreg8(priv, STMPE811_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.
@ -248,7 +248,7 @@ uint16_t stmpe11_adcread(STMPE11_HANDLE handle, int pin)
/* Check if the conversion is complete */
regval = stmpe11_getreg8(priv, STMPE11_ADC_CAPT);
regval = stmpe811_getreg8(priv, STMPE811_ADC_CAPT);
if ((regval & pinmask) != 0)
{
break;
@ -259,8 +259,8 @@ uint16_t stmpe11_adcread(STMPE11_HANDLE handle, int pin)
* from the channel register associated with the pin.
*/
return stmpe11_getreg16(priv, STMPE11_ADC_DATACH(pin));
return stmpe811_getreg16(priv, STMPE811_ADC_DATACH(pin));
}
#endif /* CONFIG_INPUT && CONFIG_INPUT_STMPE11 && !CONFIG_STMPE11_ADC_DISABLE */
#endif /* CONFIG_INPUT && CONFIG_INPUT_STMPE811 && !CONFIG_STMPE811_ADC_DISABLE */

View File

@ -1,5 +1,5 @@
/****************************************************************************
* drivers/input/stmpe11_base.c
* drivers/input/stmpe811_base.c
*
* Copyright (C) 2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
@ -48,11 +48,11 @@
#include <debug.h>
#include <nuttx/kmalloc.h>
#include <nuttx/input/stmpe11.h>
#include <nuttx/input/stmpe811.h>
#include "stmpe11.h"
#include "stmpe811.h"
#if defined(CONFIG_INPUT) && defined(CONFIG_INPUT_STMPE11)
#if defined(CONFIG_INPUT) && defined(CONFIG_INPUT_STMPE811)
/****************************************************************************
* Private Types
@ -62,17 +62,17 @@
* Private Data
****************************************************************************/
/* If only a single STMPE11 device is supported, then the driver state
/* If only a single STMPE811 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;
#ifndef CONFIG_STMPE811_MULTIPLE
static struct stmpe811_dev_s g_stmpe811;
/* Otherwise, we will need to maintain allocated driver instances in a list */
#else
static struct stmpe11_dev_s *g_stmpe11list;
static struct stmpe811_dev_s *g_stmpe811list;
#endif
/****************************************************************************
@ -80,56 +80,56 @@ static struct stmpe11_dev_s *g_stmpe11list;
****************************************************************************/
/****************************************************************************
* Name: stmpe11_worker
* Name: stmpe811_worker
*
* Description:
* This is the "bottom half" of the STMPE11 interrupt handler
* This is the "bottom half" of the STMPE811 interrupt handler
*
****************************************************************************/
static void stmpe11_worker(FAR void *arg)
static void stmpe811_worker(FAR void *arg)
{
FAR struct stmpe11_dev_s *priv = (FAR struct stmpe11_dev_s *)arg;
FAR struct stmpe811_dev_s *priv = (FAR struct stmpe811_dev_s *)arg;
uint8_t regval;
DEBUGASSERT(priv && priv->config);
/* Get the global interrupt status */
regval = stmpe11_getreg8(priv, STMPE11_INT_STA);
regval = stmpe811_getreg8(priv, STMPE811_INT_STA);
/* Check for a touchscreen interrupt */
#ifndef CONFIG_STMPE11_TSC_DISABLE
#ifndef CONFIG_STMPE811_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)
if (stmpe811_tscworker)
#endif
{
stmpe11_tscworker(priv, regval);
stmpe811_tscworker(priv, regval);
}
stmpe11_putreg8(priv, STMPE11_INT_STA, (INT_TOUCH_DET|INT_FIFO_TH|INT_FIFO_OFLOW));
stmpe811_putreg8(priv, STMPE811_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 !defined(CONFIG_STMPE811_GPIO_DISABLE) && !defined(CONFIG_STMPE811_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)
if (stmpe811_gpioworker)
#endif
{
stmpe11_gpioworker(priv);
stmpe811_gpioworker(priv);
}
stmpe11_putreg8(priv, STMPE11_INT_STA, INT_GPIO);
stmpe811_putreg8(priv, STMPE811_INT_STA, INT_GPIO);
regval &= ~INT_GPIO;
}
#endif
@ -138,34 +138,34 @@ static void stmpe11_worker(FAR void *arg)
if (regval != 0)
{
stmpe11_putreg8(priv, STMPE11_INT_STA, regval);
stmpe811_putreg8(priv, STMPE811_INT_STA, regval);
}
/* Re-enable the STMPE11 GPIO interrupt */
/* Re-enable the STMPE811 GPIO interrupt */
priv->config->enable(priv->config, true);
}
/****************************************************************************
* Name: stmpe11_interrupt
* Name: stmpe811_interrupt
*
* Description:
* The STMPE11 interrupt handler
* The STMPE811 interrupt handler
*
****************************************************************************/
static int stmpe11_interrupt(int irq, FAR void *context)
static int stmpe811_interrupt(int irq, FAR void *context)
{
FAR struct stmpe11_dev_s *priv;
FAR struct stmpe11_config_s *config;
FAR struct stmpe811_dev_s *priv;
FAR struct stmpe811_config_s *config;
int ret;
/* Which STMPE11 device caused the interrupt? */
/* Which STMPE811 device caused the interrupt? */
#ifndef CONFIG_STMPE11_MULTIPLE
priv = &g_stmpe11;
#ifndef CONFIG_STMPE811_MULTIPLE
priv = &g_stmpe811;
#else
for (priv = g_stmpe11list;
for (priv = g_stmpe811list;
priv && priv->config->irq != irq;
priv = priv->flink);
@ -190,12 +190,12 @@ static int stmpe11_interrupt(int irq, FAR void *context)
if (work_available(&priv->work))
{
/* Yes.. Transfer processing to the worker thread. Since STMPE11
/* Yes.. Transfer processing to the worker thread. Since STMPE811
* 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);
ret = work_queue(&priv->work, stmpe811_worker, priv, 0);
if (ret != 0)
{
illdbg("Failed to queue work: %d\n", ret);
@ -209,22 +209,22 @@ static int stmpe11_interrupt(int irq, FAR void *context)
}
/****************************************************************************
* Name: stmpe11_checkid
* Name: stmpe811_checkid
*
* Description:
* Read and verify the STMPE11 chip ID
* Read and verify the STMPE811 chip ID
*
****************************************************************************/
static int stmpe11_checkid(FAR struct stmpe11_dev_s *priv)
static int stmpe811_checkid(FAR struct stmpe811_dev_s *priv)
{
uint16_t devid = 0;
/* Read device ID */
devid = stmpe11_getreg8(priv, STMPE11_CHIP_ID);
devid = stmpe811_getreg8(priv, STMPE811_CHIP_ID);
devid = (uint32_t)(devid << 8);
devid |= (uint32_t)stmpe11_getreg8(priv, STMPE11_CHIP_ID+1);
devid |= (uint32_t)stmpe811_getreg8(priv, STMPE811_CHIP_ID+1);
ivdbg("devid: %04x\n", devid);
if (devid != (uint16_t)CHIP_ID)
@ -238,18 +238,18 @@ static int stmpe11_checkid(FAR struct stmpe11_dev_s *priv)
}
/****************************************************************************
* Name: stmpe11_reset
* Name: stmpe811_reset
*
* Description:
* Reset the STMPE11
* Reset the STMPE811
*
****************************************************************************/
static void stmpe11_reset(FAR struct stmpe11_dev_s *priv)
static void stmpe811_reset(FAR struct stmpe811_dev_s *priv)
{
/* Power Down the STMPE11 */
/* Power Down the STMPE811 */
stmpe11_putreg8(priv, STMPE11_SYS_CTRL1, SYS_CTRL1_SOFTRESET);
stmpe811_putreg8(priv, STMPE811_SYS_CTRL1, SYS_CTRL1_SOFTRESET);
/* Wait a bit */
@ -257,7 +257,7 @@ static void stmpe11_reset(FAR struct stmpe11_dev_s *priv)
/* Then power on again. All registers will be in their reset state. */
stmpe11_putreg8(priv, STMPE11_SYS_CTRL1, 0);
stmpe811_putreg8(priv, STMPE811_SYS_CTRL1, 0);
}
/****************************************************************************
@ -265,10 +265,10 @@ static void stmpe11_reset(FAR struct stmpe11_dev_s *priv)
****************************************************************************/
/****************************************************************************
* Name: stmpe11_instantiate
* Name: stmpe811_instantiate
*
* Description:
* Instantiate and configure the STMPE11 device driver to use the provided
* Instantiate and configure the STMPE811 device driver to use the provided
* I2C or SPIdevice instance.
*
* Input Parameters:
@ -277,41 +277,41 @@ static void stmpe11_reset(FAR struct stmpe11_dev_s *priv)
*
* 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
* to configure the STMPE811 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)
#ifdef CONFIG_STMPE811_SPI
STMPE811_HANDLE stmpe811_instantiate(FAR struct spi_dev_s *dev,
FAR struct stmpe811_config_s *config)
#else
STMPE11_HANDLE stmpe11_instantiate(FAR struct i2c_dev_s *dev,
FAR struct stmpe11_config_s *config)
STMPE811_HANDLE stmpe811_instantiate(FAR struct i2c_dev_s *dev,
FAR struct stmpe811_config_s *config)
#endif
{
FAR struct stmpe11_dev_s *priv;
FAR struct stmpe811_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));
#ifdef CONFIG_STMPE811_MULTIPLE
priv = (FAR struct stmpe811_dev_s *)kzalloc(sizeof(struct stmpe811_dev_s));
if (!priv)
{
return NULL;
}
/* And save the device structure in the list of STMPE11 so that we can find it later */
/* And save the device structure in the list of STMPE811 so that we can find it later */
priv->flink = g_stmpe11list;
g_stmpe11list = priv;
priv->flink = g_stmpe811list;
g_stmpe811list = priv;
#else
/* Use the one-and-only STMPE11 driver instance */
/* Use the one-and-only STMPE811 driver instance */
priv = &g_stmpe11;
priv = &g_stmpe811;
#endif
/* Initialize the device state structure */
@ -319,7 +319,7 @@ STMPE11_HANDLE stmpe11_instantiate(FAR struct i2c_dev_s *dev,
sem_init(&priv->exclsem, 0, 1);
priv->config = config;
#ifdef CONFIG_STMPE11_SPI
#ifdef CONFIG_STMPE811_SPI
priv->spi = dev;
#else
priv->i2c = dev;
@ -333,79 +333,79 @@ STMPE11_HANDLE stmpe11_instantiate(FAR struct i2c_dev_s *dev,
I2C_SETFREQUENCY(dev, config->frequency);
#endif
/* Read and verify the STMPE11 chip ID */
/* Read and verify the STMPE811 chip ID */
ret = stmpe11_checkid(priv);
ret = stmpe811_checkid(priv);
if (ret < 0)
{
#ifdef CONFIG_STMPE11_MULTIPLE
#ifdef CONFIG_STMPE811_MULTIPLE
kfree(priv);
#endif
return NULL;
}
/* Generate STMPE11 Software reset */
/* Generate STMPE811 Software reset */
stmpe11_reset(priv);
stmpe811_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 = stmpe811_getreg8(priv, STMPE811_INT_CTRL);
#ifdef CONFIG_STMPE811_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
#ifdef CONFIG_STMPE811_EDGE
regval |= INT_CTRL_INT_TYPE; /* Edge interrupt */
#else
regval &= ~INT_CTRL_INT_TYPE; /* Level interrupt */
#endif
stmpe11_putreg8(priv, STMPE11_INT_CTRL, regval);
stmpe811_putreg8(priv, STMPE811_INT_CTRL, regval);
/* Attach the STMPE11 interrupt handler. */
/* Attach the STMPE811 interrupt handler. */
config->attach(config, stmpe11_interrupt);
config->attach(config, stmpe811_interrupt);
/* Clear any pending interrupts */
stmpe11_putreg8(priv, STMPE11_INT_STA, INT_ALL);
stmpe811_putreg8(priv, STMPE811_INT_STA, INT_ALL);
config->clear(config);
config->enable(config, true);
/* Enable global interrupts */
regval = stmpe11_getreg8(priv, STMPE11_INT_CTRL);
regval = stmpe811_getreg8(priv, STMPE811_INT_CTRL);
regval |= INT_CTRL_GLOBAL_INT;
stmpe11_putreg8(priv, STMPE11_INT_CTRL, regval);
stmpe811_putreg8(priv, STMPE811_INT_CTRL, regval);
/* Return our private data structure as an opaque handle */
return (STMPE11_HANDLE)priv;
return (STMPE811_HANDLE)priv;
}
/****************************************************************************
* Name: stmpe11_getreg8
* Name: stmpe811_getreg8
*
* Description:
* Read from an 8-bit STMPE11 register
* Read from an 8-bit STMPE811 register
*
****************************************************************************/
#ifdef CONFIG_STMPE11_I2C
uint8_t stmpe11_getreg8(FAR struct stmpe11_dev_s *priv, uint8_t regaddr)
#ifdef CONFIG_STMPE811_I2C
uint8_t stmpe811_getreg8(FAR struct stmpe811_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
* Start - I2C_Write_Address - STMPE811_Reg_Address -
* Repeated_Start - I2C_Read_Address - STMPE811_Read_Data - STOP
*/
struct i2c_msg_s msg[2];
uint8_t regval;
int ret;
/* Setup 8-bit STMPE11 address write message */
/* Setup 8-bit STMPE811 address write message */
msg[0].addr = priv->config->address; /* 7-bit address */
msg[0].flags = 0; /* Write transaction, beginning with START */
@ -413,7 +413,7 @@ uint8_t stmpe11_getreg8(FAR struct stmpe11_dev_s *priv, uint8_t regaddr)
msg[0].length = 1; /* Send one byte following the address
* (no STOP) */
/* Set up the 8-bit STMPE11 data read message */
/* Set up the 8-bit STMPE811 data read message */
msg[1].addr = priv->config->address; /* 7-bit address */
msg[1].flags = I2C_M_READ; /* Read transaction, beginning with Re-START */
@ -430,7 +430,7 @@ uint8_t stmpe11_getreg8(FAR struct stmpe11_dev_s *priv, uint8_t regaddr)
return 0;
}
#ifdef CONFIG_STMPE11_REGDEBUG
#ifdef CONFIG_STMPE811_REGDEBUG
dbg("%02x->%02x\n", regaddr, regval);
#endif
return regval;
@ -438,38 +438,38 @@ uint8_t stmpe11_getreg8(FAR struct stmpe11_dev_s *priv, uint8_t regaddr)
#endif
/****************************************************************************
* Name: stmpe11_putreg8
* Name: stmpe811_putreg8
*
* Description:
* Write a value to an 8-bit STMPE11 register
* Write a value to an 8-bit STMPE811 register
*
****************************************************************************/
#ifdef CONFIG_STMPE11_I2C
void stmpe11_putreg8(FAR struct stmpe11_dev_s *priv,
uint8_t regaddr, uint8_t regval)
#ifdef CONFIG_STMPE811_I2C
void stmpe811_putreg8(FAR struct stmpe811_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
* Start - I2C_Write_Address - STMPE811_Reg_Address - STMPE811_Write_Data - STOP
*/
struct i2c_msg_s msg;
uint8_t txbuffer[2];
int ret;
#ifdef CONFIG_STMPE11_REGDEBUG
#ifdef CONFIG_STMPE811_REGDEBUG
dbg("%02x<-%02x\n", regaddr, regval);
#endif
/* Setup to the data to be transferred. Two bytes: The STMPE11 register
/* Setup to the data to be transferred. Two bytes: The STMPE811 register
* address followed by one byte of data.
*/
txbuffer[0] = regaddr;
txbuffer[1] = regval;
/* Setup 8-bit STMPE11 address write message */
/* Setup 8-bit STMPE811 address write message */
msg.addr = priv->config->address; /* 7-bit address */
msg.flags = 0; /* Write transaction, beginning with START */
@ -488,21 +488,21 @@ void stmpe11_putreg8(FAR struct stmpe11_dev_s *priv,
#endif
/****************************************************************************
* Name: stmpe11_getreg16
* Name: stmpe811_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)
#ifdef CONFIG_STMPE811_I2C
uint16_t stmpe811_getreg16(FAR struct stmpe811_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
* Start - I2C_Write_Address - STMPE811_Reg_Address -
* Repeated_Start - I2C_Read_Address - STMPE811_Read_Data_1 -
* STMPE811_Read_Data_2 - STOP
*/
@ -510,7 +510,7 @@ uint16_t stmpe11_getreg16(FAR struct stmpe11_dev_s *priv, uint8_t regaddr)
uint8_t rxbuffer[2];
int ret;
/* Setup 8-bit STMPE11 address write message */
/* Setup 8-bit STMPE811 address write message */
msg[0].addr = priv->config->address; /* 7-bit address */
msg[0].flags = 0; /* Write transaction, beginning with START */
@ -518,7 +518,7 @@ uint16_t stmpe11_getreg16(FAR struct stmpe11_dev_s *priv, uint8_t regaddr)
msg[0].length = 1; /* Send one byte following the address
* (no STOP) */
/* Set up the 8-bit STMPE11 data read message */
/* Set up the 8-bit STMPE811 data read message */
msg[1].addr = priv->config->address; /* 7-bit address */
msg[1].flags = I2C_M_READ; /* Read transaction, beginning with Re-START */
@ -535,12 +535,12 @@ uint16_t stmpe11_getreg16(FAR struct stmpe11_dev_s *priv, uint8_t regaddr)
return 0;
}
#ifdef CONFIG_STMPE11_REGDEBUG
#ifdef CONFIG_STMPE811_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 */
#endif /* CONFIG_INPUT && CONFIG_INPUT_STMPE811 */

View File

@ -1,5 +1,5 @@
/****************************************************************************
* drivers/input/stmpe11_gpio.c
* drivers/input/stmpe811_gpio.c
*
* Copyright (C) 2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
@ -47,11 +47,11 @@
#include <errno.h>
#include <debug.h>
#include <nuttx/input/stmpe11.h>
#include <nuttx/input/stmpe811.h>
#include "stmpe11.h"
#include "stmpe811.h"
#if defined(CONFIG_INPUT) && defined(CONFIG_INPUT_STMPE11) && !defined(CONFIG_STMPE11_GPIO_DISABLE)
#if defined(CONFIG_INPUT) && defined(CONFIG_INPUT_STMPE811) && !defined(CONFIG_STMPE811_GPIO_DISABLE)
/****************************************************************************
* Private Types
@ -66,13 +66,13 @@
****************************************************************************/
/****************************************************************************
* Name: stmpe11_gpioinit
* Name: stmpe811_gpioinit
*
* Description:
* Initialize the GPIO interrupt subsystem
*
* Input Parameters:
* handle - The handle previously returned by stmpe11_instantiate
* handle - The handle previously returned by stmpe811_instantiate
*
* Returned Value:
* Zero is returned on success. Otherwise, a negated errno value is
@ -80,31 +80,31 @@
*
****************************************************************************/
static void stmpe11_gpioinit(FAR struct stmpe11_dev_s *priv)
static void stmpe811_gpioinit(FAR struct stmpe811_dev_s *priv)
{
uint8_t regval;
if ((priv->flags & STMPE11_FLAGS_GPIO_INITIALIZED) == 0)
if ((priv->flags & STMPE811_FLAGS_GPIO_INITIALIZED) == 0)
{
/* Enable Clocking for GPIO */
regval = stmpe11_getreg8(priv, STMPE11_SYS_CTRL2);
regval = stmpe811_getreg8(priv, STMPE811_SYS_CTRL2);
regval &= ~SYS_CTRL2_GPIO_OFF;
stmpe11_putreg8(priv, STMPE11_SYS_CTRL2, regval);
stmpe811_putreg8(priv, STMPE811_SYS_CTRL2, regval);
/* Disable all GPIO interrupts */
stmpe11_putreg8(priv, STMPE11_GPIO_EN, 0);
stmpe811_putreg8(priv, STMPE811_GPIO_EN, 0);
/* Enable global GPIO interrupts */
#ifndef CONFIG_STMPE11_GPIOINT_DISABLE
regval = stmpe11_getreg8(priv, STMPE11_INT_EN);
#ifndef CONFIG_STMPE811_GPIOINT_DISABLE
regval = stmpe811_getreg8(priv, STMPE811_INT_EN);
regval |= INT_GPIO;
stmpe11_putreg8(priv, STMPE11_INT_EN, regval);
stmpe811_putreg8(priv, STMPE811_INT_EN, regval);
#endif
priv->flags |= STMPE11_FLAGS_GPIO_INITIALIZED;
priv->flags |= STMPE811_FLAGS_GPIO_INITIALIZED;
}
}
@ -113,13 +113,13 @@ static void stmpe11_gpioinit(FAR struct stmpe11_dev_s *priv)
****************************************************************************/
/****************************************************************************
* Name: stmpe11_gpioconfig
* Name: stmpe811_gpioconfig
*
* Description:
* Configure an STMPE11 GPIO pin
* Configure an STMPE811 GPIO pin
*
* Input Parameters:
* handle - The handle previously returned by stmpe11_instantiate
* handle - The handle previously returned by stmpe811_instantiate
* pinconfig - Bit-encoded pin configuration
*
* Returned Value:
@ -128,15 +128,15 @@ static void stmpe11_gpioinit(FAR struct stmpe11_dev_s *priv)
*
****************************************************************************/
int stmpe11_gpioconfig(STMPE11_HANDLE handle, uint8_t pinconfig)
int stmpe811_gpioconfig(STMPE811_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;
FAR struct stmpe811_dev_s *priv = (FAR struct stmpe811_dev_s *)handle;
int pin = (pinconfig & STMPE811_GPIO_PIN_MASK) >> STMPE811_GPIO_PIN_SHIFT;
uint8_t pinmask = (1 << pin);
uint8_t regval;
int ret;
DEBUGASSERT(handle && (unsigned)pin < STMPE11_GPIO_NPINS);
DEBUGASSERT(handle && (unsigned)pin < STMPE811_GPIO_NPINS);
/* Get exclusive access to the device structure */
@ -159,41 +159,41 @@ int stmpe11_gpioconfig(STMPE11_HANDLE handle, uint8_t pinconfig)
/* Make sure that the GPIO block has been initialized */
stmpe11_gpioinit(priv);
stmpe811_gpioinit(priv);
/* Set the alternate function bit for the pin, making it a GPIO */
regval = stmpe11_getreg8(priv, STMPE11_GPIO_AF);
regval = stmpe811_getreg8(priv, STMPE811_GPIO_AF);
regval |= pinmask;
stmpe11_putreg8(priv, STMPE11_GPIO_AF, regval);
stmpe811_putreg8(priv, STMPE811_GPIO_AF, regval);
/* Is the pin an input or an output? */
if ((pinconfig & STMPE11_GPIO_DIR) == STMPE11_GPIO_OUTPUT)
if ((pinconfig & STMPE811_GPIO_DIR) == STMPE811_GPIO_OUTPUT)
{
/* The pin is an output */
regval = stmpe11_getreg8(priv, STMPE11_GPIO_DIR);
regval = stmpe811_getreg8(priv, STMPE811_GPIO_DIR);
regval &= ~pinmask;
stmpe11_putreg8(priv, STMPE11_GPIO_DIR, regval);
stmpe811_putreg8(priv, STMPE811_GPIO_DIR, regval);
/* Set its initial output value */
stmpe11_gpiowrite(handle, pinconfig,
(pinconfig & STMPE11_GPIO_VALUE) != STMPE11_GPIO_ZERO);
stmpe811_gpiowrite(handle, pinconfig,
(pinconfig & STMPE811_GPIO_VALUE) != STMPE811_GPIO_ZERO);
}
else
{
/* It is an input */
regval = stmpe11_getreg8(priv, STMPE11_GPIO_DIR);
regval = stmpe811_getreg8(priv, STMPE811_GPIO_DIR);
regval |= pinmask;
stmpe11_putreg8(priv, STMPE11_GPIO_DIR, regval);
stmpe811_putreg8(priv, STMPE811_GPIO_DIR, regval);
/* Set up the falling edge detection */
regval = stmpe11_getreg8(priv, STMPE11_GPIO_FE);
if ((pinconfig & STMPE11_GPIO_FALLING) != 0)
regval = stmpe811_getreg8(priv, STMPE811_GPIO_FE);
if ((pinconfig & STMPE811_GPIO_FALLING) != 0)
{
regval |= pinmask;
}
@ -201,12 +201,12 @@ int stmpe11_gpioconfig(STMPE11_HANDLE handle, uint8_t pinconfig)
{
regval &= pinmask;
}
stmpe11_putreg8(priv, STMPE11_GPIO_FE, regval);
stmpe811_putreg8(priv, STMPE811_GPIO_FE, regval);
/* Set up the rising edge detection */
regval = stmpe11_getreg8(priv, STMPE11_GPIO_RE);
if ((pinconfig & STMPE11_GPIO_FALLING) != 0)
regval = stmpe811_getreg8(priv, STMPE811_GPIO_RE);
if ((pinconfig & STMPE811_GPIO_FALLING) != 0)
{
regval |= pinmask;
}
@ -214,13 +214,13 @@ int stmpe11_gpioconfig(STMPE11_HANDLE handle, uint8_t pinconfig)
{
regval &= pinmask;
}
stmpe11_putreg8(priv, STMPE11_GPIO_RE, regval);
stmpe811_putreg8(priv, STMPE811_GPIO_RE, regval);
/* Disable interrupts for now */
regval = stmpe11_getreg8(priv, STMPE11_GPIO_EN);
regval = stmpe811_getreg8(priv, STMPE811_GPIO_EN);
regval &= ~pinmask;
stmpe11_putreg8(priv, STMPE11_GPIO_EN, regval);
stmpe811_putreg8(priv, STMPE811_GPIO_EN, regval);
}
/* Mark the pin as 'in use' */
@ -231,13 +231,13 @@ int stmpe11_gpioconfig(STMPE11_HANDLE handle, uint8_t pinconfig)
}
/****************************************************************************
* Name: stmpe11_gpiowrite
* Name: stmpe811_gpiowrite
*
* Description:
* Set or clear the GPIO output
*
* Input Parameters:
* handle - The handle previously returned by stmpe11_instantiate
* handle - The handle previously returned by stmpe811_instantiate
* pinconfig - Bit-encoded pin configuration
* value = true: write logic '1'; false: write logic '0;
*
@ -246,13 +246,13 @@ int stmpe11_gpioconfig(STMPE11_HANDLE handle, uint8_t pinconfig)
*
****************************************************************************/
void stmpe11_gpiowrite(STMPE11_HANDLE handle, uint8_t pinconfig, bool value)
void stmpe811_gpiowrite(STMPE811_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;
FAR struct stmpe811_dev_s *priv = (FAR struct stmpe811_dev_s *)handle;
int pin = (pinconfig & STMPE811_GPIO_PIN_MASK) >> STMPE811_GPIO_PIN_SHIFT;
int ret;
DEBUGASSERT(handle && (unsigned)pin < STMPE11_GPIO_NPINS);
DEBUGASSERT(handle && (unsigned)pin < STMPE811_GPIO_NPINS);
/* Get exclusive access to the device structure */
@ -269,26 +269,26 @@ void stmpe11_gpiowrite(STMPE11_HANDLE handle, uint8_t pinconfig, bool value)
{
/* Set the output valu(s)e by writing to the SET register */
stmpe11_putreg8(priv, STMPE11_GPIO_SETPIN, (1 << pin));
stmpe811_putreg8(priv, STMPE811_GPIO_SETPIN, (1 << pin));
}
else
{
/* Clear the output value(s) by writing to the CLR register */
stmpe11_putreg8(priv, STMPE11_GPIO_CLRPIN, (1 << pin));
stmpe811_putreg8(priv, STMPE811_GPIO_CLRPIN, (1 << pin));
}
sem_post(&priv->exclsem);
}
/****************************************************************************
* Name: stmpe11_gpioread
* Name: stmpe811_gpioread
*
* Description:
* Set or clear the GPIO output
*
* Input Parameters:
* handle - The handle previously returned by stmpe11_instantiate
* handle - The handle previously returned by stmpe811_instantiate
* pinconfig - Bit-encoded pin configuration
* value - The location to return the state of the GPIO pin
*
@ -298,14 +298,14 @@ void stmpe11_gpiowrite(STMPE11_HANDLE handle, uint8_t pinconfig, bool value)
*
****************************************************************************/
int stmpe11_gpioread(STMPE11_HANDLE handle, uint8_t pinconfig, bool *value)
int stmpe811_gpioread(STMPE811_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;
FAR struct stmpe811_dev_s *priv = (FAR struct stmpe811_dev_s *)handle;
int pin = (pinconfig & STMPE811_GPIO_PIN_MASK) >> STMPE811_GPIO_PIN_SHIFT;
uint8_t regval;
int ret;
DEBUGASSERT(handle && (unsigned)pin < STMPE11_GPIO_NPINS);
DEBUGASSERT(handle && (unsigned)pin < STMPE811_GPIO_NPINS);
/* Get exclusive access to the device structure */
@ -317,14 +317,14 @@ int stmpe11_gpioread(STMPE11_HANDLE handle, uint8_t pinconfig, bool *value)
return -errval;
}
regval = stmpe11_getreg8(priv, STMPE11_GPIO_MPSTA);
regval = stmpe811_getreg8(priv, STMPE811_GPIO_MPSTA);
*value = ((regval & GPIO_PIN(pin)) != 0);
sem_post(&priv->exclsem);
return OK;
}
/***********************************************************************************
* Name: stmpe11_gpioattach
* Name: stmpe811_gpioattach
*
* Description:
* Attach to a GPIO interrupt input pin and enable interrupts on the pin. Using
@ -335,7 +335,7 @@ int stmpe11_gpioread(STMPE11_HANDLE handle, uint8_t pinconfig, bool *value)
* context of the worker thread.
*
* Input Parameters:
* handle - The handle previously returned by stmpe11_instantiate
* handle - The handle previously returned by stmpe811_instantiate
* pinconfig - Bit-encoded pin configuration
* handler - The handler that will be called when the interrupt occurs.
*
@ -345,16 +345,16 @@ int stmpe11_gpioread(STMPE11_HANDLE handle, uint8_t pinconfig, bool *value)
*
************************************************************************************/
#ifndef CONFIG_STMPE11_GPIOINT_DISABLE
int stmpe11_gpioattach(STMPE11_HANDLE handle, uint8_t pinconfig,
stmpe11_handler_t handler)
#ifndef CONFIG_STMPE811_GPIOINT_DISABLE
int stmpe811_gpioattach(STMPE811_HANDLE handle, uint8_t pinconfig,
stmpe811_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;
FAR struct stmpe811_dev_s *priv = (FAR struct stmpe811_dev_s *)handle;
int pin = (pinconfig & STMPE811_GPIO_PIN_MASK) >> STMPE811_GPIO_PIN_SHIFT;
uint8_t regval;
int ret;
DEBUGASSERT(handle && (unsigned)pin < STMPE11_GPIO_NPINS);
DEBUGASSERT(handle && (unsigned)pin < STMPE811_GPIO_NPINS);
/* Get exclusive access to the device structure */
@ -368,7 +368,7 @@ int stmpe11_gpioattach(STMPE11_HANDLE handle, uint8_t pinconfig,
/* Make sure that the GPIO interrupt system has been gpioinitialized */
stmpe11_gpioinit(priv);
stmpe811_gpioinit(priv);
/* Set/clear the handler */
@ -376,7 +376,7 @@ int stmpe11_gpioattach(STMPE11_HANDLE handle, uint8_t pinconfig,
/* If an handler has provided, then we are enabling interrupts */
regval = stmpe11_getreg8(priv, STMPE11_GPIO_EN);
regval = stmpe811_getreg8(priv, STMPE811_GPIO_EN);
if (handler)
{
/* Enable interrupts for this GPIO */
@ -389,7 +389,7 @@ int stmpe11_gpioattach(STMPE11_HANDLE handle, uint8_t pinconfig,
regval &= ~GPIO_PIN(pin);
}
stmpe11_putreg8(priv, STMPE11_GPIO_EN, regval);
stmpe811_putreg8(priv, STMPE811_GPIO_EN, regval);
sem_post(&priv->exclsem);
return OK;
@ -397,7 +397,7 @@ int stmpe11_gpioattach(STMPE11_HANDLE handle, uint8_t pinconfig,
#endif
/****************************************************************************
* Name: stmpe11_gpioworker
* Name: stmpe811_gpioworker
*
* Description:
* Handle GPIO interrupt events (this function actually executes in the
@ -405,8 +405,8 @@ int stmpe11_gpioattach(STMPE11_HANDLE handle, uint8_t pinconfig,
*
****************************************************************************/
#ifndef CONFIG_STMPE11_GPIOINT_DISABLE
void stmpe11_gpioworker(FAR struct stmpe11_dev_s *priv)
#ifndef CONFIG_STMPE811_GPIOINT_DISABLE
void stmpe811_gpioworker(FAR struct stmpe811_dev_s *priv)
{
uint8_t regval;
uint8_t pinmask;
@ -414,11 +414,11 @@ void stmpe11_gpioworker(FAR struct stmpe11_dev_s *priv)
/* Get the set of pending GPIO interrupts */
regval = stmpe11_getreg8(priv, STMPE11_GPIO_INTSTA);
regval = stmpe811_getreg8(priv, STMPE811_GPIO_INTSTA);
/* Look at each pin */
for (pin = 0; pin < SMTPE11_GPIO_NPINS; pin++)
for (pin = 0; pin < STMPE811_GPIO_NPINS; pin++)
{
pinmask = GPIO_INT(pin);
if ((regval & pinmask) != 0)
@ -444,11 +444,11 @@ void stmpe11_gpioworker(FAR struct stmpe11_dev_s *priv)
* pin position in the status register.
*/
stmpe11_putreg8(priv, STMPE11_GPIO_INTSTA, pinmask);
stmpe811_putreg8(priv, STMPE811_GPIO_INTSTA, pinmask);
}
}
}
#endif
#endif /* CONFIG_INPUT && CONFIG_INPUT_STMPE11 && !CONFIG_STMPE11_GPIO_DISABLE */
#endif /* CONFIG_INPUT && CONFIG_INPUT_STMPE811 && !CONFIG_STMPE811_GPIO_DISABLE */

View File

@ -1,5 +1,5 @@
/****************************************************************************
* drivers/input/stmpe11_temp.c
* drivers/input/stmpe811_temp.c
*
* Copyright (C) 2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
@ -47,11 +47,11 @@
#include <errno.h>
#include <debug.h>
#include <nuttx/input/stmpe11.h>
#include <nuttx/input/stmpe811.h>
#include "stmpe11.h"
#include "stmpe811.h"
#if defined(CONFIG_INPUT) && defined(CONFIG_INPUT_STMPE11) && !defined(CONFIG_STMPE11_TEMP_DISABLE)
#if defined(CONFIG_INPUT) && defined(CONFIG_INPUT_STMPE811) && !defined(CONFIG_STMPE811_TEMP_DISABLE)
/****************************************************************************
* Private Types
@ -70,13 +70,13 @@
****************************************************************************/
/****************************************************************************
* Name: stmpe11_tempinitialize
* Name: stmpe811_tempinitialize
*
* Description:
* Configure the temperature sensor.
*
* Input Parameters:
* handle - The handle previously returned by stmpe11_instantiate
* handle - The handle previously returned by stmpe811_instantiate
*
* Returned Value:
* Zero is returned on success. Otherwise, a negated errno value is
@ -84,36 +84,36 @@
*
****************************************************************************/
int stmpe11_tempinitialize(STMPE11_HANDLE handle)
int stmpe811_tempinitialize(STMPE811_HANDLE handle)
{
FAR struct stmpe11_dev_s *priv = (FAR struct stmpe11_dev_s *)handle;
FAR struct stmpe811_dev_s *priv = (FAR struct stmpe811_dev_s *)handle;
uint8_t regval;
/* Enable clocking for ADC and the temperature sensor */
regval = stmpe11_getreg8(priv, STMPE11_SYS_CTRL2);
regval = stmpe811_getreg8(priv, STMPE811_SYS_CTRL2);
regval &= ~(SYS_CTRL2_TS_OFF | SYS_CTRL2_ADC_OFF);
stmpe11_putreg8(priv, STMPE11_SYS_CTRL2, regval);
stmpe811_putreg8(priv, STMPE811_SYS_CTRL2, regval);
/* Enable the temperature sensor */
stmpe11_putreg8(priv, STMPE11_TEMP_CTRL, TEMP_CTRL_ENABLE);
stmpe811_putreg8(priv, STMPE811_TEMP_CTRL, TEMP_CTRL_ENABLE);
/* Aquire data enable */
stmpe11_putreg8(priv, STMPE11_TEMP_CTRL, (TEMP_CTRL_ACQ|TEMP_CTRL_ENABLE));
stmpe811_putreg8(priv, STMPE811_TEMP_CTRL, (TEMP_CTRL_ACQ|TEMP_CTRL_ENABLE));
return OK;
}
/****************************************************************************
* Name: stmpe11_tempread
* Name: stmpe811_tempread
*
* Description:
* Configure the temperature sensor.
*
* Input Parameters:
* handle - The handle previously returned by stmpe11_instantiate
* handle - The handle previously returned by stmpe811_instantiate
*
* Returned Value:
* Zero is returned on success. Otherwise, a negated errno value is
@ -121,21 +121,21 @@ int stmpe11_tempinitialize(STMPE11_HANDLE handle)
*
****************************************************************************/
uint16_t stmpe11_tempread(STMPE11_HANDLE handle)
uint16_t stmpe811_tempread(STMPE811_HANDLE handle)
{
FAR struct stmpe11_dev_s *priv = (FAR struct stmpe11_dev_s *)handle;
FAR struct stmpe811_dev_s *priv = (FAR struct stmpe811_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));
stmpe811_putreg8(priv, STMPE811_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);
temp1 = stmpe811_getreg8(priv, STMPE811_SYS_CTRL2);
temp2 = stmpe811_getreg8(priv, STMPE811_SYS_CTRL2+1);
/* Scale the temperature (where Vio is assumed to be .33) */
@ -147,7 +147,7 @@ uint16_t stmpe11_tempread(STMPE11_HANDLE handle)
}
/****************************************************************************
* Name: stmpe11_tempinterrupt
* Name: stmpe811_tempinterrupt
*
* Description:
* Configure the temperature sensor to sample the temperature periodically.
@ -155,7 +155,7 @@ uint16_t stmpe11_tempread(STMPE11_HANDLE handle)
* to the client using the provide callback function pointer.
*
* Input Parameters:
* handle - The handle previously returned by stmpe11_instantiate
* handle - The handle previously returned by stmpe811_instantiate
* threshold - The threshold temperature value
* direction - True: Generate an interrupt if the temperate exceeds the
* threshold value; False: Generate an interrupt if the
@ -170,5 +170,5 @@ uint16_t stmpe11_tempread(STMPE11_HANDLE handle)
****************************************************************************/
/* Not implemented */
#endif /* CONFIG_INPUT && CONFIG_INPUT_STMPE11 && !CONFIG_STMPE11_TEMP_DISABLE */
#endif /* CONFIG_INPUT && CONFIG_INPUT_STMPE811 && !CONFIG_STMPE811_TEMP_DISABLE */

View File

@ -1,5 +1,5 @@
/****************************************************************************
* drivers/input/stmpe11_tsc.c
* drivers/input/stmpe811_tsc.c
*
* Copyright (C) 2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
@ -65,11 +65,11 @@
#include <nuttx/arch.h>
#include <nuttx/input/touchscreen.h>
#include <nuttx/input/stmpe11.h>
#include <nuttx/input/stmpe811.h>
#include "stmpe11.h"
#include "stmpe811.h"
#if defined(CONFIG_INPUT) && defined(CONFIG_INPUT_STMPE11) && !defined(CONFIG_STMPE11_TSC_DISABLE)
#if defined(CONFIG_INPUT) && defined(CONFIG_INPUT_STMPE811) && !defined(CONFIG_STMPE811_TSC_DISABLE)
/****************************************************************************
* Pre-processor Definitions
@ -110,28 +110,28 @@
****************************************************************************/
/* Internal logic */
static void stmpe11_notify(FAR struct stmpe11_dev_s *priv);
static int stmpe11_sample(FAR struct stmpe11_dev_s *priv,
FAR struct stmpe11_sample_s *sample);
static inline int stmpe11_waitsample(FAR struct stmpe11_dev_s *priv,
FAR struct stmpe11_sample_s *sample);
static void stmpe811_notify(FAR struct stmpe811_dev_s *priv);
static int stmpe811_sample(FAR struct stmpe811_dev_s *priv,
FAR struct stmpe811_sample_s *sample);
static inline int stmpe811_waitsample(FAR struct stmpe811_dev_s *priv,
FAR struct stmpe811_sample_s *sample);
/* Character driver methods */
static int stmpe11_open(FAR struct file *filep);
static int stmpe11_close(FAR struct file *filep);
static ssize_t stmpe11_read(FAR struct file *filep, FAR char *buffer,
static int stmpe811_open(FAR struct file *filep);
static int stmpe811_close(FAR struct file *filep);
static ssize_t stmpe811_read(FAR struct file *filep, FAR char *buffer,
size_t len);
static int stmpe11_ioctl(FAR struct file *filep, int cmd,
static int stmpe811_ioctl(FAR struct file *filep, int cmd,
unsigned long arg);
#ifndef CONFIG_DISABLE_POLL
static int stmpe11_poll(FAR struct file *filep, struct pollfd *fds,
static int stmpe811_poll(FAR struct file *filep, struct pollfd *fds,
bool setup);
#endif
/* Initialization logic */
static inline void stmpe11_tscinitialize(FAR struct stmpe11_dev_s *priv);
static inline void stmpe811_tscinitialize(FAR struct stmpe811_dev_s *priv);
/****************************************************************************
* Private Data
@ -139,16 +139,16 @@ static inline void stmpe11_tscinitialize(FAR struct stmpe11_dev_s *priv);
/* This the the vtable that supports the character driver interface */
static const struct file_operations g_stmpe11fops =
static const struct file_operations g_stmpe811fops =
{
stmpe11_open, /* open */
stmpe11_close, /* close */
stmpe11_read, /* read */
stmpe811_open, /* open */
stmpe811_close, /* close */
stmpe811_read, /* read */
0, /* write */
0, /* seek */
stmpe11_ioctl /* ioctl */
stmpe811_ioctl /* ioctl */
#ifndef CONFIG_DISABLE_POLL
, stmpe11_poll /* poll */
, stmpe811_poll /* poll */
#endif
};
@ -156,7 +156,7 @@ static const struct file_operations g_stmpe11fops =
* Private Functions
****************************************************************************/
/****************************************************************************
* Name: stmpe11_notify
* Name: stmpe811_notify
*
* Description:
* Notify any threads waiting on touchscreen data that data is now
@ -164,7 +164,7 @@ static const struct file_operations g_stmpe11fops =
*
****************************************************************************/
static void stmpe11_notify(FAR struct stmpe11_dev_s *priv)
static void stmpe811_notify(FAR struct stmpe811_dev_s *priv)
{
#ifndef CONFIG_DISABLE_POLL
int i;
@ -176,21 +176,21 @@ static void stmpe11_notify(FAR struct stmpe11_dev_s *priv)
if (priv->nwaiters > 0)
{
/* After posting this semaphore, we need to exit because the STMPE11
/* After posting this semaphore, we need to exit because the STMPE811
* is no longer available.
*/
sem_post(&priv->waitsem);
}
/* If there are threads waiting on poll() for STMPE11 data to become available,
/* If there are threads waiting on poll() for STMPE811 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++)
for (i = 0; i < CONFIG_STMPE811_NPOLLWAITERS; i++)
{
struct pollfd *fds = priv->fds[i];
if (fds)
@ -204,11 +204,11 @@ static void stmpe11_notify(FAR struct stmpe11_dev_s *priv)
}
/****************************************************************************
* Name: stmpe11_sample
* Name: stmpe811_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.
* the sample data. This is part of the stmpe811_read logic.
*
* Assumption:
* Pre-emption is disable to prevent the worker thread from running.
@ -216,12 +216,12 @@ static void stmpe11_notify(FAR struct stmpe11_dev_s *priv)
*
****************************************************************************/
static int stmpe11_sample(FAR struct stmpe11_dev_s *priv,
FAR struct stmpe11_sample_s *sample)
static int stmpe811_sample(FAR struct stmpe811_dev_s *priv,
FAR struct stmpe811_sample_s *sample)
{
int ret = -EAGAIN;
/* Is there new STMPE11 sample data available? */
/* Is there new STMPE811 sample data available? */
if (priv->penchange)
{
@ -229,7 +229,7 @@ static int stmpe11_sample(FAR struct stmpe11_dev_s *priv,
* sampled data.
*/
memcpy(sample, &priv->sample, sizeof(struct stmpe11_sample_s));
memcpy(sample, &priv->sample, sizeof(struct stmpe811_sample_s));
/* Now manage state transitions */
@ -264,16 +264,16 @@ static int stmpe11_sample(FAR struct stmpe11_dev_s *priv,
}
/****************************************************************************
* Name: stmpe11_waitsample
* Name: stmpe811_waitsample
*
* Description:
* Wait for a sample to become available (this is really part of the
* stmpe11_read logic).
* stmpe811_read logic).
*
****************************************************************************/
static inline int stmpe11_waitsample(FAR struct stmpe11_dev_s *priv,
FAR struct stmpe11_sample_s *sample)
static inline int stmpe811_waitsample(FAR struct stmpe811_dev_s *priv,
FAR struct stmpe811_sample_s *sample)
{
int ret;
@ -294,9 +294,9 @@ static inline int stmpe11_waitsample(FAR struct stmpe11_dev_s *priv,
* that is posted when new sample data is availble.
*/
while (stmpe11_sample(priv, sample) < 0)
while (stmpe811_sample(priv, sample) < 0)
{
/* Wait for a change in the STMPE11 state */
/* Wait for a change in the STMPE811 state */
priv->nwaiters++;
ret = sem_wait(&priv->waitsem);
@ -333,7 +333,7 @@ static inline int stmpe11_waitsample(FAR struct stmpe11_dev_s *priv,
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
* were two threads reading from the STMPE811 for some reason, the data
* might be read out of order.
*/
@ -342,18 +342,18 @@ errout:
}
/****************************************************************************
* Name: stmpe11_open
* Name: stmpe811_open
*
* Description:
* Standard character driver open method.
*
****************************************************************************/
static int stmpe11_open(FAR struct file *filep)
static int stmpe811_open(FAR struct file *filep)
{
#ifdef CONFIG_STMPE11_REFCNT
#ifdef CONFIG_STMPE811_REFCNT
FAR struct inode *inode;
FAR struct stmpe11_dev_s *priv;
FAR struct stmpe811_dev_s *priv;
uint8_t tmp;
int ret;
@ -361,7 +361,7 @@ static int stmpe11_open(FAR struct file *filep)
inode = filep->f_inode;
DEBUGASSERT(inode && inode->i_private);
priv = (FAR struct stmpe11_dev_s *)inode->i_private;
priv = (FAR struct stmpe811_dev_s *)inode->i_private;
/* Get exclusive access to the driver data structure */
@ -402,25 +402,25 @@ errout_with_sem:
}
/****************************************************************************
* Name: stmpe11_close
* Name: stmpe811_close
*
* Description:
* Standard character driver close method.
*
****************************************************************************/
static int stmpe11_close(FAR struct file *filep)
static int stmpe811_close(FAR struct file *filep)
{
#ifdef CONFIG_STMPE11_REFCNT
#ifdef CONFIG_STMPE811_REFCNT
FAR struct inode *inode;
FAR struct stmpe11_dev_s *priv;
FAR struct stmpe811_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;
priv = (FAR struct stmpe811_dev_s *)inode->i_private;
/* Get exclusive access to the driver data structure */
@ -449,19 +449,19 @@ static int stmpe11_close(FAR struct file *filep)
}
/****************************************************************************
* Name: stmpe11_read
* Name: stmpe811_read
*
* Description:
* Standard character driver read method.
*
****************************************************************************/
static ssize_t stmpe11_read(FAR struct file *filep, FAR char *buffer, size_t len)
static ssize_t stmpe811_read(FAR struct file *filep, FAR char *buffer, size_t len)
{
FAR struct inode *inode;
FAR struct stmpe11_dev_s *priv;
FAR struct stmpe811_dev_s *priv;
FAR struct touch_sample_s *report;
struct stmpe11_sample_s sample;
struct stmpe811_sample_s sample;
int ret;
ivdbg("len=%d\n", len);
@ -469,7 +469,7 @@ static ssize_t stmpe11_read(FAR struct file *filep, FAR char *buffer, size_t len
inode = filep->f_inode;
DEBUGASSERT(inode && inode->i_private);
priv = (FAR struct stmpe11_dev_s *)inode->i_private;
priv = (FAR struct stmpe811_dev_s *)inode->i_private;
/* Verify that the caller has provided a buffer large enough to receive
* the touch data.
@ -497,7 +497,7 @@ static ssize_t stmpe11_read(FAR struct file *filep, FAR char *buffer, size_t len
/* Try to read sample data. */
ret = stmpe11_sample(priv, &sample);
ret = stmpe811_sample(priv, &sample);
if (ret < 0)
{
/* Sample data is not available now. We would ave to wait to get
@ -513,7 +513,7 @@ static ssize_t stmpe11_read(FAR struct file *filep, FAR char *buffer, size_t len
/* Wait for sample data */
ret = stmpe11_waitsample(priv, &sample);
ret = stmpe811_waitsample(priv, &sample);
if (ret < 0)
{
/* We might have been awakened by a signal */
@ -522,7 +522,7 @@ static ssize_t stmpe11_read(FAR struct file *filep, FAR char *buffer, size_t len
}
}
/* In any event, we now have sampled STMPE11 data that we can report
/* In any event, we now have sampled STMPE811 data that we can report
* to the caller.
*/
@ -576,25 +576,25 @@ errout:
}
/****************************************************************************
* Name: stmpe11_ioctl
* Name: stmpe811_ioctl
*
* Description:
* Standard character driver ioctl method.
*
****************************************************************************/
static int stmpe11_ioctl(FAR struct file *filep, int cmd, unsigned long arg)
static int stmpe811_ioctl(FAR struct file *filep, int cmd, unsigned long arg)
{
FAR struct inode *inode;
FAR struct stmpe11_dev_s *priv;
int ret;
FAR struct inode *inode;
FAR struct stmpe811_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;
priv = (FAR struct stmpe811_dev_s *)inode->i_private;
/* Get exclusive access to the driver data structure */
@ -637,7 +637,7 @@ static int stmpe11_ioctl(FAR struct file *filep, int cmd, unsigned long arg)
}
/****************************************************************************
* Name: stmpe11_poll
* Name: stmpe811_poll
*
* Description:
* Standard character driver poll method.
@ -645,20 +645,20 @@ static int stmpe11_ioctl(FAR struct file *filep, int cmd, unsigned long arg)
****************************************************************************/
#ifndef CONFIG_DISABLE_POLL
static int stmpe11_poll(FAR struct file *filep, FAR struct pollfd *fds,
bool setup)
static int stmpe811_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;
FAR struct inode *inode;
FAR struct stmpe811_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;
priv = (FAR struct stmpe811_dev_s *)inode->i_private;
/* Are we setting up the poll? Or tearing it down? */
@ -686,7 +686,7 @@ static int stmpe11_poll(FAR struct file *filep, FAR struct pollfd *fds,
* slot for the poll structure reference
*/
for (i = 0; i < CONFIG_STMPE11_NPOLLWAITERS; i++)
for (i = 0; i < CONFIG_STMPE811_NPOLLWAITERS; i++)
{
/* Find an available slot */
@ -700,7 +700,7 @@ static int stmpe11_poll(FAR struct file *filep, FAR struct pollfd *fds,
}
}
if (i >= CONFIG_STMPE11_NPOLLWAITERS)
if (i >= CONFIG_STMPE811_NPOLLWAITERS)
{
idbg("ERROR: No availabled slot found: %d\n", i);
fds->priv = NULL;
@ -712,7 +712,7 @@ static int stmpe11_poll(FAR struct file *filep, FAR struct pollfd *fds,
if (priv->penchange)
{
stmpe11_notify(priv);
stmpe811_notify(priv);
}
}
else if (fds->priv)
@ -735,26 +735,26 @@ errout:
#endif
/****************************************************************************
* Name: stmpe11_timeoutworker
* Name: stmpe811_timeoutworker
*
* Description:
* A timer has expired without receiving a pen up event. Check again.
*
****************************************************************************/
static void stmpe11_timeoutworker(FAR void *arg)
static void stmpe811_timeoutworker(FAR void *arg)
{
FAR struct stmpe11_dev_s *priv = (FAR struct stmpe11_dev_s *)arg;
FAR struct stmpe811_dev_s *priv = (FAR struct stmpe811_dev_s *)arg;
DEBUGASSERT(priv);
/* Treat the timeout just like an interrupt occurred */
stmpe11_tscworker(priv, stmpe11_getreg8(priv, STMPE11_INT_STA));
stmpe811_tscworker(priv, stmpe811_getreg8(priv, STMPE811_INT_STA));
}
/****************************************************************************
* Name: stmpe11_timeout
* Name: stmpe811_timeout
*
* Description:
* A timer has expired without receiving a pen up event. Schedule work
@ -762,9 +762,9 @@ static void stmpe11_timeoutworker(FAR void *arg)
*
****************************************************************************/
static void stmpe11_timeout(int argc, uint32_t arg1, ...)
static void stmpe811_timeout(int argc, uint32_t arg1, ...)
{
FAR struct stmpe11_dev_s *priv = (FAR struct stmpe11_dev_s *)((uintptr_t)arg1);
FAR struct stmpe811_dev_s *priv = (FAR struct stmpe811_dev_s *)((uintptr_t)arg1);
int ret;
/* Are we still stuck in the pen down state? */
@ -778,12 +778,12 @@ static void stmpe11_timeout(int argc, uint32_t arg1, ...)
if (work_available(&priv->timeout))
{
/* Yes.. Transfer processing to the worker thread. Since STMPE11
/* Yes.. Transfer processing to the worker thread. Since STMPE811
* 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);
ret = work_queue(&priv->timeout, stmpe811_timeoutworker, priv, 0);
if (ret != 0)
{
illdbg("Failed to queue work: %d\n", ret);
@ -793,15 +793,15 @@ static void stmpe11_timeout(int argc, uint32_t arg1, ...)
}
/****************************************************************************
* Name: stmpe11_tscinitialize
* Name: stmpe811_tscinitialize
*
* Description:
* Initialize the touchscreen controller. This is really a part of the
* stmpe11_register logic,
* stmpe811_register logic,
*
****************************************************************************/
static inline void stmpe11_tscinitialize(FAR struct stmpe11_dev_s *priv)
static inline void stmpe811_tscinitialize(FAR struct stmpe811_dev_s *priv)
{
uint8_t regval;
@ -809,19 +809,19 @@ static inline void stmpe11_tscinitialize(FAR struct stmpe11_dev_s *priv)
/* Enable TSC and ADC functions */
regval = stmpe11_getreg8(priv, STMPE11_SYS_CTRL2);
regval = stmpe811_getreg8(priv, STMPE811_SYS_CTRL2);
regval &= ~(SYS_CTRL2_TSC_OFF | SYS_CTRL2_ADC_OFF);
stmpe11_putreg8(priv, STMPE11_SYS_CTRL2, regval);
stmpe811_putreg8(priv, STMPE811_SYS_CTRL2, regval);
/* Enable the TSC global interrupts */
regval = stmpe11_getreg8(priv, STMPE11_INT_EN);
regval = stmpe811_getreg8(priv, STMPE811_INT_EN);
regval |= (uint32_t)(INT_TOUCH_DET | INT_FIFO_TH | INT_FIFO_OFLOW);
stmpe11_putreg8(priv, STMPE11_INT_EN, regval);
stmpe811_putreg8(priv, STMPE811_INT_EN, regval);
/* Select Sample Time, bit number and ADC Reference */
stmpe11_putreg8(priv, STMPE11_ADC_CTRL1, priv->config->ctrl1);
stmpe811_putreg8(priv, STMPE811_ADC_CTRL1, priv->config->ctrl1);
/* Wait for 20 ms */
@ -829,45 +829,45 @@ static inline void stmpe11_tscinitialize(FAR struct stmpe11_dev_s *priv)
/* Select the ADC clock speed */
stmpe11_putreg8(priv, STMPE11_ADC_CTRL2, priv->config->ctrl2);
stmpe811_putreg8(priv, STMPE811_ADC_CTRL2, priv->config->ctrl2);
/* Select TSC pins in non-GPIO mode (AF=0) */
regval = stmpe11_getreg8(priv, STMPE11_GPIO_AF);
regval = stmpe811_getreg8(priv, STMPE811_GPIO_AF);
regval &= ~(uint8_t)TSC_PIN_SET;
stmpe11_putreg8(priv, STMPE11_GPIO_AF, regval);
stmpe811_putreg8(priv, STMPE811_GPIO_AF, regval);
/* Select 2 nF filter capacitor */
stmpe11_putreg8(priv, STMPE11_TSC_CFG,
stmpe811_putreg8(priv, STMPE811_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);
stmpe811_putreg8(priv, STMPE811_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);
stmpe811_putreg8(priv, STMPE811_FIFO_STA, FIFO_STA_FIFO_RESET);
stmpe811_putreg8(priv, STMPE811_FIFO_STA, 0);
/* set the data format for Z value: 7 fractional part and 1 whole part */
stmpe11_putreg8(priv, STMPE11_TSC_FRACTIONZ, 0x01);
stmpe811_putreg8(priv, STMPE811_TSC_FRACTIONZ, 0x01);
/* Set the driving capability of the device for TSC pins: 50mA */
stmpe11_putreg8(priv, STMPE11_TSC_IDRIVE, TSC_IDRIVE_50MA);
stmpe811_putreg8(priv, STMPE811_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);
stmpe811_putreg8(priv, STMPE811_TSC_CTRL, TSC_CTRL_EN);
/* Clear all the status pending bits */
stmpe11_putreg8(priv, STMPE11_INT_STA, INT_ALL);
stmpe811_putreg8(priv, STMPE811_INT_STA, INT_ALL);
}
/****************************************************************************
@ -875,7 +875,7 @@ static inline void stmpe11_tscinitialize(FAR struct stmpe11_dev_s *priv)
****************************************************************************/
/****************************************************************************
* Name: stmpe11_register
* Name: stmpe811_register
*
* Description:
* Enable TSC functionality. GPIO4-7 must be available. This function
@ -883,7 +883,7 @@ static inline void stmpe11_tscinitialize(FAR struct stmpe11_dev_s *priv)
* device number
*
* Input Parameters:
* handle - The handle previously returned by stmpe11_register
* handle - The handle previously returned by stmpe811_register
* minor - The input device minor number
*
* Returned Value:
@ -892,9 +892,9 @@ static inline void stmpe11_tscinitialize(FAR struct stmpe11_dev_s *priv)
*
****************************************************************************/
int stmpe11_register(STMPE11_HANDLE handle, int minor)
int stmpe811_register(STMPE811_HANDLE handle, int minor)
{
FAR struct stmpe11_dev_s *priv = (FAR struct stmpe11_dev_s *)handle;
FAR struct stmpe811_dev_s *priv = (FAR struct stmpe811_dev_s *)handle;
char devname[DEV_NAMELEN];
int ret;
@ -940,7 +940,7 @@ int stmpe11_register(STMPE11_HANDLE handle, int minor)
/* Register the character driver */
snprintf(devname, DEV_NAMELEN, DEV_FORMAT, minor);
ret = register_driver(devname, &g_stmpe11fops, 0666, priv);
ret = register_driver(devname, &g_stmpe811fops, 0666, priv);
if (ret < 0)
{
idbg("ERROR: Failed to register driver %s: %d\n", devname, ret);
@ -950,34 +950,34 @@ int stmpe11_register(STMPE11_HANDLE handle, int minor)
/* Initialize the touchscreen controller */
stmpe11_tscinitialize(priv);
stmpe811_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 */
priv->flags |= STMPE811_FLAGS_TSC_INITIALIZED; /* TSC function is initialized */
sem_post(&priv->exclsem);
return ret;
}
/****************************************************************************
* Name: stmpe11_tscworker
* Name: stmpe811_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"
* an interrupt handle because it is called from the STMPE811 "bottom half"
* logic that runs on the worker thread.
*
****************************************************************************/
void stmpe11_tscworker(FAR struct stmpe11_dev_s *priv, uint8_t intsta)
void stmpe811_tscworker(FAR struct stmpe811_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 */
FAR struct stmpe811_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);
@ -992,9 +992,9 @@ void stmpe11_tscworker(FAR struct stmpe11_dev_s *priv, uint8_t intsta)
config = priv->config;
DEBUGASSERT(config != NULL);
/* Check for pen up or down from the TSC_STA ibit n the STMPE11_TSC_CTRL register. */
/* Check for pen up or down from the TSC_STA ibit n the STMPE811_TSC_CTRL register. */
pendown = (stmpe11_getreg8(priv, STMPE11_TSC_CTRL) & TSC_CTRL_TSC_STA) != 0;
pendown = (stmpe811_getreg8(priv, STMPE811_TSC_CTRL) & TSC_CTRL_TSC_STA) != 0;
/* Handle the change from pen down to pen up */
@ -1031,12 +1031,12 @@ void stmpe11_tscworker(FAR struct stmpe11_dev_s *priv, uint8_t intsta)
{
/* 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);
#ifdef CONFIG_STMPE811_SWAPXY
x = stmpe811_getreg16(priv, STMPE811_TSC_DATAX);
y = stmpe811_getreg16(priv, STMPE811_TSC_DATAY);
#else
x = stmpe11_getreg16(priv, STMPE11_TSC_DATAY);
y = stmpe11_getreg16(priv, STMPE11_TSC_DATAX);
x = stmpe811_getreg16(priv, STMPE811_TSC_DATAY);
y = stmpe811_getreg16(priv, STMPE811_TSC_DATAX);
#endif
/* If we have not yet processed the last pen up event, then we
@ -1066,7 +1066,7 @@ void stmpe11_tscworker(FAR struct stmpe11_dev_s *priv, uint8_t intsta)
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)
if (xdiff < CONFIG_STMPE811_THRESHX && ydiff < CONFIG_STMPE811_THRESHY)
{
/* Little or no change in either direction ... don't report anything. */
@ -1085,7 +1085,7 @@ void stmpe11_tscworker(FAR struct stmpe11_dev_s *priv, uint8_t intsta)
/* Update the Z pressure index */
priv->sample.z = stmpe11_getreg8(priv, STMPE11_TSC_DATAZ);
priv->sample.z = stmpe811_getreg8(priv, STMPE811_TSC_DATAZ);
priv->sample.valid = true;
/* If this is the first (acknowledged) pen down report, then report
@ -1118,9 +1118,9 @@ void stmpe11_tscworker(FAR struct stmpe11_dev_s *priv, uint8_t intsta)
priv->sample.id = priv->id;
priv->penchange = true;
/* Notify any waiters that new STMPE11 data is available */
/* Notify any waiters that new STMPE811 data is available */
stmpe11_notify(priv);
stmpe811_notify(priv);
/* If we think that the pend is still down, the start/re-start the pen up
* timer.
@ -1130,15 +1130,15 @@ ignored:
if (priv->sample.contact == CONTACT_MOVE ||
priv->sample.contact == CONTACT_MOVE)
{
(void)wd_start(priv->wdog, STMPE11_PENUP_TICKS, stmpe11_timeout,
(void)wd_start(priv->wdog, STMPE811_PENUP_TICKS, stmpe811_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);
stmpe811_putreg8(priv, STMPE811_FIFO_STA, FIFO_STA_FIFO_RESET);
stmpe811_putreg8(priv, STMPE811_FIFO_STA, 0);
}
#endif /* CONFIG_INPUT && CONFIG_INPUT_STMPE11 && !CONFIG_STMPE11_TSC_DISABLE */
#endif /* CONFIG_INPUT && CONFIG_INPUT_STMPE811 && !CONFIG_STMPE811_TSC_DISABLE */

View File

@ -546,10 +546,10 @@ extern "C" {
#ifdef CONFIG_STMPE811_SPI
EXTERN STMPE811_HANDLE stmpe811_instantiate(FAR struct spi_dev_s *dev,
FAR struct stmpe811_config_s *config);
FAR struct stmpe811_config_s *config);
#else
EXTERN STMPE811_HANDLE stmpe811_instantiate(FAR struct i2c_dev_s *dev,
FAR struct stmpe811_config_s *config);
FAR struct stmpe811_config_s *config);
#endif
/********************************************************************************************
@ -657,7 +657,7 @@ EXTERN int stmpe811_gpioread(STMPE811_HANDLE handle, uint8_t pinconfig, bool *va
#if !defined(CONFIG_STMPE811_GPIO_DISABLE) && !defined(CONFIG_STMPE811_GPIOINT_DISABLE)
EXTERN int stmpe811_gpioattach(STMPE811_HANDLE handle, uint8_t pinconfig,
stmpe811_handler_t handler);
stmpe811_handler_t handler);
#endif
/********************************************************************************************