summaryrefslogtreecommitdiff
path: root/nuttx/configs/ea3131/src
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx/configs/ea3131/src')
-rwxr-xr-xnuttx/configs/ea3131/src/Makefile4
-rwxr-xr-xnuttx/configs/ea3131/src/ea3131_internal.h254
-rwxr-xr-xnuttx/configs/ea3131/src/up_boot.c238
-rwxr-xr-xnuttx/configs/ea3131/src/up_clkinit.c6
-rwxr-xr-xnuttx/configs/ea3131/src/up_fillpage.c28
-rwxr-xr-xnuttx/configs/ea3131/src/up_leds.c2
-rwxr-xr-xnuttx/configs/ea3131/src/up_mem.c96
-rwxr-xr-xnuttx/configs/ea3131/src/up_nsh.c11
-rwxr-xr-xnuttx/configs/ea3131/src/up_spi.c30
9 files changed, 335 insertions, 334 deletions
diff --git a/nuttx/configs/ea3131/src/Makefile b/nuttx/configs/ea3131/src/Makefile
index c97c4fecf..6e62138d6 100755
--- a/nuttx/configs/ea3131/src/Makefile
+++ b/nuttx/configs/ea3131/src/Makefile
@@ -44,13 +44,13 @@ CSRCS = up_boot.c up_clkinit.c
ifeq ($(CONFIG_ARCH_BUTTONS),y)
CSRCS += up_buttons.c
endif
-ifeq ($(CONFIG_LPC313X_EXTSDRAM),y)
+ifeq ($(CONFIG_LPC31XX_EXTSDRAM),y)
CSRCS += up_mem.c
endif
ifeq ($(CONFIG_ARCH_LEDS),y)
CSRCS += up_leds.c
endif
-ifeq ($(CONFIG_LPC313X_SPI),y)
+ifeq ($(CONFIG_LPC31XX_SPI),y)
CSRCS += up_spi.c
endif
ifeq ($(CONFIG_NSH_ARCHINIT),y)
diff --git a/nuttx/configs/ea3131/src/ea3131_internal.h b/nuttx/configs/ea3131/src/ea3131_internal.h
index 0f28ea1cc..ca2a5b570 100755
--- a/nuttx/configs/ea3131/src/ea3131_internal.h
+++ b/nuttx/configs/ea3131/src/ea3131_internal.h
@@ -1,127 +1,127 @@
-/************************************************************************************
- * configs/ea3131/src/ea3131_internal.h
- * arch/arm/src/board/ea3131_internal.n
- *
- * Copyright (C) 2009-2010 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.
- *
- ************************************************************************************/
-
-#ifndef __CONFIGS_EA3131_SRC_EA3131_INTERNAL_H
-#define __CONFIGS_EA3131_SRC_EA3131_INTERNAL_H
-
-/************************************************************************************
- * Included Files
- ************************************************************************************/
-
-#include <nuttx/config.h>
-#include <nuttx/compiler.h>
-#include <stdint.h>
-
-#include "lpc313x_ioconfig.h"
-
-/************************************************************************************
- * Definitions
- ************************************************************************************/
-
-/* EA3131L GPIOs ********************************************************************/
-
-/* LEDs -- interface through an I2C GPIO expander */
-
-/* BUTTONS -- NOTE that some have EXTI interrupts configured */
-
-/* SPI Chip Selects */
-/* SPI NOR flash is the only device on SPI. SPI_CS_OUT0 is its chip select */
-
-#define SPINOR_CS IOCONFIG_SPI_CSOUT0
-
-/* USB Soft Connect Pullup -- NONE */
-
-/************************************************************************************
- * Public Types
- ************************************************************************************/
-
-/************************************************************************************
- * Public data
- ************************************************************************************/
-
-#ifndef __ASSEMBLY__
-
-/************************************************************************************
- * Public Functions
- ************************************************************************************/
-
-/************************************************************************************
- * Name: lpc313x_meminitialize
- *
- * Description:
- * Initialize external memory resources (sram, sdram, nand, nor, etc.)
- *
- ************************************************************************************/
-
-#ifdef CONFIG_LPC313X_EXTSDRAM
-extern void lpc313x_meminitialize(void);
-#endif
-
-/************************************************************************************
- * Name: lpc313x_spiinitialize
- *
- * Description:
- * Called to configure SPI chip select GPIO pins for the EA3131 board.
- *
- ************************************************************************************/
-
-extern void weak_function lpc313x_spiinitialize(void);
-
-/************************************************************************************
- * Name: lpc313x_usbinitialize
- *
- * Description:
- * Called to setup USB-related GPIO pins for the EA3131 board.
- *
- ************************************************************************************/
-
-extern void weak_function lpc313x_usbinitialize(void);
-
-/************************************************************************************
- * Name: lpc313x_pginitialize
- *
- * Description:
- * Set up mass storage device to support on demand paging.
- *
- ************************************************************************************/
-
-#ifdef CONFIG_PAGING
-extern void weak_function lpc313x_pginitialize(void);
-#endif
-
-#endif /* __ASSEMBLY__ */
-#endif /* __CONFIGS_EA3131_SRC_EA3131_INTERNAL_H */
-
+/************************************************************************************
+ * configs/ea3131/src/ea3131_internal.h
+ * arch/arm/src/board/ea3131_internal.n
+ *
+ * Copyright (C) 2009-2010 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.
+ *
+ ************************************************************************************/
+
+#ifndef __CONFIGS_EA3131_SRC_EA3131_INTERNAL_H
+#define __CONFIGS_EA3131_SRC_EA3131_INTERNAL_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+#include <nuttx/compiler.h>
+#include <stdint.h>
+
+#include "lpc31_ioconfig.h"
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+
+/* EA3131L GPIOs ********************************************************************/
+
+/* LEDs -- interface through an I2C GPIO expander */
+
+/* BUTTONS -- NOTE that some have EXTI interrupts configured */
+
+/* SPI Chip Selects */
+/* SPI NOR flash is the only device on SPI. SPI_CS_OUT0 is its chip select */
+
+#define SPINOR_CS IOCONFIG_SPI_CSOUT0
+
+/* USB Soft Connect Pullup -- NONE */
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public data
+ ************************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: lpc31_meminitialize
+ *
+ * Description:
+ * Initialize external memory resources (sram, sdram, nand, nor, etc.)
+ *
+ ************************************************************************************/
+
+#ifdef CONFIG_LPC31XX_EXTSDRAM
+extern void lpc31_meminitialize(void);
+#endif
+
+/************************************************************************************
+ * Name: lpc31_spiinitialize
+ *
+ * Description:
+ * Called to configure SPI chip select GPIO pins for the EA3131 board.
+ *
+ ************************************************************************************/
+
+extern void weak_function lpc31_spiinitialize(void);
+
+/************************************************************************************
+ * Name: lpc31_usbinitialize
+ *
+ * Description:
+ * Called to setup USB-related GPIO pins for the EA3131 board.
+ *
+ ************************************************************************************/
+
+extern void weak_function lpc31_usbinitialize(void);
+
+/************************************************************************************
+ * Name: lpc31_pginitialize
+ *
+ * Description:
+ * Set up mass storage device to support on demand paging.
+ *
+ ************************************************************************************/
+
+#ifdef CONFIG_PAGING
+extern void weak_function lpc31_pginitialize(void);
+#endif
+
+#endif /* __ASSEMBLY__ */
+#endif /* __CONFIGS_EA3131_SRC_EA3131_INTERNAL_H */
+
diff --git a/nuttx/configs/ea3131/src/up_boot.c b/nuttx/configs/ea3131/src/up_boot.c
index 59ed9e778..94c4d8a9c 100755
--- a/nuttx/configs/ea3131/src/up_boot.c
+++ b/nuttx/configs/ea3131/src/up_boot.c
@@ -1,119 +1,119 @@
-/************************************************************************************
- * configs/ea3131/src/up_boot.c
- * arch/arm/src/board/up_boot.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 <debug.h>
-
-#include <arch/board/board.h>
-
-#include "up_arch.h"
-#include "up_internal.h"
-#include "lpc313x_internal.h"
-#include "ea3131_internal.h"
-
-/************************************************************************************
- * Definitions
- ************************************************************************************/
-
-/************************************************************************************
- * Private Functions
- ************************************************************************************/
-
-/************************************************************************************
- * Public Functions
- ************************************************************************************/
-
-/************************************************************************************
- * Name: lpc313x_boardinitialize
- *
- * Description:
- * All LPC313X architectures must provide the following entry point. This entry
- * point is called early in the intitialization -- after all memory has been
- * configured and mapped but before any devices have been initialized.
- *
- ************************************************************************************/
-
-void lpc313x_boardinitialize(void)
-{
- /* Initialize configured, external memory resources */
-
-#ifdef CONFIG_LPC313X_EXTSDRAM
- lpc313x_meminitialize();
-#endif
-
- /* Configure SPI chip selects if 1) SPI is not disabled, and 2) the weak function
- * lpc313x_spiinitialize() has been brought into the link.
- */
-
-#if defined(CONFIG_LPC313X_SPI)
- if (lpc313x_spiinitialize)
- {
- lpc313x_spiinitialize();
- }
-#endif
-
- /* Initialize USB is 1) USBDEV is selected, 2) the USB controller is not
- * disabled, and 3) the weak function lpc313x_usbinitialize() has been brought
- * into the build.
- */
-
-#if defined(CONFIG_USBDEV) && defined(CONFIG_LPC313X_USB)
- if (lpc313x_usbinitialize)
- {
- lpc313x_usbinitialize();
- }
-#endif
-
- /* Configure on-board LEDs if LED support has been selected. */
-
-#ifdef CONFIG_ARCH_LEDS
- up_ledinit();
-#endif
-
- /* Set up mass storage device to support on demand paging */
-
-#if defined(CONFIG_PAGING)
- if (lpc313x_pginitialize)
- {
- lpc313x_pginitialize();
- }
-#endif
-}
+/************************************************************************************
+ * configs/ea3131/src/up_boot.c
+ * arch/arm/src/board/up_boot.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 <debug.h>
+
+#include <arch/board/board.h>
+
+#include "up_arch.h"
+#include "up_internal.h"
+#include "lpc31_internal.h"
+#include "ea3131_internal.h"
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Private Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: lpc31_boardinitialize
+ *
+ * Description:
+ * All LPC31XX architectures must provide the following entry point. This entry
+ * point is called early in the intitialization -- after all memory has been
+ * configured and mapped but before any devices have been initialized.
+ *
+ ************************************************************************************/
+
+void lpc31_boardinitialize(void)
+{
+ /* Initialize configured, external memory resources */
+
+#ifdef CONFIG_LPC31XX_EXTSDRAM
+ lpc31_meminitialize();
+#endif
+
+ /* Configure SPI chip selects if 1) SPI is not disabled, and 2) the weak function
+ * lpc31_spiinitialize() has been brought into the link.
+ */
+
+#if defined(CONFIG_LPC31XX_SPI)
+ if (lpc31_spiinitialize)
+ {
+ lpc31_spiinitialize();
+ }
+#endif
+
+ /* Initialize USB is 1) USBDEV is selected, 2) the USB controller is not
+ * disabled, and 3) the weak function lpc31_usbinitialize() has been brought
+ * into the build.
+ */
+
+#if defined(CONFIG_USBDEV) && defined(CONFIG_LPC31XX_USB)
+ if (lpc31_usbinitialize)
+ {
+ lpc31_usbinitialize();
+ }
+#endif
+
+ /* Configure on-board LEDs if LED support has been selected. */
+
+#ifdef CONFIG_ARCH_LEDS
+ up_ledinit();
+#endif
+
+ /* Set up mass storage device to support on demand paging */
+
+#if defined(CONFIG_PAGING)
+ if (lpc31_pginitialize)
+ {
+ lpc31_pginitialize();
+ }
+#endif
+}
diff --git a/nuttx/configs/ea3131/src/up_clkinit.c b/nuttx/configs/ea3131/src/up_clkinit.c
index 8277e633b..a0eba9c75 100755
--- a/nuttx/configs/ea3131/src/up_clkinit.c
+++ b/nuttx/configs/ea3131/src/up_clkinit.c
@@ -44,8 +44,8 @@
#include <nuttx/config.h>
-#include "lpc313x_cgu.h"
-#include "lpc313x_cgudrvr.h"
+#include "lpc31_cgu.h"
+#include "lpc31_cgudrvr.h"
/****************************************************************************
* Definitions
@@ -284,7 +284,7 @@
* 11 - DOMAIN_SYSCLKO FFAST - -
*/
-const struct lpc313x_clkinit_s g_boardclks =
+const struct lpc31_clkinit_s g_boardclks =
{
/* Domain 0 (DOMAINID_SYS), Clocks 0 - 29, Fraction dividers 0-6 */
diff --git a/nuttx/configs/ea3131/src/up_fillpage.c b/nuttx/configs/ea3131/src/up_fillpage.c
index 2d3412bef..531675aa0 100755
--- a/nuttx/configs/ea3131/src/up_fillpage.c
+++ b/nuttx/configs/ea3131/src/up_fillpage.c
@@ -58,7 +58,7 @@
# include <sys/mount.h>
# include <nuttx/sdio.h>
# include <nuttx/mmcsd.h>
-# include "lpc313x_internal.h"
+# include "lpc31_internal.h"
# endif
#endif
@@ -85,8 +85,8 @@
# undef CONFIG_PAGING_SDSLOT
# endif
#else
- /* Add configuration for new LPC313X boards here */
-# error "Unrecognized LPC313X board"
+ /* Add configuration for new LPC31XX boards here */
+# error "Unrecognized LPC31XX board"
# undef CONFIG_PAGING_SDSLOT
# undef HAVE_SD
# undef HAVE_SPINOR
@@ -122,7 +122,7 @@
* is not enabled.
*/
-# if defined(CONFIG_DISABLE_MOUNTPOINT) || !defined(CONFIG_LPC313X_MCI)
+# if defined(CONFIG_DISABLE_MOUNTPOINT) || !defined(CONFIG_LPC31XX_MCI)
# ifdef CONFIG_PAGING_SDSLOT
# error "Mountpoints and/or MCI disabled"
# endif
@@ -152,7 +152,7 @@
/* Verify that SPI support is enabld */
-#ifndef CONFIG_LPC313X_SPI
+#ifndef CONFIG_LPC31XX_SPI
# error "SPI support is not enabled"
#endif
@@ -219,7 +219,7 @@ static struct pg_source_s g_pgsrc;
****************************************************************************/
/****************************************************************************
- * Name: lpc313x_initsrc()
+ * Name: lpc31_initsrc()
*
* Description:
* Initialize the source device that will support paging.
@@ -230,7 +230,7 @@ static struct pg_source_s g_pgsrc;
****************************************************************************/
#if defined(CONFIG_PAGING_BINPATH)
-static inline void lpc313x_initsrc(void)
+static inline void lpc31_initsrc(void)
{
#ifdef CONFIG_PAGING_SDSLOT
FAR struct sdio_dev_s *sdio;
@@ -287,7 +287,7 @@ static inline void lpc313x_initsrc(void)
}
#elif defined(CONFIG_PAGING_M25PX) || defined(CONFIG_PAGING_AT45DB)
-static inline void lpc313x_initsrc(void)
+static inline void lpc31_initsrc(void)
{
FAR struct spi_dev_s *spi;
#ifdef CONFIG_DEBUG
@@ -339,7 +339,7 @@ static inline void lpc313x_initsrc(void)
}
#else
-# define lpc313x_initsrc()
+# define lpc31_initsrc()
#endif
/****************************************************************************
@@ -425,7 +425,7 @@ int up_fillpage(FAR _TCB *tcb, FAR void *vpage)
/* Perform initialization of the paging source device (if necessary) */
- lpc313x_initsrc();
+ lpc31_initsrc();
/* Create an offset into the binary image that corresponds to the
* virtual address. File offset 0 corresponds to PG_LOCKED_VBASE.
@@ -448,7 +448,7 @@ int up_fillpage(FAR _TCB *tcb, FAR void *vpage)
/* Perform initialization of the paging source device (if necessary) */
- lpc313x_initsrc();
+ lpc31_initsrc();
/* Create an offset into the binary image that corresponds to the
* virtual address. File offset 0 corresponds to PG_LOCKED_VBASE.
@@ -493,21 +493,21 @@ int up_fillpage(FAR _TCB *tcb, FAR void *vpage, up_pgcallback_t pg_callback)
#endif /* CONFIG_PAGING_BLOCKINGFILL */
/************************************************************************************
- * Name: lpc313x_pginitialize
+ * Name: lpc31_pginitialize
*
* Description:
* Set up mass storage device to support on demand paging.
*
************************************************************************************/
-void weak_function lpc313x_pginitialize(void)
+void weak_function lpc31_pginitialize(void)
{
/* This initialization does nothing in this example setup. But this function is
* where you might, for example:
*
* - Initialize and configure a mass storage device to support on-demand paging.
* This might be, perhaps an SD card or NAND memory. An SPI FLASH would probably
- * already have been configured by lpc313x_spiinitialize(void);
+ * already have been configured by lpc31_spiinitialize(void);
* - Set up resources to support up_fillpage() operation. For example, perhaps the
* the text image is stored in a named binary file. In this case, the virtual
* text addresses might map to offsets into that file.
diff --git a/nuttx/configs/ea3131/src/up_leds.c b/nuttx/configs/ea3131/src/up_leds.c
index 43a9847db..a0bec01b0 100755
--- a/nuttx/configs/ea3131/src/up_leds.c
+++ b/nuttx/configs/ea3131/src/up_leds.c
@@ -49,7 +49,7 @@
#include "chip.h"
#include "up_arch.h"
#include "up_internal.h"
-#include "lpc313x_internal.h"
+#include "lpc31_internal.h"
/****************************************************************************
* Definitions
diff --git a/nuttx/configs/ea3131/src/up_mem.c b/nuttx/configs/ea3131/src/up_mem.c
index 956e3ee75..1559468ac 100755
--- a/nuttx/configs/ea3131/src/up_mem.c
+++ b/nuttx/configs/ea3131/src/up_mem.c
@@ -54,12 +54,12 @@
#include "chip.h"
#include "up_arch.h"
-#include "lpc313x_syscreg.h"
-#include "lpc313x_cgudrvr.h"
-#include "lpc313x_mpmc.h"
+#include "lpc31_syscreg.h"
+#include "lpc31_cgudrvr.h"
+#include "lpc31_mpmc.h"
#include "ea3131_internal.h"
-#ifdef CONFIG_LPC313X_EXTSDRAM
+#ifdef CONFIG_LPC31XX_EXTSDRAM
/****************************************************************************
* Pre-processor Definitions
@@ -103,7 +103,7 @@
****************************************************************************/
/****************************************************************************
- * Name: lpc313x_sdraminitialize
+ * Name: lpc31_sdraminitialize
*
* Description:
* Configure SDRAM on the EA3131 board
@@ -155,7 +155,7 @@
*
****************************************************************************/
-static void lpc313x_sdraminitialize(void)
+static void lpc31_sdraminitialize(void)
{
uint32_t tmp;
uint32_t regval;
@@ -164,10 +164,10 @@ static void lpc313x_sdraminitialize(void)
* replaced with an apriori value.
*/
-#ifdef CONFIG_LPC313X_SDRAMHCLK
-# define HCLK CONFIG_LPC313X_SDRAMHCLK
+#ifdef CONFIG_LPC31XX_SDRAMHCLK
+# define HCLK CONFIG_LPC31XX_SDRAMHCLK
#else
- uint32_t hclk = lpc313x_clkfreq(CLKID_MPMCCFGCLK2, DOMAINID_SYS);
+ uint32_t hclk = lpc31_clkfreq(CLKID_MPMCCFGCLK2, DOMAINID_SYS);
# define HCLK hclk
#endif
@@ -175,7 +175,7 @@ static void lpc313x_sdraminitialize(void)
#if 0
uint32_t hclk2 = hclk;
- if (((getreg32(LPC313X_MPMC_CONFIG) & MPMC_CONFIG_CLK)) != 0)
+ if (((getreg32(LPC31_MPMC_CONFIG) & MPMC_CONFIG_CLK)) != 0)
{
hclk2 >>= 1;
}
@@ -187,45 +187,45 @@ static void lpc313x_sdraminitialize(void)
/* Set command delay startergy */
- putreg32(MPMC_DYNREADCONFIG_CMDDEL, LPC313X_MPMC_DYNREADCONFIG);
+ putreg32(MPMC_DYNREADCONFIG_CMDDEL, LPC31_MPMC_DYNREADCONFIG);
/* Configure device config register nSDCE0 for proper width SDRAM */
putreg32((MPMC_DYNCONFIG0_MDSDRAM|MPMC_DYNCONFIG_HP16_32MX16),
- LPC313X_MPMC_DYNCONFIG0);
+ LPC31_MPMC_DYNCONFIG0);
putreg32((MPMC_DYNRASCAS0_RAS2CLK|MPMC_DYNRASCAS0_CAS2CLK),
- LPC313X_MPMC_DYNRASCAS0);
+ LPC31_MPMC_DYNRASCAS0);
/* Min 20ns program 1 so that at least 2 HCLKs are used */
putreg32(NS2HCLKS(EA3131_SDRAM_TRP, HCLK2, MPMC_DYNTRP_MASK),
- LPC313X_MPMC_DYNTRP);
+ LPC31_MPMC_DYNTRP);
putreg32(NS2HCLKS(EA3131_SDRAM_TRAS, HCLK2, MPMC_DYNTRAS_MASK),
- LPC313X_MPMC_DYNTRAS);
+ LPC31_MPMC_DYNTRAS);
putreg32(NS2HCLKS(EA3131_SDRAM_TREX, HCLK2, MPMC_DYNTSREX_MASK),
- LPC313X_MPMC_DYNTSREX);
+ LPC31_MPMC_DYNTSREX);
putreg32(EA3131_SDRAM_TARP,
- LPC313X_MPMC_DYNTAPR);
+ LPC31_MPMC_DYNTAPR);
putreg32(NS2HCLKS(EA3131_SDRAM_TDAL, HCLK2, MPMC_DYNTDAL_MASK),
- LPC313X_MPMC_DYNTDAL);
+ LPC31_MPMC_DYNTDAL);
putreg32(NS2HCLKS(EA3131_SDRAM_TWR, HCLK2, MPMC_DYNTWR_MASK),
- LPC313X_MPMC_DYNTWR);
+ LPC31_MPMC_DYNTWR);
putreg32(NS2HCLKS(EA3131_SDRAM_TRC, HCLK2, MPMC_DYNTRC_MASK),
- LPC313X_MPMC_DYNTRC);
+ LPC31_MPMC_DYNTRC);
putreg32(NS2HCLKS(EA3131_SDRAM_TRFC, HCLK2, MPMC_DYNTRFC_MASK),
- LPC313X_MPMC_DYNTRFC);
+ LPC31_MPMC_DYNTRFC);
putreg32(NS2HCLKS(EA3131_SDRAM_TXSR, HCLK2, MPMC_DYNTXSR_MASK),
- LPC313X_MPMC_DYNTXSR);
+ LPC31_MPMC_DYNTXSR);
putreg32(NS2HCLKS(EA3131_SDRAM_TRRD, HCLK2, MPMC_DYNTRRD_MASK),
- LPC313X_MPMC_DYNTRRD);
+ LPC31_MPMC_DYNTRRD);
putreg32(NS2HCLKS(EA3131_SDRAM_TMRD, HCLK2, MPMC_DYNTMRD_MASK),
- LPC313X_MPMC_DYNTMRD);
+ LPC31_MPMC_DYNTMRD);
up_udelay(100);
/* Issue continuous NOP commands */
putreg32((MPMC_DYNCONTROL_CE|MPMC_DYNCONTROL_CS|MPMC_DYNCONTROL_INOP),
- LPC313X_MPMC_DYNCONTROL);
+ LPC31_MPMC_DYNCONTROL);
/* Load ~200us delay value to timer1 */
@@ -234,14 +234,14 @@ static void lpc313x_sdraminitialize(void)
/* Issue a "pre-charge all" command */
putreg32((MPMC_DYNCONTROL_CE|MPMC_DYNCONTROL_CS|MPMC_DYNCONTROL_IPALL),
- LPC313X_MPMC_DYNCONTROL);
+ LPC31_MPMC_DYNCONTROL);
/* Minimum refresh pulse interval (tRFC) for MT48LC32M16A2=80nsec,
* 100nsec provides more than adequate interval.
*/
putreg32(NS2HCLKS(EA3131_SDRAM_REFRESH, HCLK, MPMC_DYNREFRESH_TIMER_MASK),
- LPC313X_MPMC_DYNREFRESH);
+ LPC31_MPMC_DYNREFRESH);
/* Load ~250us delay value to timer1 */
@@ -253,12 +253,12 @@ static void lpc313x_sdraminitialize(void)
*/
putreg32(NS2HCLKS(EA3131_SDRAM_OPERREFRESH, HCLK, MPMC_DYNREFRESH_TIMER_MASK),
- LPC313X_MPMC_DYNREFRESH);
+ LPC31_MPMC_DYNREFRESH);
/* Select mode register update mode */
putreg32((MPMC_DYNCONTROL_CE|MPMC_DYNCONTROL_CS|MPMC_DYNCONTROL_IMODE),
- LPC313X_MPMC_DYNCONTROL);
+ LPC31_MPMC_DYNCONTROL);
/* Program the SDRAM internal mode registers on bank nSDCE0 and reconfigure
* the SDRAM chips. Bus speeds up to 90MHz requires use of a CAS latency = 2.
@@ -266,26 +266,26 @@ static void lpc313x_sdraminitialize(void)
* 16bit mode
*/
- tmp = getreg32(LPC313X_EXTSDRAM0_VSECTION | (0x23 << 13));
+ tmp = getreg32(LPC31_EXTSDRAM0_VSECTION | (0x23 << 13));
putreg32((MPMC_DYNCONFIG0_MDSDRAM|MPMC_DYNCONFIG_HP16_32MX16),
- LPC313X_MPMC_DYNCONFIG0);
+ LPC31_MPMC_DYNCONFIG0);
putreg32((MPMC_DYNRASCAS0_RAS2CLK|MPMC_DYNRASCAS0_CAS2CLK),
- LPC313X_MPMC_DYNRASCAS0);
+ LPC31_MPMC_DYNRASCAS0);
/* Select normal operating mode */
putreg32((MPMC_DYNCONTROL_CE|MPMC_DYNCONTROL_CS|MPMC_DYNCONTROL_INORMAL),
- LPC313X_MPMC_DYNCONTROL);
+ LPC31_MPMC_DYNCONTROL);
/* Enable buffers */
- regval = getreg32(LPC313X_MPMC_DYNCONFIG0);
+ regval = getreg32(LPC31_MPMC_DYNCONFIG0);
regval |= MPMC_DYNCONFIG0_B;
- putreg32(regval, LPC313X_MPMC_DYNCONFIG0);
+ putreg32(regval, LPC31_MPMC_DYNCONFIG0);
putreg32((MPMC_DYNCONTROL_INORMAL|MPMC_DYNCONTROL_CS),
- LPC313X_MPMC_DYNCONTROL);
+ LPC31_MPMC_DYNCONTROL);
}
/****************************************************************************
@@ -293,14 +293,14 @@ static void lpc313x_sdraminitialize(void)
****************************************************************************/
/****************************************************************************
- * Name: lpc313x_meminitialize
+ * Name: lpc31_meminitialize
*
* Description:
* Initialize external memory resources (sram, sdram, nand, nor, etc.)
*
****************************************************************************/
-void lpc313x_meminitialize(void)
+void lpc31_meminitialize(void)
{
/* Configure the LCD pins in external bus interface (EBI/MPMC) memory mode.
*
@@ -326,34 +326,34 @@ void lpc313x_meminitialize(void)
* LCD_DB_15 -> EBI_A_15
*/
- putreg32(SYSCREG_MUX_LCDEBISEL_EBIMPMC, LPC313X_SYSCREG_MUX_LCDEBISEL);
+ putreg32(SYSCREG_MUX_LCDEBISEL_EBIMPMC, LPC31_SYSCREG_MUX_LCDEBISEL);
/* Enable EBI clock */
- lpc313x_enableclock(CLKID_EBICLK);
+ lpc31_enableclock(CLKID_EBICLK);
/* Enable MPMC controller clocks */
- lpc313x_enableclock(CLKID_MPMCCFGCLK);
- lpc313x_enableclock(CLKID_MPMCCFGCLK2);
- lpc313x_enableclock(CLKID_MPMCCFGCLK3);
+ lpc31_enableclock(CLKID_MPMCCFGCLK);
+ lpc31_enableclock(CLKID_MPMCCFGCLK2);
+ lpc31_enableclock(CLKID_MPMCCFGCLK3);
/* Enable the external memory controller */
- putreg32(MPMC_CONTROL_E, LPC313X_MPMC_CONTROL);
+ putreg32(MPMC_CONTROL_E, LPC31_MPMC_CONTROL);
/* Force HCLK to MPMC_CLK to 1:1 ratio, little-endian mode */
- putreg32(0, LPC313X_MPMC_CONFIG);
+ putreg32(0, LPC31_MPMC_CONFIG);
/* Set MPMC delay based on trace lengths between SDRAM and the chip
* and on the delay strategy used for SDRAM.
*/
- putreg32(EA3131_MPMC_DELAY, LPC313X_SYSCREG_MPMC_DELAYMODES);
+ putreg32(EA3131_MPMC_DELAY, LPC31_SYSCREG_MPMC_DELAYMODES);
/* Configure Micron MT48LC32M16A2 SDRAM on the EA3131 board */
- lpc313x_sdraminitialize();
+ lpc31_sdraminitialize();
}
-#endif /* CONFIG_LPC313X_EXTSDRAM */
+#endif /* CONFIG_LPC31XX_EXTSDRAM */
diff --git a/nuttx/configs/ea3131/src/up_nsh.c b/nuttx/configs/ea3131/src/up_nsh.c
index c0848c9f1..c8dbf017b 100755
--- a/nuttx/configs/ea3131/src/up_nsh.c
+++ b/nuttx/configs/ea3131/src/up_nsh.c
@@ -45,12 +45,12 @@
#include <debug.h>
#include <errno.h>
-#ifdef CONFIG_LPC313X_MCI
+#ifdef CONFIG_LPC31XX_MCI
# include <nuttx/sdio.h>
# include <nuttx/mmcsd.h>
#endif
-#include "lpc313x_internal.h"
+#include "lpc31_internal.h"
/****************************************************************************
* Pre-Processor Definitions
@@ -71,8 +71,9 @@
# define CONFIG_NSH_MMCSDSLOTNO 0
# endif
#else
- /* Add configuration for new LPC313X boards here */
-# error "Unrecognized LPC313X board"
+ /* Add configuration for new LPC31XX boards here */
+
+# error "Unrecognized LPC31XX board"
# undef CONFIG_NSH_HAVEUSBDEV
# undef CONFIG_NSH_HAVEMMCSD
#endif
@@ -87,7 +88,7 @@
* is not enabled.
*/
-#if defined(CONFIG_DISABLE_MOUNTPOINT) || !defined(CONFIG_LPC313X_MCI)
+#if defined(CONFIG_DISABLE_MOUNTPOINT) || !defined(CONFIG_LPC31XX_MCI)
# undef CONFIG_NSH_HAVEMMCSD
#endif
diff --git a/nuttx/configs/ea3131/src/up_spi.c b/nuttx/configs/ea3131/src/up_spi.c
index c2df60a48..7755e55b4 100755
--- a/nuttx/configs/ea3131/src/up_spi.c
+++ b/nuttx/configs/ea3131/src/up_spi.c
@@ -2,7 +2,7 @@
* configs/ea3131/src/up_spi.c
* arch/arm/src/board/up_spi.c
*
- * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009-2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -49,12 +49,12 @@
#include "up_arch.h"
#include "chip.h"
-#include "lpc313x_internal.h"
+#include "lpc31_internal.h"
#include "ea3131_internal.h"
-#ifdef CONFIG_LPC313X_SPI
-#if 0 /* At present, EA3131 specific logic is hard-coded in the file lpc313x_spi.c
- * in arch/arm/src/lpc313x */
+#ifdef CONFIG_LPC31XX_SPI
+#if 0 /* At present, EA3131 specific logic is hard-coded in the file lpc31_spi.c
+ * in arch/arm/src/lpc31xx */
/************************************************************************************
* Definitions
@@ -87,14 +87,14 @@
************************************************************************************/
/************************************************************************************
- * Name: lpc313x_spiinitialize
+ * Name: lpc31_spiinitialize
*
* Description:
* Called to configure SPI chip select GPIO pins for the EA3131 board.
*
************************************************************************************/
-void weak_function lpc313x_spiinitialize(void)
+void weak_function lpc31_spiinitialize(void)
{
/* NOTE: Clocking for SPI has already been provided. Pin configuration is performed
* on-the-fly, so no additional setup is required.
@@ -102,19 +102,19 @@ void weak_function lpc313x_spiinitialize(void)
}
/************************************************************************************
- * Name: lpc313x_spiselect and lpc313x_spistatus
+ * Name: lpc31_spiselect and lpc31_spistatus
*
* Description:
- * The external functions, lpc313x_spiselect and lpc313x_spistatus must be
+ * The external functions, lpc31_spiselect and lpc31_spistatus must be
* provided by board-specific logic. They are implementations of the select
* and status methods of the SPI interface defined by struct spi_ops_s (see
* include/nuttx/spi.h). All other methods (including up_spiinitialize())
- * are provided by common LPC313X logic. To use this common SPI logic on your
+ * are provided by common LPC31XX logic. To use this common SPI logic on your
* board:
*
- * 1. Provide logic in lpc313x_boardinitialize() to configure SPI chip select
+ * 1. Provide logic in lpc31_boardinitialize() to configure SPI chip select
* pins.
- * 2. Provide lpc313x_spiselect() and lpc313x_spistatus() functions in your
+ * 2. Provide lpc31_spiselect() and lpc31_spistatus() functions in your
* board-specific logic. These functions will perform chip selection and
* status operations using GPIOs in the way your board is configured.
* 3. Add a calls to up_spiinitialize() in your low level application
@@ -126,17 +126,17 @@ void weak_function lpc313x_spiinitialize(void)
*
************************************************************************************/
-void lpc313x_spiselect(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
+void lpc31_spiselect(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
{
spidbg("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert");
#warning "Missing logic"
}
-uint8_t lpc313x_spistatus(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
+uint8_t lpc31_spistatus(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
{
return SPI_STATUS_PRESENT;
}
#endif /* 0 */
-#endif /* CONFIG_LPC313X_SPI */
+#endif /* CONFIG_LPC31XX_SPI */