summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-10-04 17:08:59 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-10-04 17:08:59 +0000
commit68c47baf9fce581d0078384ef0fcdb6436292fcb (patch)
tree2acea35bd828c7017ca8e48dd2bafc4fe2610c15
parent0eda7244af71108683fb409517ccb18dd78dd65c (diff)
downloadpx4-nuttx-68c47baf9fce581d0078384ef0fcdb6436292fcb.tar.gz
px4-nuttx-68c47baf9fce581d0078384ef0fcdb6436292fcb.tar.bz2
px4-nuttx-68c47baf9fce581d0078384ef0fcdb6436292fcb.zip
ADS7843E driver is code complete
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@4018 42af7a65-404d-4744-a932-0658087f49c3
-rw-r--r--nuttx/arch/arm/src/sam3u/sam3u_spi.c210
-rw-r--r--nuttx/configs/sam3u-ek/src/sam3uek_internal.h7
-rw-r--r--nuttx/configs/sam3u-ek/src/up_spi.c1
-rwxr-xr-xnuttx/configs/sam3u-ek/src/up_touchscreen.c72
-rwxr-xr-xnuttx/configs/sam3u-ek/touchscreen/defconfig2
-rw-r--r--[-rwxr-xr-x]nuttx/drivers/input/Make.defs0
-rw-r--r--nuttx/drivers/input/ads7843e.c377
-rw-r--r--nuttx/drivers/input/ads7843e.h101
-rw-r--r--[-rwxr-xr-x]nuttx/drivers/lcd/Make.defs0
-rw-r--r--[-rwxr-xr-x]nuttx/drivers/lcd/nokia6100.c0
-rw-r--r--[-rwxr-xr-x]nuttx/drivers/lcd/p14201.c0
-rw-r--r--[-rwxr-xr-x]nuttx/drivers/lcd/pcf8833.h0
-rw-r--r--[-rwxr-xr-x]nuttx/drivers/lcd/s1d15g10.h0
-rw-r--r--[-rwxr-xr-x]nuttx/drivers/lcd/sd1329.h0
-rw-r--r--[-rwxr-xr-x]nuttx/drivers/lcd/skeleton.c0
-rw-r--r--[-rwxr-xr-x]nuttx/drivers/lcd/ssd1305.h0
-rw-r--r--[-rwxr-xr-x]nuttx/drivers/lcd/ug-9664hswag01.c0
-rw-r--r--[-rwxr-xr-x]nuttx/drivers/mtd/at24xx.c0
-rw-r--r--[-rwxr-xr-x]nuttx/drivers/mtd/flash_eraseall.c0
-rw-r--r--[-rwxr-xr-x]nuttx/drivers/mtd/ftl.c0
-rw-r--r--[-rwxr-xr-x]nuttx/drivers/mtd/ramtron.c0
-rw-r--r--[-rwxr-xr-x]nuttx/drivers/net/cs89x0.h0
-rw-r--r--[-rwxr-xr-x]nuttx/drivers/net/enc28j60.c0
-rw-r--r--[-rwxr-xr-x]nuttx/drivers/net/enc28j60.h0
-rw-r--r--[-rwxr-xr-x]nuttx/drivers/pm/Make.defs0
-rw-r--r--[-rwxr-xr-x]nuttx/drivers/serial/uart_16550.c0
-rw-r--r--[-rwxr-xr-x]nuttx/drivers/usbdev/usbdev_trprintf.c0
-rw-r--r--[-rwxr-xr-x]nuttx/drivers/usbhost/usbhost_enumerate.c0
-rw-r--r--nuttx/include/nuttx/input/ads7843e.h6
29 files changed, 546 insertions, 230 deletions
diff --git a/nuttx/arch/arm/src/sam3u/sam3u_spi.c b/nuttx/arch/arm/src/sam3u/sam3u_spi.c
index 72f35ebe3..d16598c71 100644
--- a/nuttx/arch/arm/src/sam3u/sam3u_spi.c
+++ b/nuttx/arch/arm/src/sam3u/sam3u_spi.c
@@ -120,13 +120,21 @@ struct sam3u_spidev_s
#ifndef CONFIG_SPI_OWNBUS
static int spi_lock(FAR struct spi_dev_s *dev, bool lock);
#endif
-static void spi_select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected);
-static uint32_t spi_setfrequency(FAR struct spi_dev_s *dev, uint32_t frequency);
-static void spi_setmode(FAR struct spi_dev_s *dev, enum spi_mode_e mode);
+static void spi_select(FAR struct spi_dev_s *dev, enum spi_dev_e devid,
+ bool selected);
+static uint32_t spi_setfrequency(FAR struct spi_dev_s *dev,
+ uint32_t frequency);
+static void spi_setmode(FAR struct spi_dev_s *dev,
+ enum spi_mode_e mode);
static void spi_setbits(FAR struct spi_dev_s *dev, int nbits);
static uint16_t spi_send(FAR struct spi_dev_s *dev, uint16_t ch);
+#ifdef CONFIG_SPI_EXCHANGE
+static void spi_exchange(FAR struct spi_dev_s *dev,
+ FAR const void *txbuffer, FAR void *rxbuffer, size_t nwords);
+#else
static void spi_sndblock(FAR struct spi_dev_s *dev, FAR const void *buffer, size_t nwords);
static void spi_recvblock(FAR struct spi_dev_s *dev, FAR void *buffer, size_t nwords);
+#endif
/****************************************************************************
* Private Data
@@ -148,8 +156,12 @@ static const struct spi_ops_s g_spiops =
.cmddata = sam3u_spicmddata,
#endif
.send = spi_send,
+#ifdef CONFIG_SPI_EXCHANGE
+ .exchange = spi_exchange,
+#else
.sndblock = spi_sndblock,
.recvblock = spi_recvblock,
+#endif
.registercallback = 0, /* Not implemented */
};
@@ -300,7 +312,9 @@ static uint32_t spi_setfrequency(FAR struct spi_dev_s *dev, uint32_t frequency)
{
FAR struct sam3u_spidev_s *priv = (FAR struct sam3u_spidev_s *)dev;
uint32_t actual;
- uint32_t divisor;
+ uint32_t scbr;
+ uint32_t dlybs;
+ uint32_t dlybct;
uint32_t regval;
uint32_t regaddr;
@@ -317,33 +331,65 @@ static uint32_t spi_setfrequency(FAR struct spi_dev_s *dev, uint32_t frequency)
}
#endif
- /* Configure SPI to a frequency as close as possible to the requested frequency. */
-
- /* frequency = SPI_CLOCK / divisor, or divisor = SPI_CLOCK / frequency */
+ /* Configure SPI to a frequency as close as possible to the requested frequency.
+ *
+ * SPCK frequency = MCK / SCBR, or SCBR = MCK / frequency
+ */
- divisor = SAM3U_MCK_FREQUENCY / frequency;
+ scbr = SAM3U_MCK_FREQUENCY / frequency;
- if (divisor < 8)
+ if (scbr < 8)
{
- divisor = 8;
+ scbr = 8;
}
- else if (divisor > 254)
+ else if (scbr > 254)
{
- divisor = 254;
+ scbr = 254;
}
- divisor = (divisor + 1) & ~1;
+ scbr = (scbr + 1) & ~1;
- /* Save the new divisor value */
+ /* Save the new scbr value */
regaddr = g_csraddr[priv->cs];
regval = getreg32(regaddr);
- regval &= ~SPI_CSR_SCBR_MASK;
- putreg32(divisor << SPI_CSR_SCBR_SHIFT, regaddr);
+ regval &= ~(SPI_CSR_SCBR_MASK|SPI_CSR_DLYBS_MASK|SPI_CSR_DLYBCT_MASK);
+ regval |= scbr << SPI_CSR_SCBR_SHIFT;
+
+ /* DLYBS: Delay Before SPCK. This field defines the delay from NPCS valid to the
+ * first valid SPCK transition. When DLYBS equals zero, the NPCS valid to SPCK
+ * transition is 1/2 the SPCK clock period. Otherwise, the following equations
+ * determine the delay:
+ *
+ * Delay Before SPCK = DLYBS / MCK
+ *
+ * For a 2uS delay
+ *
+ * DLYBS = MCK * 0.000002 = MCK / 500000
+ */
+
+ dlybs = SAM3U_MCK_FREQUENCY / 500000;
+ regval |= dlybs << SPI_CSR_DLYBS_SHIFT;
+
+ /* DLYBCT: Delay Between Consecutive Transfers. This field defines the delay
+ * between two consecutive transfers with the same peripheral without removing
+ * the chip select. The delay is always inserted after each transfer and
+ * before removing the chip select if needed.
+ *
+ * Delay Between Consecutive Transfers = (32 x DLYBCT) / MCK
+ *
+ * For a 5uS delay:
+ *
+ * DLYBCT = MCK * 0.000005 / 32 = MCK / 200000 / 32
+ */
- /* Calculate the new actual */
+ dlybct = SAM3U_MCK_FREQUENCY / 200000 / 32;
+ regval |= dlybct << SPI_CSR_DLYBCT_SHIFT;
+ putreg32(regval, regaddr);
- actual = SAM3U_MCK_FREQUENCY / divisor;
+ /* Calculate the new actual frequency */
+
+ actual = SAM3U_MCK_FREQUENCY / scbr;
/* Save the frequency setting */
@@ -487,6 +533,11 @@ static void spi_setbits(FAR struct spi_dev_s *dev, int nbits)
static uint16_t spi_send(FAR struct spi_dev_s *dev, uint16_t wd)
{
+#ifdef CONFIG_SPI_VARSELECT
+ FAR struct sam3u_spidev_s *priv = (FAR struct sam3u_spidev_s *)dev;
+ uint32_t tdr = (uint32_t)priv->cs << SPI_TDR_PCS_SHIFT;
+#endif
+
/* Wait for any previous data written to the TDR to be transferred to the
* serializer.
*/
@@ -495,7 +546,11 @@ static uint16_t spi_send(FAR struct spi_dev_s *dev, uint16_t wd)
/* Write the data to transmitted to the Transmit Data Register (TDR) */
+#ifdef CONFIG_SPI_VARSELECT
+ putreg32((uint32_t)wd | tdr | SPI_TDR_LASTXFER, SAM3U_SPI_TDR);
+#else
putreg32((uint32_t)wd, SAM3U_SPI_TDR);
+#endif
/* Wait for the read data to be available in the RDR */
@@ -506,7 +561,91 @@ static uint16_t spi_send(FAR struct spi_dev_s *dev, uint16_t wd)
return (uint16_t)getreg32(SAM3U_SPI_RDR);
}
-/*************************************************************************
+/****************************************************************************
+ * Name: spi_exchange
+ *
+ * Description:
+ * Exahange a block of data from SPI. Required.
+ *
+ * Input Parameters:
+ * dev - Device-specific state data
+ * txbuffer - A pointer to the buffer of data to be sent
+ * rxbuffer - A pointer to the buffer in which to recieve data
+ * nwords - the length of data that to be exchanged in units of words.
+ * The wordsize is determined by the number of bits-per-word
+ * selected for the SPI interface. If nbits <= 8, the data is
+ * packed into uint8_t's; if nbits >8, the data is packed into
+ * uint16_t's
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_SPI_EXCHANGE
+static void spi_exchange(FAR struct spi_dev_s *dev,
+ FAR const void *txbuffer, FAR void *rxbuffer,
+ size_t nwords)
+{
+#ifdef CONFIG_SPI_VARSELECT
+ FAR struct sam3u_spidev_s *priv = (FAR struct sam3u_spidev_s *)dev;
+ uint32_t tdr = (uint32_t)priv->cs << SPI_TDR_PCS_SHIFT;
+#endif
+ FAR uint8_t *rxptr = (FAR uint8_t*)rxbuffer;
+ FAR uint8_t *txptr = (FAR uint8_t*)txbuffer;
+ uint8_t data;
+
+ spidbg("nwords: %d\n", nwords);
+
+ /* Loop, sending each word in the user-provied data buffer */
+
+ for ( ; nwords > 0; nwords--)
+ {
+ /* Wait for any previous data written to the TDR to be transferred
+ * to the serializer.
+ */
+
+ while ((getreg32(SAM3U_SPI_SR) & SPI_INT_TDRE) == 0);
+
+ /* Get the data to send (0xff if there is no data source) */
+
+ if (rxptr)
+ {
+ data = *txptr++;
+ }
+ else
+ {
+ data = 0xff;
+ }
+
+ /* Write the data to transmitted to the Transmit Data Register (TDR) */
+
+#ifdef CONFIG_SPI_VARSELECT
+ if (nwords == 1)
+ {
+ tdr |= SPI_TDR_LASTXFER;
+ }
+ putreg32((uint32_t)data | tdr, SAM3U_SPI_TDR);
+#else
+ putreg32((uint32_t)data, SAM3U_SPI_TDR);
+#endif
+
+ /* Wait for the read data to be available in the RDR */
+
+ while ((getreg32(SAM3U_SPI_SR) & SPI_INT_RDRF) == 0);
+
+ /* Read the received data from the SPI Data Register */
+
+ data = (uint8_t)getreg32(SAM3U_SPI_RDR);
+ if (rxptr)
+ {
+ *txptr++ = data;
+ }
+ }
+}
+#endif
+
+/***************************************************************************
* Name: spi_sndblock
*
* Description:
@@ -525,8 +664,13 @@ static uint16_t spi_send(FAR struct spi_dev_s *dev, uint16_t wd)
*
****************************************************************************/
+#ifndef CONFIG_SPI_EXCHANGE
static void spi_sndblock(FAR struct spi_dev_s *dev, FAR const void *buffer, size_t nwords)
{
+#ifdef CONFIG_SPI_VARSELECT
+ FAR struct sam3u_spidev_s *priv = (FAR struct sam3u_spidev_s *)dev;
+ uint32_t tdr = (uint32_t)priv->cs << SPI_TDR_PCS_SHIFT;
+#endif
FAR uint8_t *ptr = (FAR uint8_t*)buffer;
uint8_t data;
@@ -545,9 +689,18 @@ static void spi_sndblock(FAR struct spi_dev_s *dev, FAR const void *buffer, size
/* Write the data to transmitted to the Transmit Data Register (TDR) */
data = *ptr++;
+#ifdef CONFIG_SPI_VARSELECT
+ if (nwords == 1)
+ {
+ tdr |= SPI_TDR_LASTXFER;
+ }
+ putreg32((uint32_t)data | tdr, SAM3U_SPI_TDR);
+#else
putreg32((uint32_t)data, SAM3U_SPI_TDR);
+#endif
}
}
+#endif
/****************************************************************************
* Name: spi_recvblock
@@ -568,8 +721,13 @@ static void spi_sndblock(FAR struct spi_dev_s *dev, FAR const void *buffer, size
*
****************************************************************************/
+#ifndef CONFIG_SPI_EXCHANGE
static void spi_recvblock(FAR struct spi_dev_s *dev, FAR void *buffer, size_t nwords)
{
+#ifdef CONFIG_SPI_VARSELECT
+ FAR struct sam3u_spidev_s *priv = (FAR struct sam3u_spidev_s *)dev;
+ uint32_t tdr = (uint32_t)priv->cs << SPI_TDR_PCS_SHIFT;
+#endif
FAR uint8_t *ptr = (FAR uint8_t*)buffer;
spidbg("nwords: %d\n", nwords);
@@ -588,8 +746,15 @@ static void spi_recvblock(FAR struct spi_dev_s *dev, FAR void *buffer, size_t nw
* to clock the read data.
*/
+#ifdef CONFIG_SPI_VARSELECT
+ if (nwords == 1)
+ {
+ tdr |= SPI_TDR_LASTXFER;
+ }
+ putreg32(0xff | tdr, SAM3U_SPI_TDR);
+#else
putreg32(0xff, SAM3U_SPI_TDR);
-
+#endif
/* Wait for the read data to be available in the RDR */
while ((getreg32(SAM3U_SPI_SR) & SPI_INT_RDRF) == 0);
@@ -599,6 +764,7 @@ static void spi_recvblock(FAR struct spi_dev_s *dev, FAR void *buffer, size_t nw
*ptr++ = (uint8_t)getreg32(SAM3U_SPI_RDR);
}
}
+#endif
/****************************************************************************
* Public Functions
@@ -657,8 +823,8 @@ FAR struct spi_dev_s *up_spiinitialize(int port)
irqrestore(flags);
/* Configure the SPI mode register */
-#warning "Need to review this -- what other settngs are necessary"
- putreg32(SPI_MR_MSTR, SAM3U_SPI_MR);
+
+ putreg32(SPI_MR_MSTR | SPI_MR_MODFDIS, SAM3U_SPI_MR);
/* And enable the SPI */
diff --git a/nuttx/configs/sam3u-ek/src/sam3uek_internal.h b/nuttx/configs/sam3u-ek/src/sam3uek_internal.h
index c7f9d4278..1aa66d517 100644
--- a/nuttx/configs/sam3u-ek/src/sam3uek_internal.h
+++ b/nuttx/configs/sam3u-ek/src/sam3uek_internal.h
@@ -46,6 +46,7 @@
#include <stdint.h>
+#include <arch/irq.h>
#include <nuttx/irq.h>
/************************************************************************************
@@ -138,8 +139,10 @@
/* Touchscreen controller (TSC) */
-#define GPIO_TCS_IRQ (PIO_INPUT|GPIO_CFG_PULLUP|GPIO_PORT_PIOA|GPIO_PIN6)
-#define GPIO_TCS_BUSY (PIO_INPUT|GPIO_CFG_PULLUP|GPIO_PORT_PIOA|GPIO_PIN6)
+#define GPIO_TCS_IRQ (GPIO_INPUT|GPIO_CFG_PULLUP|GPIO_PORT_PIOA|GPIO_PIN24)
+#define GPIO_TCS_BUSY (GPIO_INPUT|GPIO_CFG_PULLUP|GPIO_PORT_PIOA|GPIO_PIN2)
+
+#define SAM3U_TCS_IRQ SAM3U_IRQ_PA24
/* LEDs */
diff --git a/nuttx/configs/sam3u-ek/src/up_spi.c b/nuttx/configs/sam3u-ek/src/up_spi.c
index 5c70a5ab5..515dab2e7 100644
--- a/nuttx/configs/sam3u-ek/src/up_spi.c
+++ b/nuttx/configs/sam3u-ek/src/up_spi.c
@@ -43,6 +43,7 @@
#include <stdint.h>
#include <stdbool.h>
#include <debug.h>
+#include <errno.h>
#include <nuttx/spi.h>
#include <arch/board/board.h>
diff --git a/nuttx/configs/sam3u-ek/src/up_touchscreen.c b/nuttx/configs/sam3u-ek/src/up_touchscreen.c
index 40dd2db15..699c245b7 100755
--- a/nuttx/configs/sam3u-ek/src/up_touchscreen.c
+++ b/nuttx/configs/sam3u-ek/src/up_touchscreen.c
@@ -45,7 +45,7 @@
#include <debug.h>
#include <errno.h>
-#include <nuttx/sdio.h>
+#include <nuttx/spi.h>
#include <nuttx/input/touchscreen.h>
#include <nuttx/input/ads7843e.h>
@@ -66,6 +66,26 @@
# error "Touchscreen support requires CONFIG_SAM3U_SPI"
#endif
+#ifndef CONFIG_GPIOA_IRQ
+# error "Touchscreen support requires CONFIG_GPIOA_IRQ"
+#endif
+
+#ifndef CONFIG_ADS7843E_FREQUENCY
+# define CONFIG_ADS7843E_FREQUENCY 500000
+#endif
+
+#ifndef CONFIG_ADS7843E_SPIDEV
+# define CONFIG_ADS7843E_SPIDEV 0
+#endif
+
+#if CONFIG_ADS7843E_SPIDEV != 0
+# error "CONFIG_ADS7843E_SPIDEV must be zero"
+#endif
+
+#ifndef CONFIG_ADS7843E_DEVMINOR
+# define CONFIG_ADS7843E_DEVMINOR 0
+#endif
+
/****************************************************************************
* Static Function Prototypes
****************************************************************************/
@@ -85,6 +105,7 @@
static int tsc_attach(FAR struct ads7843e_config_s *state, xcpt_t isr);
static void tsc_enable(FAR struct ads7843e_config_s *state, bool enable);
static void tsc_clear(FAR struct ads7843e_config_s *state);
+static bool tsc_busy(FAR struct ads7843e_config_s *state);
static bool tsc_pendown(FAR struct ads7843e_config_s *state);
/****************************************************************************
@@ -103,12 +124,12 @@ static bool tsc_pendown(FAR struct ads7843e_config_s *state);
static struct ads7843e_config_s g_tscinfo =
{
- .calib = CONFIG_INPUT_TSCCALIB,
- .frequency = CONFIG_INPUT_TSCFREQUENCY,
+ .frequency = CONFIG_ADS7843E_FREQUENCY,
.attach = tsc_attach,
.enable = tsc_enable,
.clear = tsc_clear,
+ .busy = tsc_busy,
.pendown = tsc_pendown,
};
@@ -130,22 +151,24 @@ static struct ads7843e_config_s g_tscinfo =
static int tsc_attach(FAR struct ads7843e_config_s *state, xcpt_t isr)
{
-#warning "Missing logic"
- return OK;
+ /* Attach the ADS7843E interrupt */
+
+ ivdbg("Attaching %p to IRQ %d\n", isr, SAM3U_TCS_IRQ);
+ return irq_attach(SAM3U_TCS_IRQ, isr);
}
static void tsc_enable(FAR struct ads7843e_config_s *state, bool enable)
{
/* Attach and enable, or detach and disable */
- if (enable && g_tschandler)
+ ivdbg("IRQ:%d enable:%d\n", SAM3U_TCS_IRQ, enable);
+ if (enable)
{
- /* Configure and enable the ADS7843E interrupt */
-#warning "Missing logic"
+ sam3u_gpioirqenable(SAM3U_TCS_IRQ);
}
else
{
-#warning "Missing logic"
+ sam3u_gpioirqdisable(SAM3U_TCS_IRQ);
}
}
@@ -154,11 +177,22 @@ static void tsc_clear(FAR struct ads7843e_config_s *state)
/* Does nothing */
}
+static bool tsc_busy(FAR struct ads7843e_config_s *state)
+{
+ /* REVISIT: This might need to be inverted */
+
+ bool busy = sam3u_gpioread(GPIO_TCS_BUSY);
+ ivdbg("busy:%d\n", busy);
+ return busy;
+}
+
static bool tsc_pendown(FAR struct ads7843e_config_s *state)
{
/* REVISIT: This might need to be inverted */
- return sam3u_gpioread(GPIO_ADS7843E);
+ bool pendown = sam3u_gpioread(GPIO_TCS_IRQ);
+ ivdbg("pendown:%d\n", pendown);
+ return pendown;
}
/****************************************************************************
@@ -178,26 +212,32 @@ int up_tcinitialize(void)
FAR struct spi_dev_s *dev;
int ret;
+ ivdbg("Initializing\n");
+
/* Configure and enable the ADS7843E interrupt pin as an input */
- (void)sam3u_configgpio(GPIO_ADS7843E_BUY);
- (void)sam3u_configgpio(GPIO_ADS7843E_IRQ);
+ (void)sam3u_configgpio(GPIO_TCS_BUSY);
+ (void)sam3u_configgpio(GPIO_TCS_IRQ);
+
+ /* Configure the PIO interrupt */
+
+ sam3u_gpioirq(GPIO_TCS_IRQ);
/* Get an instance of the SPI interface */
- dev = up_spiinitialize(CONFIG_INPUT_TSCSPIDEV);
+ dev = up_spiinitialize(CONFIG_ADS7843E_SPIDEV);
if (!dev)
{
- dbg("Failed to initialize SPI bus %d\n", CONFIG_INPUT_TSCSPIDEV);
+ idbg("Failed to initialize SPI bus %d\n", CONFIG_ADS7843E_SPIDEV);
return -ENODEV;
}
/* Initialize and register the SPI touschscreen device */
- ret = ads7843e_register(dev, &g_tscinfo, CONFIG_INPUT_TSCMINOR);
+ ret = ads7843e_register(dev, &g_tscinfo, CONFIG_ADS7843E_DEVMINOR);
if (ret < 0)
{
- dbg("Failed to initialize SPI bus %d\n", CONFIG_INPUT_TSCSPIDEV);
+ idbg("Failed to initialize SPI bus %d\n", CONFIG_ADS7843E_SPIDEV);
/* up_spiuninitialize(dev); */
return -ENODEV;
}
diff --git a/nuttx/configs/sam3u-ek/touchscreen/defconfig b/nuttx/configs/sam3u-ek/touchscreen/defconfig
index 4ce1dea24..68d53e4e9 100755
--- a/nuttx/configs/sam3u-ek/touchscreen/defconfig
+++ b/nuttx/configs/sam3u-ek/touchscreen/defconfig
@@ -115,7 +115,7 @@ CONFIG_SAM3U_USART3=n
# The drivers need to know how to configure the subsystem.
#
-CONFIG_GPIOA_IRQ=n
+CONFIG_GPIOA_IRQ=y
CONFIG_GPIOB_IRQ=n
CONFIG_GPIOC_IRQ=n
CONFIG_USART0_ISUART=y
diff --git a/nuttx/drivers/input/Make.defs b/nuttx/drivers/input/Make.defs
index e32dc4549..e32dc4549 100755..100644
--- a/nuttx/drivers/input/Make.defs
+++ b/nuttx/drivers/input/Make.defs
diff --git a/nuttx/drivers/input/ads7843e.c b/nuttx/drivers/input/ads7843e.c
index d92073b72..16842f4cf 100644
--- a/nuttx/drivers/input/ads7843e.c
+++ b/nuttx/drivers/input/ads7843e.c
@@ -53,6 +53,7 @@
#include <fcntl.h>
#include <semaphore.h>
#include <poll.h>
+#include <wdog.h>
#include <errno.h>
#include <assert.h>
#include <debug.h>
@@ -71,77 +72,11 @@
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
-/* Configuration ************************************************************/
-/* Reference counting is partially implemented, but not needed in the
- * current design.
- */
-
-#undef CONFIG_ADS7843E_REFCNT
-
-/* Driver support ***********************************************************/
-/* This format is used to construct the /dev/input[n] device driver path. It
- * defined here so that it will be used consistently in all places.
- */
-
-#define DEV_FORMAT "/dev/input%d"
-#define DEV_NAMELEN 16
/****************************************************************************
* Private Types
****************************************************************************/
-/* This describes the state of one contact */
-
-enum ads7843e_contact_3
-{
- CONTACT_NONE = 0, /* No contact */
- CONTACT_DOWN, /* First contact */
- CONTACT_MOVE, /* Same contact, possibly different position */
- CONTACT_UP, /* Contact lost */
-};
-
-/* This structure describes the results of one ADS7843E sample */
-
-struct ads7843e_sample_s
-{
- uint8_t id; /* Sampled touch point ID */
- uint8_t contact; /* Contact state (see enum ads7843e_contact_e) */
- uint16_t x; /* Measured X position */
- uint16_t y; /* Measured Y position */
-#warning "Missing other measurement data" /* Like size and pressure */
-};
-
-/* This structure describes the state of one ADS7843E driver instance */
-
-struct ads7843e_dev_s
-{
-#ifdef CONFIG_ADS7843E_MULTIPLE
- FAR struct ads7843e_dev_s *flink; /* Supports a singly linked list of drivers */
-#endif
-#ifdef CONFIG_ADS7843E_REFCNT
- uint8_t crefs; /* Number of times the device has been opened */
-#endif
- uint8_t nwaiters; /* Number of threads waiting for ADS7843E data */
- uint8_t id; /* Current touch point ID */
- volatile bool penchange; /* An unreported event is buffered */
- sem_t devsem; /* Manages exclusive access to this structure */
- sem_t waitsem; /* Used to wait for the availability of data */
-
- FAR struct ads7843e_config_s *config; /* Board configuration data */
- FAR struct spi_dev_s *spi; /* Saved SPI driver instance */
- struct work_s work; /* Supports the interrupt handling "bottom half" */
- struct ads7843e_sample_s sample; /* Last sampled touch point data */
-
- /* The following is a list if poll structures of threads waiting for
- * driver events. The 'struct pollfd' reference for each open is also
- * retained in the f_priv field of the 'struct file'.
- */
-
-#ifndef CONFIG_DISABLE_POLL
- struct pollfd *fds[CONFIG_ADS7843E_NPOLLWAITERS];
-#endif
-};
-
/****************************************************************************
* Private Function Prototypes
****************************************************************************/
@@ -156,6 +91,9 @@ static void ads7843e_select(FAR struct spi_dev_s *spi);
static void ads7843e_deselect(FAR struct spi_dev_s *spi);
#endif
+static inline void ads7843e_waitbusy(FAR struct ads7843e_dev_s *priv);
+static uint16_t ads7843e_sendcmd(FAR struct ads7843e_dev_s *priv, uint8_t cmd);
+
/* Interrupts and data sampling */
static void ads7843e_notify(FAR struct ads7843e_dev_s *priv);
@@ -163,7 +101,6 @@ static int ads7843e_sample(FAR struct ads7843e_dev_s *priv,
FAR struct ads7843e_sample_s *sample);
static int ads7843e_waitsample(FAR struct ads7843e_dev_s *priv,
FAR struct ads7843e_sample_s *sample);
-static int ads7843e_transfer(FAR struct ads7843e_dev_s *priv, uint8_t cmd);
static void ads7843e_worker(FAR void *arg);
static int ads7843e_interrupt(int irq, FAR void *context);
@@ -214,47 +151,6 @@ static struct ads7843e_dev_s *g_ads7843elist;
****************************************************************************/
/****************************************************************************
- * Function: ads7843e_configspi
- *
- * Description:
- * Configure the SPI for use with the ADS7843E. This funcution should be
- * called once during touchscreen initialization to configure the SPI
- * bus. Note that if CONFIG_SPI_OWNBUS is not defined, then this function
- * does nothing.
- *
- * Parameters:
- * spi - Reference to the SPI driver structure
- *
- * Returned Value:
- * None
- *
- * Assumptions:
- *
- ****************************************************************************/
-
-static inline void ads7843e_configspi(FAR struct spi_dev_s *spi)
-{
-#ifdef CONFIG_ADS7843E_FREQUENCY
- idbg("Mode: %d Bits: 8 Frequency: %d\n",
- CONFIG_ADS7843E_SPIMODE, CONFIG_ADS7843E_FREQUENCY);
-#else
- idbg("Mode: %d Bits: 8\n", CONFIG_ADS7843E_SPIMODE);
-#endif
-
- /* Configure SPI for the P14201. But only if we own the SPI bus. Otherwise, don't
- * bother because it might change.
- */
-
-#ifdef CONFIG_SPI_OWNBUS
- SPI_SETMODE(spi, CONFIG_ADS7843E_SPIMODE);
- SPI_SETBITS(spi, 8);
-#ifdef CONFIG_ADS7843E_FREQUENCY
- SPI_SETFREQUENCY(spi, CONFIG_ADS7843E_FREQUENCY)
-#endif
-#endif
-}
-
-/****************************************************************************
* Function: ads7843e_select
*
* Description:
@@ -278,7 +174,7 @@ static inline void ads7843e_select(FAR struct spi_dev_s *spi)
{
/* We own the SPI bus, so just select the chip */
- SPI_SELECT(spi, SPIDEV_DISPLAY, true);
+ SPI_SELECT(spi, SPIDEV_TOUCHSCREEN, true);
}
#else
static void ads7843e_select(FAR struct spi_dev_s *spi)
@@ -288,7 +184,7 @@ static void ads7843e_select(FAR struct spi_dev_s *spi)
*/
SPI_LOCK(spi, true);
- SPI_SELECT(spi, SPIDEV_DISPLAY, true);
+ SPI_SELECT(spi, SPIDEV_TOUCHSCREEN, true);
/* Now make sure that the SPI bus is configured for the P14201 (it
* might have gotten configured for a different device while unlocked)
@@ -302,7 +198,6 @@ static void ads7843e_select(FAR struct spi_dev_s *spi)
}
#endif
-
/****************************************************************************
* Function: ads7843e_deselect
*
@@ -328,19 +223,101 @@ static inline void ads7843e_deselect(FAR struct spi_dev_s *spi)
{
/* We own the SPI bus, so just de-select the chip */
- SPI_SELECT(spi, SPIDEV_DISPLAY, false);
+ SPI_SELECT(spi, SPIDEV_TOUCHSCREEN, false);
}
#else
static void ads7843e_deselect(FAR struct spi_dev_s *spi)
{
/* De-select P14201 chip and relinquish the SPI bus. */
- SPI_SELECT(spi, SPIDEV_DISPLAY, false);
+ SPI_SELECT(spi, SPIDEV_TOUCHSCREEN, false);
SPI_LOCK(spi, false);
}
#endif
/****************************************************************************
+ * Function: ads7843e_configspi
+ *
+ * Description:
+ * Configure the SPI for use with the ADS7843E. This funcution should be
+ * called once during touchscreen initialization to configure the SPI
+ * bus. Note that if CONFIG_SPI_OWNBUS is not defined, then this function
+ * does nothing.
+ *
+ * Parameters:
+ * spi - Reference to the SPI driver structure
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+static inline void ads7843e_configspi(FAR struct spi_dev_s *spi)
+{
+#ifdef CONFIG_ADS7843E_FREQUENCY
+ idbg("Mode: %d Bits: 8 Frequency: %d\n",
+ CONFIG_ADS7843E_SPIMODE, CONFIG_ADS7843E_FREQUENCY);
+#else
+ idbg("Mode: %d Bits: 8\n", CONFIG_ADS7843E_SPIMODE);
+#endif
+
+ /* Configure SPI for the P14201. But only if we own the SPI bus. Otherwise, don't
+ * bother because it might change.
+ */
+
+#ifdef CONFIG_SPI_OWNBUS
+ SPI_SELECT(spi, SPIDEV_TOUCHSCREEN, true);
+ SPI_SETMODE(spi, CONFIG_ADS7843E_SPIMODE);
+ SPI_SETBITS(spi, 8);
+#ifdef CONFIG_ADS7843E_FREQUENCY
+ SPI_SETFREQUENCY(spi, CONFIG_ADS7843E_FREQUENCY)
+#endif
+ SPI_SELECT(spi, SPIDEV_TOUCHSCREEN, false);
+#endif
+}
+
+/****************************************************************************
+ * Name: ads7843e_waitbusy
+ ****************************************************************************/
+
+static inline void ads7843e_waitbusy(FAR struct ads7843e_dev_s *priv)
+{
+ while (priv->config->busy(priv->config));
+}
+
+/****************************************************************************
+ * Name: ads7843e_sendcmd
+ ****************************************************************************/
+
+static uint16_t ads7843e_sendcmd(FAR struct ads7843e_dev_s *priv, uint8_t cmd)
+{
+ uint8_t buffer[2];
+ uint16_t result;
+
+ /* Select the ADS7843E */
+
+ ads7843e_select(priv->spi);
+
+ /* Send the command */
+
+ (void)SPI_SEND(priv->spi, cmd);
+ ads7843e_waitbusy(priv);
+
+ /* Read the data */
+
+ SPI_RECVBLOCK(priv->spi, buffer, 2);
+ ads7843e_deselect(priv->spi);
+
+ result = ((uint16_t)buffer[0] << 8) | (uint16_t)buffer[1];
+ result = result >> 4;
+
+ ivdbg("cmd:%02x response:%04x\n", cmd, result);
+ return result;
+}
+
+/****************************************************************************
* Name: ads7843e_notify
****************************************************************************/
@@ -470,6 +447,7 @@ static int ads7843e_waitsample(FAR struct ads7843e_dev_s *priv,
{
/* Wait for a change in the ADS7843E state */
+ ivdbg("Waiting..\n");
priv->nwaiters++;
ret = sem_wait(&priv->waitsem);
priv->nwaiters--;
@@ -480,13 +458,16 @@ static int ads7843e_waitsample(FAR struct ads7843e_dev_s *priv,
* the failure now.
*/
+ idbg("sem_wait: %d\n", errno);
DEBUGASSERT(errno == EINTR);
ret = -EINTR;
goto errout;
}
}
- /* Re-acquire the the semaphore that manages mutually exclusive access to
+ ivdbg("Sampled\n");
+
+ /* Re-acquire the the semaphore that manages mutually exclusive access to
* the device structure. We may have to wait here. But we have our sample.
* Interrupts and pre-emption will be re-enabled while we wait.
*/
@@ -512,15 +493,56 @@ errout:
}
/****************************************************************************
- * Name: ads7843e_transfer
+ * Name: ads7843e_schedule
****************************************************************************/
-static int ads7843e_transfer(FAR struct ads7843e_dev_s *priv, uint8_t cmd)
+static int ads7843e_schedule(FAR struct ads7843e_dev_s *priv)
{
- int ret = 0;
-#warning "Missing logic"
- ivdbg("data: 0x%04x\n", ret);
- return ret;
+ FAR struct ads7843e_config_s *config;
+ int ret;
+
+ /* Get a pointer the callbacks for convenience (and so the code is not so
+ * ugly).
+ */
+
+ config = priv->config;
+ DEBUGASSERT(config != NULL);
+
+ /* Disable further interrupts. ADS7843E interrupts will be re-enabled
+ * after the worker thread exectues.
+ */
+
+ config->enable(config, false);
+
+ /* Disable the watchdog timer. It will be re-enabled in the worker thread
+ * while the pen remains down.
+ */
+
+ wd_cancel(priv->wdog);
+
+ /* Transfer processing to the worker thread. Since ADS7843E interrupts are
+ * disabled while the work is pending, no special action should be required
+ * to protected the work queue.
+ */
+
+ DEBUGASSERT(priv->work.worker == NULL);
+ ret = work_queue(&priv->work, ads7843e_worker, priv, 0);
+ if (ret != 0)
+ {
+ illdbg("Failed to queue work: %d\n", ret);
+ }
+
+ return OK;
+}
+
+/****************************************************************************
+ * Name: ads7843e_wdog
+ ****************************************************************************/
+
+static void ads7843e_wdog(int argc, uint32_t arg1, ...)
+{
+ FAR struct ads7843e_dev_s *priv = (FAR struct ads7843e_dev_s *)((uintptr_t)arg1);
+ (void)ads7843e_schedule(priv);
}
/****************************************************************************
@@ -530,11 +552,8 @@ static int ads7843e_transfer(FAR struct ads7843e_dev_s *priv, uint8_t cmd)
static void ads7843e_worker(FAR void *arg)
{
FAR struct ads7843e_dev_s *priv = (FAR struct ads7843e_dev_s *)arg;
- FAR struct ads7843e_config_s *config; /* Convenience pointer */
- bool pendown; /* true: pend is down */
- uint16_t x; /* X position */
- uint16_t y; /* Y position */
-#warning "Missing other measurement data" /* Like size and pressure */
+ FAR struct ads7843e_config_s *config;
+ bool pendown;
ASSERT(priv != NULL);
@@ -545,6 +564,10 @@ static void ads7843e_worker(FAR void *arg)
config = priv->config;
DEBUGASSERT(config != NULL);
+ /* Disable the watchdog timer */
+
+ wd_cancel(priv->wdog);
+
/* Check for pen up or down by reading the PENIRQ GPIO. */
pendown = config->pendown(config);
@@ -561,24 +584,22 @@ static void ads7843e_worker(FAR void *arg)
{
goto errout;
}
+
+ /* The pen is up. NOTE: We know from a previous test, that this is a
+ * loss of contact condition. This will be changed to CONTACT_NONE
+ * after the loss of contact is sampled.
+ */
+
+ priv->sample.contact = CONTACT_UP;
}
else
{
/* Handle all pen down events. First, sample positional values. */
-#warning "Missing logic"
-
- /* Save the measurements */
+ priv->sample.x = ads7843e_sendcmd(priv, ADS7843_CMD_XPOSITION);
+ priv->sample.y = ads7843e_sendcmd(priv, ADS7843_CMD_YPOSITION);
+ (void)ads7843e_sendcmd(priv, ADS7843_CMD_ENABPINIRQ);
- priv->sample.x = x;
- priv->sample.y = y;
-#warning "Missing other measurement data" /* Like size and pressure */
- }
-
- /* Note the availability of new measurements */
-
- if (pendown)
- {
/* If this is the first (acknowledged) pend down report, then report
* this as the first contact. If contact == CONTACT_DOWN, it will be
* set to set to CONTACT_MOVE after the contact is first sampled.
@@ -590,15 +611,10 @@ static void ads7843e_worker(FAR void *arg)
priv->sample.contact = CONTACT_DOWN;
}
- }
- else /* if (priv->sample.contact != CONTACT_NONE) */
- {
- /* The pen is up. NOTE: We know from a previous test, that this is a
- * loss of contact condition. This will be changed to CONTACT_NONE
- * after the loss of contact is sampled.
- */
- priv->sample.contact = CONTACT_UP;
+ /* Continue to sample the position while the pen is down */
+
+ wd_start(priv->wdog, ADS7843E_WDOG_DELAY, ads7843e_wdog, 1, (uint32_t)priv);
}
/* Indicate the availability of new sample data for this ID */
@@ -624,7 +640,7 @@ static int ads7843e_interrupt(int irq, FAR void *context)
{
FAR struct ads7843e_dev_s *priv;
FAR struct ads7843e_config_s *config;
- int ret;
+ int ret;
/* Which ADS7843E device caused the interrupt? */
@@ -645,26 +661,14 @@ static int ads7843e_interrupt(int irq, FAR void *context)
config = priv->config;
DEBUGASSERT(config != NULL);
- /* Disable further interrupts */
-
- config->enable(config, false);
-
- /* Transfer processing to the worker thread. Since ADS7843E interrupts are
- * disabled while the work is pending, no special action should be required
- * to protected the work queue.
- */
+ /* Schedule sampling to occur on the worker thread */
- DEBUGASSERT(priv->work.worker == NULL);
- ret = work_queue(&priv->work, ads7843e_worker, priv, 0);
- if (ret != 0)
- {
- illdbg("Failed to queue work: %d\n", ret);
- }
+ ret = ads7843e_schedule(priv);
/* Clear any pending interrupts and return success */
config->clear(config);
- return OK;
+ return ret;
}
/****************************************************************************
@@ -679,6 +683,8 @@ static int ads7843e_open(FAR struct file *filep)
uint8_t tmp;
int ret;
+ ivdbg("Opening\n");
+
DEBUGASSERT(filep);
inode = filep->f_inode;
@@ -719,6 +725,7 @@ errout_with_sem:
sem_post(&priv->devsem);
return ret;
#else
+ ivdbg("Opening\n");
return OK;
#endif
}
@@ -734,6 +741,7 @@ static int ads7843e_close(FAR struct file *filep)
FAR struct ads7843e_dev_s *priv;
int ret;
+ ivdbg("Closing\n");
DEBUGASSERT(filep);
inode = filep->f_inode;
@@ -763,6 +771,7 @@ static int ads7843e_close(FAR struct file *filep)
sem_post(&priv->devsem);
#endif
+ ivdbg("Closing\n");
return OK;
}
@@ -773,11 +782,12 @@ static int ads7843e_close(FAR struct file *filep)
static ssize_t ads7843e_read(FAR struct file *filep, FAR char *buffer, size_t len)
{
FAR struct inode *inode;
- FAR struct ads7843e_dev_s *priv;
+ FAR struct ads7843e_dev_s *priv;
FAR struct touch_sample_s *report;
- struct ads7843e_sample_s sample;
+ struct ads7843e_sample_s sample;
int ret;
+ ivdbg("buffer:%p len:%d\n", buffer, len);
DEBUGASSERT(filep);
inode = filep->f_inode;
@@ -794,6 +804,7 @@ static ssize_t ads7843e_read(FAR struct file *filep, FAR char *buffer, size_t le
* handle smaller reads... but why?
*/
+ idbg("Unsupported read size: %d\n", len);
return -ENOSYS;
}
@@ -804,6 +815,7 @@ static ssize_t ads7843e_read(FAR struct file *filep, FAR char *buffer, size_t le
{
/* This should only happen if the wait was canceled by an signal */
+ idbg("sem_wait: %d\n", errno);
DEBUGASSERT(errno == EINTR);
return -EINTR;
}
@@ -818,6 +830,7 @@ static ssize_t ads7843e_read(FAR struct file *filep, FAR char *buffer, size_t le
* option, then just return an error.
*/
+ ivdbg("Sample data is not available\n");
if (filep->f_oflags & O_NONBLOCK)
{
ret = -EAGAIN;
@@ -831,6 +844,7 @@ static ssize_t ads7843e_read(FAR struct file *filep, FAR char *buffer, size_t le
{
/* We might have been awakened by a signal */
+ idbg("ads7843e_waitsample: %d\n", ret);
goto errout;
}
}
@@ -845,7 +859,6 @@ static ssize_t ads7843e_read(FAR struct file *filep, FAR char *buffer, size_t le
report->point[0].id = priv->id;
report->point[0].x = sample.x;
report->point[0].y = sample.y;
- report->point[0].pressure = 42; /* ???????????????????? */
/* Report the appropriate flags */
@@ -859,19 +872,25 @@ static ssize_t ads7843e_read(FAR struct file *filep, FAR char *buffer, size_t le
{
/* First contact */
- report->point[0].flags = TOUCH_DOWN | TOUCH_ID_VALID | TOUCH_POS_VALID | TOUCH_PRESSURE_VALID;
+ report->point[0].flags = TOUCH_DOWN | TOUCH_ID_VALID | TOUCH_POS_VALID;
}
else /* if (sample->contact == CONTACT_MOVE) */
{
/* Movement of the same contact */
- report->point[0].flags = TOUCH_MOVE | TOUCH_ID_VALID | TOUCH_POS_VALID | TOUCH_PRESSURE_VALID;
+ report->point[0].flags = TOUCH_MOVE | TOUCH_ID_VALID | TOUCH_POS_VALID;
}
+ ivdbg(" id: %d\n", report->point[0].id);
+ ivdbg(" flags: %02x\n", report->point[0].flags);
+ ivdbg(" x: %d\n", report->point[0].x);
+ ivdbg(" y: %d\n", report->point[0].y);
+
ret = SIZEOF_TOUCH_SAMPLE_S(1);
errout:
sem_post(&priv->devsem);
+ ivdbg("Returning: %d\n", ret);
return ret;
}
@@ -907,22 +926,6 @@ static int ads7843e_ioctl(FAR struct file *filep, int cmd, unsigned long arg)
switch (cmd)
{
- case TSIOC_SETCALIB: /* arg: Pointer to int calibration value */
- {
- FAR int *ptr = (FAR int *)((uintptr_t)arg);
- DEBUGASSERT(priv->config != NULL && ptr != NULL);
- priv->config->calib = *ptr;
- }
- break;
-
- case TSIOC_GETCALIB: /* arg: Pointer to int calibration value */
- {
- FAR int *ptr = (FAR int *)((uintptr_t)arg);
- DEBUGASSERT(priv->config != NULL && ptr != NULL);
- *ptr = priv->config->calib;
- }
- break;
-
case TSIOC_SETFREQUENCY: /* arg: Pointer to uint32_t frequency value */
{
FAR uint32_t *ptr = (FAR uint32_t *)((uintptr_t)arg);
@@ -1084,8 +1087,6 @@ int ads7843e_register(FAR struct spi_dev_s *dev,
/* Debug-only sanity checks */
DEBUGASSERT(dev != NULL && config != NULL && minor >= 0 && minor < 100);
- DEBUGASSERT(config->attach != NULL && config->enable != NULL &&
- config->clear != NULL && config->pendown != NULL);
/* Create and initialize a ADS7843E device driver instance */
@@ -1105,6 +1106,7 @@ int ads7843e_register(FAR struct spi_dev_s *dev,
memset(priv, 0, sizeof(struct ads7843e_dev_s));
priv->spi = dev; /* Save the SPI device handle */
priv->config = config; /* Save the board configuration */
+ priv->wdog = wd_create(); /* Create a watchdog timer */
sem_init(&priv->devsem, 0, 1); /* Initialize device structure semaphore */
sem_init(&priv->waitsem, 0, 0); /* Initialize pen event wait semaphore */
@@ -1126,10 +1128,13 @@ int ads7843e_register(FAR struct spi_dev_s *dev,
goto errout_with_priv;
}
- /* Initialize the touchscreen device */
+ /* Configure the SPI interface */
ads7843e_configspi(dev);
-#warning "Missing logic"
+
+ /* Enable the PEN IRQ */
+
+ ads7843e_sendcmd(priv, ADS7843_CMD_ENABPINIRQ);
/* Register the device as an input device */
diff --git a/nuttx/drivers/input/ads7843e.h b/nuttx/drivers/input/ads7843e.h
index 80106c3b8..17671aefd 100644
--- a/nuttx/drivers/input/ads7843e.h
+++ b/nuttx/drivers/input/ads7843e.h
@@ -44,14 +44,115 @@
* Included Files
********************************************************************************************/
+#include <nuttx/config.h>
+
+#include <stdint.h>
+#include <semaphore.h>
+#include <poll.h>
+#include <wdog.h>
+#include <nuttx/wqueue.h>
+
+#include <nuttx/spi.h>
+#include <nuttx/clock.h>
+#include <nuttx/input/ads7843e.h>
+
/********************************************************************************************
* Pre-Processor Definitions
********************************************************************************************/
+/* Configuration ****************************************************************************/
+/* Reference counting is partially implemented, but not needed in the
+ * current design.
+ */
+
+#undef CONFIG_ADS7843E_REFCNT
+
+/* ADS7843E Interfaces *********************************************************************/
+/* ADS7843E command bit settings */
+
+#define ADS7843E_CMD_PD0 (1 << 0) /* PD0 */
+#define ADS7843E_CMD_PD1 (1 << 1) /* PD1 */
+#define ADS7843E_CMD_DFR (1 << 2) /* SER/DFR */
+#define ADS7843E_CMD_EIGHT_BITS_MOD (1 << 3) /* Mode */
+#define ADS7843E_CMD_START (1 << 7) /* Start Bit */
+#define ADS7843E_CMD_SWITCH_SHIFT 4 /* Address setting */
+
+/* ADS7843E Commands */
+
+#define ADS7843_CMD_YPOSITION \
+ ((1 << ADS7843E_CMD_SWITCH_SHIFT)|ADS7843E_CMD_START|ADS7843E_CMD_PD0|ADS7843E_CMD_PD1)
+#define ADS7843_CMD_XPOSITION \
+ ((5 << ADS7843E_CMD_SWITCH_SHIFT)|ADS7843E_CMD_START|ADS7843E_CMD_PD0|ADS7843E_CMD_PD1)
+#define ADS7843_CMD_ENABPINIRQ \
+ ((1 << ADS7843E_CMD_SWITCH_SHIFT)|ADS7843E_CMD_START)
+
+/* Driver support **************************************************************************/
+/* This format is used to construct the /dev/input[n] device driver path. It
+ * defined here so that it will be used consistently in all places.
+ */
+
+#define DEV_FORMAT "/dev/input%d"
+#define DEV_NAMELEN 16
+
+/* Poll the pen position while the pen is down at this rate (50MS): */
+
+#define ADS7843E_WDOG_DELAY ((50 + (MSEC_PER_TICK-1))/ MSEC_PER_TICK)
/********************************************************************************************
* Public Types
********************************************************************************************/
+/* This describes the state of one contact */
+
+enum ads7843e_contact_3
+{
+ CONTACT_NONE = 0, /* No contact */
+ CONTACT_DOWN, /* First contact */
+ CONTACT_MOVE, /* Same contact, possibly different position */
+ CONTACT_UP, /* Contact lost */
+};
+
+/* This structure describes the results of one ADS7843E sample */
+
+struct ads7843e_sample_s
+{
+ uint8_t id; /* Sampled touch point ID */
+ uint8_t contact; /* Contact state (see enum ads7843e_contact_e) */
+ uint16_t x; /* Measured X position */
+ uint16_t y; /* Measured Y position */
+};
+
+/* This structure describes the state of one ADS7843E driver instance */
+
+struct ads7843e_dev_s
+{
+#ifdef CONFIG_ADS7843E_MULTIPLE
+ FAR struct ads7843e_dev_s *flink; /* Supports a singly linked list of drivers */
+#endif
+#ifdef CONFIG_ADS7843E_REFCNT
+ uint8_t crefs; /* Number of times the device has been opened */
+#endif
+ uint8_t nwaiters; /* Number of threads waiting for ADS7843E data */
+ uint8_t id; /* Current touch point ID */
+ volatile bool penchange; /* An unreported event is buffered */
+ sem_t devsem; /* Manages exclusive access to this structure */
+ sem_t waitsem; /* Used to wait for the availability of data */
+
+ FAR struct ads7843e_config_s *config; /* Board configuration data */
+ FAR struct spi_dev_s *spi; /* Saved SPI driver instance */
+ struct work_s work; /* Supports the interrupt handling "bottom half" */
+ struct ads7843e_sample_s sample; /* Last sampled touch point data */
+ WDOG_ID wdog; /* Poll the position while the pen is down */
+
+ /* The following is a list if poll structures of threads waiting for
+ * driver events. The 'struct pollfd' reference for each open is also
+ * retained in the f_priv field of the 'struct file'.
+ */
+
+#ifndef CONFIG_DISABLE_POLL
+ struct pollfd *fds[CONFIG_ADS7843E_NPOLLWAITERS];
+#endif
+};
+
/********************************************************************************************
* Public Function Prototypes
********************************************************************************************/
diff --git a/nuttx/drivers/lcd/Make.defs b/nuttx/drivers/lcd/Make.defs
index 596cce7d5..596cce7d5 100755..100644
--- a/nuttx/drivers/lcd/Make.defs
+++ b/nuttx/drivers/lcd/Make.defs
diff --git a/nuttx/drivers/lcd/nokia6100.c b/nuttx/drivers/lcd/nokia6100.c
index d450e05db..d450e05db 100755..100644
--- a/nuttx/drivers/lcd/nokia6100.c
+++ b/nuttx/drivers/lcd/nokia6100.c
diff --git a/nuttx/drivers/lcd/p14201.c b/nuttx/drivers/lcd/p14201.c
index 9dd2e6da9..9dd2e6da9 100755..100644
--- a/nuttx/drivers/lcd/p14201.c
+++ b/nuttx/drivers/lcd/p14201.c
diff --git a/nuttx/drivers/lcd/pcf8833.h b/nuttx/drivers/lcd/pcf8833.h
index b0a7e14d4..b0a7e14d4 100755..100644
--- a/nuttx/drivers/lcd/pcf8833.h
+++ b/nuttx/drivers/lcd/pcf8833.h
diff --git a/nuttx/drivers/lcd/s1d15g10.h b/nuttx/drivers/lcd/s1d15g10.h
index df2dd8be2..df2dd8be2 100755..100644
--- a/nuttx/drivers/lcd/s1d15g10.h
+++ b/nuttx/drivers/lcd/s1d15g10.h
diff --git a/nuttx/drivers/lcd/sd1329.h b/nuttx/drivers/lcd/sd1329.h
index f578d808c..f578d808c 100755..100644
--- a/nuttx/drivers/lcd/sd1329.h
+++ b/nuttx/drivers/lcd/sd1329.h
diff --git a/nuttx/drivers/lcd/skeleton.c b/nuttx/drivers/lcd/skeleton.c
index 1cb8b5955..1cb8b5955 100755..100644
--- a/nuttx/drivers/lcd/skeleton.c
+++ b/nuttx/drivers/lcd/skeleton.c
diff --git a/nuttx/drivers/lcd/ssd1305.h b/nuttx/drivers/lcd/ssd1305.h
index 87c955de4..87c955de4 100755..100644
--- a/nuttx/drivers/lcd/ssd1305.h
+++ b/nuttx/drivers/lcd/ssd1305.h
diff --git a/nuttx/drivers/lcd/ug-9664hswag01.c b/nuttx/drivers/lcd/ug-9664hswag01.c
index bb49f20e6..bb49f20e6 100755..100644
--- a/nuttx/drivers/lcd/ug-9664hswag01.c
+++ b/nuttx/drivers/lcd/ug-9664hswag01.c
diff --git a/nuttx/drivers/mtd/at24xx.c b/nuttx/drivers/mtd/at24xx.c
index 2aa116d83..2aa116d83 100755..100644
--- a/nuttx/drivers/mtd/at24xx.c
+++ b/nuttx/drivers/mtd/at24xx.c
diff --git a/nuttx/drivers/mtd/flash_eraseall.c b/nuttx/drivers/mtd/flash_eraseall.c
index 5f607da35..5f607da35 100755..100644
--- a/nuttx/drivers/mtd/flash_eraseall.c
+++ b/nuttx/drivers/mtd/flash_eraseall.c
diff --git a/nuttx/drivers/mtd/ftl.c b/nuttx/drivers/mtd/ftl.c
index f01a19470..f01a19470 100755..100644
--- a/nuttx/drivers/mtd/ftl.c
+++ b/nuttx/drivers/mtd/ftl.c
diff --git a/nuttx/drivers/mtd/ramtron.c b/nuttx/drivers/mtd/ramtron.c
index 9f1844762..9f1844762 100755..100644
--- a/nuttx/drivers/mtd/ramtron.c
+++ b/nuttx/drivers/mtd/ramtron.c
diff --git a/nuttx/drivers/net/cs89x0.h b/nuttx/drivers/net/cs89x0.h
index c2073eb98..c2073eb98 100755..100644
--- a/nuttx/drivers/net/cs89x0.h
+++ b/nuttx/drivers/net/cs89x0.h
diff --git a/nuttx/drivers/net/enc28j60.c b/nuttx/drivers/net/enc28j60.c
index 448decbf8..448decbf8 100755..100644
--- a/nuttx/drivers/net/enc28j60.c
+++ b/nuttx/drivers/net/enc28j60.c
diff --git a/nuttx/drivers/net/enc28j60.h b/nuttx/drivers/net/enc28j60.h
index 408224b22..408224b22 100755..100644
--- a/nuttx/drivers/net/enc28j60.h
+++ b/nuttx/drivers/net/enc28j60.h
diff --git a/nuttx/drivers/pm/Make.defs b/nuttx/drivers/pm/Make.defs
index 6204973f5..6204973f5 100755..100644
--- a/nuttx/drivers/pm/Make.defs
+++ b/nuttx/drivers/pm/Make.defs
diff --git a/nuttx/drivers/serial/uart_16550.c b/nuttx/drivers/serial/uart_16550.c
index 07c0dae36..07c0dae36 100755..100644
--- a/nuttx/drivers/serial/uart_16550.c
+++ b/nuttx/drivers/serial/uart_16550.c
diff --git a/nuttx/drivers/usbdev/usbdev_trprintf.c b/nuttx/drivers/usbdev/usbdev_trprintf.c
index 55c517b2e..55c517b2e 100755..100644
--- a/nuttx/drivers/usbdev/usbdev_trprintf.c
+++ b/nuttx/drivers/usbdev/usbdev_trprintf.c
diff --git a/nuttx/drivers/usbhost/usbhost_enumerate.c b/nuttx/drivers/usbhost/usbhost_enumerate.c
index 8e1cd80e7..8e1cd80e7 100755..100644
--- a/nuttx/drivers/usbhost/usbhost_enumerate.c
+++ b/nuttx/drivers/usbhost/usbhost_enumerate.c
diff --git a/nuttx/include/nuttx/input/ads7843e.h b/nuttx/include/nuttx/input/ads7843e.h
index 241abc87a..6b8ef1f9d 100644
--- a/nuttx/include/nuttx/input/ads7843e.h
+++ b/nuttx/include/nuttx/input/ads7843e.h
@@ -61,10 +61,10 @@
#endif
#ifndef CONFIG_ADS7843E_SPIMODE
-# define CONFIG_ADS7843E_SPIMODE SPIDEV_MODE0
+# define CONFIG_ADS7843E_SPIMODE SPIDEV_MODE1
#endif
- /* Check for some required settings. This can save the user a lot of time
+/* Check for some required settings. This can save the user a lot of time
* in getting the right configuration.
*/
@@ -94,7 +94,6 @@ struct ads7843e_config_s
{
/* Device characterization */
- uint16_t calib; /* Calibration resistance */
uint32_t frequency; /* SPI frequency */
/* If multiple ADS7843E devices are supported, then an IRQ number must
@@ -120,6 +119,7 @@ struct ads7843e_config_s
int (*attach)(FAR struct ads7843e_config_s *state, xcpt_t isr);
void (*enable)(FAR struct ads7843e_config_s *state, bool enable);
void (*clear)(FAR struct ads7843e_config_s *state);
+ bool (*busy)(FAR struct ads7843e_config_s *state);
bool (*pendown)(FAR struct ads7843e_config_s *state);
};