summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--nuttx/ChangeLog1
-rw-r--r--nuttx/Documentation/NuttX.html1
-rw-r--r--nuttx/TODO4
-rwxr-xr-xnuttx/arch/arm/src/lm3s/lm3s_ssi.c102
-rw-r--r--nuttx/arch/arm/src/lm3s/lm3s_start.c4
-rw-r--r--nuttx/configs/eagle100/httpd/defconfig7
-rw-r--r--nuttx/configs/eagle100/include/board.h7
-rw-r--r--nuttx/configs/eagle100/nettest/defconfig7
-rw-r--r--nuttx/configs/eagle100/nsh/defconfig7
-rw-r--r--nuttx/configs/eagle100/ostest/defconfig7
-rw-r--r--nuttx/configs/eagle100/src/Makefile2
-rw-r--r--nuttx/configs/eagle100/src/up_boot.c9
-rw-r--r--nuttx/configs/eagle100/src/up_ssi.c96
-rw-r--r--nuttx/examples/nsh/Makefile5
-rw-r--r--nuttx/examples/nsh/nsh_lm3s.c158
-rw-r--r--nuttx/examples/nsh/nsh_lpc214x.c2
16 files changed, 394 insertions, 25 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index 7a1ca792e..9f0d3d7f5 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -729,4 +729,5 @@
Micromint Eagle100 board.
* Documentation/NuttxPortingGuide.html: Added a section on NuttX device drivers.
* arch/arm/src/lm3s: Added an SSI driver for the LM3S6918
+ * examples/nsh: Added MMC/SD support for the LM3S6918
diff --git a/nuttx/Documentation/NuttX.html b/nuttx/Documentation/NuttX.html
index 4c67353fb..8f4d62a08 100644
--- a/nuttx/Documentation/NuttX.html
+++ b/nuttx/Documentation/NuttX.html
@@ -1419,6 +1419,7 @@ nuttx-0.4.7 2009-xx-xx Gregory Nutt <spudmonkey@racsa.co.cr>
Micromint Eagle100 board.
* Documentation/NuttxPortingGuide.html: Added a section on NuttX device drivers.
* arch/arm/src/lm3s: Added an SSI driver for the LM3S6918
+ * examples/nsh: Added MMC/SD support for the LM3S6918
pascal-0.1.3 2009-xx-xx Gregory Nutt <spudmonkey@racsa.co.cr>
diff --git a/nuttx/TODO b/nuttx/TODO
index 4c569aa4e..8a0c35b26 100644
--- a/nuttx/TODO
+++ b/nuttx/TODO
@@ -543,9 +543,9 @@ o ARM/LM3S6918 (arch/arm/src/lm3s/)
Status: Open
Priority: Low
- Description: Still need to implement I2C, SSI, MMC/SD, and Ethernet
+ Description: Still need to implement I2C
Status: Open
- Priority: High
+ Priority: Low
o pjrc-8052 / MCS51 (arch/pjrc-8051/)
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
diff --git a/nuttx/arch/arm/src/lm3s/lm3s_ssi.c b/nuttx/arch/arm/src/lm3s/lm3s_ssi.c
index 4370a05fe..4fbc83a7d 100755
--- a/nuttx/arch/arm/src/lm3s/lm3s_ssi.c
+++ b/nuttx/arch/arm/src/lm3s/lm3s_ssi.c
@@ -542,25 +542,34 @@ static int ssi_performtx(struct lm32_ssidev_s *priv)
/* Update the count of words to to transferred */
priv->ntxwords -= ntxd;
+ }
- /* Make sure that the Tx FIFO half-empty interrupt is enabled */
+ /* Check again... Now have all of the Tx words been sent? */
#ifndef CONFIG_SSI_POLLWAIT
- regval = ssi_getreg(priv, LM3S_SSI_IM_OFFSET);
+ regval = ssi_getreg(priv, LM3S_SSI_IM_OFFSET);
+ if (priv->ntxwords > 0)
+ {
+ /* No.. Enable the Tx FIFO interrupt. This interrupt occurs
+ * when the Tx FIFO is 1/2 full or less.
+ */
+
+#ifdef CONFIG_DEBUG
+ regval |= (SSI_IM_TX|SSI_RIS_ROR)
+#else
regval |= SSI_IM_TX;
- ssi_putreg(priv, LM3S_SSI_IM_OFFSET, regval);
#endif
}
-#ifndef CONFIG_SSI_POLLWAIT
else
{
- /* Yes.. The transfer is complete, disable Tx FIFO half-empty interrupt */
+ /* Yes.. Disable the Tx FIFO interrupt. The final stages of
+ * the transfer will be driven by Rx FIFO interrupts.
+ */
- regval = ssi_getreg(priv, LM3S_SSI_IM_OFFSET);
- regval &= ~SSI_IM_TX;
- ssi_putreg(priv, LM3S_SSI_IM_OFFSET, regval);
+ regval &= ~(SSI_IM_TX|SSI_RIS_ROR);
}
-#endif
+ ssi_putreg(priv, LM3S_SSI_IM_OFFSET, regval);
+#endif /* CONFIG_SSI_POLLWAIT */
}
return ntxd;
}
@@ -582,6 +591,10 @@ static int ssi_performtx(struct lm32_ssidev_s *priv)
static inline void ssi_performrx(struct lm32_ssidev_s *priv)
{
+#ifndef CONFIG_SSI_POLLWAIT
+ uint32 regval;
+#endif
+
/* Loop while data is available in the Rx FIFO */
while (ssi_rxfifonotempty(priv))
@@ -596,6 +609,38 @@ static inline void ssi_performrx(struct lm32_ssidev_s *priv)
priv->nrxwords++;
}
}
+
+ /* The Rx FIFO is now empty. While there is Tx data to be sent, the
+ * transfer will be driven by Tx FIFO interrupts. The final part
+ * of the transfer is driven by Rx FIFO interrupts only.
+ */
+
+#ifndef CONFIG_SSI_POLLWAIT
+ regval = ssi_getreg(priv, LM3S_SSI_IM_OFFSET);
+ if (priv->ntxwords == 0 && priv->nrxwords < priv->nwords)
+ {
+ /* There are no more outgoing words to send, but there are
+ * additional incoming words expected (I would think that this
+ * a real corner case, be we will handle it with an extra
+ * interrupt, probably an Rx timeout).
+ */
+
+#ifdef CONFIG_DEBUG
+ regval |= (SSI_IM_RX|SSI_IM_RT|SSI_IM_ROR);
+#else
+ regval |= (SSI_IM_RX|SSI_IM_RT);
+#endif
+ }
+ else
+ {
+ /* No.. there are either more Tx words to send or all Rx words
+ * have received. Disable Rx FIFO interrupts.
+ */
+
+ regval &= ~(SSI_IM_RX|SSI_IM_RT);
+ }
+ ssi_putreg(priv, LM3S_SSI_IM_OFFSET, regval);
+#endif /* CONFIG_SSI_POLLWAIT */
}
/****************************************************************************
@@ -659,7 +704,11 @@ static int ssi_transfer(struct lm32_ssidev_s *priv, const void *txbuffer,
priv->rxword = ssi_rxnull;
}
- /* Prime the Tx FIFO to start the sequence (saves one interrupt) */
+ /* Prime the Tx FIFO to start the sequence (saves one interrupt).
+ * At this point, all SSI interrupts should be disabled, but the
+ * operation of ssi_performtx() will set up the interrupts
+ * approapriately.
+ */
#ifndef CONFIG_SSI_POLLWAIT
flags = irqsave();
@@ -671,7 +720,11 @@ static int ssi_transfer(struct lm32_ssidev_s *priv, const void *txbuffer,
*/
irqrestore(flags);
- ssi_semtake(&priv->xfrsem);
+ do
+ {
+ ssi_semtake(&priv->xfrsem);
+ }
+ while (priv->nrxwords < priv->nwords);
#else
/* Perform the transfer using polling logic. This will totally
@@ -770,6 +823,15 @@ static int ssi_interrupt(int irq, void *context)
regval = ssi_getreg(priv, LM3S_SSI_RIS_OFFSET);
ssi_putreg(priv, LM3S_SSI_ICR_OFFSET, regval);
+ /* Check for Rx FIFO overruns */
+
+#ifdef CONFIG_DEBUG
+ if ((regval & SSI_RIS_ROR) != 0)
+ {
+ lldbg("Rx FIFO Overrun!\n");
+ }
+#endif
+
/* Handle outgoing Tx FIFO transfers */
ntxd = ssi_performtx(priv);
@@ -782,7 +844,11 @@ static int ssi_interrupt(int irq, void *context)
if (priv->nrxwords >= priv->nwords)
{
- /* Yes, wake up the waiting thread */
+ /* Yes.. Disable all SSI interrupt sources */
+
+ ssi_putreg(priv, LM3S_SSI_IM_OFFSET, 0);
+
+ /* Wake up the waiting thread */
ssi_semgive(&priv->xfrsem);
}
@@ -1235,16 +1301,13 @@ FAR struct spi_dev_s *up_spiinitialize(int port)
ssi_setfrequencyinternal(priv, 400000);
- /* Enable interrupts on data ready in the RX FIFL (and certain error conditions) */
+ /* Disable all SSI interrupt sources */
-#ifndef CONFIG_SSI_POLLWAIT
- ssi_putreg(priv, LM3S_SSI_IM_OFFSET,
- SSI_IM_ROR | /* SSI Rx FIFO Overrun */
- SSI_IM_RT | /* SSI Rx FIFO Time-Out */
- SSI_IM_RX); /* SSI Rx FIFO half full or more */
+ ssi_putreg(priv, LM3S_SSI_IM_OFFSET, 0);
/* Attach the interrupt */
+#ifndef CONFIG_SSI_POLLWAIT
#if NSSI_ENABLED > 1
irq_attach(priv->irq, (xcpt_t)ssi_interrupt);
#else
@@ -1256,7 +1319,7 @@ FAR struct spi_dev_s *up_spiinitialize(int port)
ssi_enable(priv, SSI_CR1_SSE);
- /* Enable SSI interrupts */
+ /* Enable SSI interrupts (They are still disabled at the source). */
#ifndef CONFIG_SSI_POLLWAIT
#if NSSI_ENABLED > 1
@@ -1265,6 +1328,7 @@ FAR struct spi_dev_s *up_spiinitialize(int port)
up_enable_irq(SSI_IRQ);
#endif
#endif /* CONFIG_SSI_POLLWAIT */
+
irqrestore(flags);
return (FAR struct spi_dev_s *)priv;
}
diff --git a/nuttx/arch/arm/src/lm3s/lm3s_start.c b/nuttx/arch/arm/src/lm3s/lm3s_start.c
index 848c41074..8fc05bdef 100644
--- a/nuttx/arch/arm/src/lm3s/lm3s_start.c
+++ b/nuttx/arch/arm/src/lm3s/lm3s_start.c
@@ -134,10 +134,10 @@ void __start(void)
#endif
showprogress('D');
- /* Initialize onboard LEDs */
+ /* Initialize onboard resources */
#ifdef CONFIG_ARCH_LEDS
- up_ledinit();
+ lm3s_boardinitialize();
#endif
showprogress('E');
diff --git a/nuttx/configs/eagle100/httpd/defconfig b/nuttx/configs/eagle100/httpd/defconfig
index 23104ef0b..044d5c5cb 100644
--- a/nuttx/configs/eagle100/httpd/defconfig
+++ b/nuttx/configs/eagle100/httpd/defconfig
@@ -515,6 +515,13 @@ CONFIG_EXAMPLES_NSH_FATNSECTORS=1024
CONFIG_EXAMPLES_NSH_FATMOUNTPT=/tmp
#
+# Architecture-specific NSH options
+#
+CONFIG_EXAMPLES_NSH_MMCSDSPIPORTNO=0
+CONFIG_EXAMPLES_NSH_MMCSDSLOTNO=0
+CONFIG_EXAMPLES_NSH_MMCSDMINOR=0
+
+#
# Settings for examples/dhcpd
#
CONFIG_EXAMPLE_DHCPD_NOMAC=y
diff --git a/nuttx/configs/eagle100/include/board.h b/nuttx/configs/eagle100/include/board.h
index 68204dbdf..16cae3d78 100644
--- a/nuttx/configs/eagle100/include/board.h
+++ b/nuttx/configs/eagle100/include/board.h
@@ -44,6 +44,7 @@
#ifndef __ASSEMBLY__
# include <sys/types.h>
#endif
+#include "lm3s_internal.h"
/************************************************************************************
* Definitions
@@ -109,6 +110,12 @@
#define LED_ASSERTION 6 /* ON OFF */
#define LED_PANIC 7 /* ON OFF */
+/* Eagle-100 GPIOs ******************************************************************/
+
+/* GPIO for microSD card chip select */
+
+#define SDC_CS (GPIO_PORTG | 2)
+
/************************************************************************************
* Public Function Prototypes
************************************************************************************/
diff --git a/nuttx/configs/eagle100/nettest/defconfig b/nuttx/configs/eagle100/nettest/defconfig
index 4d63e556e..c9679b551 100644
--- a/nuttx/configs/eagle100/nettest/defconfig
+++ b/nuttx/configs/eagle100/nettest/defconfig
@@ -506,6 +506,13 @@ CONFIG_EXAMPLES_NSH_FATNSECTORS=1024
CONFIG_EXAMPLES_NSH_FATMOUNTPT=/tmp
#
+# Architecture-specific NSH options
+#
+CONFIG_EXAMPLES_NSH_MMCSDSPIPORTNO=0
+CONFIG_EXAMPLES_NSH_MMCSDSLOTNO=0
+CONFIG_EXAMPLES_NSH_MMCSDMINOR=0
+
+#
# Stack and heap information
#
# CONFIG_BOOT_RUNFROMFLASH - Some configurations support XIP
diff --git a/nuttx/configs/eagle100/nsh/defconfig b/nuttx/configs/eagle100/nsh/defconfig
index dd765ce15..d40816e42 100644
--- a/nuttx/configs/eagle100/nsh/defconfig
+++ b/nuttx/configs/eagle100/nsh/defconfig
@@ -491,6 +491,13 @@ CONFIG_EXAMPLES_NSH_FATNSECTORS=1024
CONFIG_EXAMPLES_NSH_FATMOUNTPT=/tmp
#
+# Architecture-specific NSH options
+#
+CONFIG_EXAMPLES_NSH_MMCSDSPIPORTNO=0
+CONFIG_EXAMPLES_NSH_MMCSDSLOTNO=0
+CONFIG_EXAMPLES_NSH_MMCSDMINOR=0
+
+#
# Stack and heap information
#
# CONFIG_BOOT_RUNFROMFLASH - Some configurations support XIP
diff --git a/nuttx/configs/eagle100/ostest/defconfig b/nuttx/configs/eagle100/ostest/defconfig
index b10c979e5..41f811dd1 100644
--- a/nuttx/configs/eagle100/ostest/defconfig
+++ b/nuttx/configs/eagle100/ostest/defconfig
@@ -491,6 +491,13 @@ CONFIG_EXAMPLES_NSH_FATNSECTORS=1024
CONFIG_EXAMPLES_NSH_FATMOUNTPT=/tmp
#
+# Architecture-specific NSH options
+#
+CONFIG_EXAMPLES_NSH_MMCSDSPIPORTNO=0
+CONFIG_EXAMPLES_NSH_MMCSDSLOTNO=0
+CONFIG_EXAMPLES_NSH_MMCSDMINOR=0
+
+#
# Stack and heap information
#
# CONFIG_BOOT_RUNFROMFLASH - Some configurations support XIP
diff --git a/nuttx/configs/eagle100/src/Makefile b/nuttx/configs/eagle100/src/Makefile
index e79c84163..455a5b85c 100644
--- a/nuttx/configs/eagle100/src/Makefile
+++ b/nuttx/configs/eagle100/src/Makefile
@@ -39,7 +39,7 @@ CFLAGS += -I$(TOPDIR)/sched
ASRCS =
AOBJS = $(ASRCS:.S=$(OBJEXT))
-CSRCS = up_boot.c up_leds.c up_ethernet.c
+CSRCS = up_boot.c up_leds.c up_ethernet.c up_ssi.c
COBJS = $(CSRCS:.c=$(OBJEXT))
SRCS = $(ASRCS) $(CSRCS)
diff --git a/nuttx/configs/eagle100/src/up_boot.c b/nuttx/configs/eagle100/src/up_boot.c
index 602147e1b..4b7d5f6ef 100644
--- a/nuttx/configs/eagle100/src/up_boot.c
+++ b/nuttx/configs/eagle100/src/up_boot.c
@@ -68,4 +68,13 @@
void lm3s_boardinitialize(void)
{
+ /* Configure the SPI-based microSD CS GPIO */
+
+ lm3s_configgpio(SDC_CS | GPIO_PADTYPE_STDWPU | GPIO_STRENGTH_4MA | GPIO_VALUE_ONE);
+
+ /* Configure on-board LEDs */
+
+#ifdef CONFIG_ARCH_LEDS
+ up_ledinit();
+#endif
}
diff --git a/nuttx/configs/eagle100/src/up_ssi.c b/nuttx/configs/eagle100/src/up_ssi.c
new file mode 100644
index 000000000..2a09ce4a8
--- /dev/null
+++ b/nuttx/configs/eagle100/src/up_ssi.c
@@ -0,0 +1,96 @@
+/************************************************************************************
+ * configs/eagle100/src/up_ssi.c
+ * arch/arm/src/board/up_ssi.c
+ *
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+#include <sys/types.h>
+
+#include <nuttx/spi.h>
+#include <arch/board/board.h>
+
+#include "up_arch.h"
+#include "lm3s_internal.h"
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Private Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/****************************************************************************
+ * The external functions, lm3s_spiselect and lm3s_spistatus must be provided
+ * by board-specific logic. The are implementations of the select and status
+ * methods SPI interface defined by struct spi_ops_s (see include/nuttx/spi.h).
+ * All othermethods (including up_spiinitialize()) are provided by common
+ * logic. To use this common SPI logic on your board:
+ *
+ * 1. Provide lm3s_spiselect() and lm3s_spistatus() functions in your
+ * board-specific logic. This function will perform chip selection and
+ * status operations using GPIOs in the way your board is configured.
+ * 2. Add a call to up_spiinitialize() in your low level initialization
+ * logic
+ * 3. The handle returned by up_spiinitialize() may then be used to bind the
+ * SPI driver to higher level logic (e.g., calling
+ * mmcsd_spislotinitialize(), for example, will bind the SPI driver to
+ * the SPI MMC/SD driver).
+ *
+ ****************************************************************************/
+
+void lm3s_spiselect(FAR struct spi_dev_s *dev, enum spi_dev_e devid, boolean selected)
+{
+ if (devid == SPIDEV_MMCSD)
+ {
+ /* Assert the CS pin to the card */
+
+ lm3s_gpiowrite(SDC_CS, selected ? 0 : 1);
+ }
+}
+
+ubyte lm3s_spistatus(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
+{
+#warning "Need to check schematic"
+ return SPI_STATUS_PRESENT;
+}
+
diff --git a/nuttx/examples/nsh/Makefile b/nuttx/examples/nsh/Makefile
index dea17977a..6cfae5161 100644
--- a/nuttx/examples/nsh/Makefile
+++ b/nuttx/examples/nsh/Makefile
@@ -64,6 +64,11 @@ CSRCS += nsh_lpc214x.c
CFLAGS += -DCONFIG_EXAMPLES_NSH_ARCHINIT=1
endif
+ifeq ($(CONFIG_ARCH_CHIP),lm3s)
+CSRCS += nsh_lm3s.c
+CFLAGS += -DCONFIG_EXAMPLES_NSH_ARCHINIT=1
+endif
+
AOBJS = $(ASRCS:.S=$(OBJEXT))
COBJS = $(CSRCS:.c=$(OBJEXT))
diff --git a/nuttx/examples/nsh/nsh_lm3s.c b/nuttx/examples/nsh/nsh_lm3s.c
new file mode 100644
index 000000000..75576bbbe
--- /dev/null
+++ b/nuttx/examples/nsh/nsh_lm3s.c
@@ -0,0 +1,158 @@
+/****************************************************************************
+ * examples/nsh/nsh_lm3s.c
+ *
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <debug.h>
+#include <errno.h>
+
+#include <nuttx/spi.h>
+#include <nuttx/mmcsd.h>
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+/* Configuration ************************************************************/
+
+/* PORT and SLOT number probably depend on the board configuration */
+
+#ifdef CONFIG_ARCH_BOARD_EAGLE100
+# undef CONFIG_EXAMPLES_NSH_HAVEUSBDEV
+# define CONFIG_EXAMPLES_NSH_HAVEMMCSD 1
+# if !defined(CONFIG_EXAMPLES_NSH_MMCSDSPIPORTNO) || CONFIG_EXAMPLES_NSH_MMCSDSPIPORTNO != 0
+# error "The Eagle100 MMC/SD is on SSI0"
+# undef CONFIG_EXAMPLES_NSH_MMCSDSPIPORTNO
+# define CONFIG_EXAMPLES_NSH_MMCSDSPIPORTNO 0
+# endif
+# if !defined(CONFIG_EXAMPLES_NSH_MMCSDSLOTNO) || CONFIG_EXAMPLES_NSH_MMCSDSLOTNO != 0
+# error "The Eagle100 MMC/SD is on SSI0 slot 0"
+# undef CONFIG_EXAMPLES_NSH_MMCSDSLOTNO
+# define CONFIG_EXAMPLES_NSH_MMCSDSLOTNO 0
+# endif
+#else
+ /* Add configuration for new LPC214x boards here */
+# error "Unrecognized lm3s board"
+# undef CONFIG_EXAMPLES_NSH_HAVEUSBDEV
+# undef CONFIG_EXAMPLES_NSH_HAVEMMCSD
+#endif
+
+/* Can't support USB features if USB is not enabled */
+
+#ifndef CONFIG_USBDEV
+# undef CONFIG_EXAMPLES_NSH_HAVEUSBDEV
+#endif
+
+/* Can't support MMC/SD features if mountpoints are disabled */
+
+#if defined(CONFIG_DISABLE_MOUNTPOINT)
+# undef CONFIG_EXAMPLES_NSH_HAVEMMCSD
+#endif
+
+#ifndef CONFIG_EXAMPLES_NSH_MMCSDMINOR
+# define CONFIG_EXAMPLES_NSH_MMCSDMINOR 0
+#endif
+
+/* Debug ********************************************************************/
+
+#ifdef CONFIG_CPP_HAVE_VARARGS
+# ifdef CONFIG_DEBUG
+# define message(...) lib_lowprintf(__VA_ARGS__)
+# else
+# define message(...) printf(__VA_ARGS__)
+# endif
+#else
+# ifdef CONFIG_DEBUG
+# define message lib_lowprintf
+# else
+# define message printf
+# endif
+#endif
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: nsh_archinitialize
+ *
+ * Description:
+ * Perform architecture specific initialization
+ *
+ ****************************************************************************/
+
+int nsh_archinitialize(void)
+{
+ FAR struct spi_dev_s *spi;
+ int ret;
+
+ /* Get the SPI port */
+
+ message("nsh_archinitialize: Initializing SPI port %d\n",
+ CONFIG_EXAMPLES_NSH_MMCSDSPIPORTNO);
+
+ spi = up_spiinitialize(CONFIG_EXAMPLES_NSH_MMCSDSPIPORTNO);
+ if (!spi)
+ {
+ message("nsh_archinitialize: Failed to initialize SPI port %d\n",
+ CONFIG_EXAMPLES_NSH_MMCSDSPIPORTNO);
+ return -ENODEV;
+ }
+
+ message("nsh_archinitialize: Successfully initialized SPI port %d\n",
+ CONFIG_EXAMPLES_NSH_MMCSDSPIPORTNO);
+
+ /* Bind the SPI port to the slot */
+
+ message("nsh_archinitialize: Binding SPI port %d to MMC/SD slot %d\n",
+ CONFIG_EXAMPLES_NSH_MMCSDSPIPORTNO, CONFIG_EXAMPLES_NSH_MMCSDSLOTNO);
+
+ ret = mmcsd_spislotinitialize(CONFIG_EXAMPLES_NSH_MMCSDMINOR, CONFIG_EXAMPLES_NSH_MMCSDSLOTNO, spi);
+ if (ret < 0)
+ {
+ message("nsh_archinitialize: Failed to bind SPI port %d to MMC/SD slot %d: %d\n",
+ CONFIG_EXAMPLES_NSH_MMCSDSPIPORTNO, CONFIG_EXAMPLES_NSH_MMCSDSLOTNO, ret);
+ return ret;
+ }
+
+ message("nsh_archinitialize: Successfuly bound SPI port %d to MMC/SD slot %d\n",
+ CONFIG_EXAMPLES_NSH_MMCSDSPIPORTNO, CONFIG_EXAMPLES_NSH_MMCSDSLOTNO);
+ return OK;
+}
diff --git a/nuttx/examples/nsh/nsh_lpc214x.c b/nuttx/examples/nsh/nsh_lpc214x.c
index 0b49a3f1d..487d3e03f 100644
--- a/nuttx/examples/nsh/nsh_lpc214x.c
+++ b/nuttx/examples/nsh/nsh_lpc214x.c
@@ -128,7 +128,7 @@ int nsh_archinitialize(void)
message("nsh_archinitialize: Initializing SPI port %d\n",
CONFIG_EXAMPLES_NSH_MMCSDSPIPORTNO);
- spi = up_spiinitialize(1);
+ spi = up_spiinitialize(CONFIG_EXAMPLES_NSH_MMCSDSPIPORTNO);
if (!spi)
{
message("nsh_archinitialize: Failed to initialize SPI port %d\n",