summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2013-07-03 08:12:45 -0600
committerGregory Nutt <gnutt@nuttx.org>2013-07-03 08:12:45 -0600
commiteaa7f1a2b126033142b38e446c8f48e805390dcb (patch)
tree1717d0b0bbb9f20f3bc383e23a5798a31fc421a3 /nuttx
parent89fb3719698e2280accd752873f4ba6aad211496 (diff)
downloadpx4-nuttx-eaa7f1a2b126033142b38e446c8f48e805390dcb.tar.gz
px4-nuttx-eaa7f1a2b126033142b38e446c8f48e805390dcb.tar.bz2
px4-nuttx-eaa7f1a2b126033142b38e446c8f48e805390dcb.zip
Fix SAM34 interrupt handling for ports D-F; fix MISO logic in Arduino Due touchscreen driver
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/ChangeLog5
-rw-r--r--nuttx/arch/arm/src/sam34/sam_gpioirq.c27
-rw-r--r--nuttx/configs/arduino-due/README.txt21
-rw-r--r--nuttx/configs/arduino-due/src/arduino-due.h4
-rw-r--r--nuttx/configs/arduino-due/src/sam_touchscreen.c61
5 files changed, 85 insertions, 33 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index cc4767aea..9750a63f8 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -5104,3 +5104,8 @@
* configs/arduino-due/src/sam_nsh.c and sam_mmcsd.c: Add NSH customize
initialization. If so configured, initialize the SPI bit bang
interface to the MMC/SD slot on the ITEAD shield (2013-7-1).
+ * fs/fs_mount.c: Fix compilation error if no file systems are enabled:
+ Change error to ERROR (2013-7-3).
+ * arch/arm/src/sam34/sam_gpioirq.c: Fix some errors for interrupts
+ on ports D-F (2013-7-3).
+
diff --git a/nuttx/arch/arm/src/sam34/sam_gpioirq.c b/nuttx/arch/arm/src/sam34/sam_gpioirq.c
index 854644bfb..3b7c8a2a2 100644
--- a/nuttx/arch/arm/src/sam34/sam_gpioirq.c
+++ b/nuttx/arch/arm/src/sam34/sam_gpioirq.c
@@ -139,7 +139,32 @@ static int sam_irqbase(int irq, uint32_t *base, int *pin)
return OK;
}
#endif
+#ifdef CONFIG_GPIOD_IRQ
+ if (irq <= SAM_IRQ_PD31)
+ {
+ *base = SAM_PIOD_BASE;
+ *pin = irq - SAM_IRQ_PD0;
+ return OK;
+ }
+#endif
+#ifdef CONFIG_GPIOE_IRQ
+ if (irq <= SAM_IRQ_PE31)
+ {
+ *base = SAM_PIOE_BASE;
+ *pin = irq - SAM_IRQ_PE0;
+ return OK;
+ }
+#endif
+#ifdef CONFIG_GPIOF_IRQ
+ if (irq <= SAM_IRQ_PF31)
+ {
+ *base = SAM_PIOF_BASE;
+ *pin = irq - SAM_IRQ_PF0;
+ return OK;
+ }
+#endif
}
+
return -EINVAL;
}
@@ -408,7 +433,7 @@ void sam_gpioirqenable(int irq)
{
/* Clear (all) pending interrupts and enable this pin interrupt */
- (void)getreg32(base + SAM_PIO_ISR_OFFSET);
+ //(void)getreg32(base + SAM_PIO_ISR_OFFSET);
putreg32((1 << pin), base + SAM_PIO_IER_OFFSET);
}
}
diff --git a/nuttx/configs/arduino-due/README.txt b/nuttx/configs/arduino-due/README.txt
index 92b3437a7..de840eba5 100644
--- a/nuttx/configs/arduino-due/README.txt
+++ b/nuttx/configs/arduino-due/README.txt
@@ -35,11 +35,11 @@ PIO Pin Usage
----- ---------- ---- -------- ----- ------------ ---- ------ ----- ----------- ---- ---------
PA0 CANTX0 ADCH 8 PB0 ETX_CLK ETH 1 PC0 ERASE N/A
PA1 CANRX0 ACDH 7 PB1 ETX_EN ETH 3 PC1 PIN33 XIO 14
- PA2 AD7 ADCL 7 PB2 ETXD0 ETH 5 PC2 PIN34 XIO 15
- PA3 AD6 ADCL 6 PB3 ETXD1 ETH 7 PC3 PIN35 XIO 16
- PA4 AD5 ADCL 5 PB4 ERX_DV ETH 10 PC4 PIN36 XIO 17
+ PA2 AD7 ADCL 8 PB2 ETXD0 ETH 5 PC2 PIN34 XIO 15
+ PA3 AD6 ADCL 7 PB3 ETXD1 ETH 7 PC3 PIN35 XIO 16
+ PA4 AD5 ADCL 6 PB4 ERX_DV ETH 10 PC4 PIN36 XIO 17
PA5 EEXTINT ETH 8 PB5 ERXD0 ETH 9 PC5 PIN37 XIO 18
- PA6 AD4 ADCL 4 PB6 ERXD1 ETH 11 PC6 PIN38 XIO 19
+ PA6 AD4 ADCL 5 PB6 ERXD1 ETH 11 PC6 PIN38 XIO 19
PA7 PIN31 XIO 12 PB7 ERX_ER ETH 13 PC7 PIN39 XIO 20
PA8 [U]RX PWML 1 PB8 EMDC ETH 14 PC8 PIN40 XIO 21
PA9 [U]TX PWML 2 PB9 EMDIO ETH 12 PC9 PIN41 XIO 22
@@ -49,15 +49,15 @@ PIO Pin Usage
PA13 TXD1 COMM 3 PB13 SCL0-3 COMM 8 PC13 PIN50 XIO 31
PA14 PIN23 XIO 4 PB14 CANTX1/IO XIO 34 PC14 PIN49 XIO 30
PA15 PIN24 XIO 5 PB15 DAC0(CANRX1) ADCH 5 PC15 PIN48 XIO 29
- PA16 AD0 ADCL 0 PB16 DAC1 ADCH 6 PC16 PIN47 XIO 28
+ PA16 AD0 ADCL 1 PB16 DAC1 ADCH 6 PC16 PIN47 XIO 28
PA17 SDA1 PWMH 9 PB17 AD8 ADCH 1 PC17 PIN46 XIO 27
PA18 SCL1 PWMH 10 PB18 AD9 ADCH 2 PC18 PIN45 XIO 26
PA19 PIN42 XIO 23 PB19 AD10 ADCH 3 PC19 PIN44 XIO 25
PA20 PIN43 XIO 24 PB20 AD11(TXD3) ADCH 4 PC20 N/C N/A
PA21 TXL TX YELLOW LED PB21 AD14(RXD3) XIO 33 PC21 PWM9 PWMH 2
- PA22 AD3 ADCL 3 PB22 N/C N/A PC22 PWM8 PWMH 1
- PA23 AD2 ADCL 2 PB23 SS3 ??? PC23 PWM7 PWML 8
- PA24 AD1 ADCL 1 PB24 N/C N/A PC24 PWM6 PWML 7
+ PA22 AD3 ADCL 4 PB22 N/C N/A PC22 PWM8 PWMH 1
+ PA23 AD2 ADCL 3 PB23 SS3 ??? PC23 PWM7 PWML 8
+ PA24 AD1 ADCL 2 PB24 N/C N/A PC24 PWM6 PWML 7
PA25 MISO SPI 1 PB25 PWM2 PWML 3 PC25 PWM5 PWML 6
PA26 MOSI SPI 4 PB26 PIN22 ??? PC26 SS1/PWM4 PWML 10 (there are two)
PA27 SPCK SPI 3 PB27 PWM13 PWMH 6 PC27 N/C N/A
@@ -179,6 +179,7 @@ ITEAD 2.4" TFT with Touch
1. It is not possible to use any of the SPI devices on the Shield unless
a bit-bang SPI interface is used. This includes the touch controller
+ a bit-bang SPI interface is used. This includes the touch controller
and the SD card.
2. UART0 cannot be used. USARTs on the COMM connector should be available.
3. Parallel data is not contiguous in the PIO register
@@ -218,8 +219,8 @@ ITEAD 2.4" TFT with Touch
7 IN3 N/C --- --- 8 IN4 N/C --- ---
9 VREF --- --- --- 10 VCC --- --- ---
11 IRQ J2 pin 2 D9 PC21 12 DOUT J2 pin 1 D8 PC22
- 13 BUSY N/C --- --- 14 DIN J1 pin 1 D14 PA16
- 15 /CS --- --- --- 16 DCLK J1 pin 2 D15 PA24
+ 13 BUSY N/C --- --- 14 DIN J1 pin 1 A0/D15 PA16
+ 15 /CS --- --- --- 16 DCLK J1 pin 2 A1/D15 PA24
--- ------- -------- --------- -------- ---- -------- -------- --------- -------
NOTES:
diff --git a/nuttx/configs/arduino-due/src/arduino-due.h b/nuttx/configs/arduino-due/src/arduino-due.h
index 34a33b3a6..986f824bf 100644
--- a/nuttx/configs/arduino-due/src/arduino-due.h
+++ b/nuttx/configs/arduino-due/src/arduino-due.h
@@ -232,8 +232,8 @@
* 7 IN3 N/C --- --- 8 IN4 N/C --- ---
* 9 VREF --- --- --- 10 VCC --- --- ---
* 11 IRQ J2 pin 2 D9 PC21 12 DOUT J2 pin 1 D8 PC22
- * 13 BUSY N/C --- --- 14 DIN J1 pin 1 D14 PA16
- * 15 /CS --- --- --- 16 DCLK J1 pin 2 D15 PA24
+ * 13 BUSY N/C --- --- 14 DIN J1 pin 1 A0/D14 PA16
+ * 15 /CS --- --- --- 16 DCLK J1 pin 2 A1/D15 PA24
* --- ------- -------- --------- -------- ---- -------- -------- --------- -------
*
* NOTE: /CS is connected to ground (XPT2046 is always selected)
diff --git a/nuttx/configs/arduino-due/src/sam_touchscreen.c b/nuttx/configs/arduino-due/src/sam_touchscreen.c
index 7aefb1279..e3e4ee3ed 100644
--- a/nuttx/configs/arduino-due/src/sam_touchscreen.c
+++ b/nuttx/configs/arduino-due/src/sam_touchscreen.c
@@ -91,7 +91,7 @@
#define SPI_CLRSCK putreg32(1 << 24, SAM_PIOA_CODR)
#define SPI_SETMOSI putreg32(1 << 16, SAM_PIOA_SODR)
#define SPI_CLRMOSI putreg32(1 << 16, SAM_PIOA_CODR)
-#define SPI_GETMISO ((getreg32(SAM_PIOC_PDSR) >> 21) & 1)
+#define SPI_GETMISO ((getreg32(SAM_PIOC_PDSR) >> 22) & 1)
/* Only mode 0 */
@@ -174,6 +174,7 @@ static struct ads7843e_config_s g_tscinfo =
/****************************************************************************
* Private Functions
****************************************************************************/
+
/****************************************************************************
* Include the bit-band skeleton logic
****************************************************************************/
@@ -354,36 +355,50 @@ static FAR struct spi_dev_s *sam_tsc_spiinitialize(void)
int arch_tcinitialize(int minor)
{
FAR struct spi_dev_s *dev;
+ static bool initialized = false;
int ret;
idbg("minor %d\n", minor);
DEBUGASSERT(minor == 0);
- /* Configure and enable the XPT2046 interrupt pin as an input */
+ /* Have we already initialized? Since we never uninitialize we must prevent
+ * multiple initializations. This is necessary, for example, when the
+ * touchscreen example is used as a built-in application in NSH and can be
+ * called numerous time. It will attempt to initialize each time.
+ */
- (void)sam_configgpio(GPIO_TSC_IRQ);
+ if (!initialized)
+ {
+ /* Configure and enable the XPT2046 interrupt pin as an input */
- /* Configure the PIO interrupt */
+ (void)sam_configgpio(GPIO_TSC_IRQ);
- sam_gpioirq(SAM_TSC_IRQ);
+ /* Configure the PIO interrupt */
- /* Get an instance of the SPI interface for the touchscreen chip select */
+ sam_gpioirq(SAM_TSC_IRQ);
- dev = sam_tsc_spiinitialize();
- if (!dev)
- {
- idbg("Failed to initialize bit bang SPI\n");
- return -ENODEV;
- }
+ /* Get an instance of the SPI interface for the touchscreen chip select */
- /* Initialize and register the SPI touschscreen device */
+ dev = sam_tsc_spiinitialize();
+ if (!dev)
+ {
+ idbg("Failed to initialize bit bang SPI\n");
+ return -ENODEV;
+ }
- ret = ads7843e_register(dev, &g_tscinfo, CONFIG_ADS7843E_DEVMINOR);
- if (ret < 0)
- {
- idbg("Failed to register touchscreen device\n");
- /* up_spiuninitialize(dev); */
- return -ENODEV;
+ /* Initialize and register the SPI touschscreen device */
+
+ ret = ads7843e_register(dev, &g_tscinfo, CONFIG_ADS7843E_DEVMINOR);
+ if (ret < 0)
+ {
+ idbg("Failed to register touchscreen device\n");
+ /* up_spiuninitialize(dev); */
+ return -ENODEV;
+ }
+
+ /* Now we are initialized */
+
+ initialized = true;
}
return OK;
@@ -407,7 +422,13 @@ int arch_tcinitialize(int minor)
void arch_tcuninitialize(void)
{
- /* No support for un-initializing the touchscreen XPT2046 device yet */
+ /* No real support for un-initializing the touchscreen XPT2046 device.
+ * Just make sure that interrupts are disabled and that no handler is
+ * attached.
+ */
+
+ sam_gpioirqdisable(SAM_TSC_IRQ);
+ irq_detach(SAM_TSC_IRQ);
}
#endif /* CONFIG_ARDUINO_ITHEAD_TFT && CONFIG_SPI_BITBANG && CONFIG_INPUT_ADS7843E */