summaryrefslogtreecommitdiff
path: root/nuttx/configs/lpc4330-xplorer/src
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx/configs/lpc4330-xplorer/src')
-rw-r--r--nuttx/configs/lpc4330-xplorer/src/Makefile18
-rw-r--r--nuttx/configs/lpc4330-xplorer/src/up_autoleds.c (renamed from nuttx/configs/lpc4330-xplorer/src/up_leds.c)188
-rw-r--r--nuttx/configs/lpc4330-xplorer/src/up_boot.c3
-rw-r--r--nuttx/configs/lpc4330-xplorer/src/up_buttons.c3
-rw-r--r--nuttx/configs/lpc4330-xplorer/src/up_ostest.c114
-rw-r--r--nuttx/configs/lpc4330-xplorer/src/up_userleds.c157
-rw-r--r--nuttx/configs/lpc4330-xplorer/src/xplorer_internal.h (renamed from nuttx/configs/lpc4330-xplorer/src/lpc4330_xplorer_internal.h)35
7 files changed, 395 insertions, 123 deletions
diff --git a/nuttx/configs/lpc4330-xplorer/src/Makefile b/nuttx/configs/lpc4330-xplorer/src/Makefile
index b2541dc26..7be95126b 100644
--- a/nuttx/configs/lpc4330-xplorer/src/Makefile
+++ b/nuttx/configs/lpc4330-xplorer/src/Makefile
@@ -38,18 +38,28 @@
CFLAGS += -I$(TOPDIR)/sched
ASRCS =
-CSRCS = up_boot.c up_leds.c
+CSRCS = up_boot.c
ifeq ($(CONFIG_NSH_ARCHINIT),y)
CSRCS += up_nsh.c
endif
-ifeq ($(CONFIG_USBMSC),y)
-CSRCS += up_usbmsc.c
+ifeq ($(CONFIG_ARCH_FPU),y)
+CSRCS += up_ostest.c
+endif
+
+ifeq ($(CONFIG_ARCH_LEDS),y)
+CSRCS += up_autoleds.c
+else
+CSRCS += up_userleds.c
endif
ifeq ($(CONFIG_ARCH_BUTTONS),y)
-CSRCS += up_buttons.c
+CSRCS += up_buttons.c
+endif
+
+ifeq ($(CONFIG_USBMSC),y)
+CSRCS += up_usbmsc.c
endif
AOBJS = $(ASRCS:.S=$(OBJEXT))
diff --git a/nuttx/configs/lpc4330-xplorer/src/up_leds.c b/nuttx/configs/lpc4330-xplorer/src/up_autoleds.c
index e6350d6ed..89b2a1020 100644
--- a/nuttx/configs/lpc4330-xplorer/src/up_leds.c
+++ b/nuttx/configs/lpc4330-xplorer/src/up_autoleds.c
@@ -1,6 +1,6 @@
/****************************************************************************
- * configs/lpc4330-xplorer/src/up_leds.c
- * arch/arm/src/board/up_leds.c
+ * configs/lpc4330-xplorer/src/up_autoleds.c
+ * arch/arm/src/board/up_autoleds.c
*
* Copyright (C) 2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
@@ -50,28 +50,57 @@
#include "up_arch.h"
#include "up_internal.h"
-#include "lpc43_internal.h"
-
-#include "lpc4330_xplorer_internal.h"
+#include "xplorer_internal.h"
#ifdef CONFIG_ARCH_LEDS
/****************************************************************************
* Definitions
****************************************************************************/
+/* LED definitions **********************************************************/
+/* The LPC4330-Xplorer has 2 user-controllable LEDs labeled D2 an D3 in the
+ * schematic and on but referred to has LED1 and LED2 here, respectively.
+ *
+ * LED1 D2 GPIO1[12]
+ * LED2 D3 GPIO1[11]
+ *
+ * LEDs are pulled high to a low output illuminates the LED.
+ *
+ * If CONFIG_ARCH_LEDS is defined, the LEDs will be controlled as follows
+ * for NuttX debug functionality (where NC means "No Change").
+ *
+ * ON OFF
+ * LED1 LED2 LED1 LED2
+ * LED_STARTED 0 OFF OFF - -
+ * LED_HEAPALLOCATE 1 ON OFF - -
+ * LED_IRQSENABLED 1 ON OFF - -
+ * LED_STACKCREATED 1 ON OFF - -
+ * LED_INIRQ 2 NC ON NC OFF
+ * LED_SIGNAL 2 NC ON NC OFF
+ * LED_ASSERTION 2 NC ON NC OFF
+ * LED_PANIC 2 NC ON NC OFF
+ *
+ * If CONFIG_ARCH_LEDS is not defined, then the LEDs are completely under
+ * control of the application. The following interfaces are then available
+ * for application control of the LEDs:
+ *
+ * void lpc43_ledinit(void);
+ * void lpc43_setled(int led, bool ledon);
+ * void lpc43_setleds(uint8_t ledset);
+ */
+/* Debug definitions ********************************************************/
/* Enables debug output from this file (needs CONFIG_DEBUG with
* CONFIG_DEBUG_VERBOSE too)
*/
-#undef LED_DEBUG /* Define to enable debug */
-#undef LED_VERBOSE /* Define to enable verbose debug */
-
-#ifdef LED_DEBUG
+#ifdef CONFIG_DEBUG_LED
# define leddbg lldbg
-# ifdef LED_VERBOSE
+# ifdef CONFIG_DEBUG_VERBOSE
+# define LED_VERBOSE 1
# define ledvdbg lldbg
# else
+# undef LED_VERBOSE
# define ledvdbg(x...)
# endif
#else
@@ -80,44 +109,29 @@
# define ledvdbg(x...)
#endif
-/* Dump GPIO registers */
-
-#ifdef LED_VERBOSE
-# define led_dumpgpio(m) lpc43_dumpgpio(LPC4330_XPLORER_LED2, m)
-#else
-# define led_dumpgpio(m)
-#endif
-
/****************************************************************************
* Private Data
****************************************************************************/
-/* LED definitions ******************************************************************
-
-The LPC4330-Xplorer has 2 LEDs along the bottom of the board. Green or off.
-If CONFIG_ARCH_LEDS is defined, the LEDs will be controlled as follows for NuttX
-debug functionality (where NC means "No Change").
-
-During the boot phases. LED1 and LED2 will show boot status.
-
- LED1 LED2
-STARTED OFF OFF
-HEAPALLOCATE BLUE OFF
-IRQSENABLED OFF BLUE
-STACKCREATED OFF OFF
-
-After the system is booted, this logic will no longer use LEDs 1 & 2. They
-are available for use by applications using lpc43_led (prototyped below)
-*/
-
-static bool g_initialized;
-static int g_nestcount;
-
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
+ * Name: led_dumppins
+ ****************************************************************************/
+
+#ifdef LED_VERBOSE
+static void led_dumppins(FAR const char *msg)
+{
+ lpc43_dumppinconfig(PINCONFIG_LED1, msg);
+ lpc43_dumpgpio(GPIO_LED2, msg);
+}
+#else
+# define led_dumppins(m)
+#endif
+
+/****************************************************************************
* Public Functions
****************************************************************************/
@@ -127,14 +141,19 @@ static int g_nestcount;
void up_ledinit(void)
{
- /* Configure all LED GPIO lines */
+ /* Configure all LED pins as GPIO outputs */
+
+ led_dumppins("up_ledinit() Entry)");
- led_dumpgpio("up_ledinit() Entry)");
+ /* Configure LED pins as GPIOs, then configure GPIOs as outputs */
- lpc43_configgpio(LPC4330_XPLORER_LED1);
- lpc43_configgpio(LPC4330_XPLORER_LED2);
+ lpc43_pinconfig(PINCONFIG_LED1);
+ lpc43_gpioconfig(GPIO_LED1);
- led_dumpgpio("up_ledinit() Exit");
+ lpc43_pinconfig(PINCONFIG_LED2);
+ lpc43_gpioconfig(GPIO_LED2);
+
+ led_dumppins("up_ledinit() Exit");
}
/****************************************************************************
@@ -143,44 +162,22 @@ void up_ledinit(void)
void up_ledon(int led)
{
- /* We will control LED1 and LED2 not yet completed the boot sequence. */
-
- if (!g_initialized)
- {
- int led1 = 0;
- int led2 = 0;
- switch (led)
- {
- case LED_STACKCREATED:
- g_initialized = true;
- case LED_STARTED:
- default:
- break;
-
- case LED_HEAPALLOCATE:
- led1 = 1;
- break;
-
- case LED_IRQSENABLED:
- led2 = 1;
- }
- lpc43_led(LPC4330_XPLORER_LED1,led1);
- lpc43_led(LPC4330_XPLORER_LED2,led2);
- }
-
- /* We will always control the HB LED */
-
switch (led)
{
- case LED_INIRQ:
- case LED_SIGNAL:
- case LED_ASSERTION:
- case LED_PANIC:
- lpc43_gpiowrite(LPC4330_XPLORER_HEARTBEAT, false);
- g_nestcount++;
-
- default:
- break;
+ default:
+ case 0:
+ lpc43_gpiowrite(GPIO_LED1, true); /* LED1 OFF */
+ lpc43_gpiowrite(GPIO_LED2, true); /* LED2 OFF */
+ break;
+
+ case 1:
+ lpc43_gpiowrite(GPIO_LED1, false); /* LED1 ON */
+ lpc43_gpiowrite(GPIO_LED2, true); /* LED2 OFF */
+ break;
+
+ case 2:
+ lpc43_gpiowrite(GPIO_LED2, false); /* LED2 ON */
+ break;
}
}
@@ -190,30 +187,17 @@ void up_ledon(int led)
void up_ledoff(int led)
{
- /* In all states, OFF can only mean turning off the HB LED */
-
- if (g_nestcount <= 1)
- {
- lpc43_led(LPC4330_XPLORER_HEARTBEAT, true);
- g_nestcount = 0;
- }
- else
+ switch (led)
{
- g_nestcount--;
+ default:
+ case 0:
+ case 1:
+ break;
+
+ case 2:
+ lpc43_gpiowrite(GPIO_LED2, true); /* LED2 OFF */
+ break;
}
}
-/************************************************************************************
- * Name: lpc43_led
- *
- * Description:
- * Once the system has booted, these functions can be used to control the LEDs
- *
- ************************************************************************************/
-
-void lpc43_led(int lednum, int state)
-
-{
- lpc43_gpiowrite(lednum, state);
-}
#endif /* CONFIG_ARCH_LEDS */
diff --git a/nuttx/configs/lpc4330-xplorer/src/up_boot.c b/nuttx/configs/lpc4330-xplorer/src/up_boot.c
index 4543d036c..8bd4e019b 100644
--- a/nuttx/configs/lpc4330-xplorer/src/up_boot.c
+++ b/nuttx/configs/lpc4330-xplorer/src/up_boot.c
@@ -47,8 +47,7 @@
#include "up_arch.h"
#include "up_internal.h"
-#include "lpc43_internal.h"
-#include "lpc4330_xplorer_internal.h"
+#include "xplorer_internal.h"
/************************************************************************************
* Definitions
diff --git a/nuttx/configs/lpc4330-xplorer/src/up_buttons.c b/nuttx/configs/lpc4330-xplorer/src/up_buttons.c
index 6878c8203..cd3e1583f 100644
--- a/nuttx/configs/lpc4330-xplorer/src/up_buttons.c
+++ b/nuttx/configs/lpc4330-xplorer/src/up_buttons.c
@@ -47,8 +47,7 @@
#include <arch/board/board.h>
-#include "lpc43_internal.h"
-#include "lpc4330_xplorer_internal.h"
+#include "xplorer_internal.h"
#ifdef CONFIG_ARCH_BUTTONS
diff --git a/nuttx/configs/lpc4330-xplorer/src/up_ostest.c b/nuttx/configs/lpc4330-xplorer/src/up_ostest.c
new file mode 100644
index 000000000..f0988337a
--- /dev/null
+++ b/nuttx/configs/lpc4330-xplorer/src/up_ostest.c
@@ -0,0 +1,114 @@
+/************************************************************************************
+ * configs/lpc4330-xplorer/src/up_ostest.c
+ * arch/arm/src/board/up_ostest.c
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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 <stdint.h>
+#include <stdbool.h>
+#include <string.h>
+#include <debug.h>
+
+#include <arch/irq.h>
+#include <arch/board/board.h>
+
+#include "up_arch.h"
+#include "up_internal.h"
+#include "xplorer-internal.h"
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+/* Configuration ********************************************************************/
+
+#undef HAVE_FPU
+#if defined(CONFIG_ARCH_FPU) && defined(CONFIG_EXAMPLES_OSTEST_FPUSIZE) && \
+ defined(CONFIG_SCHED_WAITPID) && !defined(CONFIG_DISABLE_SIGNALS) && \
+ !defined(CONFIG_ARMV7M_CMNVECTOR)
+# define HAVE_FPU 1
+#endif
+
+#ifdef HAVE_FPU
+
+#if CONFIG_EXAMPLES_OSTEST_FPUSIZE != (4*SW_FPU_REGS)
+# error "CONFIG_EXAMPLES_OSTEST_FPUSIZE has the wrong size"
+#endif
+
+/************************************************************************************
+ * Private Data
+ ************************************************************************************/
+
+static uint32_t g_saveregs[XCPTCONTEXT_REGS];
+
+/************************************************************************************
+ * Private Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+/* Given an array of size CONFIG_EXAMPLES_OSTEST_FPUSIZE, this function will return
+ * the current FPU registers.
+ */
+
+void arch_getfpu(FAR uint32_t *fpusave)
+{
+ irqstate_t flags;
+
+ /* Take a snapshot of the thread context right now */
+
+ flags = irqsave();
+ up_saveusercontext(g_saveregs);
+
+ /* Return only the floating register values */
+
+ memcpy(fpusave, &g_saveregs[REG_S0], (4*SW_FPU_REGS));
+ irqrestore(flags);
+}
+
+/* Given two arrays of size CONFIG_EXAMPLES_OSTEST_FPUSIZE this function
+ * will compare them and return true if they are identical.
+ */
+
+bool arch_cmpfpu(FAR const uint32_t *fpusave1, FAR const uint32_t *fpusave2)
+{
+ return memcmp(fpusave1, fpusave2, (4*SW_FPU_REGS)) == 0;
+}
+
+#endif /* HAVE_FPU */
diff --git a/nuttx/configs/lpc4330-xplorer/src/up_userleds.c b/nuttx/configs/lpc4330-xplorer/src/up_userleds.c
new file mode 100644
index 000000000..0f7ccee50
--- /dev/null
+++ b/nuttx/configs/lpc4330-xplorer/src/up_userleds.c
@@ -0,0 +1,157 @@
+/****************************************************************************
+ * configs/lpc4330-xplorer/src/up_userleds.c
+ * arch/arm/src/board/up_userleds.c
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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 <stdint.h>
+#include <stdbool.h>
+#include <debug.h>
+
+#include <arch/board/board.h>
+
+#include "chip.h"
+#include "up_arch.h"
+#include "up_internal.h"
+
+#include "xplorer_internal.h"
+
+#ifndef CONFIG_ARCH_LEDS
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+/* LED definitions **********************************************************/
+/* The LPC4330-Xplorer has 2 user-controllable LEDs labeled D2 an D3 in the
+ * schematic and on but referred to has LED1 and LED2 here, respectively.
+ *
+ * LED1 D2 GPIO1[12]
+ * LED2 D3 GPIO1[11]
+ *
+ * LEDs are pulled high to a low output illuminates the LED.
+ */
+
+/* Debug definitions ********************************************************/
+/* Enables debug output from this file (needs CONFIG_DEBUG with
+ * CONFIG_DEBUG_VERBOSE too)
+ */
+
+#ifdef CONFIG_DEBUG_LED
+# define leddbg lldbg
+# ifdef CONFIG_DEBUG_VERBOSE
+# define LED_VERBOSE 1
+# define ledvdbg lldbg
+# else
+# undef LED_VERBOSE
+# define ledvdbg(x...)
+# endif
+#else
+# undef LED_VERBOSE
+# define leddbg(x...)
+# define ledvdbg(x...)
+#endif
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: led_dumppins
+ ****************************************************************************/
+
+#ifdef LED_VERBOSE
+static void led_dumppins(FAR const char *msg)
+{
+ lpc43_dumppinconfig(PINCONFIG_LED1, msg);
+ lpc43_dumpgpio(GPIO_LED2, msg);
+}
+#else
+# define led_dumppins(m)
+#endif
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: lpc43_ledinit
+ ****************************************************************************/
+
+void lpc43_ledinit(void)
+{
+ /* Configure all LED GPIO lines */
+
+ led_dumppins("lpc43_ledinit() Entry)");
+
+ /* Configure LED pins as GPIOs, then configure GPIOs as outputs */
+
+ lpc43_pinconfig(PINCONFIG_LED1);
+ lpc43_gpioconfig(GPIO_LED1);
+
+ lpc43_pinconfig(PINCONFIG_LED2);
+ lpc43_gpioconfig(GPIO_LED2);
+
+ led_dumppins("lpc43_ledinit() Exit");
+}
+
+/****************************************************************************
+ * Name: lpc43_setled
+ ****************************************************************************/
+
+void lpc43_setled(int led, bool ledon)
+{
+ uint16_t gpiocfg = (led == BOARD_LED1 ? BOARD_LED1 : BOARD_LED2);
+ lpc43_gpiowrite(GPIO_LED1, !ledon);
+}
+
+/****************************************************************************
+ * Name: lpc43_setleds
+ ****************************************************************************/
+
+void lpc43_setleds(uint8_t ledset)
+{
+ lpc43_gpiowrite(BOARD_LED1, (ledset & BOARD_LED1_BIT) == 0);
+ lpc43_gpiowrite(BOARD_LED2, (ledset & BOARD_LED2_BIT) == 0);
+}
+
+#endif /* !CONFIG_ARCH_LEDS */
diff --git a/nuttx/configs/lpc4330-xplorer/src/lpc4330_xplorer_internal.h b/nuttx/configs/lpc4330-xplorer/src/xplorer_internal.h
index 371134a4a..45c972a75 100644
--- a/nuttx/configs/lpc4330-xplorer/src/lpc4330_xplorer_internal.h
+++ b/nuttx/configs/lpc4330-xplorer/src/xplorer_internal.h
@@ -1,6 +1,6 @@
/****************************************************************************
- * configs/lpc4330-xplorer/src/lpc4330_xplorer_internal.h
- * arch/arm/src/board/lpc4330-xplorer_internal.n
+ * configs/lpc4330-xplorer/src/xplorer_internal.h
+ * arch/arm/src/board/xplorer_internal.n
*
* Copyright (C) 2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
@@ -34,8 +34,8 @@
*
****************************************************************************/
-#ifndef _CONFIGS_LPC4330_XPLORER_SRC_LPC4330_XPLORER_INTERNAL_H
-#define _CONFIGS_LPC4330_XPLORER_SRC_LPC4330_XPLORER_INTERNAL_H
+#ifndef _CONFIGS_LPC4330_XPLORER_SRC_XPLORER_INTERNAL_H
+#define _CONFIGS_LPC4330_XPLORER_SRC_XPLORER_INTERNAL_H
/****************************************************************************
* Included Files
@@ -44,6 +44,9 @@
#include <nuttx/config.h>
#include <nuttx/compiler.h>
+#include "lpc43_pinconfig.h"
+#include "lpc43_gpio.h"
+
/****************************************************************************
* Definitions
****************************************************************************/
@@ -55,14 +58,20 @@
* gpio1[11] - LED D3 J10-17 LED2
****************************************************************************/
-#define LPC4330_XPLORER_LED1 (GPIO_OUTPUT | GPIO_PORT1 | GPIO_PIN12)
-#define LPC4330_XPLORER_LED1_OFF LPC4330_XPLORER_LED1
-#define LPC4330_XPLORER_LED1_ON (LPC4330_XPLORER_LED1 | GPIO_VALUE_ONE)
-#define LPC4330_XPLORER_LED2 (GPIO_OUTPUT | GPIO_PORT1 | GPIO_PIN11)
-#define LPC4330_XPLORER_LED2_OFF LPC4330_XPLORER_LED2
-#define LPC4330_XPLORER_LED2_ON (LPC4330_XPLORER_LED2 | GPIO_VALUE_ONE)
+/* Definitions to configure LED pins as GPIOs:
+ *
+ * - Floating
+ * - Normal drive
+ * - No buffering, glitch filtering, slew=slow
+ */
+
+#define PINCONFIG_LED1 PINCONF_GPIO1p12
+#define PINCONFIG_LED2 PINCONF_GPIO1p11
+
+/* Definitions to configure LED GPIOs as outputs */
-#define LPC4330_XPLORER_HEARTBEAT LPC4330_XPLORER_LED2
+#define GPIO_LED1 (GPIO_MODE_OUTPUT | GPIO_VALUE_ONE | GPIO_PORT1 | GPIO_PIN12)
+#define GPIO_LED2 (GPIO_MODE_OUTPUT | GPIO_VALUE_ONE | GPIO_PORT1 | GPIO_PIN11)
/****************************************************************************
* Buttons GPIO PIN SIGNAL NAME
@@ -70,7 +79,7 @@
* gpio0[7] - User Button SW2 J8-25 BTN1
****************************************************************************/
-#define LPC4330_XPLORER_BUT1 (GPIO_INTBOTH | GPIO_FLOAT | GPIO_PORT0 | GPIO_PIN7)
+#define LPC4330_XPLORER_BUT1 (GPIO_INTBOTH | GPIO_FLOAT | GPIO_PORT0 | GPIO_PIN7)
/* Button IRQ numbers */
@@ -101,4 +110,4 @@
extern void weak_function lpc43_sspinitialize(void);
#endif /* __ASSEMBLY__ */
-#endif /* _CONFIGS_LPC4330_XPLORER_SRC_LPC4330_XPLORER_INTERNAL_H */
+#endif /* _CONFIGS_LPC4330_XPLORER_SRC_XPLORER_INTERNAL_H */