summaryrefslogtreecommitdiff
path: root/nuttx/configs/open1788
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-03-12 23:16:25 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-03-12 23:16:25 +0000
commit1125cbdc2d38da82d9631aa0ae1d9030f641126e (patch)
treef25cfaffc830ded461fbf7c2b46b80cfa06dafff /nuttx/configs/open1788
parent177f3484f71b2d03fc5b809a024ff32d137494ba (diff)
downloadpx4-nuttx-1125cbdc2d38da82d9631aa0ae1d9030f641126e.tar.gz
px4-nuttx-1125cbdc2d38da82d9631aa0ae1d9030f641126e.tar.bz2
px4-nuttx-1125cbdc2d38da82d9631aa0ae1d9030f641126e.zip
SD fixes from Rommel + SD card detect GPIO logic for Open1788
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@5737 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/configs/open1788')
-rw-r--r--nuttx/configs/open1788/include/board.h10
-rwxr-xr-xnuttx/configs/open1788/knsh/defconfig4
-rw-r--r--nuttx/configs/open1788/nsh/defconfig4
-rw-r--r--nuttx/configs/open1788/src/lpc17_nsh.c90
-rw-r--r--nuttx/configs/open1788/src/open1788.h12
5 files changed, 102 insertions, 18 deletions
diff --git a/nuttx/configs/open1788/include/board.h b/nuttx/configs/open1788/include/board.h
index b71ea577a..3bcd00bc6 100644
--- a/nuttx/configs/open1788/include/board.h
+++ b/nuttx/configs/open1788/include/board.h
@@ -152,21 +152,21 @@
*/
#define SDCARD_CLKDIV_INIT 74 /* 400Khz */
-#define SDCARD_INIT_CLKDIV (BOARD_PCLK_FREQUENCY/(2*(SDCARD_CLKDIV_INIT+1)))
+#define SDCARD_INIT_CLKDIV (SDCARD_CLKDIV_INIT+1)
#define SDCARD_NORMAL_CLKDIV 1 /* DMA ON: SDCARD_CLOCK=15MHz */
#define SDCARD_SLOW_CLKDIV 2 /* DMA OFF: SDCARD_CLOCK=10MHz */
#ifdef CONFIG_SDIO_DMA
-# define SDCARD_MMCXFR_CLKDIV (BOARD_PCLK_FREQUENCY/(2*(SDCARD_NORMAL_CLKDIV+1)))
+# define SDCARD_MMCXFR_CLKDIV (SDCARD_NORMAL_CLKDIV+1)
#else
-# define SDCARD_MMCXFR_CLKDIV (BOARD_PCLK_FREQUENCY/(2*(SDCARD_SLOW_CLKDIV+1)))
+# define SDCARD_MMCXFR_CLKDIV (SDCARD_SLOW_CLKDIV+1)
#endif
#ifdef CONFIG_SDIO_DMA
-# define SDCARD_SDXFR_CLKDIV (BOARD_PCLK_FREQUENCY/(2*(SDCARD_NORMAL_CLKDIV+1)))
+# define SDCARD_SDXFR_CLKDIV (SDCARD_NORMAL_CLKDIV+1)
#else
-# define SDCARD_SDXFR_CLKDIV (BOARD_PCLK_FREQUENCY/(2*(SDCARD_SLOW_CLKDIV+1)))
+# define SDCARD_SDXFR_CLKDIV (SDCARD_SLOW_CLKDIV+1)
#endif
/* Set EMC delay values:
diff --git a/nuttx/configs/open1788/knsh/defconfig b/nuttx/configs/open1788/knsh/defconfig
index ab64744e3..22042073c 100755
--- a/nuttx/configs/open1788/knsh/defconfig
+++ b/nuttx/configs/open1788/knsh/defconfig
@@ -137,7 +137,7 @@ CONFIG_LPC17_PLL1=y
# CONFIG_LPC17_LCD is not set
# CONFIG_LPC17_USBHOST is not set
# CONFIG_LPC17_USBDEV is not set
-# CONFIG_LPC17_SDCARD=y
+CONFIG_LPC17_SDCARD=y
CONFIG_LPC17_UART0=y
# CONFIG_LPC17_UART1 is not set
# CONFIG_LPC17_UART2 is not set
@@ -191,7 +191,7 @@ CONFIG_LPC17_GPDMA=y
#
# SDIO Configuration
#
-CONFIG_SDIO_DMA=y
+# CONFIG_SDIO_DMA=y
CONFIG_SDIO_DMAPRIO=0x0
# CONFIG_SDIO_WIDTH_D1_ONLY is not set
diff --git a/nuttx/configs/open1788/nsh/defconfig b/nuttx/configs/open1788/nsh/defconfig
index a869ccb04..d4139111a 100644
--- a/nuttx/configs/open1788/nsh/defconfig
+++ b/nuttx/configs/open1788/nsh/defconfig
@@ -131,7 +131,7 @@ CONFIG_LPC17_PLL1=y
# CONFIG_LPC17_LCD is not set
# CONFIG_LPC17_USBHOST is not set
# CONFIG_LPC17_USBDEV is not set
-# CONFIG_LPC17_SDCARD=y
+CONFIG_LPC17_SDCARD=y
CONFIG_LPC17_UART0=y
# CONFIG_LPC17_UART1 is not set
# CONFIG_LPC17_UART2 is not set
@@ -185,7 +185,7 @@ CONFIG_LPC17_GPDMA=y
#
# SDIO Configuration
#
-CONFIG_SDIO_DMA=y
+# CONFIG_SDIO_DMA=y
CONFIG_SDIO_DMAPRIO=0x0
# CONFIG_SDIO_WIDTH_D1_ONLY is not set
diff --git a/nuttx/configs/open1788/src/lpc17_nsh.c b/nuttx/configs/open1788/src/lpc17_nsh.c
index 189dfc5f6..32ba32712 100644
--- a/nuttx/configs/open1788/src/lpc17_nsh.c
+++ b/nuttx/configs/open1788/src/lpc17_nsh.c
@@ -50,17 +50,20 @@
#include <nuttx/usb/usbhost.h>
#include "lpc17_gpio.h"
+#include "lpc17_sdcard.h"
#include "open1788.h"
/****************************************************************************
* Pre-Processor Definitions
****************************************************************************/
-
/* Configuration ************************************************************/
-#define NSH_HAVE_MMCSD 1
-#define NSH_HAVE_USBHOST 1
-#define NSH_HAVE_USBHDEV 1
+#define NSH_HAVE_MMCSD 1
+#define NSH_HAVE_USBHOST 1
+#define NSH_HAVE_USBHDEV 1
+
+#undef NSH_HAVE_MMCSD_CD
+#undef NSH_HAVE_MMCSD_CDINT
/* MMC/SD support */
@@ -90,6 +93,25 @@
# endif
#endif
+/* 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.
+ */
+
+#ifdef NSH_HAVE_MMCSD
+# ifdef CONFIG_MMCSD_HAVECARDDETECT
+# define NSH_HAVE_MMCSD_CD 1
+# ifdef CONFIG_GPIO_IRQ
+# define NSH_HAVE_MMCSD_CDINT 1
+# endif
+# endif
+#endif
+
+#if defined(NSH_HAVE_MMCSD_CD) && \
+ (defined(CONFIG_LPC17_SSP1) || defined(CONFIG_LPC17_USBDEV))
+# warning "Use of SD Card Detect pin conflicts with SSP1 and/or USB device"
+#endif
+
/* USB Host */
#ifndef CONFIG_USBHOST
@@ -189,6 +211,31 @@ static int nsh_waiter(int argc, char *argv[])
#endif
/****************************************************************************
+ * Name: nsh_cdinterrupt
+ *
+ * Description:
+ * Card detect interrupt handler.
+ *
+ ****************************************************************************/
+
+#ifdef NSH_HAVE_MMCSD_CDINT
+static int nsh_cdinterrupt(int irq, FAR void *context)
+{
+ static bool inserted = 0xff; /* Impossible value */
+ bool present;
+
+ present = !lpc17_gpioread(GPIO_SD_CD);
+ if (present != inserted)
+ {
+ sdio_mediachange(sdio, preset);
+ inserted = present;
+ }
+
+ return OK;
+}
+#endif
+
+/****************************************************************************
* Name: nsh_sdinitialize
*
* Description:
@@ -202,6 +249,23 @@ static int nsh_sdinitialize(void)
FAR struct sdio_dev_s *sdio;
int ret;
+#ifdef NSH_HAVE_MMCSD_CD
+ /* Configure the SD card detect GPIO */
+
+ lpc17_configgpio(GPIO_SD_CD);
+
+ /* Attach an interrupt handler to get notifications when a card is
+ * inserted or deleted.
+ */
+
+#if NSH_HAVE_MMCSD_CDINT
+
+ (void)irq_attach(LPC17_IRQ_P0p13, nsh_cdinterrupt);
+ up_enable_irq(LPC17_IRQ_P0p13);
+
+#endif
+#endif
+
/* First, get an instance of the SDIO interface */
sdio = sdio_initialize(CONFIG_NSH_MMCSDSLOTNO);
@@ -217,16 +281,24 @@ static int nsh_sdinitialize(void)
ret = mmcsd_slotinitialize(CONFIG_NSH_MMCSDMINOR, sdio);
if (ret != OK)
{
- message("nsh_archinitialize: Failed to bind SDIO to the MMC/SD driver: %d\n", ret);
+ message("nsh_archinitialize: "
+ "Failed to bind SDIO to the MMC/SD driver: %d\n",
+ ret);
+
return ret;
}
- /* Then let's guess and say that there is a card in the slot. I need to check to
- * see if the STM3240G-EVAL board supports a GPIO to detect if there is a card in
- * the slot.
+ /* Check if there is a card in the slot and inform the SDCARD driver. If
+ * we do not support the card detect, then let's assume that there is
+ * one.
*/
- sdio_mediachange(sdio, true);
+#ifdef NSH_HAVE_MMCSD_CD
+ sdio_mediachange(sdio, !lpc17_gpioread(GPIO_SD_CD));
+#else
+ sdio_mediachange(sdio, true);
+#endif
+ return OK;
}
#else
# define nsh_sdinitialize() (OK)
diff --git a/nuttx/configs/open1788/src/open1788.h b/nuttx/configs/open1788/src/open1788.h
index f5c4cdcd6..9a839704a 100644
--- a/nuttx/configs/open1788/src/open1788.h
+++ b/nuttx/configs/open1788/src/open1788.h
@@ -101,6 +101,18 @@
#define GPIO_JOY_D (GPIO_INTBOTH | GPIO_FLOAT | GPIO_PORT2 | GPIO_PIN19)
#define GPIO_JOY_CTR (GPIO_INTBOTH | GPIO_FLOAT | GPIO_PORT0 | GPIO_PIN14)
+/* SD Card **************************************************************************/
+/* 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.
+ */
+
+#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
+
/************************************************************************************
* Public Types
************************************************************************************/