summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-03-19 13:33:00 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-03-19 13:33:00 +0000
commit18f9d0eaa3b20a4c3a11c9a3f4e60a150e11d69f (patch)
treec45ec62823b73b604d46dea1ce90d9decd5ba523
parented784e97c354a92faafe8760beb933688b3e9a30 (diff)
downloadpx4-nuttx-18f9d0eaa3b20a4c3a11c9a3f4e60a150e11d69f.tar.gz
px4-nuttx-18f9d0eaa3b20a4c3a11c9a3f4e60a150e11d69f.tar.bz2
px4-nuttx-18f9d0eaa3b20a4c3a11c9a3f4e60a150e11d69f.zip
More LPC1788 updates from Rommel Marcelo
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@5759 42af7a65-404d-4744-a932-0658087f49c3
-rw-r--r--nuttx/arch/arm/src/armv7-m/nvic.h7
-rw-r--r--nuttx/arch/arm/src/armv7-m/up_ramvec_initialize.c10
-rw-r--r--nuttx/arch/arm/src/lpc17xx/chip.h10
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_gpioint.c20
-rw-r--r--nuttx/configs/open1788/include/board.h2
-rw-r--r--nuttx/configs/open1788/src/lpc17_buttons.c5
-rw-r--r--nuttx/configs/open1788/src/lpc17_nsh.c16
-rw-r--r--nuttx/configs/open1788/src/open1788.h8
8 files changed, 41 insertions, 37 deletions
diff --git a/nuttx/arch/arm/src/armv7-m/nvic.h b/nuttx/arch/arm/src/armv7-m/nvic.h
index 46837ab99..e6d6f8e9e 100644
--- a/nuttx/arch/arm/src/armv7-m/nvic.h
+++ b/nuttx/arch/arm/src/armv7-m/nvic.h
@@ -483,11 +483,12 @@
#define NVIC_SYSH_PRIORITY_PR15_SHIFT 24
#define NVIC_SYSH_PRIORITY_PR15_MASK (0xff << NVIC_SYSH_PRIORITY_PR15_SHIFT)
-/* Vector Table Offset Register (VECTAB) */
+/* Vector Table Offset Register (VECTAB). This mask seems to vary among
+ * ARMv7-M implementations. It may be be redefined in the architecture-
+ * specific chip.h header file.
+ */
#define NVIC_VECTAB_TBLOFF_MASK (0xffffffc0)
-#define NVIC_VECTAB_TBLBASE (0)
-#define NVIC_VECTAB_ALIGN_MASK (0x0000003f)
/* Application Interrupt and Reset Control Register (AIRCR) */
diff --git a/nuttx/arch/arm/src/armv7-m/up_ramvec_initialize.c b/nuttx/arch/arm/src/armv7-m/up_ramvec_initialize.c
index 4511e1b9e..3d33f61c8 100644
--- a/nuttx/arch/arm/src/armv7-m/up_ramvec_initialize.c
+++ b/nuttx/arch/arm/src/armv7-m/up_ramvec_initialize.c
@@ -100,7 +100,7 @@ void up_ramvec_initialize(void)
/* The vector table must be aligned */
- DEBUGASSERT(((uintptr)g_ram_vectors & NVIC_VECTAB_ALIGN_MASK) == 0);
+ DEBUGASSERT(((uintptr)g_ram_vectors & ~NVIC_VECTAB_TBLOFF_MASK) == 0);
/* Copy the ROM vector table at address zero to RAM vector table.
*
@@ -116,13 +116,9 @@ void up_ramvec_initialize(void)
*dest++ = *src++;
}
- /* Now configure the NVIC to use the new vector table. The TBLBASE bit
- * indicates that the vectors are in RAM. NOTE: These fields appear to
- * differ among various ARMv7-M implementations.
- */
+ /* Now configure the NVIC to use the new vector table. */
- putreg32(((uint32_t)g_ram_vectors & NVIC_VECTAB_TBLOFF_MASK) | NVIC_VECTAB_TBLBASE,
- NVIC_VECTAB);
+ putreg32((uint32_t)g_ram_vectors, NVIC_VECTAB);
}
#endif /* !CONFIG_ARCH_RAMVECTORS */
diff --git a/nuttx/arch/arm/src/lpc17xx/chip.h b/nuttx/arch/arm/src/lpc17xx/chip.h
index 4138ef934..6691ab8b0 100644
--- a/nuttx/arch/arm/src/lpc17xx/chip.h
+++ b/nuttx/arch/arm/src/lpc17xx/chip.h
@@ -61,17 +61,15 @@
# endif
#endif
-/* Vector Table Offset Register (VECTAB). Redefine some bits defined in
+/* Vector Table Offset Register (VECTAB). Redefine the mask defined in
* arch/arm/src/armv7-m/nvic.h; The LPC178x/7x User manual definitions
- * do not match the ARMv7M field definitions.
+ * do not match the ARMv7M field definitions. Any bits set above bit
+ * 29 would be an error and apparently the register wants 8- not 6-bit
+ * alignment.
*/
#undef NVIC_VECTAB_TBLOFF_MASK
#define NVIC_VECTAB_TBLOFF_MASK (0x3fffff00)
-#undef NVIC_VECTAB_TBLBASE
-#define NVIC_VECTAB_TBLBASE (1 << 29)
-#undef NVIC_VECTAB_ALIGN_MASK
-#define NVIC_VECTAB_ALIGN_MASK (0x000000ff)
/* Include the memory map file. Other chip hardware files should then include
* this file for the proper setup.
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_gpioint.c b/nuttx/arch/arm/src/lpc17xx/lpc17_gpioint.c
index de16885ab..3c3d4b17b 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_gpioint.c
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_gpioint.c
@@ -261,9 +261,9 @@ static int lpc17_irq2pin(int irq)
/* Set 3: 15 interrupts p2.16-p2.30
*
- * LPC17_VALID_SHIFT2H 0 - Bit 0 is the first bit in a group of 14 interrupts
- * LPC17_VALID_FIRST2H irq - IRQ number associated with p2.0
- * LPC17_VALID_NIRQS2H 15 - 15 interrupt bits in the group
+ * LPC17_VALID_SHIFT2L 0 - Bit 0 is the first bit in a group of 14 interrupts
+ * LPC17_VALID_FIRST2L irq - IRQ number associated with p2.0
+ * LPC17_VALID_NIRQS2L 15 - 15 interrupt bits in the group
*/
else if (irq >= LPC17_VALID_FIRST2H && irq < (LPC17_VALID_FIRST2H+LPC17_VALID_NIRQS2H))
@@ -418,12 +418,22 @@ void lpc17_gpioirqinitialize(void)
putreg32(0, LPC17_GPIOINT2_INTENR);
putreg32(0, LPC17_GPIOINT2_INTENF);
- /* Attach and enable the GPIO IRQ. Note: GPIO0 and GPIO2 interrupts share
- * the same position in the NVIC with External Interrupt 3
+ /* Attach and enable the GPIO IRQ. */
+
+#if defined(LPC176x)
+ /* For the LPC176x family, GPIO0 and GPIO2 interrupts share the same
+ * position in the NVIC with External Interrupt 3
*/
(void)irq_attach(LPC17_IRQ_EINT3, lpc17_gpiointerrupt);
up_enable_irq(LPC17_IRQ_EINT3);
+
+#elif defined(LPC178x)
+
+ (void)irq_attach(LPC17_IRQ_GPIO, lpc17_gpiointerrupt);
+ up_enable_irq(LPC17_IRQ_GPIO);
+
+#endif
}
/****************************************************************************
diff --git a/nuttx/configs/open1788/include/board.h b/nuttx/configs/open1788/include/board.h
index 53392bed2..a5062e3fb 100644
--- a/nuttx/configs/open1788/include/board.h
+++ b/nuttx/configs/open1788/include/board.h
@@ -155,7 +155,7 @@
#define SDCARD_INIT_CLKDIV (SDCARD_CLKDIV_INIT)
#define SDCARD_NORMAL_CLKDIV 1 /* DMA ON: SDCARD_CLOCK=15MHz */
-#define SDCARD_SLOW_CLKDIV 2 /* DMA OFF: SDCARD_CLOCK=10MHz */
+#define SDCARD_SLOW_CLKDIV 14 /* DMA OFF: SDCARD_CLOCK=2MHz */
#ifdef CONFIG_SDIO_DMA
# define SDCARD_MMCXFR_CLKDIV (SDCARD_NORMAL_CLKDIV)
diff --git a/nuttx/configs/open1788/src/lpc17_buttons.c b/nuttx/configs/open1788/src/lpc17_buttons.c
index a203b67fb..474924510 100644
--- a/nuttx/configs/open1788/src/lpc17_buttons.c
+++ b/nuttx/configs/open1788/src/lpc17_buttons.c
@@ -101,9 +101,8 @@ static xcpt_t g_buttonisr[BOARD_NUM_BUTTONS];
static uint8_t g_buttonirq[BOARD_NUM_BUTTONS] =
{
- GPIO_USER1_IRQ, GPIO_USER2_IRQ, GPIO_WAKEUP_IRQ, GPIO_USER3_IRQ,
- GPIO_JOY_A_IRQ, GPIO_JOY_B_IRQ, GPIO_JOY_C_IRQ, GPIO_JOY_D_IRQ,
- GPIO_JOY_CTR_IRQ
+ GPIO_USER1_IRQ, GPIO_USER2_IRQ, GPIO_USER3_IRQ, GPIO_JOY_A_IRQ,
+ GPIO_JOY_B_IRQ, GPIO_JOY_C_IRQ, GPIO_JOY_D_IRQ, GPIO_JOY_CTR_IRQ
};
#endif
diff --git a/nuttx/configs/open1788/src/lpc17_nsh.c b/nuttx/configs/open1788/src/lpc17_nsh.c
index 32ba32712..6611e601a 100644
--- a/nuttx/configs/open1788/src/lpc17_nsh.c
+++ b/nuttx/configs/open1788/src/lpc17_nsh.c
@@ -164,6 +164,9 @@
#ifdef NSH_HAVE_USBHOST
static struct usbhost_driver_s *g_drvr;
#endif
+#ifdef NSH_HAVE_MMCSD
+static FAR struct sdio_dev_s *g_sdiodev;
+#endif
/****************************************************************************
* Private Functions
@@ -227,7 +230,7 @@ static int nsh_cdinterrupt(int irq, FAR void *context)
present = !lpc17_gpioread(GPIO_SD_CD);
if (present != inserted)
{
- sdio_mediachange(sdio, preset);
+ sdio_mediachange(g_sdiodev, present);
inserted = present;
}
@@ -246,7 +249,6 @@ static int nsh_cdinterrupt(int irq, FAR void *context)
#ifdef NSH_HAVE_MMCSD
static int nsh_sdinitialize(void)
{
- FAR struct sdio_dev_s *sdio;
int ret;
#ifdef NSH_HAVE_MMCSD_CD
@@ -268,8 +270,8 @@ static int nsh_sdinitialize(void)
/* First, get an instance of the SDIO interface */
- sdio = sdio_initialize(CONFIG_NSH_MMCSDSLOTNO);
- if (!sdio)
+ g_sdiodev = sdio_initialize(CONFIG_NSH_MMCSDSLOTNO);
+ if (!g_sdiodev)
{
message("nsh_archinitialize: Failed to initialize SDIO slot %d\n",
CONFIG_NSH_MMCSDSLOTNO);
@@ -278,7 +280,7 @@ static int nsh_sdinitialize(void)
/* Now bind the SDIO interface to the MMC/SD driver */
- ret = mmcsd_slotinitialize(CONFIG_NSH_MMCSDMINOR, sdio);
+ ret = mmcsd_slotinitialize(CONFIG_NSH_MMCSDMINOR, g_sdiodev);
if (ret != OK)
{
message("nsh_archinitialize: "
@@ -294,9 +296,9 @@ static int nsh_sdinitialize(void)
*/
#ifdef NSH_HAVE_MMCSD_CD
- sdio_mediachange(sdio, !lpc17_gpioread(GPIO_SD_CD));
+ sdio_mediachange(g_sdiodev, !lpc17_gpioread(GPIO_SD_CD));
#else
- sdio_mediachange(sdio, true);
+ sdio_mediachange(g_sdiodev, true);
#endif
return OK;
}
diff --git a/nuttx/configs/open1788/src/open1788.h b/nuttx/configs/open1788/src/open1788.h
index 9a839704a..8078fe9c5 100644
--- a/nuttx/configs/open1788/src/open1788.h
+++ b/nuttx/configs/open1788/src/open1788.h
@@ -105,13 +105,11 @@
/* The SD card detect (CD) signal is on P0[13]. This signal is shared. It is also
* used for MOSI1 and USB_UP_LED. The CD pin may be disconnected. There is a jumper
* on board that enables the CD pin.
+ *
+ * The CD pin is interrupting:
*/
-#if 0 /* The CD pin may be interrupting */
-# define GPIO_SD_CD (GPIO_INTBOTH | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN13)
-#else
-# define GPIO_SD_CD (GPIO_INPUT | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN13)
-#endif
+#define GPIO_SD_CD (GPIO_INTBOTH | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN13)
/************************************************************************************
* Public Types