summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-12-31 00:11:55 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-12-31 00:11:55 +0000
commit03cf528b833689d018e1930ab193e94df5dbcfc2 (patch)
treedeb8c1e0cc1938f33902f45d5b5a0ff5e073f97d /nuttx
parentb3aa316f2e4affe5e17c50a178e6c25c08be30c5 (diff)
downloadpx4-nuttx-03cf528b833689d018e1930ab193e94df5dbcfc2.tar.gz
px4-nuttx-03cf528b833689d018e1930ab193e94df5dbcfc2.tar.bz2
px4-nuttx-03cf528b833689d018e1930ab193e94df5dbcfc2.zip
Extend lpc1766-stk LED support
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@4242 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx')
-rwxr-xr-xnuttx/arch/arm/src/lpc17xx/lpc17_allocateheap.c5
-rwxr-xr-xnuttx/arch/arm/src/lpc17xx/lpc17_ssp.c5
-rwxr-xr-xnuttx/configs/hymini-stm32v/usbserial/defconfig4
-rwxr-xr-xnuttx/configs/olimex-lpc1766stk/ftpc/ld.script6
-rwxr-xr-xnuttx/configs/olimex-lpc1766stk/hidkbd/defconfig2
-rwxr-xr-xnuttx/configs/olimex-lpc1766stk/hidkbd/ld.script6
-rwxr-xr-xnuttx/configs/olimex-lpc1766stk/include/board.h82
-rwxr-xr-xnuttx/configs/olimex-lpc1766stk/nettest/ld.script8
-rwxr-xr-xnuttx/configs/olimex-lpc1766stk/nsh/defconfig24
-rwxr-xr-xnuttx/configs/olimex-lpc1766stk/nsh/ld.script6
-rwxr-xr-xnuttx/configs/olimex-lpc1766stk/nx/ld.script8
-rwxr-xr-xnuttx/configs/olimex-lpc1766stk/ostest/ld.script8
-rwxr-xr-xnuttx/configs/olimex-lpc1766stk/slip-httpd/defconfig2
-rwxr-xr-xnuttx/configs/olimex-lpc1766stk/slip-httpd/ld.script6
-rwxr-xr-xnuttx/configs/olimex-lpc1766stk/src/Makefile2
-rwxr-xr-xnuttx/configs/olimex-lpc1766stk/src/lpc1766stk_internal.h470
-rwxr-xr-xnuttx/configs/olimex-lpc1766stk/src/up_leds.c41
-rwxr-xr-xnuttx/configs/olimex-lpc1766stk/src/up_nsh.c2
-rwxr-xr-xnuttx/configs/olimex-lpc1766stk/thttpd/ld.script8
-rwxr-xr-xnuttx/configs/olimex-lpc1766stk/usbserial/ld.script8
-rwxr-xr-xnuttx/configs/olimex-lpc1766stk/usbstorage/ld.script8
-rwxr-xr-xnuttx/configs/olimex-lpc1766stk/wlan/ld.script6
-rwxr-xr-xnuttx/configs/stm3210e-eval/usbserial/defconfig4
23 files changed, 417 insertions, 304 deletions
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_allocateheap.c b/nuttx/arch/arm/src/lpc17xx/lpc17_allocateheap.c
index 4507679a5..501358716 100755
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_allocateheap.c
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_allocateheap.c
@@ -1,8 +1,8 @@
/****************************************************************************
* arch/arm/src/lpc17xx/lpc17_allocateheap.c
*
- * Copyright (C) 2010 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Copyright (C) 2010-2011 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
@@ -43,6 +43,7 @@
#include <debug.h>
#include <nuttx/arch.h>
+#include <nuttx/mm.h>
#include <arch/board/board.h>
#include "chip.h"
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_ssp.c b/nuttx/arch/arm/src/lpc17xx/lpc17_ssp.c
index 448177345..94f6427d0 100755
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_ssp.c
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_ssp.c
@@ -1,8 +1,8 @@
/****************************************************************************
* arch/arm/src/lpc17xx/lpc17_ssp.c
*
- * Copyright (C) 2010 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Copyright (C) 2010-2011 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
@@ -139,7 +139,6 @@ static inline void ssp_putreg(FAR struct lpc17_sspdev_s *priv, uint8_t offset,
#ifndef CONFIG_SPI_OWNBUS
static int ssp_lock(FAR struct spi_dev_s *dev, bool lock);
#endif
-static void ssp_select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected);
static uint32_t ssp_setfrequency(FAR struct spi_dev_s *dev, uint32_t frequency);
static void ssp_setmode(FAR struct spi_dev_s *dev, enum spi_mode_e mode);
static void ssp_setbits(FAR struct spi_dev_s *dev, int nbits);
diff --git a/nuttx/configs/hymini-stm32v/usbserial/defconfig b/nuttx/configs/hymini-stm32v/usbserial/defconfig
index 0e062ef6f..33d4033f7 100755
--- a/nuttx/configs/hymini-stm32v/usbserial/defconfig
+++ b/nuttx/configs/hymini-stm32v/usbserial/defconfig
@@ -893,7 +893,7 @@ CONFIG_EXAMPLES_USBSERIAL_TRACEINTERRUPTS=n
#
# Settings for examples/usbterm
#
-# CONFIG_EXAMPLES_UBSTERM_BUILTIN - Build the usbterm example as an NSH
+# CONFIG_EXAMPLES_USBTERM_BUILTIN - Build the usbterm example as an NSH
# built-in command. NOTE: This is not fully functional as of this
# writing.. It should work, but there is no mechanism in place yet
# to exit the USB terminal program and return to NSH.
@@ -910,7 +910,7 @@ CONFIG_EXAMPLES_USBSERIAL_TRACEINTERRUPTS=n
# CONFIG_EXAMPLES_USBTERM_TRACECONTROLLER - Show controller events
# CONFIG_EXAMPLES_USBTERM_TRACEINTERRUPTS - Show interrupt-related events
#
-CONFIG_EXAMPLES_UBSTERM_BUILTIN=n
+CONFIG_EXAMPLES_USBTERM_BUILTIN=n
CONFIG_EXAMPLES_USBTERM_BUFLEN=256
CONFIG_EXAMPLES_USBTERM_TRACEINIT=n
CONFIG_EXAMPLES_USBTERM_TRACECLASS=n
diff --git a/nuttx/configs/olimex-lpc1766stk/ftpc/ld.script b/nuttx/configs/olimex-lpc1766stk/ftpc/ld.script
index 1dba6b80d..59b80c9bd 100755
--- a/nuttx/configs/olimex-lpc1766stk/ftpc/ld.script
+++ b/nuttx/configs/olimex-lpc1766stk/ftpc/ld.script
@@ -2,7 +2,7 @@
* configs/olimex-lpc1766stk/ftpc/ld.script
*
* Copyright (C) 2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * 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
@@ -80,11 +80,11 @@ SECTIONS
*(.ARM.extab*)
} >sram
+ __exidx_start = ABSOLUTE(.);
.ARM.exidx : {
- __exidx_start = ABSOLUTE(.);
*(.ARM.exidx*)
- __exidx_end = ABSOLUTE(.);
} >sram
+ __exidx_end = ABSOLUTE(.);
.bss : { /* BSS */
_sbss = ABSOLUTE(.);
diff --git a/nuttx/configs/olimex-lpc1766stk/hidkbd/defconfig b/nuttx/configs/olimex-lpc1766stk/hidkbd/defconfig
index 5f1eb61be..36746d15e 100755
--- a/nuttx/configs/olimex-lpc1766stk/hidkbd/defconfig
+++ b/nuttx/configs/olimex-lpc1766stk/hidkbd/defconfig
@@ -2,7 +2,7 @@
# configs/olimex-lpc1766stk/hidkbd/defconfig
#
# Copyright (C) 2011 Gregory Nutt. All rights reserved.
-# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+# 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
diff --git a/nuttx/configs/olimex-lpc1766stk/hidkbd/ld.script b/nuttx/configs/olimex-lpc1766stk/hidkbd/ld.script
index 0d497e7e5..c6c97d402 100755
--- a/nuttx/configs/olimex-lpc1766stk/hidkbd/ld.script
+++ b/nuttx/configs/olimex-lpc1766stk/hidkbd/ld.script
@@ -2,7 +2,7 @@
* configs/olimex-lpc1766stk/hidkbd/ld.script
*
* Copyright (C) 2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * 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
@@ -80,11 +80,11 @@ SECTIONS
*(.ARM.extab*)
} >sram
+ __exidx_start = ABSOLUTE(.);
.ARM.exidx : {
- __exidx_start = ABSOLUTE(.);
*(.ARM.exidx*)
- __exidx_end = ABSOLUTE(.);
} >sram
+ __exidx_end = ABSOLUTE(.);
.bss : { /* BSS */
_sbss = ABSOLUTE(.);
diff --git a/nuttx/configs/olimex-lpc1766stk/include/board.h b/nuttx/configs/olimex-lpc1766stk/include/board.h
index 33c44b885..de630b4bc 100755
--- a/nuttx/configs/olimex-lpc1766stk/include/board.h
+++ b/nuttx/configs/olimex-lpc1766stk/include/board.h
@@ -2,8 +2,8 @@
* configs/olimex-lpc1766stk/include/board.h
* include/arch/board/board.h
*
- * Copyright (C) 2010 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Copyright (C) 2010-2011 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
@@ -46,9 +46,7 @@
/************************************************************************************
* Definitions
************************************************************************************/
-
/* Clocking *************************************************************************/
-
/* NOTE: The following definitions require lpc17_syscon.h. It is not included here
* because the including C file may not have that file in its include path.
*/
@@ -130,7 +128,28 @@
#define ETH_MCFG_CLKSEL_DIV ETH_MCFG_CLKSEL_DIV20
/* LED definitions ******************************************************************/
+/* If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in
+ * any way. The following definitions are used to access individual LEDs.
+ *
+ * LED1 -- Connected to P1[25]
+ * LED2 -- Connected to P0[4]
+ */
+
+/* LED index values for use with lpc17_setled() */
+
+#define BOARD_LED1 0
+#define BOARD_LED2 1
+#define BOARD_NLEDS 2
+
+/* LED bits for use with lpc17_setleds() */
+#define BOARD_LED1_BIT (1 << BOARD_LED1)
+#define BOARD_LED2_BIT (1 << BOARD_LED2)
+
+/* If CONFIG_ARCH_LEDs is defined, then NuttX will control the 3 LEDs
+ * on board the Olimex LPC1766-STK. The following definitions
+ * describe how NuttX controls the LEDs:
+ */
/* LED1 LED2 */
#define LED_STARTED 0 /* OFF OFF = Still initializing */
#define LED_HEAPALLOCATE 0 /* OFF OFF = Still initializing */
@@ -142,6 +161,45 @@
#define LED_PANIC 2 /* N/C ON = Oops! We crashed. (flashing) */
#define LED_IDLE 3 /* OFF N/C = LPC17 in sleep mode (LED1 glowing) */
+/* Button definitions ***************************************************************/
+/* The LPC1766-STK supports several buttons. All will read "1" when open and "0"
+ * when closed
+ *
+ * BUT1 -- Connected to P0[23]
+ * BUT2 -- Connected to P2[13]
+ * WAKE-UP -- Connected to P2[12]
+ *
+ * And a Joystick
+ *
+ * CENTER -- Connected to P0[4]
+ * DOWN -- Connected to P2[1]
+ * LEFT -- Connected to P2[7]
+ * RIGHT -- Connected to P2[8]
+ * UP -- Connected to P2[0]
+ */
+
+#define BOARD_BUTTON_1 0
+#define BOARD_BUTTON_2 1
+#define BOARD_BUTTON_WAKEUP 2
+
+#define BOARD_JOYSTICK_CENTER 3
+#define BOARD_JOYSTICK_DOWN 4
+#define BOARD_JOYSTICK_LEFT 5
+#define BOARD_JOYSTICK_RIGHT 6
+#define BOARD_JOYSTICK_UP 7
+
+#define BOARD_NUM_BUTTONS 8
+
+#define BOARD_BUTTON_BUTTON1_BIT (1 << BOARD_BUTTON_1)
+#define BOARD_BUTTON_BUTTON2_BIT (1 << BOARD_BUTTON_2)
+#define BOARD_BUTTON_WAKEUP_BIT (1 << BOARD_BUTTON_WAKEUP)
+
+#define BOARD_JOYSTICK_CENTER_BIT (1 << BOARD_JOYSTICK_CENTER)
+#define BOARD_JOYSTICK_DOWN_BIT (1 << BOARD_JOYSTICK_DOWN)
+#define BOARD_JOYSTICK_LEFT_BIT (1 << BOARD_JOYSTICK_LEFT)
+#define BOARD_JOYSTICK_RIGHT_BIT (1 << BOARD_JOYSTICK_RIGHT)
+#define BOARD_JOYSTICK_UP_BIT (1 << BOARD_JOYSTICK_UP)
+
/* Alternate pin selections *********************************************************/
/* CAN1 GPIO PIN SIGNAL NAME
@@ -318,6 +376,22 @@ extern "C" {
EXTERN void lpc17_boardinitialize(void);
+/****************************************************************************
+ * Name: lpc17_ledinit and lpc17_setled
+ *
+ * Description:
+ * If CONFIG_ARCH_LEDS is defined, then NuttX will control the on-board
+ * LEDs. If CONFIG_ARCH_LEDS is not defined, then the following interfaces
+ * are available to control the LEDs from user applications.
+ *
+ ****************************************************************************/
+
+#ifndef CONFIG_ARCH_LEDS
+EXTERN void lpc17_ledinit(void);
+EXTERN void lpc17_setled(int led, bool ledon);
+EXTERN void lpc17_setleds(uint8_t ledset);
+#endif
+
#undef EXTERN
#if defined(__cplusplus)
}
diff --git a/nuttx/configs/olimex-lpc1766stk/nettest/ld.script b/nuttx/configs/olimex-lpc1766stk/nettest/ld.script
index af9113c81..cc05746ba 100755
--- a/nuttx/configs/olimex-lpc1766stk/nettest/ld.script
+++ b/nuttx/configs/olimex-lpc1766stk/nettest/ld.script
@@ -1,8 +1,8 @@
/****************************************************************************
* configs/olimex-lpc1766stk/nettest/ld.script
*
- * Copyright (C) 2010 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Copyright (C) 2010-2011 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
@@ -80,11 +80,11 @@ SECTIONS
*(.ARM.extab*)
} >sram
+ __exidx_start = ABSOLUTE(.);
.ARM.exidx : {
- __exidx_start = ABSOLUTE(.);
*(.ARM.exidx*)
- __exidx_end = ABSOLUTE(.);
} >sram
+ __exidx_end = ABSOLUTE(.);
.bss : { /* BSS */
_sbss = ABSOLUTE(.);
diff --git a/nuttx/configs/olimex-lpc1766stk/nsh/defconfig b/nuttx/configs/olimex-lpc1766stk/nsh/defconfig
index 89175c4fb..ba1e2133e 100755
--- a/nuttx/configs/olimex-lpc1766stk/nsh/defconfig
+++ b/nuttx/configs/olimex-lpc1766stk/nsh/defconfig
@@ -1,8 +1,8 @@
############################################################################
# configs/olimex-lpc1766stk/nsh/defconfig
#
-# Copyright (C) 2010 Gregory Nutt. All rights reserved.
-# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+# Copyright (C) 2010-2011 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
@@ -304,9 +304,6 @@ CONFIG_HAVE_LIBM=n
# CONFIG_SDCLONE_DISABLE. Disable cloning of all socket
# desciptors by task_create() when a new task is started. If
# set, all sockets will appear to be closed in the new task.
-# CONFIG_NXFLAT. Enable support for the NXFLAT binary format.
-# This format will support execution of NuttX binaries located
-# in a ROMFS filesystem (see examples/nxflat).
# CONFIG_SCHED_WORKQUEUE. Create a dedicated "worker" thread to
# handle delayed processing from interrupt handlers. This feature
# is required for some drivers but, if there are not complaints,
@@ -325,20 +322,23 @@ CONFIG_HAVE_LIBM=n
# thread. Default: CONFIG_IDLETHREAD_STACKSIZE.
# CONFIG_SIG_SIGWORK - The signal number that will be used to wake-up
# the worker thread. Default: 4
+# CONFIG_SCHED_WAITPID - Enable the waitpid() API
+# CONFIG_SCHED_ATEXIT - Enabled the atexit() API
#
#CONFIG_APPS_DIR=
CONFIG_DEBUG=n
CONFIG_DEBUG_VERBOSE=n
CONFIG_DEBUG_SYMBOLS=n
+CONFIG_DEBUG_NET=n
CONFIG_DEBUG_USB=n
CONFIG_MM_REGIONS=2
CONFIG_ARCH_LOWPUTC=y
CONFIG_RR_INTERVAL=200
CONFIG_SCHED_INSTRUMENTATION=n
CONFIG_TASK_NAME_SIZE=0
-CONFIG_START_YEAR=2010
-CONFIG_START_MONTH=11
-CONFIG_START_DAY=10
+CONFIG_START_YEAR=2011
+CONFIG_START_MONTH=12
+CONFIG_START_DAY=30
CONFIG_GREGORIAN_TIME=n
CONFIG_JULIAN_TIME=n
CONFIG_DEV_CONSOLE=y
@@ -355,6 +355,8 @@ CONFIG_SCHED_WORKPRIORITY=50
CONFIG_SCHED_WORKPERIOD=(50*1000)
CONFIG_SCHED_WORKSTACKSIZE=1024
CONFIG_SIG_SIGWORK=4
+CONFIG_SCHED_WAITPID=y
+CONFIG_SCHED_ATEXIT=n
#
# Settings for NXFLAT
@@ -562,7 +564,7 @@ CONFIG_NET_UDP_CHECKSUMS=y
CONFIG_NET_ICMP=y
CONFIG_NET_ICMP_PING=y
#CONFIG_NET_PINGADDRCONF=0
-CONFIG_NET_STATISTICS=y
+CONFIG_NET_STATISTICS=n
#CONFIG_NET_RECEIVE_WINDOW=
#CONFIG_NET_ARPTAB_SIZE=8
CONFIG_NET_BROADCAST=n
@@ -788,6 +790,9 @@ CONFIG_EXAMPLES_OSTEST_NBARRIER_THREADS=3
#
# Settings for apps/nshlib
#
+# CONFIG_NSH_BUILTIN_APPS - Support external registered,
+# "named" applications that can be executed from the NSH
+# command line (see apps/README.txt for more information).
# CONFIG_NSH_FILEIOSIZE - Size of a static I/O buffer
# CONFIG_NSH_STRERROR - Use strerror(errno)
# CONFIG_NSH_LINELEN - Maximum length of one command line
@@ -819,6 +824,7 @@ CONFIG_EXAMPLES_OSTEST_NBARRIER_THREADS=3
# CONFIG_NSH_FATNSECTORS - FAT FS number of sectors
# CONFIG_NSH_FATMOUNTPT - FAT FS mountpoint
#
+CONFIG_NSH_BUILTIN_APPS=y
CONFIG_NSH_FILEIOSIZE=512
CONFIG_NSH_STRERROR=n
CONFIG_NSH_LINELEN=64
diff --git a/nuttx/configs/olimex-lpc1766stk/nsh/ld.script b/nuttx/configs/olimex-lpc1766stk/nsh/ld.script
index f3b023bdd..5f6adbecd 100755
--- a/nuttx/configs/olimex-lpc1766stk/nsh/ld.script
+++ b/nuttx/configs/olimex-lpc1766stk/nsh/ld.script
@@ -2,7 +2,7 @@
* configs/olimex-lpc1766stk/nsh/ld.script
*
* Copyright (C) 2010 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * 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
@@ -80,11 +80,11 @@ SECTIONS
*(.ARM.extab*)
} >sram
+ __exidx_start = ABSOLUTE(.);
.ARM.exidx : {
- __exidx_start = ABSOLUTE(.);
*(.ARM.exidx*)
- __exidx_end = ABSOLUTE(.);
} >sram
+ __exidx_end = ABSOLUTE(.);
.bss : { /* BSS */
_sbss = ABSOLUTE(.);
diff --git a/nuttx/configs/olimex-lpc1766stk/nx/ld.script b/nuttx/configs/olimex-lpc1766stk/nx/ld.script
index 3981dd3ac..a4ad7e35b 100755
--- a/nuttx/configs/olimex-lpc1766stk/nx/ld.script
+++ b/nuttx/configs/olimex-lpc1766stk/nx/ld.script
@@ -1,8 +1,8 @@
/****************************************************************************
* configs/olimex-lpc1766stk/nx/ld.script
*
- * Copyright (C) 2010 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Copyright (C) 2010-2011 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
@@ -80,11 +80,11 @@ SECTIONS
*(.ARM.extab*)
} >sram
+ __exidx_start = ABSOLUTE(.);
.ARM.exidx : {
- __exidx_start = ABSOLUTE(.);
*(.ARM.exidx*)
- __exidx_end = ABSOLUTE(.);
} >sram
+ __exidx_end = ABSOLUTE(.);
.bss : { /* BSS */
_sbss = ABSOLUTE(.);
diff --git a/nuttx/configs/olimex-lpc1766stk/ostest/ld.script b/nuttx/configs/olimex-lpc1766stk/ostest/ld.script
index 10300e929..323f1ec1d 100755
--- a/nuttx/configs/olimex-lpc1766stk/ostest/ld.script
+++ b/nuttx/configs/olimex-lpc1766stk/ostest/ld.script
@@ -1,8 +1,8 @@
/****************************************************************************
* configs/olimex-lpc1766stk/ostest/ld.script
*
- * Copyright (C) 2010 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Copyright (C) 2010-2011 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
@@ -80,11 +80,11 @@ SECTIONS
*(.ARM.extab*)
} >sram
+ __exidx_start = ABSOLUTE(.);
.ARM.exidx : {
- __exidx_start = ABSOLUTE(.);
*(.ARM.exidx*)
- __exidx_end = ABSOLUTE(.);
} >sram
+ __exidx_end = ABSOLUTE(.);
.bss : { /* BSS */
_sbss = ABSOLUTE(.);
diff --git a/nuttx/configs/olimex-lpc1766stk/slip-httpd/defconfig b/nuttx/configs/olimex-lpc1766stk/slip-httpd/defconfig
index 641572163..55aca7aec 100755
--- a/nuttx/configs/olimex-lpc1766stk/slip-httpd/defconfig
+++ b/nuttx/configs/olimex-lpc1766stk/slip-httpd/defconfig
@@ -2,7 +2,7 @@
# configs/olimex-lpc1766stk/slip-httpd/defconfig
#
# Copyright (C) 2011 Gregory Nutt. All rights reserved.
-# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+# 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
diff --git a/nuttx/configs/olimex-lpc1766stk/slip-httpd/ld.script b/nuttx/configs/olimex-lpc1766stk/slip-httpd/ld.script
index ed46b49a7..43d2662c8 100755
--- a/nuttx/configs/olimex-lpc1766stk/slip-httpd/ld.script
+++ b/nuttx/configs/olimex-lpc1766stk/slip-httpd/ld.script
@@ -2,7 +2,7 @@
* configs/olimex-lpc1766stk/slip-httpd/ld.script
*
* Copyright (C) 2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * 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
@@ -80,11 +80,11 @@ SECTIONS
*(.ARM.extab*)
} >sram
+ __exidx_start = ABSOLUTE(.);
.ARM.exidx : {
- __exidx_start = ABSOLUTE(.);
*(.ARM.exidx*)
- __exidx_end = ABSOLUTE(.);
} >sram
+ __exidx_end = ABSOLUTE(.);
.bss : { /* BSS */
_sbss = ABSOLUTE(.);
diff --git a/nuttx/configs/olimex-lpc1766stk/src/Makefile b/nuttx/configs/olimex-lpc1766stk/src/Makefile
index 70f57f4ac..981a4b4df 100755
--- a/nuttx/configs/olimex-lpc1766stk/src/Makefile
+++ b/nuttx/configs/olimex-lpc1766stk/src/Makefile
@@ -2,7 +2,7 @@
# configs/olimex-lpc1766stk/src/Makefile
#
# Copyright (C) 2010 Gregory Nutt. All rights reserved.
-# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+# 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
diff --git a/nuttx/configs/olimex-lpc1766stk/src/lpc1766stk_internal.h b/nuttx/configs/olimex-lpc1766stk/src/lpc1766stk_internal.h
index 3d84f4bda..db9915eef 100755
--- a/nuttx/configs/olimex-lpc1766stk/src/lpc1766stk_internal.h
+++ b/nuttx/configs/olimex-lpc1766stk/src/lpc1766stk_internal.h
@@ -1,235 +1,235 @@
-/************************************************************************************
- * configs/olimex-lpc1766stk/src/lpc1766stk_internal.h
- * arch/arm/src/board/lpc1766stk_internal.n
- *
- * Copyright (C) 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_OLIMEX_LPC1766STK_SRC_LPC1766STK_INTERNAL_H
-#define _CONFIGS_OLIMEX_LPC1766STK_SRC_LPC1766STK_INTERNAL_H
-
-/************************************************************************************
- * Included Files
- ************************************************************************************/
-
-#include <nuttx/config.h>
-#include <nuttx/compiler.h>
-
-/************************************************************************************
- * Definitions
- ************************************************************************************/
-
-/* LPC1766-STK GPIO Pin Definitions *************************************************/
-/* Board GPIO Usage:
- *
- * GPIO PIN SIGNAL NAME
- * -------------------------------- ---- --------------
- * P0[0]/RD1/TXD3/SDA1 46 RD1
- * P0[1]/TD1/RXD3/SCL1 47 TD1
- * P0[2]/TXD0/AD0[7] 98 TXD0
- * P0[3]/RXD0/AD0[6] 99 RXD0
- * P0[4]/I2SRX_CLK/RD2/CAP2[0] 81 LED2/ACC IRQ
- * P0[5]/I2SRX_WS/TD2/CAP2[1] 80 CENTER
- * P0[6]/I2SRX_SDA/SSEL1/MAT2[0] 79 SSEL1
- * P0[7]/I2STX_CLK/SCK1/MAT2[1] 78 SCK1
- * P0[8]/I2STX_WS/MISO1/MAT2[2] 77 MISO1
- * P0[9]/I2STX_SDA/MOSI1/MAT2[3] 76 MOSI1
- * P0[10]/TXD2/SDA2/MAT3[0] 48 SDA2
- * P0[11]/RXD2/SCL2/MAT3[1] 49 SCL2
- * P0[15]/TXD1/SCK0/SCK 62 TXD1
- * P0[16]/RXD1/SSEL0/SSEL 63 RXD1
- * P0[17]/CTS1/MISO0/MISO 61 CTS1
- * P0[18]/DCD1/MOSI0/MOSI 60 DCD1
- * P0[19]/DSR1/SDA1 59 DSR1
- * P0[20]/DTR1/SCL1 58 DTR1
- * P0[21]/RI1/RD1 57 MMC PWR
- * P0[22]/RTS1/TD1 56 RTS1
- * P0[23]/AD0[0]/I2SRX_CLK/CAP3[0] 9 BUT1
- * P0[24]/AD0[1]/I2SRX_WS/CAP3[1] 8 TEMP
- * P0[25]/AD0[2]/I2SRX_SDA/TXD3 7 MIC IN
- * P0[26]/AD0[3]/AOUT/RXD3 6 AOUT
- * P0[27]/SDA0/USB_SDA 25 USB_SDA
- * P0[28]/SCL0/USB_SCL 24 USB_SCL
- * P0[29]/USB_D+ 29 USB_D+
- * P0[30]/USB_D- 30 USB_D-
- * P1[0]/ENET_TXD0 95 E_TXD0
- * P1[1]/ENET_TXD1 94 E_TXD1
- * P1[4]/ENET_TX_EN 93 E_TX_EN
- * P1[8]/ENET_CRS 92 E_CRS
- * P1[9]/ENET_RXD0 91 E_RXD0
- * P1[10]/ENET_RXD1 90 E_RXD1
- * P1[14]/ENET_RX_ER 89 E_RX_ER
- * P1[15]/ENET_REF_CLK 88 E_REF_CLK
- * P1[16]/ENET_MDC 87 E_MDC
- * P1[17]/ENET_MDIO 86 E_MDIO
- * P1[18]/USB_UP_LED/PWM1[1]/CAP1[0] 32 USB_UP_LED
- * P1[19]/MC0A/#USB_PPWR/CAP1[1] 33 #USB_PPWR
- * P1[20]/MCFB0/PWM1[2]/SCK0 34 SCK0
- * P1[21]/MCABORT/PWM1[3]/SSEL0 35 SSEL0
- * P1[22]/MC0B/USB_PWRD/MAT1[0] 36 USBH_PWRD
- * P1[23]/MCFB1/PWM1[4]/MISO0 37 MISO0
- * P1[24]/MCFB2/PWM1[5]/MOSI0 38 MOSI0
- * P1[25]/MC1A/MAT1[1] 39 LED1
- * P1[26]/MC1B/PWM1[6]/CAP0[0] 40 CS_UEXT
- * P1[27]/CLKOUT/#USB_OVRCR/CAP0[1] 43 #USB_OVRCR
- * P1[28]/MC2A/PCAP1[0]/MAT0[0] 44 P1.28
- * P1[29]/MC2B/PCAP1[1]/MAT0[1] 45 P1.29
- * P1[30]/VBUS/AD0[4] 21 VBUS
- * P1[31]/SCK1/AD0[5] 20 AIN5
- * P2[0]/PWM1[1]/TXD1 75 UP
- * P2[1]/PWM1[2]/RXD1 74 DOWN
- * P2[2]/PWM1[3]/CTS1/TRACEDATA[3] 73 TRACE_D3
- * P2[3]/PWM1[4]/DCD1/TRACEDATA[2] 70 TRACE_D2
- * P2[4]/PWM1[5]/DSR1/TRACEDATA[1] 69 TRACE_D1
- * P2[5]/PWM1[6]/DTR1/TRACEDATA[0] 68 TRACE_D0
- * P2[6]/PCAP1[0]/RI1/TRACECLK 67 TRACE_CLK
- * P2[7]/RD2/RTS1 66 LEFT
- * P2[8]/TD2/TXD2 65 RIGHT
- * P2[9]/USB_CONNECT/RXD2 64 USBD_CONNECT
- * P2[10]/#EINT0/NMI 53 ISP_E4
- * P2[11]/#EINT1/I2STX_CLK 52 #EINT1
- * P2[12]/#EINT2/I2STX_WS 51 WAKE-UP
- * P2[13]/#EINT3/I2STX_SDA 50 BUT2
- * P3[25]/MAT0[0]/PWM1[2] 27 LCD_RST
- * P3[26]/STCLK/MAT0[1]/PWM1[3] 26 LCD_BL
- */
-
-/* LEDs GPIO PIN SIGNAL NAME
- * -------------------------------- ---- --------------
- * P1[25]/MC1A/MAT1[1] 39 LED1
- * P0[4]/I2SRX_CLK/RD2/CAP2[0] 81 LED2/ACC IRQ
- */
-
-#define LPC1766STK_LED1 (GPIO_OUTPUT | GPIO_VALUE_ZERO | GPIO_PORT1 | GPIO_PIN25)
-#define LPC1766STK_LED2 (GPIO_OUTPUT | GPIO_VALUE_ZERO | GPIO_PORT0 | GPIO_PIN4)
-
-/* Buttons GPIO PIN SIGNAL NAME
- * -------------------------------- ---- --------------
- * P2[12]/#EINT2/I2STX_WS 51 WAKE-UP
- * P0[23]/AD0[0]/I2SRX_CLK/CAP3[0] 9 BUT1
- * P2[13]/#EINT3/I2STX_SDA 50 BUT2
- */
-
-#define LPC1766STK_WAKE_UP (GPIO_INPUT | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN12)
-#define LPC1766STK_BUT1 (GPIO_INPUT | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN23)
-#define LPC1766STK_BUT2 (GPIO_INPUT | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN13)
-
-/* Joystick GPIO PIN SIGNAL NAME
- * -------------------------------- ---- --------------
- * P0[5]/I2SRX_WS/TD2/CAP2[1] 80 CENTER
- * P2[0]/PWM1[1]/TXD1 75 UP
- * P2[1]/PWM1[2]/RXD1 74 DOWN
- * P2[7]/RD2/RTS1 66 LEFT
- * P2[8]/TD2/TXD2 65 RIGHT
- */
-
-#define LPC1766STK_CENTER (GPIO_INPUT | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN5)
-#define LPC1766STK_UP (GPIO_INPUT | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN0)
-#define LPC1766STK_DOWN (GPIO_INPUT | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN1)
-#define LPC1766STK_LEFT (GPIO_INPUT | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN7)
-#define LPC1766STK_RIGHT (GPIO_INPUT | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN8)
-
-/* Nokia LCD GPIO PIN SIGNAL NAME
- * -------------------------------- ---- --------------
- * P1[21]/MCABORT/PWM1[3]/SSEL0 35 SSEL0
- * P1[20]/MCFB0/PWM1[2]/SCK0 34 SCK0
- * P1[23]/MCFB1/PWM1[4]/MISO0 37 MISO0
- * P1[24]/MCFB2/PWM1[5]/MOSI0 38 MOSI0
- * P3[25]/MAT0[0]/PWM1[2] 27 LCD_RST
- * P3[26]/STCLK/MAT0[1]/PWM1[3] 26 LCD_BL (PWM1)
- */
-
-#define LPC1766STK_LCD_CS (GPIO_OUTPUT | GPIO_VALUE_ONE | GPIO_PORT1 | GPIO_PIN21)
-#define LPC1766STK_LCD_RST (GPIO_OUTPUT | GPIO_VALUE_ZERO | GPIO_PORT3 | GPIO_PIN25)
-#define LPC1766STK_LCD_BL GPIO_PWM1p3_3
-#define GPIO_PWM1p3 GPIO_PWM1p3_3
-
-/* SD/MMC GPIO PIN SIGNAL NAME
- * -------------------------------- ---- --------------
- * P0[6]/I2SRX_SDA/SSEL1/MAT2[0] 79 SSEL1 (active low)
- * P0[7]/I2STX_CLK/SCK1/MAT2[1] 78 SCK1
- * P0[8]/I2STX_WS/MISO1/MAT2[2] 77 MISO1
- * P0[9]/I2STX_SDA/MOSI1/MAT2[3] 76 MOSI1
- * P0[21]/RI1/RD1 57 MMC PWR (active low)
- */
-
-#define LPC1766STK_MMC_CS (GPIO_OUTPUT | GPIO_VALUE_ONE | GPIO_PORT0 | GPIO_PIN6)
-#define LPC1766STK_MMC_PWR (GPIO_OUTPUT | GPIO_VALUE_ONE | GPIO_PORT0 | GPIO_PIN21)
-
-/* AD GPIO PIN SIGNAL NAME
- * -------------------------------- ---- --------------
- * P0[24]/AD0[1]/I2SRX_WS/CAP3[1] 8 TEMP
- * P0[25]/AD0[2]/I2SRX_SDA/TXD3 7 MIC IN
- */
-
-#define LPC1766STK_TEMP GPIO_AD0p1
-#define LPC1766STK_MIC_IN GPIO_AD0p2
-
-/* UEXT GPIO PIN SIGNAL NAME
- * -------------------------------- ---- --------------
- * P1[26]/MC1B/PWM1[6]/CAP0[0] 40 CS_UEXT
- */
-
-#define LPC1766STK_CS_UEXT (GPIO_OUTPUT | GPIO_VALUE_ONE | GPIO_PORT1 | GPIO_PIN26)
-
-/* ISP? GPIO PIN SIGNAL NAME
- * -------------------------------- ---- --------------
- * P2[10]/#EINT0/NMI 53 ISP_E4
- */
-
-/************************************************************************************
- * Public Types
- ************************************************************************************/
-
-/************************************************************************************
- * Public data
- ************************************************************************************/
-
-#ifndef __ASSEMBLY__
-
-/************************************************************************************
- * Public Functions
- ************************************************************************************/
-
-/************************************************************************************
- * Name: lpc17_sspinitialize
- *
- * Description:
- * Called to configure SPI chip select GPIO pins for the Olimex LPC1766-STK board.
- *
- ************************************************************************************/
-
-extern void weak_function lpc17_sspinitialize(void);
-
-#endif /* __ASSEMBLY__ */
-#endif /* _CONFIGS_OLIMEX_LPC1766STK_SRC_LPC1766STK_INTERNAL_H */
-
+/************************************************************************************
+ * configs/olimex-lpc1766stk/src/lpc1766stk_internal.h
+ * arch/arm/src/board/lpc1766stk_internal.n
+ *
+ * Copyright (C) 2010 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.
+ *
+ ************************************************************************************/
+
+#ifndef _CONFIGS_OLIMEX_LPC1766STK_SRC_LPC1766STK_INTERNAL_H
+#define _CONFIGS_OLIMEX_LPC1766STK_SRC_LPC1766STK_INTERNAL_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+#include <nuttx/compiler.h>
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+
+/* LPC1766-STK GPIO Pin Definitions *************************************************/
+/* Board GPIO Usage:
+ *
+ * GPIO PIN SIGNAL NAME
+ * -------------------------------- ---- --------------
+ * P0[0]/RD1/TXD3/SDA1 46 RD1
+ * P0[1]/TD1/RXD3/SCL1 47 TD1
+ * P0[2]/TXD0/AD0[7] 98 TXD0
+ * P0[3]/RXD0/AD0[6] 99 RXD0
+ * P0[4]/I2SRX_CLK/RD2/CAP2[0] 81 LED2/ACC IRQ
+ * P0[5]/I2SRX_WS/TD2/CAP2[1] 80 CENTER
+ * P0[6]/I2SRX_SDA/SSEL1/MAT2[0] 79 SSEL1
+ * P0[7]/I2STX_CLK/SCK1/MAT2[1] 78 SCK1
+ * P0[8]/I2STX_WS/MISO1/MAT2[2] 77 MISO1
+ * P0[9]/I2STX_SDA/MOSI1/MAT2[3] 76 MOSI1
+ * P0[10]/TXD2/SDA2/MAT3[0] 48 SDA2
+ * P0[11]/RXD2/SCL2/MAT3[1] 49 SCL2
+ * P0[15]/TXD1/SCK0/SCK 62 TXD1
+ * P0[16]/RXD1/SSEL0/SSEL 63 RXD1
+ * P0[17]/CTS1/MISO0/MISO 61 CTS1
+ * P0[18]/DCD1/MOSI0/MOSI 60 DCD1
+ * P0[19]/DSR1/SDA1 59 DSR1
+ * P0[20]/DTR1/SCL1 58 DTR1
+ * P0[21]/RI1/RD1 57 MMC PWR
+ * P0[22]/RTS1/TD1 56 RTS1
+ * P0[23]/AD0[0]/I2SRX_CLK/CAP3[0] 9 BUT1
+ * P0[24]/AD0[1]/I2SRX_WS/CAP3[1] 8 TEMP
+ * P0[25]/AD0[2]/I2SRX_SDA/TXD3 7 MIC IN
+ * P0[26]/AD0[3]/AOUT/RXD3 6 AOUT
+ * P0[27]/SDA0/USB_SDA 25 USB_SDA
+ * P0[28]/SCL0/USB_SCL 24 USB_SCL
+ * P0[29]/USB_D+ 29 USB_D+
+ * P0[30]/USB_D- 30 USB_D-
+ * P1[0]/ENET_TXD0 95 E_TXD0
+ * P1[1]/ENET_TXD1 94 E_TXD1
+ * P1[4]/ENET_TX_EN 93 E_TX_EN
+ * P1[8]/ENET_CRS 92 E_CRS
+ * P1[9]/ENET_RXD0 91 E_RXD0
+ * P1[10]/ENET_RXD1 90 E_RXD1
+ * P1[14]/ENET_RX_ER 89 E_RX_ER
+ * P1[15]/ENET_REF_CLK 88 E_REF_CLK
+ * P1[16]/ENET_MDC 87 E_MDC
+ * P1[17]/ENET_MDIO 86 E_MDIO
+ * P1[18]/USB_UP_LED/PWM1[1]/CAP1[0] 32 USB_UP_LED
+ * P1[19]/MC0A/#USB_PPWR/CAP1[1] 33 #USB_PPWR
+ * P1[20]/MCFB0/PWM1[2]/SCK0 34 SCK0
+ * P1[21]/MCABORT/PWM1[3]/SSEL0 35 SSEL0
+ * P1[22]/MC0B/USB_PWRD/MAT1[0] 36 USBH_PWRD
+ * P1[23]/MCFB1/PWM1[4]/MISO0 37 MISO0
+ * P1[24]/MCFB2/PWM1[5]/MOSI0 38 MOSI0
+ * P1[25]/MC1A/MAT1[1] 39 LED1
+ * P1[26]/MC1B/PWM1[6]/CAP0[0] 40 CS_UEXT
+ * P1[27]/CLKOUT/#USB_OVRCR/CAP0[1] 43 #USB_OVRCR
+ * P1[28]/MC2A/PCAP1[0]/MAT0[0] 44 P1.28
+ * P1[29]/MC2B/PCAP1[1]/MAT0[1] 45 P1.29
+ * P1[30]/VBUS/AD0[4] 21 VBUS
+ * P1[31]/SCK1/AD0[5] 20 AIN5
+ * P2[0]/PWM1[1]/TXD1 75 UP
+ * P2[1]/PWM1[2]/RXD1 74 DOWN
+ * P2[2]/PWM1[3]/CTS1/TRACEDATA[3] 73 TRACE_D3
+ * P2[3]/PWM1[4]/DCD1/TRACEDATA[2] 70 TRACE_D2
+ * P2[4]/PWM1[5]/DSR1/TRACEDATA[1] 69 TRACE_D1
+ * P2[5]/PWM1[6]/DTR1/TRACEDATA[0] 68 TRACE_D0
+ * P2[6]/PCAP1[0]/RI1/TRACECLK 67 TRACE_CLK
+ * P2[7]/RD2/RTS1 66 LEFT
+ * P2[8]/TD2/TXD2 65 RIGHT
+ * P2[9]/USB_CONNECT/RXD2 64 USBD_CONNECT
+ * P2[10]/#EINT0/NMI 53 ISP_E4
+ * P2[11]/#EINT1/I2STX_CLK 52 #EINT1
+ * P2[12]/#EINT2/I2STX_WS 51 WAKE-UP
+ * P2[13]/#EINT3/I2STX_SDA 50 BUT2
+ * P3[25]/MAT0[0]/PWM1[2] 27 LCD_RST
+ * P3[26]/STCLK/MAT0[1]/PWM1[3] 26 LCD_BL
+ */
+
+/* LEDs GPIO PIN SIGNAL NAME
+ * -------------------------------- ---- --------------
+ * P1[25]/MC1A/MAT1[1] 39 LED1
+ * P0[4]/I2SRX_CLK/RD2/CAP2[0] 81 LED2/ACC IRQ
+ */
+
+#define LPC1766STK_LED1 (GPIO_OUTPUT | GPIO_VALUE_ZERO | GPIO_PORT1 | GPIO_PIN25)
+#define LPC1766STK_LED2 (GPIO_OUTPUT | GPIO_VALUE_ZERO | GPIO_PORT0 | GPIO_PIN4)
+
+/* Buttons GPIO PIN SIGNAL NAME
+ * -------------------------------- ---- --------------
+ * P2[12]/#EINT2/I2STX_WS 51 WAKE-UP
+ * P0[23]/AD0[0]/I2SRX_CLK/CAP3[0] 9 BUT1
+ * P2[13]/#EINT3/I2STX_SDA 50 BUT2
+ */
+
+#define LPC1766STK_WAKE_UP (GPIO_INPUT | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN12)
+#define LPC1766STK_BUT1 (GPIO_INPUT | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN23)
+#define LPC1766STK_BUT2 (GPIO_INPUT | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN13)
+
+/* Joystick GPIO PIN SIGNAL NAME
+ * -------------------------------- ---- --------------
+ * P0[5]/I2SRX_WS/TD2/CAP2[1] 80 CENTER
+ * P2[0]/PWM1[1]/TXD1 75 UP
+ * P2[1]/PWM1[2]/RXD1 74 DOWN
+ * P2[7]/RD2/RTS1 66 LEFT
+ * P2[8]/TD2/TXD2 65 RIGHT
+ */
+
+#define LPC1766STK_CENTER (GPIO_INPUT | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN5)
+#define LPC1766STK_UP (GPIO_INPUT | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN0)
+#define LPC1766STK_DOWN (GPIO_INPUT | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN1)
+#define LPC1766STK_LEFT (GPIO_INPUT | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN7)
+#define LPC1766STK_RIGHT (GPIO_INPUT | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN8)
+
+/* Nokia LCD GPIO PIN SIGNAL NAME
+ * -------------------------------- ---- --------------
+ * P1[21]/MCABORT/PWM1[3]/SSEL0 35 SSEL0
+ * P1[20]/MCFB0/PWM1[2]/SCK0 34 SCK0
+ * P1[23]/MCFB1/PWM1[4]/MISO0 37 MISO0
+ * P1[24]/MCFB2/PWM1[5]/MOSI0 38 MOSI0
+ * P3[25]/MAT0[0]/PWM1[2] 27 LCD_RST
+ * P3[26]/STCLK/MAT0[1]/PWM1[3] 26 LCD_BL (PWM1)
+ */
+
+#define LPC1766STK_LCD_CS (GPIO_OUTPUT | GPIO_VALUE_ONE | GPIO_PORT1 | GPIO_PIN21)
+#define LPC1766STK_LCD_RST (GPIO_OUTPUT | GPIO_VALUE_ZERO | GPIO_PORT3 | GPIO_PIN25)
+#define LPC1766STK_LCD_BL GPIO_PWM1p3_3
+#define GPIO_PWM1p3 GPIO_PWM1p3_3
+
+/* SD/MMC GPIO PIN SIGNAL NAME
+ * -------------------------------- ---- --------------
+ * P0[6]/I2SRX_SDA/SSEL1/MAT2[0] 79 SSEL1 (active low)
+ * P0[7]/I2STX_CLK/SCK1/MAT2[1] 78 SCK1
+ * P0[8]/I2STX_WS/MISO1/MAT2[2] 77 MISO1
+ * P0[9]/I2STX_SDA/MOSI1/MAT2[3] 76 MOSI1
+ * P0[21]/RI1/RD1 57 MMC PWR (active low)
+ */
+
+#define LPC1766STK_MMC_CS (GPIO_OUTPUT | GPIO_VALUE_ONE | GPIO_PORT0 | GPIO_PIN6)
+#define LPC1766STK_MMC_PWR (GPIO_OUTPUT | GPIO_VALUE_ONE | GPIO_PORT0 | GPIO_PIN21)
+
+/* AD GPIO PIN SIGNAL NAME
+ * -------------------------------- ---- --------------
+ * P0[24]/AD0[1]/I2SRX_WS/CAP3[1] 8 TEMP
+ * P0[25]/AD0[2]/I2SRX_SDA/TXD3 7 MIC IN
+ */
+
+#define LPC1766STK_TEMP GPIO_AD0p1
+#define LPC1766STK_MIC_IN GPIO_AD0p2
+
+/* UEXT GPIO PIN SIGNAL NAME
+ * -------------------------------- ---- --------------
+ * P1[26]/MC1B/PWM1[6]/CAP0[0] 40 CS_UEXT
+ */
+
+#define LPC1766STK_CS_UEXT (GPIO_OUTPUT | GPIO_VALUE_ONE | GPIO_PORT1 | GPIO_PIN26)
+
+/* ISP? GPIO PIN SIGNAL NAME
+ * -------------------------------- ---- --------------
+ * P2[10]/#EINT0/NMI 53 ISP_E4
+ */
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public data
+ ************************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: lpc17_sspinitialize
+ *
+ * Description:
+ * Called to configure SPI chip select GPIO pins for the Olimex LPC1766-STK board.
+ *
+ ************************************************************************************/
+
+extern void weak_function lpc17_sspinitialize(void);
+
+#endif /* __ASSEMBLY__ */
+#endif /* _CONFIGS_OLIMEX_LPC1766STK_SRC_LPC1766STK_INTERNAL_H */
+
diff --git a/nuttx/configs/olimex-lpc1766stk/src/up_leds.c b/nuttx/configs/olimex-lpc1766stk/src/up_leds.c
index da23e18d3..088f04583 100755
--- a/nuttx/configs/olimex-lpc1766stk/src/up_leds.c
+++ b/nuttx/configs/olimex-lpc1766stk/src/up_leds.c
@@ -3,7 +3,7 @@
* arch/arm/src/board/up_leds.c
*
* Copyright (C) 2010-2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * 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
@@ -54,8 +54,6 @@
#include "lpc1766stk_internal.h"
-#ifdef CONFIG_ARCH_LEDS
-
/****************************************************************************
* Definitions
****************************************************************************/
@@ -92,7 +90,9 @@
* Private Data
****************************************************************************/
+#ifdef CONFIG_ARCH_LEDS
static bool g_uninitialized = true;
+#endif
/****************************************************************************
* Private Functions
@@ -118,9 +118,40 @@ void up_ledinit(void)
}
/****************************************************************************
+ * Name: lpc17_setled
+ ****************************************************************************/
+
+#ifndef CONFIG_ARCH_LEDS
+void lpc17_setled(int led, bool ledon)
+{
+ if (led == BOARD_LED1)
+ {
+ lpc17_gpiowrite(LPC1766STK_LED1, !ledon);
+ }
+ else if (led == BOARD_LED2)
+ {
+ lpc17_gpiowrite(LPC1766STK_LED2, !ledon);
+ }
+}
+#endif
+
+/****************************************************************************
+ * Name: lpc17_setleds
+ ****************************************************************************/
+
+#ifndef CONFIG_ARCH_LEDS
+void lpc17_setleds(uint8_t ledset)
+{
+ lpc17_gpiowrite(LPC1766STK_LED1, (ledset & BOARD_LED1_BIT) == 0);
+ lpc17_gpiowrite(LPC1766STK_LED2, (ledset & BOARD_LED2_BIT) == 0);
+}
+#endif
+
+/****************************************************************************
* Name: up_ledon
****************************************************************************/
+#ifdef CONFIG_ARCH_LEDS
void up_ledon(int led)
{
switch (led)
@@ -146,11 +177,13 @@ void up_ledon(int led)
break;
}
}
+#endif
/****************************************************************************
* Name: up_ledoff
****************************************************************************/
+#ifdef CONFIG_ARCH_LEDS
void up_ledoff(int led)
{
switch (led)
@@ -169,4 +202,4 @@ void up_ledoff(int led)
break;
}
}
-#endif /* CONFIG_ARCH_LEDS */
+#endif
diff --git a/nuttx/configs/olimex-lpc1766stk/src/up_nsh.c b/nuttx/configs/olimex-lpc1766stk/src/up_nsh.c
index df51c3cab..57789676c 100755
--- a/nuttx/configs/olimex-lpc1766stk/src/up_nsh.c
+++ b/nuttx/configs/olimex-lpc1766stk/src/up_nsh.c
@@ -3,7 +3,7 @@
* arch/arm/src/board/up_nsh.c
*
* Copyright (C) 2010 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * 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
diff --git a/nuttx/configs/olimex-lpc1766stk/thttpd/ld.script b/nuttx/configs/olimex-lpc1766stk/thttpd/ld.script
index 407a97dd2..9225b8da6 100755
--- a/nuttx/configs/olimex-lpc1766stk/thttpd/ld.script
+++ b/nuttx/configs/olimex-lpc1766stk/thttpd/ld.script
@@ -1,8 +1,8 @@
/****************************************************************************
* configs/olimex-lpc1766stk/thttpd/ld.script
*
- * Copyright (C) 2010 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Copyright (C) 2010-2011 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
@@ -80,11 +80,11 @@ SECTIONS
*(.ARM.extab*)
} >sram
+ __exidx_start = ABSOLUTE(.);
.ARM.exidx : {
- __exidx_start = ABSOLUTE(.);
*(.ARM.exidx*)
- __exidx_end = ABSOLUTE(.);
} >sram
+ __exidx_end = ABSOLUTE(.);
.bss : { /* BSS */
_sbss = ABSOLUTE(.);
diff --git a/nuttx/configs/olimex-lpc1766stk/usbserial/ld.script b/nuttx/configs/olimex-lpc1766stk/usbserial/ld.script
index 9cf8ddd70..26e03a20e 100755
--- a/nuttx/configs/olimex-lpc1766stk/usbserial/ld.script
+++ b/nuttx/configs/olimex-lpc1766stk/usbserial/ld.script
@@ -1,8 +1,8 @@
/****************************************************************************
* configs/olimex-lpc1766stk/usbserial/ld.script
*
- * Copyright (C) 2010 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Copyright (C) 2010-2011 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
@@ -80,11 +80,11 @@ SECTIONS
*(.ARM.extab*)
} >sram
+ __exidx_start = ABSOLUTE(.);
.ARM.exidx : {
- __exidx_start = ABSOLUTE(.);
*(.ARM.exidx*)
- __exidx_end = ABSOLUTE(.);
} >sram
+ __exidx_end = ABSOLUTE(.);
.bss : { /* BSS */
_sbss = ABSOLUTE(.);
diff --git a/nuttx/configs/olimex-lpc1766stk/usbstorage/ld.script b/nuttx/configs/olimex-lpc1766stk/usbstorage/ld.script
index 3f4b72f6f..8c81ff85a 100755
--- a/nuttx/configs/olimex-lpc1766stk/usbstorage/ld.script
+++ b/nuttx/configs/olimex-lpc1766stk/usbstorage/ld.script
@@ -1,8 +1,8 @@
/****************************************************************************
* configs/olimex-lpc1766stk/usbstorage/ld.script
*
- * Copyright (C) 2010 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Copyright (C) 2010-2011 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
@@ -80,11 +80,11 @@ SECTIONS
*(.ARM.extab*)
} >sram
+ __exidx_start = ABSOLUTE(.);
.ARM.exidx : {
- __exidx_start = ABSOLUTE(.);
*(.ARM.exidx*)
- __exidx_end = ABSOLUTE(.);
} >sram
+ __exidx_end = ABSOLUTE(.);
.bss : { /* BSS */
_sbss = ABSOLUTE(.);
diff --git a/nuttx/configs/olimex-lpc1766stk/wlan/ld.script b/nuttx/configs/olimex-lpc1766stk/wlan/ld.script
index 4677219cd..82fc20a44 100755
--- a/nuttx/configs/olimex-lpc1766stk/wlan/ld.script
+++ b/nuttx/configs/olimex-lpc1766stk/wlan/ld.script
@@ -2,7 +2,7 @@
* configs/olimex-lpc1766stk/wlan/ld.script
*
* Copyright (C) 2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * 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
@@ -80,11 +80,11 @@ SECTIONS
*(.ARM.extab*)
} >sram
+ __exidx_start = ABSOLUTE(.);
.ARM.exidx : {
- __exidx_start = ABSOLUTE(.);
*(.ARM.exidx*)
- __exidx_end = ABSOLUTE(.);
} >sram
+ __exidx_end = ABSOLUTE(.);
.bss : { /* BSS */
_sbss = ABSOLUTE(.);
diff --git a/nuttx/configs/stm3210e-eval/usbserial/defconfig b/nuttx/configs/stm3210e-eval/usbserial/defconfig
index be28df966..010889b31 100755
--- a/nuttx/configs/stm3210e-eval/usbserial/defconfig
+++ b/nuttx/configs/stm3210e-eval/usbserial/defconfig
@@ -917,7 +917,7 @@ CONFIG_EXAMPLES_USBSERIAL_TRACEINTERRUPTS=n
#
# Settings for examples/usbterm
#
-# CONFIG_EXAMPLES_UBSTERM_BUILTIN - Build the usbterm example as an NSH
+# CONFIG_EXAMPLES_USBTERM_BUILTIN - Build the usbterm example as an NSH
# built-in command. NOTE: This is not fully functional as of this
# writing.. It should work, but there is no mechanism in place yet
# to exit the USB terminal program and return to NSH.
@@ -934,7 +934,7 @@ CONFIG_EXAMPLES_USBSERIAL_TRACEINTERRUPTS=n
# CONFIG_EXAMPLES_USBTERM_TRACECONTROLLER - Show controller events
# CONFIG_EXAMPLES_USBTERM_TRACEINTERRUPTS - Show interrupt-related events
#
-CONFIG_EXAMPLES_UBSTERM_BUILTIN=n
+CONFIG_EXAMPLES_USBTERM_BUILTIN=n
CONFIG_EXAMPLES_USBTERM_BUFLEN=256
CONFIG_EXAMPLES_USBTERM_TRACEINIT=n
CONFIG_EXAMPLES_USBTERM_TRACECLASS=n