summaryrefslogtreecommitdiff
path: root/nuttx/configs/open1788
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 /nuttx/configs/open1788
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
Diffstat (limited to 'nuttx/configs/open1788')
-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
4 files changed, 15 insertions, 16 deletions
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