summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2013-06-16 14:31:18 -0600
committerGregory Nutt <gnutt@nuttx.org>2013-06-16 14:31:18 -0600
commit052f500a9580ff671090388abd4085adad67dd72 (patch)
tree5b4bcae4777312dd66629bf05d48e502df362aa9
parent71b4709004ce55e2fe546b5a3f77b7b76064c78b (diff)
downloadpx4-nuttx-052f500a9580ff671090388abd4085adad67dd72.tar.gz
px4-nuttx-052f500a9580ff671090388abd4085adad67dd72.tar.bz2
px4-nuttx-052f500a9580ff671090388abd4085adad67dd72.zip
SAM3U-EK: Correct polarity of the PENIRQ signal
-rw-r--r--nuttx/ChangeLog5
-rw-r--r--nuttx/arch/arm/src/sam34/sam_spi.c10
-rw-r--r--nuttx/configs/sam3u-ek/README.txt14
-rw-r--r--nuttx/configs/sam3u-ek/src/sam3u-ek.h17
-rw-r--r--nuttx/configs/sam3u-ek/src/up_touchscreen.c4
-rw-r--r--nuttx/drivers/input/ads7843e.c35
-rw-r--r--nuttx/include/nuttx/input/ads7843e.h13
7 files changed, 42 insertions, 56 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index 9f21e5769..df87260fc 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -4989,4 +4989,7 @@
maybe it is not supposed to. From my reading of the ADS7843 spec, it
would not be appropriate to wait for the BUSY bit to de-asserted
anyway (since it is only de-asserted when we read the data)
- (2013-6-16). \ No newline at end of file
+ (2013-6-16).
+ * configs/sam3u-ek/src/up_touchscreen.c: Fix polarity of the /PENIRQ
+ signal (it is active low) (2013-6-16).
+
diff --git a/nuttx/arch/arm/src/sam34/sam_spi.c b/nuttx/arch/arm/src/sam34/sam_spi.c
index 65ebfa922..507ab2647 100644
--- a/nuttx/arch/arm/src/sam34/sam_spi.c
+++ b/nuttx/arch/arm/src/sam34/sam_spi.c
@@ -447,7 +447,7 @@ static uint32_t spi_setfrequency(FAR struct spi_dev_s *dev, uint32_t frequency)
/* Configure SPI to a frequency as close as possible to the requested frequency.
*
- * SPCK frequency = MCK / SCBR, or SCBR = MCK / frequency
+ * SPCK frequency = SPI_CLK / SCBR, or SCBR = SPI_CLK / frequency
*/
scbr = SAM_SPI_CLOCK / frequency;
@@ -475,11 +475,11 @@ static uint32_t spi_setfrequency(FAR struct spi_dev_s *dev, uint32_t frequency)
* transition is 1/2 the SPCK clock period. Otherwise, the following equations
* determine the delay:
*
- * Delay Before SPCK = DLYBS / MCK
+ * Delay Before SPCK = DLYBS / SPI_CLK
*
* For a 2uS delay
*
- * DLYBS = MCK * 0.000002 = MCK / 500000
+ * DLYBS = SPI_CLK * 0.000002 = SPI_CLK / 500000
*/
dlybs = SAM_SPI_CLOCK / 500000;
@@ -490,11 +490,11 @@ static uint32_t spi_setfrequency(FAR struct spi_dev_s *dev, uint32_t frequency)
* 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
+ * Delay Between Consecutive Transfers = (32 x DLYBCT) / SPI_CLK
*
* For a 5uS delay:
*
- * DLYBCT = MCK * 0.000005 / 32 = MCK / 200000 / 32
+ * DLYBCT = SPI_CLK * 0.000005 / 32 = SPI_CLK / 200000 / 32
*/
dlybct = SAM_SPI_CLOCK / 200000 / 32;
diff --git a/nuttx/configs/sam3u-ek/README.txt b/nuttx/configs/sam3u-ek/README.txt
index 32d994329..b26b96e4a 100644
--- a/nuttx/configs/sam3u-ek/README.txt
+++ b/nuttx/configs/sam3u-ek/README.txt
@@ -581,6 +581,7 @@ Configuration sub-directories
CONFIG_INPUT_ADS7843E=y : Enable support for the XPT2048
CONFIG_ADS7843E_SPIDEV=2 : Use SPI CS 2 for communication
CONFIG_ADS7843E_SPIMODE=0 : Use SPI mode 0
+ CONFIG_ADS7843E_FREQUENCY=1000000 : SPI BAUD 1MHz
CONFIG_ADS7843E_THRESHX=39 : These will probably need to be tuned
CONFIG_ADS7843E_THRESHY=51
@@ -609,14 +610,11 @@ Configuration sub-directories
CONFIG_DEBUG_INPUT=y : Enable debug output from input devices
STATUS:
- 2013-6-14: The touchscreen is not functional. BUSY is initially
- '0' when asserted says '1'. The pend down GPIO inputis always
- '1' and there seems to be many spurious interrupts (but not so
- many as to lock up the system).
-
- So there are GIO issues, but on the positive side, the driver
- does appear to produce good touch data when touched but a lot
- of clean-up is needed.
+ 2013-6-16: The touchscreen is not functional. It seems to
+ perform good measurements but I am not getting the /PENIRQ
+ interrupt. The interrupt is set up correctly (I can ground
+ A24 and I get the interrupt), so apparently the ADS7843E is
+ not generating interrupts.
nx:
Configures to use examples/nx using the HX834x LCD hardware on
diff --git a/nuttx/configs/sam3u-ek/src/sam3u-ek.h b/nuttx/configs/sam3u-ek/src/sam3u-ek.h
index af68df42a..a9841dcc6 100644
--- a/nuttx/configs/sam3u-ek/src/sam3u-ek.h
+++ b/nuttx/configs/sam3u-ek/src/sam3u-ek.h
@@ -143,14 +143,19 @@
*
* The IRQ is active low and pulled up.
*
+ * Pen Interrupt. Open anode output, requires 10kO to 100kO pull-up resistor
+ * externally. There is a 100KO pull-up on the SAM3U-EK board so no additional
+ * pull-up should be required.
+ *
* BUSY is high impedance when CS is high (not selected). When CS is
* is low, BUSY is active high. Since the pin is pulled up, it will appear
- * busy if CS is not selected.
+ * busy if CS is not selected (there is no pull-up onboard).
*/
#define GPIO_TCS_IRQ (GPIO_INPUT | GPIO_CFG_PULLUP | GPIO_INT_BOTHEDGES | \
GPIO_PORT_PIOA | GPIO_PIN24)
-#define GPIO_TCS_BUSY (GPIO_INPUT | GPIO_CFG_PULLUP | GPIO_PORT_PIOA | GPIO_PIN2)
+#define GPIO_TCS_BUSY (GPIO_INPUT | GPIO_CFG_PULLUP | GPIO_PORT_PIOA | \
+ GPIO_PIN2)
#define SAM_TCS_IRQ SAM_IRQ_PA24
@@ -165,10 +170,10 @@
/* BUTTONS */
-#define GPIO_BUTTON1 (GPIO_INPUT | GPIO_CFG_PULLUP | GPIO_CFG_DEGLITCH | GPIO_INT_BOTHEDGES | \
- GPIO_PORT_PIOA | GPIO_PIN18)
-#define GPIO_BUTTON2 (GPIO_INPUT | GPIO_CFG_PULLUP | GPIO_CFG_DEGLITCH | GPIO_INT_BOTHEDGES | \
- GPIO_PORT_PIOA | GPIO_PIN19)
+#define GPIO_BUTTON1 (GPIO_INPUT | GPIO_CFG_PULLUP | GPIO_CFG_DEGLITCH | \
+ GPIO_INT_BOTHEDGES | GPIO_PORT_PIOA | GPIO_PIN18)
+#define GPIO_BUTTON2 (GPIO_INPUT | GPIO_CFG_PULLUP | GPIO_CFG_DEGLITCH | \
+ GPIO_INT_BOTHEDGES | GPIO_PORT_PIOA | GPIO_PIN19)
#define IRQ_BUTTON1 SAM_IRQ_PA18
#define IRQ_BUTTON2 SAM_IRQ_PA19
diff --git a/nuttx/configs/sam3u-ek/src/up_touchscreen.c b/nuttx/configs/sam3u-ek/src/up_touchscreen.c
index 46a814c6f..41799d5e1 100644
--- a/nuttx/configs/sam3u-ek/src/up_touchscreen.c
+++ b/nuttx/configs/sam3u-ek/src/up_touchscreen.c
@@ -201,9 +201,9 @@ static bool tsc_busy(FAR struct ads7843e_config_s *state)
static bool tsc_pendown(FAR struct ads7843e_config_s *state)
{
- /* REVISIT: This might need to be inverted */
+ /* The /PENIRQ value is active low */
- bool pendown = sam_gpioread(GPIO_TCS_IRQ);
+ bool pendown = !sam_gpioread(GPIO_TCS_IRQ);
ivdbg("pendown:%d\n", pendown);
return pendown;
}
diff --git a/nuttx/drivers/input/ads7843e.c b/nuttx/drivers/input/ads7843e.c
index 7d1a0c3ea..567e332b6 100644
--- a/nuttx/drivers/input/ads7843e.c
+++ b/nuttx/drivers/input/ads7843e.c
@@ -104,9 +104,6 @@ static void ads7843e_lock(FAR struct spi_dev_s *spi);
static void ads7843e_unlock(FAR struct spi_dev_s *spi);
#endif
-#if 0
-static inline void ads7843e_waitbusy(FAR struct ads7843e_dev_s *priv);
-#endif
static uint16_t ads7843e_sendcmd(FAR struct ads7843e_dev_s *priv, uint8_t cmd);
/* Interrupts and data sampling */
@@ -267,22 +264,6 @@ static inline void ads7843e_configspi(FAR struct spi_dev_s *spi)
#endif
/****************************************************************************
- * Name: ads7843e_waitbusy
- ****************************************************************************/
-
-#if 0 /* Not used */
-static inline void ads7843e_waitbusy(FAR struct ads7843e_dev_s *priv)
-{
- /* BUSY is high impedance when the ads7843e not selected. When the
- * ads7843e selected, BUSY is active high. Hence, it is necessary to have
- * the ads7843e selected when this function is called.
- */
-
- while (priv->config->busy(priv->config));
-}
-#endif
-
-/****************************************************************************
* Name: ads7843e_sendcmd
*
* Description.
@@ -312,8 +293,8 @@ static inline void ads7843e_waitbusy(FAR struct ads7843e_dev_s *priv)
* nominally 2 microseconds.
*
* So what good is this BUSY? Many boards do not even bother to bring it
- * to the MCU. It looks like busy will stick high until we read the data
- * so it does not really make any sense to wait on it.
+ * to the MCU. Busy will stick high until we read the data so you cannot
+ * wait on it before reading.
*
****************************************************************************/
@@ -330,15 +311,9 @@ static uint16_t ads7843e_sendcmd(FAR struct ads7843e_dev_s *priv, uint8_t cmd)
(void)SPI_SEND(priv->spi, cmd);
-#if 1
/* Wait a tiny amount to make sure that the aquisition time is complete */
up_udelay(3); /* 3 microseconds */
-#else
- /* Wait until busy is no longer asserted */
-
- ads7843e_waitbusy(priv);
-#endif
/* Read the 12-bit data (LS 4 bits will be padded with zero) */
@@ -372,7 +347,7 @@ static void ads7843e_notify(FAR struct ads7843e_dev_s *priv)
* is no longer available.
*/
- sem_post(&priv->waitsem);
+ sem_post(&priv->waitsem);
}
/* If there are threads waiting on poll() for ADS7843E data to become available,
@@ -484,7 +459,7 @@ static int ads7843e_waitsample(FAR struct ads7843e_dev_s *priv,
while (ads7843e_sample(priv, sample) < 0)
{
/* Wait for a change in the ADS7843E state */
-
+
ivdbg("Waiting..\n");
priv->nwaiters++;
ret = sem_wait(&priv->waitsem);
@@ -1283,7 +1258,7 @@ int ads7843e_register(FAR struct spi_dev_s *spi,
ads7843e_configspi(spi);
/* Enable the PEN IRQ */
-
+
ads7843e_sendcmd(priv, ADS7843_CMD_ENABPENIRQ);
/* Unlock the bus */
diff --git a/nuttx/include/nuttx/input/ads7843e.h b/nuttx/include/nuttx/input/ads7843e.h
index fe4382f2f..dc8b97faf 100644
--- a/nuttx/include/nuttx/input/ads7843e.h
+++ b/nuttx/include/nuttx/input/ads7843e.h
@@ -126,10 +126,15 @@ struct ads7843e_config_s
* interrupts should be configured on both rising and falling edges
* so that contact and loss-of-contact events can be detected.
*
- * attach - Attach the ADS7843E interrupt handler to the GPIO interrupt
- * enable - Enable or disable the GPIO interrupt
- * clear - Acknowledge/clear any pending GPIO interrupt
- * pendown - Return the state of the pen down GPIO input
+ * attach - Attach the ADS7843E interrupt handler to the GPIO interrupt
+ * enable - Enable or disable the GPIO interrupt
+ * clear - Acknowledge/clear any pending GPIO interrupt
+ * busy - Return the state of the BUSY GPIO input (for debug only)
+ * pendown - Return the state of the pen down GPIO input
+ *
+ * NOTE: The busy() method is not currently used by the driver. The BUSY
+ * signal is only an informative signal that is raised after a command has
+ * been send but before the sample data has been obtained.
*/
int (*attach)(FAR struct ads7843e_config_s *state, xcpt_t isr);