summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2013-10-02 16:55:22 -0600
committerGregory Nutt <gnutt@nuttx.org>2013-10-02 16:55:22 -0600
commite96afc264a3b53bfc067d76957d442e9156eb20d (patch)
treef07fb8d3071dcba9a4ba87f95aacb46547bec3d1
parentb98e458fea73dd81b1f28640e0434fdcebbe7e23 (diff)
downloadpx4-nuttx-e96afc264a3b53bfc067d76957d442e9156eb20d.tar.gz
px4-nuttx-e96afc264a3b53bfc067d76957d442e9156eb20d.tar.bz2
px4-nuttx-e96afc264a3b53bfc067d76957d442e9156eb20d.zip
SAMA Touchscreen/ADC: More progress
-rw-r--r--nuttx/arch/arm/src/sama5/chip/sam_adc.h12
-rw-r--r--nuttx/arch/arm/src/sama5/sam_adc.c373
-rw-r--r--nuttx/arch/arm/src/sama5/sam_touchscreen.c898
-rw-r--r--nuttx/arch/arm/src/sama5/sam_touchscreen.h4
-rw-r--r--nuttx/configs/sama5d3x-ek/include/board_384mhz.h3
-rw-r--r--nuttx/configs/sama5d3x-ek/include/board_396mhz.h3
6 files changed, 1185 insertions, 108 deletions
diff --git a/nuttx/arch/arm/src/sama5/chip/sam_adc.h b/nuttx/arch/arm/src/sama5/chip/sam_adc.h
index f466e2b73..da94e51e0 100644
--- a/nuttx/arch/arm/src/sama5/chip/sam_adc.h
+++ b/nuttx/arch/arm/src/sama5/chip/sam_adc.h
@@ -50,7 +50,9 @@
****************************************************************************************/
/* General definitions ******************************************************************/
-#define SAM_ADC_NCHANNELS 12 /* 12 ADC Channels */
+#define SAM_ADC_NCHANNELS 12 /* 12 ADC Channels */
+#define SAM_ADC_MAXPERCLK 66000000 /* Maximum peripheral clock frequency */
+#define SAM_ADC_CLOCKMAX 20000000 /* Maximum ADC Clock Frequency (Hz) */
/* ADC register offsets ****************************************************************/
@@ -263,6 +265,10 @@
#define ADC_CH10 (1 << 10) /* Bit 10: Channel 10 Enable */
#define ADC_CH11 (1 << 11) /* Bit 11: Channel 11 Enable */
+#define TSD_4WIRE_ALL (0x0000000f)
+#define TSD_5WIRE_ALL (0x0000001f)
+#define ADC_CHALL (0x00000fff)
+
/* Last Converted Data Register */
#define ADC_LCDR_DATA_SHIFT (0) /* Bits 0-11: Last Data Converted */
@@ -448,7 +454,7 @@
# define ADC_TSMR_TSSCTIM(n) ((uint32_t)(n) << ADC_TSMR_TSSCTIM_SHIFT)
#define ADC_TSMR_NOTSDMA (1 << 22) /* Bit 22: No TouchScreen DMA */
#define ADC_TSMR_PENDET (1 << 24) /* Bit 24: Pen Contact Detection Enable */
-#define ADC_TSMR_PENDBC_SHIFT (28) /* Bit 28-31: Pen Detect Debouncing Period */
+#define ADC_TSMR_PENDBC_SHIFT (28) /* Bit 28-31: Pen Detect Debouncing Period */
#define ADC_TSMR_PENDBC_MASK (15 << ADC_TSMR_PENDBC_SHIFT)
# define ADC_TSMR_PENDBC(n) ((uint32_t)(n) << ADC_TSMR_PENDBC_SHIFT)
@@ -465,7 +471,7 @@
#define ADC_YPOSR_YPOS_MASK (0xfff << ADC_YPOSR_YPOS_SHIFT)
#define ADC_YPOSR_YSCALE_SHIFT (16) /* Bit 16-27: Scale of YPOS */
#define ADC_YPOSR_YSCALE_MASK (0xfff << ADC_YPOSR_YSCALE_SHIFT)
-0xfff
+
/* Touchscreen Pressure Register */
#define ADC_PRESSR_Z1_SHIFT (0) /* Bit 0-11: Data of Z1 Measurement */
diff --git a/nuttx/arch/arm/src/sama5/sam_adc.c b/nuttx/arch/arm/src/sama5/sam_adc.c
index eb8f8c2ac..b9c52ff3a 100644
--- a/nuttx/arch/arm/src/sama5/sam_adc.c
+++ b/nuttx/arch/arm/src/sama5/sam_adc.c
@@ -4,6 +4,16 @@
* Copyright (C) 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
+ * References:
+ *
+ * SAMA5D3 Series Data Sheet
+ * Atmel NoOS sample code.
+ *
+ * The Atmel sample code has a BSD compatibile license that requires this
+ * copyright notice:
+ *
+ * Copyright (c) 2012, Atmel Corporation
+ *
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
@@ -14,8 +24,8 @@
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
- * 3. Neither the name NuttX nor the names of its contributors may be
- * used to endorse or promote products derived from this software
+ * 3. Neither the names NuttX nor Atmel nor the names of its contributors
+ * may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
@@ -58,6 +68,7 @@
#include "chip.h"
#include "chip/sam_adc.h"
+#include "chip/sam_pmc.h"
#include "sam_dmac.h"
#include "sam_adc.h"
@@ -125,6 +136,16 @@
SAMA5_CHAN6_ENABLE || SAMA5_CHAN7_ENABLE || SAMA5_CHAN8_ENABLE || \
SAMA5_CHAN9_ENABLE || SAMA5_CHAN10_ENABLE || SAMA5_CHAN11_ENABLE)
+#ifdef CONFIG_SAMA5_TOUCHSCREEN
+# ifdef CONFIG_SAMA5_TSD_5WIRE
+# SAMA5_ADC_CHALL (ADC_CHALL & ~TSD_5WIRE_ALL)
+# else
+# SAMA5_ADC_CHALL (ADC_CHALL & ~TSD_4WIRE_ALL)
+# endif
+#else
+# SAMA5_ADC_CHALL ADC_CHALL
+#endif
+
/* DMA configuration flags */
#ifdef CONFIG_SAMA5_ADC_DMA
@@ -138,7 +159,53 @@
DMACH_FLAG_MEMCHUNKSIZE_1)
#endif
-#define ADC_CLOCK_MAX 20000000 /* Max ADC Clock Frequency (Hz) */
+/* Pick an unused channel number */
+
+#if defined(CONFIG_SAMA5_ADC_CHAN0)
+# define SAMA5_ADC_UNUSED 0
+#elif defined(CONFIG_SAMA5_ADC_CHAN1)
+# define SAMA5_ADC_UNUSED 1
+#elif defined(CONFIG_SAMA5_ADC_CHAN2)
+# define SAMA5_ADC_UNUSED 2
+#elif defined(CONFIG_SAMA5_ADC_CHAN3)
+# define SAMA5_ADC_UNUSED 3
+#elif defined(CONFIG_SAMA5_ADC_CHAN4)
+# define SAMA5_ADC_UNUSED 4
+#elif defined(CONFIG_SAMA5_ADC_CHAN5)
+# define SAMA5_ADC_UNUSED 5
+#elif defined(CONFIG_SAMA5_ADC_CHAN6)
+# define SAMA5_ADC_UNUSED 6
+#elif defined(CONFIG_SAMA5_ADC_CHAN7)
+# define SAMA5_ADC_UNUSED 7
+#elif defined(CONFIG_SAMA5_ADC_CHAN8)
+# define SAMA5_ADC_UNUSED 8
+#elif defined(CONFIG_SAMA5_ADC_CHAN9)
+# define SAMA5_ADC_UNUSED 9
+#elif defined(CONFIG_SAMA5_ADC_CHAN10)
+# define SAMA5_ADC_UNUSED 10
+#elif defined(CONFIG_SAMA5_ADC_CHAN11)
+# define SAMA5_ADC_UNUSED 11
+#else
+# undef SAMA5_ADC_UNUSED
+#endif
+
+/* Clocking */
+
+#if BOARD_MCK_FREQUENCY <= SAM_ADC_MAXPERCLK
+# define ADC_FREQUENCY BOARD_MCK_FREQUENCY
+# define ADC_PCR_DIV PMC_PCR_DIV1
+#elif (BOARD_MCK_FREQUENCY >> 1) <= SAM_ADC_MAXPERCLK
+# define ADC_FREQUENCY (BOARD_MCK_FREQUENCY >> 1)
+# define ADC_PCR_DIV PMC_PCR_DIV2
+#elif (BOARD_MCK_FREQUENCY >> 2) <= SAM_ADC_MAXPERCLK
+# define ADC_FREQUENCY (BOARD_MCK_FREQUENCY >> 2)
+# define ADC_PCR_DIV PMC_PCR_DIV4
+#elif (BOARD_MCK_FREQUENCY >> 3) <= SAM_ADC_MAXPERCLK
+# define ADC_FREQUENCY (BOARD_MCK_FREQUENCY >> 3)
+# define ADC_PCR_DIV PMC_PCR_DIV8
+#else
+# error Cannot realize ADC input frequency
+#endif
/****************************************************************************
* Private Types
@@ -202,6 +269,11 @@ static int sam_adc_setup(struct adc_dev_s *dev);
static void sam_adc_shutdown(struct adc_dev_s *dev);
static void sam_adc_rxint(struct adc_dev_s *dev, bool enable);
static int sam_adc_ioctl(struct adc_dev_s *dev, int cmd, unsigned long arg);
+
+/* Initialization/Configuration */
+
+static void sam_adc_sequencer(struct sam_tsd_s *priv);
+static void sam_adc_channels(truct sam_tsd_s *priv);
#endif
/****************************************************************************
@@ -547,24 +619,28 @@ static int sam_adc_interrupt(int irq, void *context)
static void sam_adc_reset(struct adc_dev_s *dev)
{
struct sam_adc_s *priv = (struct sam_adc_s *)dev->ad_priv;
- irqstate_t flags;
uint32_t regval;
-#ifdef CONFIG_SAMA5_ADC_DMA
- /* Stop any ongoing DMA */
+ /* NOTE: We can't really reset the ADC hardware without losing the
+ * touchscreen configuration.
+ */
- sam_dmastop(priv->dma);
-#endif
+ /* Disable all EOC interrupts */
- /* Reset the ADC controller */
+ sam_adc_putreg(priv, SAM_ADC_IDR, ADC_INT_EOCALL);
- flags = irqsave();
- sam_adc_putreg(priv, SAM_ADC_CR, ADC_CR_SWRST);
+ /* Disable all channels */
- /* Reset Mode Register */
+ sam_adc_putreg(priv, SAM_ADC_CHDR, SAMA5_ADC_CHALL);
- sam_adc_putreg(priv, SAM_ADC_MR, 0);
- irqrestore(flags);
+ /* Disable the sequencer */
+
+ regval = sam_adc_getreg(priv, SAM_ADC_MR);
+ regval &= ~ADC_MR_USEQ;
+ sam_adc_putreg(priv, SAM_ADC_MR, regval);
+
+ /* Gain, offset, autocal, trigger mode, etc */
+#warning Missing logic
}
/****************************************************************************
@@ -583,6 +659,30 @@ static int sam_adc_setup(struct adc_dev_s *dev)
struct sam_adc_s *priv = (struct sam_adc_s *)dev->ad_priv;
int ret;
+ /* Enable (or disable) the sequencer */
+
+ sam_adc_sequencer(priv);
+
+ /* Enable ADC channels */
+
+ sam_adc_channels(priv);
+
+ /* Set gain and offset (only single ended mode used here) */
+#warning Missing logic
+
+ /* Set Auto Calibration Mode*/
+#warning Missing logic
+
+#ifdef CONFIG_SAMA5_ADC_DMA
+ /* Configure for DMA transfer */
+#warning Missing logic
+
+#else
+ /* Enable end-of-conversion interrupts for all enabled channels. */
+#warning Missing logic
+
+#endif
+
/* Attach the ADC interrupt */
ret = irq_attach(SAM_IRQ_ADC, sam_adc_interrupt);
@@ -595,6 +695,10 @@ static int sam_adc_setup(struct adc_dev_s *dev)
/* Enable the ADC interrupt */
up_enable_irq(SAM_IRQ_ADC);
+
+ /* Configure trigger mode and start convention */
+#warning Missing logic
+
return OK;
}
@@ -655,7 +759,7 @@ static void sam_adc_rxint(struct adc_dev_s *dev, bool enable)
* Name: sam_adc_ioctl
*
* Description:
- * All ioctl calls will be routed through this method
+ * All ioctl calls will be routed through this method
*
****************************************************************************/
@@ -667,6 +771,206 @@ static int sam_adc_ioctl(struct adc_dev_s *dev, int cmd, unsigned long arg)
}
/****************************************************************************
+ * Name: sam_adc_sequencer
+ *
+ * Description:
+ * Configure and enable the sequencer
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_SAMA5_ADC_SEQUENCER
+static void sam_adc_setseqr(int chan, uint32_t *seqr1, uint32_t *seqr2, int seq)
+{
+ if (seq > 8)
+ {
+ *seqr2 |= ADC_SEQR2_USCH(seq, chan);
+ }
+ else
+ {
+ *seqr1 |= ADC_SEQR1_USCH(seq, chan);
+ }
+}
+#endif
+
+static void sam_adc_sequencer(truct sam_tsd_s *priv)
+{
+#ifdef CONFIG_SAMA5_ADC_SEQUENCER
+ uint32_t seqr1;
+ uint32_t seqr2;
+ int seq;
+
+ /* Set user configured channel sequence */
+
+ seqr1 = 0;
+ seqr2 = 0;
+ seq = 0;
+
+#ifdef CONFIG_SAMA5_ADC_CHAN0
+ sam_adc_setseqr(0, &seqr1, &seqr2, seq++);
+#endif
+
+#ifdef CONFIG_SAMA5_ADC_CHAN1
+ sam_adc_setseqr(1, &seqr1, &seqr2, seq++);
+#endif
+
+#ifdef CONFIG_SAMA5_ADC_CHAN2
+ sam_adc_setseqr(2, &seqr1, &seqr2, seq++);
+#endif
+
+#ifdef CONFIG_SAMA5_ADC_CHAN3
+ sam_adc_setseqr(3, &seqr1, &seqr2, seq++);
+#endif
+
+#ifdef CONFIG_SAMA5_ADC_CHAN4
+ sam_adc_setseqr(4, &seqr1, &seqr2, seq++);
+#endif
+
+#ifdef CONFIG_SAMA5_ADC_CHAN5
+ sam_adc_setseqr(5, &seqr1, &seqr2, seq++);
+#endif
+
+#ifdef CONFIG_SAMA5_ADC_CHAN6
+ sam_adc_setseqr(6, &seqr1, &seqr2, seq++);
+#endif
+
+#ifdef CONFIG_SAMA5_ADC_CHAN7
+ sam_adc_setseqr(7, &seqr1, &seqr2, seq++);
+#endif
+
+#ifdef CONFIG_SAMA5_ADC_CHAN8
+ sam_adc_setseqr(8, &seqr1, &seqr2, seq++);
+#endif
+
+#ifdef CONFIG_SAMA5_ADC_CHAN9
+ sam_adc_setseqr(9, &seqr1, &seqr2, seq++);
+#endif
+
+#ifdef CONFIG_SAMA5_ADC_CHAN10
+ sam_adc_setseqr(10, &seqr1, &seqr2, seq++);
+#endif
+
+#ifdef CONFIG_SAMA5_ADC_CHAN11
+ sam_adc_setseqr(11, &seqr1, &seqr2, seq++);
+#endif
+
+ /* If not all channels are used, then program an unused channel number
+ * into the remaining slots. If we don't do this, we will get multiple
+ * samples for the enabled channels.
+ */
+
+#ifdef SAMA5_ADC_UNUSED
+ for (; seq < 9; seq++)
+ {
+ seqr1 |= ADC_SEQR1_USCH(seq, SAMA5_ADC_UNUSED);
+ }
+
+ for (; seq < 12; seq++)
+ {
+ seqr2 |= ADC_SEQR2_USCH(seq, SAMA5_ADC_UNUSED);
+ }
+#endif
+
+ /* Save the new values to the SEQR1 and SEQR2 registers */
+
+ sam_adc_putreg(priv, SAM_ADC_SEQR1, seqr1);
+ sam_adc_putreg(priv, SAM_ADC_SEQR2, seqr2);
+
+ /* Enable sequencer. Any channel that is not enabled will be skipped by
+ * the sequencer (that is why we programmed the unused channels above.
+ */
+
+ regval = sam_adc_getreg(priv, SAM_ADC_MR);
+ regval |= ADC_MR_USEQ;
+ sam_adc_putreg(priv, SAM_ADC_MR, regval);
+
+#else
+ uint32_t regval;
+
+ /* Disable the sequencer */
+
+ regval = sam_adc_getreg(priv, SAM_ADC_MR);
+ regval &= ~ADC_MR_USEQ;
+ sam_adc_putreg(priv, SAM_ADC_MR, regval);
+
+#endif
+}
+#endif
+
+/****************************************************************************
+ * Name: sam_adc_channels
+ *
+ * Description:
+ * Configure and enable the channels
+ *
+ ****************************************************************************/
+
+static void sam_adc_channels(truct sam_tsd_s *priv)
+{
+ uint32_t regval;
+
+ /* Disable the sequencer */
+
+ regval = sam_adc_getreg(priv, SAM_ADC_MR);
+ regval &= ~ADC_MR_USEQ;
+ sam_adc_putreg(priv, SAM_ADC_MR, regval);
+
+ /* Enable channels. */
+
+ regval = 0;
+
+ #ifdef CONFIG_SAMA5_ADC_CHAN0
+ regval |= ADC_CH0;
+#endif
+
+#ifdef CONFIG_SAMA5_ADC_CHAN1
+ regval |= ADC_CH0;
+#endif
+
+#ifdef CONFIG_SAMA5_ADC_CHAN2
+ regval |= ADC_CH0;
+#endif
+
+#ifdef CONFIG_SAMA5_ADC_CHAN3
+ regval |= ADC_CH0;
+#endif
+
+#ifdef CONFIG_SAMA5_ADC_CHAN4
+ regval |= ADC_CH0;
+#endif
+
+#ifdef CONFIG_SAMA5_ADC_CHAN5
+ regval |= ADC_CH0;
+#endif
+
+#ifdef CONFIG_SAMA5_ADC_CHAN6
+ regval |= ADC_CH0;
+#endif
+
+#ifdef CONFIG_SAMA5_ADC_CHAN7
+ regval |= ADC_CH0;
+#endif
+
+#ifdef CONFIG_SAMA5_ADC_CHAN8
+ regval |= ADC_CH0;
+#endif
+
+#ifdef CONFIG_SAMA5_ADC_CHAN9
+ regval |= ADC_CH0;
+#endif
+
+#ifdef CONFIG_SAMA5_ADC_CHAN10
+ regval |= ADC_CH0;
+#endif
+
+#ifdef CONFIG_SAMA5_ADC_CHAN11
+ regval |= ADC_CH0;
+#endif
+
+ sam_adc_putreg(priv, SAM_ADC_CHER, regval);
+}
+#endif
+
+/****************************************************************************
* Public Functions
****************************************************************************/
@@ -683,9 +987,9 @@ static int sam_adc_ioctl(struct adc_dev_s *dev, int cmd, unsigned long arg)
struct adc_dev_s *sam_adc_initialize(void)
{
- /* Enable the ADC peripheral clock*/
+ /* Disable ADC peripheral clock */
- sam_adc_enableclk();
+ sam_adc_disableclk();
/* Configure ADC pins */
@@ -740,6 +1044,15 @@ struct adc_dev_s *sam_adc_initialize(void)
DEBUGASSERT(priv->dma);
#endif
+ /* Set the maximum ADC peripheral clock frequency */
+
+ regval = PMC_PCR_PID(SAM_PID_ADC) | PMC_PCR_CMD | ADC_PCR_DIV | PMC_PCR_EN;
+ sam_adc_putreg(priv, SAM_PMC_PCR, regval);
+
+ /* Enable the ADC peripheral clock*/
+
+ sam_adc_enableclk();
+
/* Reset the ADC controller */
sam_adc_putreg(priv, SAM_ADC_CR, ADC_CR_SWRST);
@@ -748,6 +1061,32 @@ struct adc_dev_s *sam_adc_initialize(void)
sam_adc_putreg(priv, SAM_ADC_MR, 0);
+ /* Set the MCK clock prescaler: ADCClock = MCK / ((PRESCAL+1)*2) */
+
+ regval = sam_adc_getreg(priv, SAM_ADC_MR);
+ regval &= ~ADC_MR_PRESCAL_MASK;
+ regval |= ADC_MR_PRESCAL(BOARD_ADC_PRESCAL);
+ sam_adc_putreg(priv, SAM_ADC_MR, regval);
+
+ /* Formula:
+ * Startup Time = startup value / ADCClock
+ * Transfer Time = (TRANSFER * 2 + 3) / ADCClock
+ * Tracking Time = (TRACKTIM + 1) / ADCClock
+ * Settling Time = settling value / ADCClock
+ * For example, ADC clock = 6MHz (166.7 ns)
+ * Startup time = 512 / 6MHz = 85.3 us
+ * Transfer Time = (1 * 2 + 3) / 6MHz = 833.3 ns
+ * Tracking Time = (0 + 1) / 6MHz = 166.7 ns
+ * Settling Time = 3 / 6MHz = 500 ns
+ */
+
+ /* Set ADC timing */
+
+ regval = sam_adc_getreg(priv, SAM_ADC_MR);
+ regval &= ~(ADC_MR_STARTUP_MASK | ADC_MR_TRACKTIM_MASK | ADC_MR_SETTLING_MASK);
+ regval |= ADC_MR_STARTUP_SUT512 | ADC_MR_TRACKTIM(0) | ADC_MR_SETTLING_AST17;
+ sam_adc_puttreg(priv, SAM_ADC_MR, regval);
+
/* Return a pointer to the device structure */
return &g_adcdev;
diff --git a/nuttx/arch/arm/src/sama5/sam_touchscreen.c b/nuttx/arch/arm/src/sama5/sam_touchscreen.c
index ee59677cd..8b3db2818 100644
--- a/nuttx/arch/arm/src/sama5/sam_touchscreen.c
+++ b/nuttx/arch/arm/src/sama5/sam_touchscreen.c
@@ -4,6 +4,16 @@
* Copyright (C) 2013 Gregory Nutt. All rights reserved.
* Authors: Gregory Nutt <gnutt@nuttx.org>
*
+ * References:
+ *
+ * SAMA5D3 Series Data Sheet
+ * Atmel NoOS sample code.
+ *
+ * The Atmel sample code has a BSD compatibile license that requires this
+ * copyright notice:
+ *
+ * Copyright (c) 2011, Atmel Corporation
+ *
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
@@ -14,8 +24,8 @@
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
- * 3. Neither the name NuttX nor the names of its contributors may be
- * used to endorse or promote products derived from this software
+ * 3. Neither the names NuttX nor Atmel nor the names of its contributors
+ * may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
@@ -95,13 +105,34 @@
#define ADC_TSD_ALLSTATUS (ADC_TSD_ALLINTS | ADC_INT_PENS)
#define ADC_TSD_RELEASEINTS ADC_TSD_CMNINTS
-/* Data ready/pen status bit definitions */
+/* Data read bit definitions */
#define TSD_XREADY (1 << 0) /* X value is ready */
#define TSD_YREADY (1 << 1) /* Y value is ready */
-#define TSD_PREADY (1 << 2) /* Pressure value is ready */
-#define TSD_PENDOWN (1 << 3) /* Pen is down */
-#define TSD_ALLREADY (TSD_XREADY | TSD_YREADY | TSD_PREADY)
+
+#ifdef CONFIG_SAMA5_TSD_4WIRE
+# define TSD_PREADY (1 << 2) /* Pressure value is ready */
+# define TSD_ALLREADY (TSD_XREADY | TSD_YREADY | TSD_PREADY)
+#else
+# define TSD_ALLREADY (TSD_XREADY | TSD_YREADY)
+#endif
+
+/* Pen sample state bit sets */
+
+#ifdef CONFIG_SAMA5_TSD_4WIRE
+# define TSD_PENUP_VALID (TOUCH_UP | TOUCH_ID_VALID | TOUCH_POS_VALID | \
+ TOUCH_PRESSURE_VALID)
+# define TSD_PENUP_INVALID (TOUCH_UP | TOUCH_ID_VALID)
+# define TSD_PENDOWN (TOUCH_DOWN | TOUCH_ID_VALID | TOUCH_POS_VALID | \
+ TOUCH_PRESSURE_VALID)
+# define TSD_PENMOVE (TOUCH_MOVE | TOUCH_ID_VALID | TOUCH_POS_VALID | \
+ TOUCH_PRESSURE_VALID)
+#else
+# define TSD_PENUP_VALID (TOUCH_UP | TOUCH_ID_VALID | TOUCH_POS_VALID)
+# define TSD_PENUP_INVALID (TOUCH_UP | TOUCH_ID_VALID)
+# define TSD_PENDOWN (TOUCH_DOWN | TOUCH_ID_VALID | TOUCH_POS_VALID)
+# define TSD_PENMOVE (TOUCH_MOVE | TOUCH_ID_VALID | TOUCH_POS_VALID)
+#endif
/****************************************************************************
* Private Types
@@ -123,9 +154,12 @@ struct sam_sample_s
{
uint8_t id; /* Sampled touch point ID */
uint8_t contact; /* Contact state (see enum sam_contact_e) */
- bool valid; /* True: x,y contain valid, sampled data */
+ bool valid; /* True: x,y,p contain valid, sampled data */
uint16_t x; /* Measured X position */
uint16_t y; /* Measured Y position */
+#ifdef CONFIG_SAMA5_TSD_4WIRE
+ uint16_t p; /* Measured pressure */
+#endif
};
/* This structure describes the state of one touchscreen driver instance */
@@ -134,10 +168,11 @@ struct sam_tsd_s
{
uint8_t nwaiters; /* Number of threads waiting for touchscreen data */
uint8_t id; /* Current touch point ID */
- uint8_t status; /* Data ready/pen status bit set */
+ uint8_t valid; /* Data ready bit set */
+ uint8_t crefs; /* The number of times the device has been opened */
volatile bool penchange; /* An unreported event is buffered */
- uint16_t threshx; /* Thresholding X value */
- uint16_t threshy; /* Thresholding Y value */
+ uint32_t threshx; /* Thresholding X value */
+ uint32_t threshy; /* Thresholding Y value */
volatile uint32_t pending; /* Pending interrupt set set */
sem_t waitsem; /* Used to wait for the availability of data */
@@ -180,6 +215,15 @@ static int sam_tsd_ioctl(struct file *filep, int cmd, unsigned long arg);
static int sam_tsd_poll(struct file *filep, struct pollfd *fds, bool setup);
#endif
+/* Initialization and configuration */
+
+static void sam_tsd_startuptime(struct sam_tsd_s *priv, uint32_t time);
+static void sam_tsd_tracking(struct sam_tsd_s *priv, uint32_t time);
+static void sam_tsd_trigperiod(struct sam_tsd_s *priv, uint32_t period);
+static void sam_tsd_debounce(struct sam_tsd_s *priv, uint32_t time);
+static void sam_tsd_initialize(struct sam_tsd_s *priv);
+static void sam_tsd_uninitialize(struct sam_tsd_s *priv);
+
/****************************************************************************
* Private Data
****************************************************************************/
@@ -399,7 +443,7 @@ errout:
*
****************************************************************************/
-static void sam_tsd_setaverage(truct sam_tsd_s *priv, uint32_t tsav)
+static void sam_tsd_setaverage(struct sam_tsd_s *priv, uint32_t tsav)
{
uint32_t regval;
uint32_t minfreq;
@@ -464,11 +508,18 @@ static void sam_tsd_bottomhalf(void *arg)
{
struct sam_tsd_s *priv = (struct sam_tsd_s *)arg;
uint32_t pending;
+ uint32_t ier;
uint32_t regval;
- uint16_t x;
- uint16_t y;
- uint16_t xdiff;
- uint16_t ydiff;
+ uint32_t xr;
+ uint32_t x;
+ uint32_t xdiff;
+ uint32_t yr;
+ uint32_t y;
+ uint32_t ydiff;
+ uint32_t xpos;
+ uint32_t z1;
+ uint32_t z2;
+ uint32_t pressr;
bool pendown;
int ret;
@@ -488,8 +539,9 @@ static void sam_tsd_bottomhalf(void *arg)
sam_adc_lock(priv->adc);
- /* Check for pen up or down by reading the PENIRQ GPIO. */
-#warning Missing logic
+ /* Check the pen state */
+
+ pendown = ((pending & ADC_SR_PENS) != 0);
/* Handle the change from pen down to pen up */
@@ -500,6 +552,16 @@ static void sam_tsd_bottomhalf(void *arg)
priv->threshx = INVALID_THRESHOLD;
priv->threshy = INVALID_THRESHOLD;
+ /* Clear data validity bits: There is no valid data to be sampled */
+
+ priv->valid = 0;
+
+ /* We will enable only the ADC_INT_PEN interrupt on exit. We don't
+ * want to hear anything from the touchscreen until the next touch.
+ */
+
+ ier = ADC_INT_PEN;
+
/* Ignore the interrupt if the pen was already up (CONTACT_NONE == pen up
* and already reported; CONTACT_UP == pen up, but not reported)
*/
@@ -517,6 +579,16 @@ static void sam_tsd_bottomhalf(void *arg)
*/
priv->sample.contact = CONTACT_UP;
+
+ /* Stop periodic trigger & enable pen */
+
+ sam_tsd_setaverage(priv, ADC_TSMR_TSAV_NO_FILTER);
+ sam_tsd_debounce(priv, BOARD_TSD_DEBOUNCE);
+
+ regval = sam_adc_getreg(priv, SAM_ADC_TRGR);
+ regval &= ~ADC_TRGR_TRGMOD_MASK;
+ regval |= ADC_TRGR_TRGMOD_PEN_TRIG;
+ sam_adc_putreg(priv, SAM_ADC_TRGR, regval);
}
/* It is a pen down event. If the last loss-of-contact event has not been
@@ -529,62 +601,177 @@ static void sam_tsd_bottomhalf(void *arg)
/* If we have not yet processed the last pen up event, then we
* cannot handle this pen down event. We will have to discard it. That
* should be okay because we will set the timer to to sample again
- * later.
+ * a little later. NOTE that pen interrupts are not re-enabled in
+ * this case; we rely on the timer expiry to get us going again.
*/
wd_start(priv->wdog, TSD_WDOG_DELAY, sam_tsd_expiry, 1, (uint32_t)priv);
+ ier = 0;
goto ignored;
}
else
{
- /* Handle pen down events. First, sample positional values. */
-#warning Missing logic
-
- /* Perform a thresholding operation so that the results will be more stable.
- * If the difference from the last sample is small, then ignore the event.
- * REVISIT: Should a large change in pressure also generate a event?
+ /* The pen is down and the driver has accepted the last sample values.
+ * check if we have accumulated all of the samples that we need.
*/
- xdiff = x > priv->threshx ? (x - priv->threshx) : (priv->threshx - x);
- ydiff = y > priv->threshy ? (y - priv->threshy) : (priv->threshy - y);
+ /* Check X data availability */
- /* Continue to sample the position while the pen is down */
-
- wd_start(priv->wdog, TSD_WDOG_DELAY, sam_tsd_expiry, 1, (uint32_t)priv);
+ if (pending & ADC_INT_XRDY)
+ {
+ priv->valid |= TSD_XREADY;
+ }
- /* Check the thresholds. Bail if there is no significant difference */
+ /* Check Y data availability */
- if (xdiff < CONFIG_SAMA5_TSD_THRESHX && ydiff < CONFIG_SAMA5_TSD_THRESHY)
+ if (pending & ADC_INT_YRDY)
{
- /* Little or no change in either direction ... don't report anything. */
+ priv->valid |= TSD_YREADY;
+ }
- goto ignored;
+#ifdef CONFIG_SAMA5_TSD_4WIRE
+ /* Check pressure data availability: (X/1024)*[(Z2/Z1)-1] */
+
+ if (pending & ADC_INT_PRDY)
+ {
+ priv->valid |= TSD_PREADY;
}
+#endif
+
+ /* While the pen is down we want interrupts on all day ready an pen
+ * release events.
+ */
+
+ ier = ADC_TSD_RELEASEINTS
- /* When we see a big difference, snap to the new x/y thresholds */
+ /* Check if all data is ready. If not, just re-enable interrupts and
+ * wait until it is.
+ */
- priv->threshx = x;
- priv->threshy = y;
+ if ((priv->valid & TSD_ALLREADY) == TSD_ALLREADY)
+ {
+ /* Clear data ready bits in the data validity bitset */
- /* Update the x/y position in the sample data */
+ priv->valid = 0;
- priv->sample.x = priv->threshx;
- priv->sample.y = priv->threshy;
+ /* Sample positional values. Get raw X and Y position data */
- /* The X/Y positional data is now valid */
+ xr = sam_adc_getreg(priv, SAM_ADC_XPOSR);
+ yr = sam_adc_getreg(priv, SAM_ADC_YPOSR);
- priv->sample.valid = true;
+#ifdef CONFIG_SAMA5_TSD_SWAPXY
+ /* Scale the measurements */
- /* If this is the first (acknowledged) pen down report, then report
- * this as the first contact. If contact == CONTACT_DOWN, it will be
- * set to set to CONTACT_MOVE after the contact is first sampled.
- */
+ x = ((yr & ADC_YPOSR_YPOS_MASK) >> ADC_YPOSR_YPOS_SHIFT) * 1024;
+ x /= ((yr & ADC_YPOSR_YSCALE_MASK) >> ADC_YPOSR_YSCALE_SHIFT);
- if (priv->sample.contact != CONTACT_MOVE)
- {
- /* First contact */
+ y = ((xr & ADC_XPOSR_XPOS_MASK) >> ADC_XPOSR_XPOS_SHIFT) * 1024;
+ y /= ((xr & ADC_XPOSR_XSCALE_MASK) >> ADC_XPOSR_XSCALE_SHIFT);
+#else
+ /* Scale the measurements */
+
+ x = ((xr & ADC_XPOSR_XPOS_MASK) >> ADC_XPOSR_XPOS_SHIFT) * 1024;
+ x /= ((xr & ADC_XPOSR_XSCALE_MASK) >> ADC_XPOSR_XSCALE_SHIFT);
+
+ y = ((yr & ADC_YPOSR_YPOS_MASK) >> ADC_YPOSR_YPOS_SHIFT) * 1024;
+ y /= ((yr & ADC_YPOSR_YSCALE_MASK) >> ADC_YPOSR_YSCALE_SHIFT);
+#endif
+
+#ifdef CONFIG_SAMA5_TSD_4WIRE
+ /* Read the PRESSR register now, but don't do anything until we
+ * decide if we are going to use this measurement.
+ */
+
+ pressr = sam_adc_getreg(priv, SAM_ADC_PRESSR);
+#endif
+
+ /* Perform a thresholding operation so that the results will be
+ * more stable. If the difference from the last sample is small,
+ * then ignore the event. REVISIT: Should a large change in
+ * pressure also generate a event?
+ */
+
+ xdiff = x > priv->threshx ? (x - priv->threshx) :
+ (priv->threshx - x);
+ ydiff = y > priv->threshy ? (y - priv->threshy) :
+ (priv->threshy - y);
+
+ /* Continue to sample the position while the pen is down */
+
+ wd_start(priv->wdog, TSD_WDOG_DELAY, sam_tsd_expiry,
+ 1, (uint32_t)priv);
- priv->sample.contact = CONTACT_DOWN;
+ /* Check the thresholds. Bail if (1) this is not the first
+ * measurement and (2) there is no significant difference from
+ * the last measurement.
+ */
+
+ if (priv->sample.contact == CONTACT_MOVE &&
+ xdiff < CONFIG_SAMA5_TSD_THRESHX &&
+ ydiff < CONFIG_SAMA5_TSD_THRESHY)
+ {
+ /* Little or no change in either direction ... don't report
+ * anything.
+ */
+
+ goto ignored;
+ }
+
+ /* When we see a big difference, snap to the new x/y thresholds */
+
+ priv->threshx = x;
+ priv->threshy = y;
+
+ /* Update the x/y position in the sample data */
+
+ priv->sample.x = MIN(x, UINT16_MAX);
+ priv->sample.y = MIN(x, UINT16_MAX);
+
+#ifdef CONFIG_SAMA5_TSD_4WIRE
+ /* Scale the pressure and update the pressure in the sample data.
+ *
+ * The method to measure the pressure (Rp) applied to the
+ * touchscreen is based on the known resistance of the X-Panel
+ * resistance (Rxp). Three conversions (Xpos, Z1, Z2) are
+ * necessary to determine the value of Rp (Zaxis resistance).
+ *
+ * Rp = Rxp*(Xpos/1024)*[(Z2/Z1)-1]
+ */
+
+ xpos = (xr & ADC_XPOSR_XPOS_MASK) >> ADC_XPOSR_XPOS_SHIFT;
+ z2 = (pressr & ADC_PRESSR_Z2_MASK) >> ADC_PRESSR_Z2_SHIFT;
+ z1 = (pressr & ADC_PRESSR_Z1_MASK) >> ADC_PRESSR_Z1_SHIFT;
+ p = CONFIG_SAMA_TSD_RXP * xpos * (z2 - z1) / z1;
+
+ priv->sample.p = MIN(p, UINT16_MAX);
+#endif
+
+ /* The X/Y positional data is now valid */
+
+ priv->sample.valid = true;
+
+ /* If this is the first (acknowledged) pen down report, then
+ * report this as the first contact. If contact == CONTACT_DOWN,
+ * it will be set to set to CONTACT_MOVE after the contact is
+ * first sampled.
+ */
+
+ if (priv->sample.contact != CONTACT_MOVE)
+ {
+ /* First contact. Handle transitions from pen UP to pen DOWN */
+
+ priv->sample.contact = CONTACT_DOWN;
+
+ /* Configure for periodic trigger */
+
+ sam_tsd_setaverage(priv, ADC_TSMR_TSAV_AVG8CONV);
+ sam_tsd_debounce(priv, 300); /* 300ns */
+
+ regval = sam_adc_getreg(priv, SAM_ADC_TRGR);
+ regval &= ~ADC_TRGR_TRGMOD_MASK;
+ regval |= ADC_TRGR_TRGMOD_PERIOD_TRIG;
+ sam_adc_putreg(priv, SAM_ADC_TRGR, regval);
+ }
}
}
@@ -600,9 +787,9 @@ static void sam_tsd_bottomhalf(void *arg)
/* Exit, re-enabling touchscreen interrupts */
ignored:
- /* Re-enable touchscreen interrupts. */
+ /* Re-enable touchscreen interrupts as appropriate. */
- sam_adc_putreg32(priv->adc, SAM_ADC_IER, ADC_TSD_ALLINTS);
+ sam_adc_putreg32(priv->adc, SAM_ADC_IER, ier);
/* Release our lock on the state structure */
@@ -678,18 +865,95 @@ static void sam_tsd_expiry(int argc, uint32_t arg1, ...)
static int sam_tsd_open(struct file *filep)
{
- ivdbg("Opening\n");
- return OK;
+ FAR struct inode *inode = filep->f_inode;
+ FAR struct sam_tsd_s *priv = inode->i_private;
+ uint8_t tmp;
+ int ret;
+
+ ivdbg("crefs: %d\n", priv->crefs);
+
+ /* Get exclusive access to the device structures */
+
+ sam_adc_lock(priv->adc);
+
+ /* Increment the count of references to the device. If this the first
+ * time that the driver has been opened for this device, then initialize
+ * the device.
+ */
+
+ tmp = priv->crefs + 1;
+ if (tmp == 0)
+ {
+ /* More than 255 opens; uint8_t overflows to zero */
+
+ ret = -EAGAIN;
+ }
+ else
+ {
+ /* Save the new open count */
+
+ priv->crefs = tmp;
+
+ /* Initialize the touchscreen when it is first opened */
+
+ ret = OK;
+ if (tmp == 1)
+ {
+ ret = sam_tsd_initialize(priv);
+ }
+ }
+
+errout_with_lock:
+ sam_adc_unlock(priv->adc);
+
+errout:
+ return ret;
}
+ /* Enable pen contact detection */
+
+ regval |= ADC_TSMR_PENDET;
+ sam_adc_putreg(priv->adc, SAM_ADC_TSMR, regval);
+
+ /* Set up pen debounce time */
+
+ sam_tsd_debounce(priv, BOARD_TSD_DEBOUNCE);
+
/****************************************************************************
* Name: sam_tsd_close
****************************************************************************/
static int sam_tsd_close(struct file *filep)
{
- ivdbg("Closing\n");
- return OK;
+ FAR struct inode *inode = filep->f_inode;
+ FAR struct watchdog_upperhalf_s *priv = inode->i_private;
+ int ret;
+
+ wdvdbg("crefs: %d\n", priv->crefs);
+
+ /* Get exclusive access to the device structures */
+
+ ret = sem_wait(&priv->exclsem);
+ if (ret < 0)
+ {
+ ret = -errno;
+ goto errout;
+ }
+
+ /* Decrement the references to the driver. If the reference count will
+ * decrement to 0, then uninitialize the driver.
+ */
+
+ if (priv->crefs > 0)
+ {
+ priv->crefs--;
+ }
+
+ sem_post(&priv->exclsem);
+ ret = OK;
+
+errout:
+ return ret;
}
/****************************************************************************
@@ -764,40 +1028,43 @@ static ssize_t sam_tsd_read(struct file *filep, char *buffer, size_t len)
report = (struct touch_sample_s *)buffer;
memset(report, 0, SIZEOF_TOUCH_SAMPLE_S(1));
- report->npoints = 1;
- report->point[0].id = sample.id;
- report->point[0].x = sample.x;
- report->point[0].y = sample.y;
+ report->npoints = 1;
+ report->point[0].id = sample.id;
+ report->point[0].x = sample.x;
+ report->point[0].y = sample.y;
+#ifdef CONFIG_SAMA5_TSD_4WIRE
+ report->point[0].pressure = sample.p;
+#endif
/* Report the appropriate flags */
if (sample.contact == CONTACT_UP)
{
- /* Pen is now up. Is the positional data valid? This is important to
- * know because the release will be sent to the window based on its
- * last positional data.
+ /* Pen is now up. Is the positional data valid? This is important
+ * to know because the release will be sent to the window based on
+ * its last positional data.
*/
if (sample.valid)
{
- report->point[0].flags = TOUCH_UP | TOUCH_ID_VALID | TOUCH_POS_VALID;
- }
+ report->point[0].flags = TSD_PENUP_VALID;
+# }
else
{
- report->point[0].flags = TOUCH_UP | TOUCH_ID_VALID;
+ report->point[0].flags = TSD_PENUP_INVALID;
}
}
else if (sample.contact == CONTACT_DOWN)
{
/* First contact */
- report->point[0].flags = TOUCH_DOWN | TOUCH_ID_VALID | TOUCH_POS_VALID;
+ report->point[0].flags = TSD_PENDOWN;
}
else /* if (sample->contact == CONTACT_MOVE) */
{
/* Movement of the same contact */
- report->point[0].flags = TOUCH_MOVE | TOUCH_ID_VALID | TOUCH_POS_VALID;
+ report->point[0].flags = TSD_PENMOVE;
}
ivdbg(" id: %d\n", report->point[0].id);
@@ -934,9 +1201,482 @@ errout:
#endif
/****************************************************************************
- * Public Functions
+ * Initialization and Configuration
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: sam_tsd_startuptime
+ *
+ * Description:
+ * Set the STARTUP field of the ADC MR register.
+ *
+ * Input Parameters:
+ * priv - A reference to the touchscreen device structure
+ * time - The new startup time in nanoseconds
+ *
+ * Returned Value:
+ * None
+ *
****************************************************************************/
+static void sam_tsd_startuptime(struct sam_tsd_s *priv, uint32_t time)
+{
+ uint32_t startup;
+ uint32_t regval;
+
+ /* Formula for STARTUP is:
+ *
+ * STARTUP = (time x ADCCLK) / (1000000) - 1
+ *
+ * Division multiplied by 10 for higher precision.
+ */
+
+ startup = (time * BOARD_ADCCLK_FREQUENCY) / 100000;
+
+ if (startup % 10)
+ {
+ /* Handle partial values by not decrementing startup. This is
+ * basically a 'ceil' operation.
+ */
+
+ startup /= 10;
+ }
+ else
+ {
+ /* The final value needs to be decrement by one */
+
+ startup /= 10;
+ if (startup)
+ {
+ startup --;
+ }
+ }
+
+ /* Then set the STARTUP value in the ADC MR register. */
+
+ regval = sam_adc_getreg(priv->adc, SAM_ADC_MR);
+ regval &= ~ADC_MR_STARTUP_MASK;
+
+ if (startup > 896)
+ {
+ regval = ADC_MR_STARTUP_960;
+ }
+ else if (startup > 832)
+ {
+ regval = ADC_MR_STARTUP_896;
+ }
+ else if (startup > 768)
+ {
+ regval = ADC_MR_STARTUP_832;
+ }
+ else if (startup > 704)
+ {
+ regval = ADC_MR_STARTUP_768;
+ }
+ else if (startup > 640)
+ {
+ regval = ADC_MR_STARTUP_704;
+ }
+ else if (startup > 576)
+ {
+ regval = ADC_MR_STARTUP_640;
+ }
+ else if (startup > 512)
+ {
+ regval = ADC_MR_STARTUP_576;
+ }
+ else if (startup > 112)
+ {
+ regval = ADC_MR_STARTUP_512;
+ }
+ else if (startup > 96)
+ {
+ regval = ADC_MR_STARTUP_112;
+ }
+ else if (startup > 80)
+ {
+ regval = ADC_MR_STARTUP_96;
+ }
+ else if (startup > 64)
+ {
+ regval = ADC_MR_STARTUP_80;
+ }
+ else if (startup > 24)
+ {
+ regval = ADC_MR_STARTUP_64;
+ }
+ else if (startup > 16)
+ {
+ regval = ADC_MR_STARTUP_24;
+ }
+ else if (startup > 8)
+ {
+ regval = ADC_MR_STARTUP_16;
+ }
+ else if (startup > 0)
+ {
+ regval = ADC_MR_STARTUP_8;
+ }
+ else
+ {
+ regval = ADC_MR_STARTUP_0;
+ }
+
+ sam_adc_putreg(priv->adc, SAM_ADC_MR, regval);
+}
+
+/****************************************************************************
+ * Name: sam_tsd_tracking
+ *
+ * Description:
+ * Set the TRACKTIM field of the ADC MR register.
+ *
+ * TrackingTime = (TRACKTIM + 1) * ADCClock periods.
+ * TRACKTIM = (TrackingTime * ADCCLK) / (1000000000) - 1
+ *
+ * Input Parameters:
+ * priv - A reference to the touchscreen device structure
+ * time - The new tracking time in nanoseconds
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+static void sam_tsd_tracking(struct sam_tsd_s *priv, uint32_t time)
+{
+ uint32_t tracktim;
+ uint32_t regval;
+
+ /* Formula for SHTIM is:
+ *
+ * TRACKTIM = (TrackingTime * ADCCLK) / (1000000000) - 1
+ *
+ * Since 1 billion is close to the maximum value for an integer, we first
+ * divide ADCCLK by 1000 to avoid an overflow
+ */
+
+ tracktim = (time * (BOARD_ADCCLK_FREQUENCY / 1000)) / 100000;
+ if (tracktim % 10)
+ {
+ /* Handle partial values by not decrementing tracktim. This is
+ * basically a 'ceil' operation.
+ */
+
+ tracktim /= 10;
+ }
+ else
+ {
+ /* The final value needs to be decrement by one */
+
+ tracktim /= 10;
+ if (tracktim)
+ {
+ tracktim --;
+ }
+ }
+
+ /* Set the neew TRACKTIM field value int he ADC MR register */
+
+ regval = ADC_MR_TRACKTIM(tracktim);
+ regval |= pAdc->ADC_MR & ~ADC_MR_TRACKTIM_MASK;
+ pAdc->ADC_MR = regval;
+
+ regval = sam_adc_getreg(priv->adc, SAM_ADC_MR);
+ regval &= ~ADC_MR_TRACKTIM_MASK;
+ regval |= ADC_MR_TRACKTIM(trigper);
+ sam_adc_putreg(priv->adc, SAM_ADC_MR, regval);
+}
+
+/****************************************************************************
+ * Name: sam_tsd_trigperiod
+ *
+ * Description:
+ * Set the TGPER field of the TRGR register in order to define a periodic
+ * trigger perioc.
+ *
+ * Trigger Period = (TRGPER+1) / ADCCLK
+ *
+ * Input Parameters:
+ * priv - A reference to the touchscreen device structure
+ * time - The new trigger period in nanoseconds
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+static void sam_tsd_trigperiod(struct sam_tsd_s *priv, uint32_t period)
+{
+ uint32_t trigper;
+ uint32_t regval;
+ uint32_t div;
+
+ /* Divide trigger period avoid overflows. Division by ten is awkard, but
+ * appropriate here because times are specified in decimal with lots of
+ * zeroes.
+ */
+
+ div = 100000000;
+ while (period >= 10 && div >= 10)
+ {
+ period /= 10;
+ div /= 10;
+ }
+
+ /* Calculate and adjust the scaled trigger period:
+ *
+ * Trigger Period = (TRGPER+1) / ADCCLK
+ */
+
+ trigper = (period * BOARD_ADCCLK_FREQUENCY) / div;
+ if ((trigper % 10) != 0)
+ {
+ /* Handle partial values by not decrementing trigper. This is
+ * basically a 'ceil' operation.
+ */
+
+ trigper /= 10;
+ }
+ else
+ {
+ /* The final value needs to be decrement by one */
+
+ trigper /= 10;
+ if (trigper > 0)
+ {
+ trigper--;
+ }
+ }
+
+ /* Set the calculated trigger period in the TRGR register */
+
+ regval = sam_adc_getreg(priv->adc, SAM_ADC_TRGR);
+ regval &= ~ADC_TRGR_TRGPER_MASK;
+ regval |= ADC_TRGR_TRGPER(trigper);
+ sam_adc_putreg(priv->adc, SAM_ADC_TRGR, regval);
+}
+
+/****************************************************************************
+ * Name: sam_tsd_debounce
+ *
+ * Description:
+ * Set the Pen Detect Debouncing Period (PENBC) in the touchscreen mode
+ * register.
+ *
+ * Debouncing period = 2 ** PENDBC ADCClock periods.
+ *
+ * Input Parameters:
+ * priv - A reference to the touchscreen device structure
+ * time - The new debounce time in nanoseconds
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+static void sam_tsd_debounce(struct sam_tsd_s *priv, uint32_t time)
+{
+ uint32_t candidate;
+ uint32_t target;
+ uint32_t regval;
+ uint32_t penbc;
+ uint32_t div;
+ uint32_t clk;
+
+ /* Make sure that a valid debounce time was provided */
+
+ DEBUGASSERT(time > 0);
+
+ /* Divide time and ADCCLK to avoid overflows. Division by ten is awkard,
+ * but appropriate here because times are specified in decimal with lots of
+ * zeroes.
+ */
+
+ div = 1000000000;
+ while (div > 1 && (time % 10) == 0)
+ {
+ time /= 10;
+ div /= 10;
+ }
+
+ clk = BOARD_ADCCLK_FREQUENCY;
+ while (div > 1 && (clk % 10) == 0)
+ {
+ clk /= 10;
+ div /= 10;
+ }
+
+ /* Compute PENDBC */
+
+ target = time * clk / div;
+ candidate = 1;
+ penbc = 0;
+
+ while (candidate < target)
+ {
+ penbc++;
+ candidate *= 2;
+ }
+
+ DEBUGASSERT(pendbc > 0);
+
+ /* Update the TSMR with the new PENBC value */
+
+ regval = sam_adc_getreg(priv->adc, SAM_ADC_TSMR);
+ regval &= ~ADC_TSMR_PENDBC_MASK;
+ regval |= ADC_TSMR_PENDBC(pendbc);
+ sam_adc_puttreg(priv->adc, SAM_ADC_TSMR, regval);
+}
+
+/****************************************************************************
+ * Name: sam_tsd_initialize
+ *
+ * Description:
+ * Initialize the touchscreen for normal operation. This function is
+ * called from sam_tsd_open() the first time that the driver is opened.
+ *
+ * Input Parameters:
+ * priv - A reference to the touchscreen device structure
+ *
+ * Returned Value:
+ * Zero is returned on success. Otherwise, a negated errno value is
+ * returned to indicate the nature of the failure.
+ *
+ ****************************************************************************/
+
+static void sam_tsd_initialize(struct sam_tsd_s *priv)
+{
+ uint32_t regval;
+
+ /* Disable touch trigger */
+
+ regval = sam_adc_getreg(priv, SAM_ADC_TRGR);
+ regval &= ~ADC_TRGR_TRGMOD_MASK;
+ regval |= ADC_TRGR_TRGMOD_NO_TRIGGER;
+ sam_adc_putreg(priv, SAM_ADC_TRGR, regval);
+
+ /* Setup timing */
+
+ sam_tsd_startuptime(priv, BOARD_TSD_STARTUP);
+ sam_tsd_tracking(priv, BOARD_TSD_TRACKTIM);
+ sam_tsd_trigperiod(priv, 20000000); /* 20ms */
+
+ /* Setup the touchscreen mode */
+
+ regval = sam_adc_getreg(priv->adc, SAM_ADC_TSMR);
+ regval &= ~ADC_TSMR_TSMODE_MASK;
+
+#if defined(CONFIG_SAMA5_TSD_5WIRE)
+ regval |= ADC_TSMR_TSMODE_5WIRE;
+#elif defined(CONFIG_SAMA5_TSD_4WIRENPM)
+ regval |= ADC_TSMR_TSMODE_4WIRENPM;
+#else /* if defined(CONFIG_SAMA5_TSD_4WIRE) */
+ regval |= ADC_TSMR_TSMODE_4WIRE;
+#endif
+
+ sam_adc_putreg(priv->adc, SAM_ADC_TSMR, regval);
+
+ /* Disable averaging */
+
+ sam_tsd_setaverage(priv, ADC_TSMR_TSAV_NO_FILTER);
+
+ /* Select 4-wire w/pressure, 4-wire w/o pressure, or 5 wire modes */
+
+ regval = sam_adc_getreg(priv->adc, SAM_ADC_TSMR);
+ regval &= ~ADC_TSMR_TSMODE_MASK;
+
+#if defined(CONFIG_SAMA5_TSD_5WIRE)
+ regval |= ADC_TSMR_TSMODE_5WIRE;
+#elif defined(CONFIG_SAMA5_TSD_4WIRENPM)
+ regval |= ADC_TSMR_TSMODE_4WIRENPM;
+#else /* if defined(CONFIG_SAMA5_TSD_4WIRE) */
+ regval |= ADC_TSMR_TSMODE_4WIRE;
+#endif
+
+ /* Disable all TSD-related interrupts */
+
+ sam_adc_putreg(priv, SAM_ADC_IDR, ADC_TSD_ALLINTS);
+
+ /* Clear any pending TSD interrupts */
+
+ sam_adc_getreg(priv->dev, SAM_ADC_ISR);
+
+ /* Read and discard any samples */
+
+ sam_adc_getreg(priv, SAM_ADC_XPOSR);
+ sam_adc_getreg(priv, SAM_ADC_YPOSR);
+#if CONFIG_SAMA5_TSD_4WIRE
+ sam_adc_getreg(priv, SAM_ADC_PRESSR);
+#endif
+
+ /* Configure interrupt generation. */
+
+ sam_tsd_setaverage(priv, ADC_TSMR_TSAV_NO_FILTER);
+ sam_adc_putreg(priv, SAM_ADC_SR, ADC_CR_TSCALIB);
+
+ regval = sam_adc_getreg(priv, SAM_ADC_TRGR);
+ regval &= ~ADC_TRGR_TRGMOD_MASK;
+ regval |= ADC_TRGR_TRGMOD_PEN_TRIG;
+ sam_adc_putreg(priv, SAM_ADC_TRGR, regval);
+
+ sam_adc_putreg(priv, SAM_ADC_IER, ADC_INT_PEN);
+ return OK;
+}
+
+/****************************************************************************
+ * Name: sam_tsd_uninitialize
+ *
+ * Description:
+ * Uninitialize the touchscreen. This function is called from
+ * sam_tsd_close() when the final driver instance is closed.
+ *
+ * Input Parameters:
+ * priv - A reference to the touchscreen device structure
+ *
+ * Returned Value:
+ * Zero is returned on success. Otherwise, a negated errno value is
+ * returned to indicate the nature of the failure.
+ *
+ ****************************************************************************/
+
+static void sam_tsd_uninitialize(struct sam_tsd_s *priv)
+{
+
+ /* Disable the watchdog timer. It will be re-enabled in the worker thread
+ * while the pen remains down.
+ */
+
+ wd_cancel(priv->wdog);
+
+ /* Disable further touchscreen interrupts. Touchscreen interrupts will be
+ * re-enabled after the worker thread executes.
+ */
+
+ sam_adc_putreg32(priv->adc, SAM_ADC_IDR, ADC_TSD_ALLINTS);
+
+ /* Disable touch trigger */
+
+ regval = sam_adc_getreg(priv, SAM_ADC_TRGR);
+ regval &= ~ADC_TRGR_TRGMOD_MASK;
+ regval |= ADC_TRGR_TRGMOD_NO_TRIGGER;
+ sam_adc_putreg(priv, SAM_ADC_TRGR, regval);
+
+ /* Disable the touchscreen mode */
+
+ regval = sam_adc_getreg(priv->adc, SAM_ADC_TSMR);
+ regval &= ~ADC_TSMR_TSMODE_MASK;
+ regval |= ADC_TSMR_TSMODE_NONE;
+ sam_adc_putreg(priv->adc, SAM_ADC_TSMR, regval);
+
+ /* No touch and no valid sample data */
+
+ priv->sample.contact = CONTACT_NONE;
+ priv->sample.valid = false;
+ priv->valid = 0;
+ return OK;
+}
+
/****************************************************************************
* Public Functions
****************************************************************************/
@@ -980,15 +1720,6 @@ int sam_tsd_register(struct sam_adc_s *adc, int minor)
sem_init(&priv->waitsem, 0, 0); /* Initialize pen event wait semaphore */
- /* Make sure that interrupts are disabled and clear any pending interrupts */
-#warning Missing logic
-
- /* Attach the interrupt handler */
-#warning Missing logic
-
- /* Enable the PEN IRQ */
-#warning Missing logic
-
/* Register the device as an input device */
(void)snprintf(devname, DEV_NAMELEN, DEV_FORMAT, minor);
@@ -1001,19 +1732,10 @@ int sam_tsd_register(struct sam_adc_s *adc, int minor)
goto errout_with_priv;
}
- /* Schedule work to perform the initial sampling and to set the data
- * availability conditions.
+ /* And return success. The hardware will be initialized as soon as the
+ * touchscreen driver is opened for the first time.
*/
- ret = work_queue(HPWORK, &priv->work, sam_tsd_bottomhalf, priv, 0);
- if (ret != 0)
- {
- idbg("ERROR: Failed to queue work: %d\n", ret);
- goto errout_with_priv;
- }
-
- /* And return success */
-
return OK;
errout_with_priv:
diff --git a/nuttx/arch/arm/src/sama5/sam_touchscreen.h b/nuttx/arch/arm/src/sama5/sam_touchscreen.h
index ddadcaf86..4e293382e 100644
--- a/nuttx/arch/arm/src/sama5/sam_touchscreen.h
+++ b/nuttx/arch/arm/src/sama5/sam_touchscreen.h
@@ -50,6 +50,10 @@
****************************************************************************/
/* Configuration ************************************************************/
+#ifdef CONFIG_SAMA_TSD_RXP
+# define CONFIG_SAMA_TSD_RXP 6
+#endif
+
/****************************************************************************
* Public Types
****************************************************************************/
diff --git a/nuttx/configs/sama5d3x-ek/include/board_384mhz.h b/nuttx/configs/sama5d3x-ek/include/board_384mhz.h
index df85ded06..2488dc1d7 100644
--- a/nuttx/configs/sama5d3x-ek/include/board_384mhz.h
+++ b/nuttx/configs/sama5d3x-ek/include/board_384mhz.h
@@ -155,6 +155,9 @@
*/
#define BOARD_ADC_PRESCAL (7)
+#define BOARD_TSD_STARTUP (40 /* 40 nanoseconds */
+#define BOARD_TSD_TRACKTIM (2000) /* Min 1µs at 8MHz */
+#define BOARD_TSD_DEBOUNCE (10000000) /* 10 milliseconds (unis nanoseconds) */
/* Resulting frequencies */
diff --git a/nuttx/configs/sama5d3x-ek/include/board_396mhz.h b/nuttx/configs/sama5d3x-ek/include/board_396mhz.h
index 9d3f45759..68cff128f 100644
--- a/nuttx/configs/sama5d3x-ek/include/board_396mhz.h
+++ b/nuttx/configs/sama5d3x-ek/include/board_396mhz.h
@@ -113,6 +113,9 @@
*/
#define BOARD_ADC_PRESCAL (7)
+#define BOARD_TSD_STARTUP (40 /* 40 nanoseconds */
+#define BOARD_TSD_TRACKTIM (2000) /* Min 1µs at 8MHz */
+#define BOARD_TSD_DEBOUNCE (10000000) /* 10 milliseconds (unis nanoseconds) */
/* Resulting frequencies */