summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2014-02-09 15:56:20 -0600
committerGregory Nutt <gnutt@nuttx.org>2014-02-09 15:56:20 -0600
commita925412669b4be59758f12bfc6b24bdc77bb87b1 (patch)
tree601d0d88fa1e1ec55e4b1b62a6eeeb1d6cf0e50a
parenta77ae02c126a5337a321ffdce24f5fe823c3e8c3 (diff)
downloadnuttx-a925412669b4be59758f12bfc6b24bdc77bb87b1.tar.gz
nuttx-a925412669b4be59758f12bfc6b24bdc77bb87b1.tar.bz2
nuttx-a925412669b4be59758f12bfc6b24bdc77bb87b1.zip
Rename Olimex LPC1766-STK files to conform with current naming standards
-rw-r--r--nuttx/configs/olimex-lpc1766stk/src/lpc1766stk.h265
-rw-r--r--nuttx/configs/olimex-lpc1766stk/src/lpc17_boot.c92
-rw-r--r--nuttx/configs/olimex-lpc1766stk/src/lpc17_buttons.c228
-rw-r--r--nuttx/configs/olimex-lpc1766stk/src/lpc17_can.c144
-rw-r--r--nuttx/configs/olimex-lpc1766stk/src/lpc17_hidbkd.c71
-rw-r--r--nuttx/configs/olimex-lpc1766stk/src/lpc17_lcd.c264
-rw-r--r--nuttx/configs/olimex-lpc1766stk/src/lpc17_leds.c205
-rw-r--r--nuttx/configs/olimex-lpc1766stk/src/lpc17_nsh.c326
-rw-r--r--nuttx/configs/olimex-lpc1766stk/src/lpc17_ssp.c380
-rw-r--r--nuttx/configs/olimex-lpc1766stk/src/lpc17_usbmsc.c155
10 files changed, 2130 insertions, 0 deletions
diff --git a/nuttx/configs/olimex-lpc1766stk/src/lpc1766stk.h b/nuttx/configs/olimex-lpc1766stk/src/lpc1766stk.h
new file mode 100644
index 000000000..1c7dd41d7
--- /dev/null
+++ b/nuttx/configs/olimex-lpc1766stk/src/lpc1766stk.h
@@ -0,0 +1,265 @@
+/************************************************************************************
+ * configs/olimex-lpc1766stk/src/lpc1766stk.h
+ *
+ * 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
+ * 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
+ *
+ * LEDs are connected to +3.3V through a diode on one side and must be pulled
+ * low (through a resistor) on the LPC17xx side in order to illuminuate them.
+ */
+
+#define LPC1766STK_LED1 (GPIO_OUTPUT | GPIO_VALUE_ONE | GPIO_PORT1 | GPIO_PIN25)
+#define LPC1766STK_LED2 (GPIO_OUTPUT | GPIO_VALUE_ONE | GPIO_PORT0 | GPIO_PIN4)
+
+/* Buttons GPIO PIN SIGNAL NAME
+ * -------------------------------- ---- --------------
+ * P0[23]/AD0[0]/I2SRX_CLK/CAP3[0] 9 BUT1
+ * P2[13]/#EINT3/I2STX_SDA 50 BUT2
+ * P2[12]/#EINT2/I2STX_WS 51 WAKE-UP
+ *
+ * NOTES:
+ * 1. Pull-ups are not required because the pins are already pulled-up by
+ * through resistors on the board.
+ * 2. All buttons are capable of supporting interrupts if board_button_irq() is
+ * called to attach an interrupt handler. Interrupts are configured to
+ * occur on both edges.
+ */
+
+#define LPC1766STK_BUT1 (GPIO_INTBOTH | GPIO_FLOAT | GPIO_PORT0 | GPIO_PIN23)
+#define LPC1766STK_BUT2 (GPIO_INTBOTH | GPIO_FLOAT | GPIO_PORT2 | GPIO_PIN13)
+#define LPC1766STK_WAKEUP (GPIO_INTBOTH | GPIO_FLOAT | GPIO_PORT2 | GPIO_PIN12)
+
+/* Button IRQ numbers */
+
+#define LPC1766STK_BUT1_IRQ LPC17_IRQ_P0p23
+#define LPC1766STK_BUT2_IRQ LPC17_IRQ_P2p13
+#define LPC1766STK_WAKEUP_IRQ LPC17_IRQ_P2p12
+
+/* 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
+ *
+ * NOTES:
+ * 1. Pull-ups are not required because the pins are already pulled-up by
+ * through resistors on the board.
+ * 2. All buttons are capable of supporting interrupts if board_button_irq() is
+ * called to attach an interrupt handler. Interrupts are configured to
+ * occur on both edges.
+ */
+
+#define LPC1766STK_CENTER (GPIO_INTBOTH | GPIO_FLOAT | GPIO_PORT0 | GPIO_PIN5)
+#define LPC1766STK_UP (GPIO_INTBOTH | GPIO_FLOAT | GPIO_PORT2 | GPIO_PIN0)
+#define LPC1766STK_DOWN (GPIO_INTBOTH | GPIO_FLOAT | GPIO_PORT2 | GPIO_PIN1)
+#define LPC1766STK_LEFT (GPIO_INTBOTH | GPIO_FLOAT | GPIO_PORT2 | GPIO_PIN7)
+#define LPC1766STK_RIGHT (GPIO_INTBOTH | GPIO_FLOAT | GPIO_PORT2 | GPIO_PIN8)
+
+/* Joystick IRQ numbers */
+
+#define LPC1766STK_CENTER_IRQ LPC17_IRQ_P0p5
+#define LPC1766STK_UP_IRQ LPC17_IRQ_P2p0
+#define LPC1766STK_DOWN_IRQ LPC17_IRQ_P2p1
+#define LPC1766STK_LEFT_IRQ LPC17_IRQ_P2p7
+#define LPC1766STK_RIGHT_IRQ LPC17_IRQ_P2p8
+
+/* 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: lpc1766stk_sspinitialize
+ *
+ * Description:
+ * Called to configure SPI chip select GPIO pins for the Olimex LPC1766-STK board.
+ *
+ ************************************************************************************/
+
+void weak_function lpc1766stk_sspinitialize(void);
+
+#endif /* __ASSEMBLY__ */
+#endif /* _CONFIGS_OLIMEX_LPC1766STK_SRC_LPC1766STK_INTERNAL_H */
+
diff --git a/nuttx/configs/olimex-lpc1766stk/src/lpc17_boot.c b/nuttx/configs/olimex-lpc1766stk/src/lpc17_boot.c
new file mode 100644
index 000000000..ed5569695
--- /dev/null
+++ b/nuttx/configs/olimex-lpc1766stk/src/lpc17_boot.c
@@ -0,0 +1,92 @@
+/************************************************************************************
+ * configs/olimex-lpc1766stk/src/lpc17_boot.c
+ *
+ * Copyright (C) 2010, 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 <debug.h>
+
+#include <arch/board/board.h>
+
+#include "up_arch.h"
+#include "up_internal.h"
+
+#include "lpc17_ssp.h"
+#include "lpc1766stk.h"
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Private Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: lpc17_boardinitialize
+ *
+ * Description:
+ * All LPC17xx 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 lpc17_boardinitialize(void)
+{
+ /* Configure SSP chip selects if 1) at least one SSP is enabled, and 2) the weak
+ * function lpc1766stk_sspinitialize() has been brought into the link.
+ */
+
+#if defined(CONFIG_LPC17_SSP0) || defined(CONFIG_LPC17_SSP1)
+ if (lpc1766stk_sspinitialize)
+ {
+ lpc1766stk_sspinitialize();
+ }
+#endif
+
+ /* Configure on-board LEDs if LED support has been selected. */
+
+#ifdef CONFIG_ARCH_LEDS
+ board_led_initialize();
+#endif
+}
diff --git a/nuttx/configs/olimex-lpc1766stk/src/lpc17_buttons.c b/nuttx/configs/olimex-lpc1766stk/src/lpc17_buttons.c
new file mode 100644
index 000000000..1d4c2da12
--- /dev/null
+++ b/nuttx/configs/olimex-lpc1766stk/src/lpc17_buttons.c
@@ -0,0 +1,228 @@
+/****************************************************************************
+ * configs/olimex-lpc1766stk/src/lpc17_buttons.c
+ *
+ * Copyright (C) 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
+ * 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 <nuttx/arch.h>
+#include <nuttx/irq.h>
+
+#include <arch/board/board.h>
+
+#include "lpc17_gpio.h"
+#include "lpc1766stk.h"
+
+#ifdef CONFIG_ARCH_BUTTONS
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+/* Pin configuration for each STM3210E-EVAL button. This array is indexed by
+ * the BUTTON_* and JOYSTICK_* definitions in board.h
+ */
+
+static const uint16_t g_buttoncfg[BOARD_NUM_BUTTONS] =
+{
+ LPC1766STK_BUT1, LPC1766STK_BUT2, LPC1766STK_WAKEUP, LPC1766STK_CENTER,
+ LPC1766STK_UP, LPC1766STK_DOWN, LPC1766STK_LEFT, LPC1766STK_RIGHT
+};
+
+/* This array defines all of the interupt handlers current attached to
+ * button events.
+ */
+
+#if defined(CONFIG_ARCH_IRQBUTTONS) && defined(CONFIG_GPIO_IRQ)
+static xcpt_t g_buttonisr[BOARD_NUM_BUTTONS];
+
+/* This array provides the mapping from button ID numbers to button IRQ
+ * numbers.
+ */
+
+static uint8_t g_buttonirq[BOARD_NUM_BUTTONS] =
+{
+ LPC1766STK_BUT1_IRQ, LPC1766STK_BUT2_IRQ, LPC1766STK_WAKEUP_IRQ,
+ LPC1766STK_CENTER_IRQ, LPC1766STK_UP_IRQ, LPC1766STK_DOWN_IRQ,
+ LPC1766STK_LEFT_IRQ, LPC1766STK_RIGHT_IRQ
+};
+#endif
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: board_button_initialize
+ *
+ * Description:
+ * board_button_initialize() must be called to initialize button resources. After
+ * that, board_buttons() may be called to collect the current state of all
+ * buttons or board_button_irq() may be called to register button interrupt
+ * handlers.
+ *
+ ****************************************************************************/
+
+void board_button_initialize(void)
+{
+ int i;
+
+ /* Configure the GPIO pins as interrupting inputs. */
+
+ for (i = 0; i < BOARD_NUM_BUTTONS; i++)
+ {
+ lpc17_configgpio(g_buttoncfg[i]);
+ }
+}
+
+/****************************************************************************
+ * Name: board_buttons
+ *
+ * Description:
+ * board_button_initialize() must be called to initialize button resources. After
+ * that, board_buttons() may be called to collect the current state of all
+ * buttons.
+ *
+ * board_buttons() may be called at any time to harvest the state of every
+ * button. The state of the buttons is returned as a bitset with one
+ * bit corresponding to each button: If the bit is set, then the button
+ * is pressed. See the BOARD_BUTTON_*_BIT and BOARD_JOYSTICK_*_BIT
+ * definitions in board.h for the meaning of each bit.
+ *
+ ****************************************************************************/
+
+uint8_t board_buttons(void)
+{
+ uint8_t ret = 0;
+ int i;
+
+ /* Check that state of each key */
+
+ for (i = 0; i < BOARD_NUM_BUTTONS; i++)
+ {
+ /* A LOW value means that the key is pressed. */
+
+ bool released = lpc17_gpioread(g_buttoncfg[i]);
+
+ /* Accumulate the set of depressed (not released) keys */
+
+ if (!released)
+ {
+ ret |= (1 << i);
+ }
+ }
+
+ return ret;
+}
+
+/****************************************************************************
+ * Button support.
+ *
+ * Description:
+ * board_button_initialize() must be called to initialize button resources. After
+ * that, board_button_irq() may be called to register button interrupt handlers.
+ *
+ * board_button_irq() may be called to register an interrupt handler that will
+ * be called when a button is depressed or released. The ID value is a
+ * button enumeration value that uniquely identifies a button resource. See the
+ * BOARD_BUTTON_* and BOARD_JOYSTICK_* definitions in board.h for the meaning
+ * of enumeration values. The previous interrupt handler address is returned
+ * (so that it may restored, if so desired).
+ *
+ * Note that board_button_irq() also enables button interrupts. Button
+ * interrupts will remain enabled after the interrupt handler is attached.
+ * Interrupts may be disabled (and detached) by calling board_button_irq with
+ * irqhandler equal to NULL.
+ *
+ ****************************************************************************/
+
+#if defined(CONFIG_ARCH_IRQBUTTONS) && defined(CONFIG_GPIO_IRQ)
+xcpt_t board_button_irq(int id, xcpt_t irqhandler)
+{
+ xcpt_t oldhandler = NULL;
+ irqstate_t flags;
+ int irq;
+
+ /* Verify that the button ID is within range */
+
+ if ((unsigned)id < BOARD_NUM_BUTTONS)
+ {
+ /* Return the current button handler and set the new interrupt handler */
+
+ oldhandler = g_buttonisr[id];
+ g_buttonisr[id] = irqhandler;
+
+ /* Disable interrupts until we are done */
+
+ flags = irqsave();
+
+ /* Configure the interrupt. Either attach and enable the new
+ * interrupt or disable and detach the old interrupt handler.
+ */
+
+ irq = g_buttonirq[id];
+ if (irqhandler)
+ {
+ /* Attach then enable the new interrupt handler */
+
+ (void)irq_attach(irq, irqhandler);
+ up_enable_irq(irq);
+ }
+ else
+ {
+ /* Disable then detach the old interrupt handler */
+
+ up_disable_irq(irq);
+ (void)irq_detach(irq);
+ }
+ irqrestore(flags);
+ }
+ return oldhandler;
+}
+#endif
+
+#endif /* CONFIG_ARCH_BUTTONS */
diff --git a/nuttx/configs/olimex-lpc1766stk/src/lpc17_can.c b/nuttx/configs/olimex-lpc1766stk/src/lpc17_can.c
new file mode 100644
index 000000000..364696ed9
--- /dev/null
+++ b/nuttx/configs/olimex-lpc1766stk/src/lpc17_can.c
@@ -0,0 +1,144 @@
+/************************************************************************************
+ * configs/solimex-lpc1766stk/src/lpc17_can.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 <errno.h>
+#include <debug.h>
+
+#include <nuttx/can.h>
+#include <arch/board/board.h>
+
+#include "chip.h"
+#include "up_arch.h"
+
+#include "lpc17_can.h"
+#include "lpc1766stk.h"
+
+#if defined(CONFIG_CAN) && (defined(CONFIG_LPC17_CAN1) || defined(CONFIG_LPC17_CAN2))
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+/* Configuration ********************************************************************/
+
+#if defined(CONFIG_LPC17_CAN1) && defined(CONFIG_LPC17_CAN2)
+# warning "Both CAN1 and CAN2 are enabled. Assuming only CAN1."
+# undef CONFIG_LPC17_CAN2
+#endif
+
+#ifdef CONFIG_LPC17_CAN2
+# warning "CAN2 is not connected on the LPC1766-STK"
+#endif
+
+#ifdef CONFIG_LPC17_CAN1
+# define CAN_PORT 1
+#else
+# define CAN_PORT 2
+#endif
+
+/* Debug ***************************************************************************/
+/* Non-standard debug that may be enabled just for testing CAN */
+
+#ifdef CONFIG_DEBUG_CAN
+# define candbg dbg
+# define canvdbg vdbg
+# define canlldbg lldbg
+# define canllvdbg llvdbg
+#else
+# define candbg(x...)
+# define canvdbg(x...)
+# define canlldbg(x...)
+# define canllvdbg(x...)
+#endif
+
+/************************************************************************************
+ * Private Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: can_devinit
+ *
+ * Description:
+ * All LPC17 architectures must provide the following interface to work with
+ * examples/can.
+ *
+ ************************************************************************************/
+
+int can_devinit(void)
+{
+ static bool initialized = false;
+ struct can_dev_s *can;
+ int ret;
+
+ /* Check if we have already initialized */
+
+ if (!initialized)
+ {
+ /* Call lpc17_caninitialize() to get an instance of the CAN interface */
+
+ can = lpc17_caninitialize(CAN_PORT);
+ if (can == NULL)
+ {
+ candbg("ERROR: Failed to get CAN interface\n");
+ return -ENODEV;
+ }
+
+ /* Register the CAN driver at "/dev/can0" */
+
+ ret = can_register("/dev/can0", can);
+ if (ret < 0)
+ {
+ candbg("ERROR: can_register failed: %d\n", ret);
+ return ret;
+ }
+
+ /* Now we are initialized */
+
+ initialized = true;
+ }
+
+ return OK;
+}
+
+#endif /* CONFIG_CAN && (CONFIG_LPC17_CAN1 || CONFIG_LPC17_CAN2) */
diff --git a/nuttx/configs/olimex-lpc1766stk/src/lpc17_hidbkd.c b/nuttx/configs/olimex-lpc1766stk/src/lpc17_hidbkd.c
new file mode 100644
index 000000000..8b0feb66d
--- /dev/null
+++ b/nuttx/configs/olimex-lpc1766stk/src/lpc17_hidbkd.c
@@ -0,0 +1,71 @@
+/****************************************************************************
+ * configs/olimex-lpc1766stk/src/lpc17_hidkbd.c
+ *
+ * Copyright (C) 2013 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 <nuttx/usb/usbhost.h>
+
+#include "lpc17_usbhost.h"
+
+#if defined(CONFIG_LPC17_USBHOST) && defined(CONFIG_USBHOST) && \
+ defined(CONFIG_EXAMPLES_HIDKBD)
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: arch_usbhost_initialize
+ *
+ * Description:
+ * The apps/example/hidkbd test requires that platform-specific code
+ * provide a wrapper called arch_usbhost_initialize() that will perform
+ * the actual USB host initialization.
+ *
+ ****************************************************************************/
+
+struct usbhost_connection_s *arch_usbhost_initialize(void)
+{
+ return lpc17_usbhost_initialize(0);
+}
+#endif /* CONFIG_LPC17_USBHOST && CONFIG_USBHOST && CONFIG_EXAMPLES_HIDKBD */
diff --git a/nuttx/configs/olimex-lpc1766stk/src/lpc17_lcd.c b/nuttx/configs/olimex-lpc1766stk/src/lpc17_lcd.c
new file mode 100644
index 000000000..5f4740957
--- /dev/null
+++ b/nuttx/configs/olimex-lpc1766stk/src/lpc17_lcd.c
@@ -0,0 +1,264 @@
+/****************************************************************************
+ * config/olimex-lpc1766stk/src/lpc17_lcd.c
+ *
+ * Copyright (C) 2010, 2013 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
+ * POSSPBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdio.h>
+#include <debug.h>
+#include <errno.h>
+
+#include <nuttx/arch.h>
+#include <nuttx/spi/spi.h>
+#include <nuttx/lcd/lcd.h>
+#include <nuttx/lcd/nokia6100.h>
+
+#include "up_arch.h"
+#include "chip/lpc17_syscon.h"
+#include "chip/lpc17_pwm.h"
+#include "lpc17_gpio.h"
+#include "lpc1766stk.h"
+
+#if defined(CONFIG_NX_LCDDRIVER) && defined(CONFIG_LCD_NOKIA6100) && defined(CONFIG_LPC17_SSP0)
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+/* Check power setting */
+
+#if !defined(CONFIG_LCD_MAXPOWER) || CONFIG_LCD_MAXPOWER != 127
+# error "CONFIG_LCD_MAXPOWER must be 127"
+#endif
+
+/* Backlight OFF PWM setting */
+
+#define NOKIA_BACKLIGHT_OFF 0x40
+
+/* Define the CONFIG_LCD_NOKIADBG to enable detailed debug output (stuff you
+ * would never want to see unless you are debugging this file).
+ *
+ * Verbose debug must also be enabled
+ */
+
+#ifndef CONFIG_DEBUG
+# undef CONFIG_DEBUG_VERBOSE
+# undef CONFIG_DEBUG_GRAPHICS
+#endif
+
+#ifndef CONFIG_DEBUG_VERBOSE
+# undef CONFIG_LCD_NOKIADBG
+#endif
+
+#ifdef CONFIG_LCD_NOKIADBG
+# define lcddbg(format, arg...) vdbg(format, ##arg)
+# define lcd_dumpgpio(m) lpc17_dumpgpio(LPC1766STK_LCD_RST, m)
+#else
+# define lcddbg(x...)
+# define lcd_dumpgpio(m)
+#endif
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: nokia_blinitialize
+ *
+ * Description:
+ * Initialize PWM1 to manage the LCD backlight.
+ *
+ ****************************************************************************/
+
+void nokia_blinitialize(void)
+{
+ uint32_t regval;
+
+ /* Enable clocking of PWM1 */
+
+ regval = getreg32(LPC17_SYSCON_PCONP);
+ regval |= SYSCON_PCONP_PCPWM1;
+ putreg32(regval, LPC17_SYSCON_PCONP);
+
+ /* Disable and reset PWM1 */
+
+ regval = getreg32(LPC17_PWM1_TCR);
+ regval &= ~(PWM_TCR_PWMEN|PWM_TCR_CNTREN);
+ regval |= PWM_TCR_CNTRRST;
+ putreg32(regval, LPC17_PWM1_TCR);
+
+ /* Put PWM1 in timer mode */
+
+ regval = getreg32(LPC17_PWM1_CTCR);
+ regval &= ~PWM_CTCR_MODE_MASK;
+ regval |= PWM_CTCR_MODE_TIMER;
+ putreg32(regval, LPC17_PWM1_CTCR);
+
+ /* Reset on MR0 */
+
+ putreg32(PWM_MCR_MR0R, LPC17_PWM1_MCR);
+
+ /* Single edge controlled mod for PWM3 and enable output */
+
+ regval = getreg32(LPC17_PWM1_PCR);
+ regval &= ~PWM_PCR_SEL3;
+ regval |= PWM_PCR_ENA3;
+ putreg32(regval, LPC17_PWM1_PCR);
+
+ /* Clear prescaler */
+
+ putreg32(0, LPC17_PWM1_PR);
+
+ /* Set 8-bit resolution */
+
+ putreg32(0xff, LPC17_PWM1_MCR);
+
+ /* Enable PWM match 1 latch */
+
+ regval = getreg32(LPC17_PWM1_LER);
+ regval |= PWM_LER_M0EN;
+ putreg32(regval, LPC17_PWM1_LER);
+
+ /* Clear match register 3 */
+
+ putreg32(0, LPC17_PWM1_MR3);
+
+ /* Enable PWM1 */
+
+ regval |= PWM_LER_M3EN;
+ putreg32(regval, LPC17_PWM1_LER);
+
+ regval = getreg32(LPC17_PWM1_TCR);
+ regval &= ~(PWM_TCR_CNTRRST);
+ regval |= (PWM_TCR_PWMEN|PWM_TCR_CNTREN);
+ putreg32(regval, LPC17_PWM1_TCR);
+
+ nokia_backlight(0);
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_nxdrvinit
+ *
+ * Description:
+ * Called NX initialization logic to configure the LCD.
+ *
+ ****************************************************************************/
+
+FAR struct lcd_dev_s *up_nxdrvinit(unsigned int devno)
+{
+ FAR struct spi_dev_s *spi;
+ FAR struct lcd_dev_s *dev;
+
+ /* Configure the LCD GPIOs */
+
+ lcd_dumpgpio("up_nxdrvinit: On entry");
+ lpc17_configgpio(LPC1766STK_LCD_RST);
+ lpc17_configgpio(LPC1766STK_LCD_BL);
+ lcd_dumpgpio("up_nxdrvinit: After GPIO setup");
+
+ /* Reset the LCD */
+
+ lpc17_gpiowrite(LPC1766STK_LCD_RST, false);
+ up_udelay(10);
+ lpc17_gpiowrite(LPC1766STK_LCD_RST, true);
+ up_mdelay(5);
+
+ /* Configure PWM1 to support the backlight */
+
+ nokia_blinitialize();
+
+ /* Get the SSP0 port (configure as a Freescale SPI port) */
+
+ spi = lpc17_sspinitialize(0);
+ if (!spi)
+ {
+ glldbg("Failed to initialize SSP port 0\n");
+ }
+ else
+ {
+ /* Bind the SSP port to the LCD */
+
+ dev = nokia_lcdinitialize(spi, devno);
+ if (!dev)
+ {
+ glldbg("Failed to bind SSP port 0 to LCD %d: %d\n", devno);
+ }
+ else
+ {
+ gllvdbg("Bound SSP port 0 to LCD %d\n", devno);
+
+ /* And turn the LCD on (CONFIG_LCD_MAXPOWER should be 1) */
+
+ (void)dev->setpower(dev, CONFIG_LCD_MAXPOWER);
+ return dev;
+ }
+ }
+ return NULL;
+}
+
+/****************************************************************************
+ * Name: nokia_backlight
+ *
+ * Description:
+ * The Nokia 6100 backlight is controlled by logic outside of the LCD
+ * assembly. This function must be provided by board specific logic to
+ * manage the backlight. This function will receive a power value (0:
+ * full off - CONFIG_LCD_MAXPOWER: full on) and should set the backlight
+ * accordingly.
+ *
+ * On the Olimex LPC1766STK, the backlight level is controlled by PWM1.
+ *
+ ****************************************************************************/
+
+int nokia_backlight(unsigned int power)
+{
+ uint32_t regval;
+
+ putreg32(NOKIA_BACKLIGHT_OFF + power, LPC17_PWM1_MR3);
+
+ regval = getreg32(LPC17_PWM1_LER);
+ regval |= PWM_LER_M3EN;
+ putreg32(regval, LPC17_PWM1_LER);
+ return OK;
+}
+
+#endif /* CONFIG_NX_LCDDRIVER && CONFIG_LCD_NOKIA6100 && CONFIG_LPC17_SSP0 */
diff --git a/nuttx/configs/olimex-lpc1766stk/src/lpc17_leds.c b/nuttx/configs/olimex-lpc1766stk/src/lpc17_leds.c
new file mode 100644
index 000000000..a11b7be1e
--- /dev/null
+++ b/nuttx/configs/olimex-lpc1766stk/src/lpc17_leds.c
@@ -0,0 +1,205 @@
+/****************************************************************************
+ * configs/olimex-lpc1766stk/src/lpc17_leds.c
+ *
+ * Copyright (C) 2010-2011, 2013 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 "lpc17_gpio.h"
+
+#include "lpc1766stk.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/* CONFIG_DEBUG_LEDS enables debug output from this file (needs CONFIG_DEBUG
+ * with CONFIG_DEBUG_VERBOSE too)
+ */
+
+#ifdef CONFIG_DEBUG_LEDS
+# define leddbg lldbg
+# ifdef CONFIG_DEBUG_VERBOSE
+# define ledvdbg lldbg
+# else
+# define ledvdbg(x...)
+# endif
+#else
+# define leddbg(x...)
+# define ledvdbg(x...)
+#endif
+
+/* Dump GPIO registers */
+
+#if defined(CONFIG_DEBUG_VERBOSE) && defined(CONFIG_DEBUG_LEDS)
+# define led_dumpgpio(m) lpc17_dumpgpio(LPC1766STK_LED1, m)
+#else
+# define led_dumpgpio(m)
+#endif
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+#ifdef CONFIG_ARCH_LEDS
+static bool g_uninitialized = true;
+#endif
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: lpc17_ledinit/board_led_initialize
+ ****************************************************************************/
+
+#ifndef CONFIG_ARCH_LEDS
+void lpc17_ledinit(void) /* Name when invoked externally */
+#else
+void board_led_initialize(void) /* Name when invoked via lpc17_boot.c */
+#endif
+{
+ /* Configure all LED GPIO lines */
+
+ led_dumpgpio("board_led_initialize() Entry)");
+
+ lpc17_configgpio(LPC1766STK_LED1);
+ lpc17_configgpio(LPC1766STK_LED2);
+
+ led_dumpgpio("board_led_initialize() Exit");
+}
+
+/****************************************************************************
+ * 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: board_led_on
+ ****************************************************************************/
+
+#ifdef CONFIG_ARCH_LEDS
+void board_led_on(int led)
+{
+ switch (led)
+ {
+ default:
+ case 0 : /* STARTED, HEAPALLOCATE, IRQSENABLED */
+ lpc17_gpiowrite(LPC1766STK_LED1, true);
+ lpc17_gpiowrite(LPC1766STK_LED2, true);
+ break;
+
+ case 1 : /* STACKCREATED */
+ lpc17_gpiowrite(LPC1766STK_LED1, false);
+ lpc17_gpiowrite(LPC1766STK_LED2, true);
+ g_uninitialized = false;
+ break;
+
+ case 2 : /* INIRQ, SIGNAL, ASSERTION, PANIC */
+ lpc17_gpiowrite(LPC1766STK_LED2, false);
+ break;
+
+ case 3 : /* IDLE */
+ lpc17_gpiowrite(LPC1766STK_LED1, true);
+ break;
+ }
+}
+#endif
+
+/****************************************************************************
+ * Name: board_led_off
+ ****************************************************************************/
+
+#ifdef CONFIG_ARCH_LEDS
+void board_led_off(int led)
+{
+ switch (led)
+ {
+ default:
+ case 0 : /* STARTED, HEAPALLOCATE, IRQSENABLED */
+ case 1 : /* STACKCREATED */
+ lpc17_gpiowrite(LPC1766STK_LED1, true);
+
+ case 2 : /* INIRQ, SIGNAL, ASSERTION, PANIC */
+ lpc17_gpiowrite(LPC1766STK_LED2, true);
+ break;
+
+ case 3 : /* IDLE */
+ lpc17_gpiowrite(LPC1766STK_LED1, g_uninitialized);
+ break;
+ }
+}
+#endif
diff --git a/nuttx/configs/olimex-lpc1766stk/src/lpc17_nsh.c b/nuttx/configs/olimex-lpc1766stk/src/lpc17_nsh.c
new file mode 100644
index 000000000..205206c88
--- /dev/null
+++ b/nuttx/configs/olimex-lpc1766stk/src/lpc17_nsh.c
@@ -0,0 +1,326 @@
+/****************************************************************************
+ * config/olimex-lpc1766stk/src/lpc17_nsh.c
+ *
+ * Copyright (C) 2010, 2013-2014 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 <stdio.h>
+#include <unistd.h>
+#include <debug.h>
+#include <errno.h>
+
+#include <nuttx/spi/spi.h>
+#include <nuttx/mmcsd.h>
+#include <nuttx/usb/usbhost.h>
+
+#include "lpc17_ssp.h"
+#include "lpc17_gpio.h"
+#include "lpc17_usbhost.h"
+#include "lpc1766stk.h"
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+/* Configuration ************************************************************/
+
+#define NSH_HAVEMMCSD 1
+#define NSH_HAVEUSBHOST 1
+
+/* MMC/SD is on SSP port 1. There is only a single slot, slot 0 */
+
+#if !defined(CONFIG_NSH_MMCSDSPIPORTNO) || CONFIG_NSH_MMCSDSPIPORTNO != 1
+# undef CONFIG_NSH_MMCSDSPIPORTNO
+# define CONFIG_NSH_MMCSDSPIPORTNO 1
+#endif
+
+#if !defined(CONFIG_NSH_MMCSDSLOTNO) || CONFIG_NSH_MMCSDSLOTNO != 0
+# undef CONFIG_NSH_MMCSDSLOTNO
+# define CONFIG_NSH_MMCSDSLOTNO 0
+#endif
+
+/* Can't support MMC/SD is SSP1 is not enabled */
+
+#ifndef CONFIG_LPC17_SSP1
+# undef NSH_HAVEMMCSD
+#endif
+
+/* Can't support MMC/SD features if mountpoints are disabled */
+
+#if defined(CONFIG_DISABLE_MOUNTPOINT)
+# undef NSH_HAVEMMCSD
+#endif
+
+#ifndef CONFIG_NSH_MMCSDMINOR
+# define CONFIG_NSH_MMCSDMINOR 0
+#endif
+
+/* USB Host */
+
+#ifdef CONFIG_USBHOST
+# ifndef CONFIG_LPC17_USBHOST
+# error "CONFIG_LPC17_USBHOST is not selected"
+# endif
+#endif
+
+#ifdef CONFIG_LPC17_USBHOST
+# ifndef CONFIG_USBHOST
+# warning "CONFIG_USBHOST is not selected"
+# endif
+#endif
+
+#if !defined(CONFIG_USBHOST) || !defined(CONFIG_LPC17_USBHOST)
+# undef NSH_HAVEUSBHOST
+#endif
+
+#ifdef NSH_HAVEUSBHOST
+# ifndef CONFIG_USBHOST_DEFPRIO
+# define CONFIG_USBHOST_DEFPRIO 50
+# endif
+# ifndef CONFIG_USBHOST_STACKSIZE
+# define CONFIG_USBHOST_STACKSIZE 1024
+# endif
+#endif
+
+/* Debug ********************************************************************/
+
+#ifdef CONFIG_CPP_HAVE_VARARGS
+# ifdef CONFIG_DEBUG
+# define message(...) lowsyslog(__VA_ARGS__)
+# else
+# define message(...) printf(__VA_ARGS__)
+# endif
+#else
+# ifdef CONFIG_DEBUG
+# define message lowsyslog
+# else
+# define message printf
+# endif
+#endif
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+#ifdef NSH_HAVEUSBHOST
+static struct usbhost_connection_s *g_usbconn;
+#endif
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: nsh_waiter
+ *
+ * Description:
+ * Wait for USB devices to be connected.
+ *
+ ****************************************************************************/
+
+#ifdef NSH_HAVEUSBHOST
+static int nsh_waiter(int argc, char *argv[])
+{
+ bool connected = false;
+ int ret;
+
+ message("nsh_waiter: Running\n");
+ for (;;)
+ {
+ /* Wait for the device to change state */
+
+ ret = CONN_WAIT(g_usbconn, &connected);
+ DEBUGASSERT(ret == OK);
+
+ connected = !connected;
+ message("nsh_waiter: %s\n", connected ? "connected" : "disconnected");
+
+ /* Did we just become connected? */
+
+ if (connected)
+ {
+ /* Yes.. enumerate the newly connected device */
+
+ (void)CONN_ENUMERATE(g_usbconn, 0);
+ }
+ }
+
+ /* Keep the compiler from complaining */
+
+ return 0;
+}
+#endif
+
+/****************************************************************************
+ * Name: nsh_sdinitialize
+ *
+ * Description:
+ * Initialize SPI-based microSD.
+ *
+ ****************************************************************************/
+
+#ifdef NSH_HAVEMMCSD
+static int nsh_sdinitialize(void)
+{
+ FAR struct spi_dev_s *ssp;
+ int ret;
+
+ /* Enable power to the SD/MMC via a GPIO. LOW enables SD/MMC. */
+
+ lpc17_gpiowrite(LPC1766STK_MMC_PWR, false);
+
+ /* Get the SSP port */
+
+ ssp = lpc17_sspinitialize(CONFIG_NSH_MMCSDSPIPORTNO);
+ if (!ssp)
+ {
+ message("nsh_archinitialize: Failed to initialize SSP port %d\n",
+ CONFIG_NSH_MMCSDSPIPORTNO);
+ ret = -ENODEV;
+ goto errout;
+ }
+
+ message("Successfully initialized SSP port %d\n",
+ CONFIG_NSH_MMCSDSPIPORTNO);
+
+ /* Bind the SSP port to the slot */
+
+ ret = mmcsd_spislotinitialize(CONFIG_NSH_MMCSDMINOR,
+ CONFIG_NSH_MMCSDSLOTNO, ssp);
+ if (ret < 0)
+ {
+ message("nsh_sdinitialize: "
+ "Failed to bind SSP port %d to MMC/SD slot %d: %d\n",
+ CONFIG_NSH_MMCSDSPIPORTNO,
+ CONFIG_NSH_MMCSDSLOTNO, ret);
+ goto errout;
+ }
+
+ message("Successfuly bound SSP port %d to MMC/SD slot %d\n",
+ CONFIG_NSH_MMCSDSPIPORTNO,
+ CONFIG_NSH_MMCSDSLOTNO);
+ return OK;
+
+ /* Disable power to the SD/MMC via a GPIO. HIGH disables SD/MMC. */
+
+errout:
+ lpc17_gpiowrite(LPC1766STK_MMC_PWR, true);
+ return ret;
+}
+#else
+# define nsh_sdinitialize() (OK)
+#endif
+
+/****************************************************************************
+ * Name: nsh_usbhostinitialize
+ *
+ * Description:
+ * Initialize SPI-based microSD.
+ *
+ ****************************************************************************/
+
+#ifdef NSH_HAVEUSBHOST
+static int nsh_usbhostinitialize(void)
+{
+ int pid;
+ int ret;
+
+ /* First, register all of the class drivers needed to support the drivers
+ * that we care about:
+ */
+
+ message("nsh_usbhostinitialize: Register class drivers\n");
+ ret = usbhost_storageinit();
+ if (ret != OK)
+ {
+ message("nsh_usbhostinitialize: Failed to register the mass storage class\n");
+ }
+
+ /* Then get an instance of the USB host interface */
+
+ message("nsh_usbhostinitialize: Initialize USB host\n");
+ g_usbconn = lpc17_usbhost_initialize(0);
+ if (g_usbconn)
+ {
+ /* Start a thread to handle device connection. */
+
+ message("nsh_usbhostinitialize: Start nsh_waiter\n");
+
+#ifndef CONFIG_CUSTOM_STACK
+ pid = task_create("usbhost", CONFIG_USBHOST_DEFPRIO,
+ CONFIG_USBHOST_STACKSIZE,
+ (main_t)nsh_waiter, (FAR char * const *)NULL);
+#else
+ pid = task_create("usbhost", CONFIG_USBHOST_DEFPRIO,
+ (main_t)nsh_waiter, (FAR char * const *)NULL);
+#endif
+ return pid < 0 ? -ENOEXEC : OK;
+ }
+ return -ENODEV;
+}
+#else
+# define nsh_usbhostinitialize() (OK)
+#endif
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: nsh_archinitialize
+ *
+ * Description:
+ * Perform architecture specific initialization
+ *
+ ****************************************************************************/
+
+int nsh_archinitialize(void)
+{
+ int ret;
+
+ /* Initialize SPI-based microSD */
+
+ ret = nsh_sdinitialize();
+ if (ret == OK)
+ {
+ /* Initialize USB host */
+
+ ret = nsh_usbhostinitialize();
+ }
+ return ret;
+}
diff --git a/nuttx/configs/olimex-lpc1766stk/src/lpc17_ssp.c b/nuttx/configs/olimex-lpc1766stk/src/lpc17_ssp.c
new file mode 100644
index 000000000..06ac2959d
--- /dev/null
+++ b/nuttx/configs/olimex-lpc1766stk/src/lpc17_ssp.c
@@ -0,0 +1,380 @@
+/************************************************************************************
+ * configs/olimex-lpc1766stk/src/lpc17_ssp.c
+ *
+ * Copyright (C) 2010, 2013 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 <nuttx/spi/spi.h>
+#ifdef CONFIG_SPI_CALLBACK
+#include <nuttx/irq.h>
+#endif
+
+#include <arch/board/board.h>
+
+#include "up_arch.h"
+#include "chip.h"
+#include "lpc17_gpio.h"
+#include "lpc17_ssp.h"
+#include "lpc1766stk.h"
+
+#if defined(CONFIG_LPC17_SSP0) || defined(CONFIG_LPC17_SSP1)
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+/* Configuration ************************************************************/
+
+#ifdef CONFIG_SPI_CALLBACK
+# ifndef CONFIG_GPIO_IRQ
+# warning "CONFIG_GPIO_IRQ is required to support CONFIG_SPI_CALLBACK"
+# endif
+#endif
+
+/* Debug ********************************************************************/
+/* The following enable debug output from this file (needs CONFIG_DEBUG too).
+ *
+ * CONFIG_SSP_DEBUG - Define to enable basic SSP debug
+ * CONFIG_SSP_VERBOSE - Define to enable verbose SSP debug
+ */
+
+#ifdef CONFIG_SSP_DEBUG
+# define sspdbg lldbg
+# ifdef CONFIG_SSP_VERBOSE
+# define sspvdbg lldbg
+# else
+# define sspvdbg(x...)
+# endif
+#else
+# undef CONFIG_SSP_VERBOSE
+# define sspdbg(x...)
+# define sspvdbg(x...)
+#endif
+
+/* Dump GPIO registers */
+
+#ifdef CONFIG_SSP_VERBOSE
+# define ssp_dumpssp0gpio(m) lpc17_dumpgpio(LPC1766STK_LCD_CS, m)
+# define ssp_dumpssp1gpio(m) lpc17_dumpgpio(LPC1766STK_MMC_CS, m)
+#else
+# define ssp_dumpssp0gpio(m)
+# define ssp_dumpssp1gpio(m)
+#endif
+
+/************************************************************************************
+ * Private Types
+ ************************************************************************************/
+
+/* This structure describes on media change callback */
+
+#ifdef CONFIG_SPI_CALLBACK
+struct lpc17_mediachange_s
+{
+ spi_mediachange_t callback; /* The media change callback */
+ FAR void *arg; /* Callback argument */
+};
+#endif
+
+/************************************************************************************
+ * Private Data
+ ************************************************************************************/
+
+/* Registered media change callback */
+
+#ifdef CONFIG_SPI_CALLBACK
+#ifdef CONFIG_LPC17_SSP0
+static struct lpc17_mediachange_s g_ssp0callback;
+#endif
+#ifdef CONFIG_LPC17_SSP1
+static struct lpc17_mediachange_s g_ssp1callback;
+#endif
+#endif
+
+/************************************************************************************
+ * Private Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: ssp_cdirqsetup
+ *
+ * Description:
+ * Setup to receive a card detection interrupt
+ *
+ ************************************************************************************/
+
+#ifdef CONFIG_SPI_CALLBACK
+static void ssp_cdirqsetup(int irq, xcpt_t irqhandler)
+{
+ irqstate_t flags;
+
+ /* Disable interrupts until we are done */
+
+ flags = irqsave();
+
+ /* Configure the interrupt. Either attach and enable the new
+ * interrupt or disable and detach the old interrupt handler.
+ */
+
+ if (irqhandler)
+ {
+ /* Attach then enable the new interrupt handler */
+
+ (void)irq_attach(irq, irqhandler);
+ up_enable_irq(irq);
+ }
+ else
+ {
+ /* Disable then detach the old interrupt handler */
+
+ up_disable_irq(irq);
+ (void)irq_detach(irq);
+ }
+}
+#endif
+
+/************************************************************************************
+ * Name: ssp0/1_cdinterrupt
+ *
+ * Description:
+ * Handle card detection interrupt
+ *
+ ************************************************************************************/
+
+#ifdef CONFIG_SPI_CALLBACK
+#ifdef CONFIG_LPC17_SSP0
+static int ssp0_cdinterrupt(int irq, FAR void *context)
+{
+ /* Invoke the media change callback */
+
+ if (g_ssp0callback.callback)
+ {
+ g_ssp0callback.callback(g_ssp0callback.arg);
+ }
+ return OK;
+}
+#endif
+
+#ifdef CONFIG_LPC17_SSP1
+static int ssp1_cdinterrupt(int irq, FAR void *context)
+{
+ /* Invoke the media change callback */
+
+ if (g_ssp1callback.callback)
+ {
+ g_ssp1callback.callback(g_ssp1callback.arg);
+ }
+ return OK;
+}
+#endif
+#endif
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: lpc1766stk_sspinitialize
+ *
+ * Description:
+ * Called to configure SPI chip select GPIO pins for the LPC1766-STK.
+ *
+ ************************************************************************************/
+
+void weak_function lpc1766stk_sspinitialize(void)
+{
+ /* Configure the SSP0 chip select GPIOs. Only the Nokia LCD is connected to SSP0 */
+
+#ifdef CONFIG_LPC17_SSP0
+ ssp_dumpssp0gpio("BEFORE SSP0 Initialization");
+ lpc17_configgpio(LPC1766STK_LCD_CS);
+ ssp_dumpssp0gpio("AFTER SSP0 Initialization");
+#endif
+
+ /* Configure SSP1 chip select GPIOs. Only the SD/MMC card slot is connected to SSP1 */
+
+#ifdef CONFIG_LPC17_SSP1
+ ssp_dumpssp0gpio("BEFORE SSP1 Initialization");
+ lpc17_configgpio(LPC1766STK_MMC_CS);
+
+ /* Also configure the SD/MMC power GPIO (but leave power off). This really has
+ * nothing to do with SSP, but does belong with other SD/MMC GPIO configuration
+ * settings.
+ */
+
+ lpc17_configgpio(LPC1766STK_MMC_PWR);
+ ssp_dumpssp0gpio("AFTER SSP1 Initialization");
+#endif
+
+#ifdef CONFIG_SPI_CALLBACK
+ /* If there were any CD detect pins for the LPC1766-STK, this is where
+ * they would be configured.
+ */
+#endif
+}
+
+/************************************************************************************
+ * Name: lpc17_ssp0/ssp1select and lpc17_ssp0/ssp1status
+ *
+ * Description:
+ * The external functions, lpc17_ssp0/ssp1select and lpc17_ssp0/ssp1status
+ * 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/spi.h). All other methods (including lpc17_sspinitialize())
+ * are provided by common LPC17xx logic. To use this common SPI logic on your
+ * board:
+ *
+ * 1. Provide logic in lpc17_boardinitialize() to configure SPI/SSP chip select
+ * pins.
+ * 2. Provide lpc17_ssp0/ssp1select() and lpc17_ssp0/ssp1status() 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 lpc17_sspinitialize() in your low level application
+ * initialization logic
+ * 4. The handle returned by lpc17_sspinitialize() may then be used to bind the
+ * SPI driver to higher level logic (e.g., calling
+ * mmcsd_spislotinitialize(), for example, will bind the SPI driver to
+ * the SPI MMC/SD driver).
+ *
+ ************************************************************************************/
+
+#ifdef CONFIG_LPC17_SSP0
+void lpc17_ssp0select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
+{
+ sspdbg("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert");
+ if (devid == SPIDEV_DISPLAY)
+ {
+ /* Assert/de-assert the CS pin to the card */
+
+ ssp_dumpssp0gpio("lpc17_ssp0select() Entry");
+ lpc17_gpiowrite(LPC1766STK_LCD_CS, !selected);
+ ssp_dumpssp0gpio("lpc17_ssp0select() Exit");
+ }
+}
+
+uint8_t lpc17_ssp0status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
+{
+ sspdbg("Returning nothing\n");
+ return 0;
+}
+#endif
+
+#ifdef CONFIG_LPC17_SSP1
+void lpc17_ssp1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
+{
+ sspdbg("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert");
+ if (devid == SPIDEV_MMCSD)
+ {
+ /* Assert/de-assert the CS pin to the card */
+
+ ssp_dumpssp1gpio("lpc17_ssp1select() Entry");
+ lpc17_gpiowrite(LPC1766STK_MMC_CS, !selected);
+ ssp_dumpssp1gpio("lpc17_ssp1select() Exit");
+ }
+}
+
+uint8_t lpc17_ssp1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
+{
+ sspdbg("Returning SPI_STATUS_PRESENT\n");
+ return SPI_STATUS_PRESENT;
+}
+#endif
+
+/************************************************************************************
+ * Name: lpc17_ssp0/1register
+ *
+ * Description:
+ * If the board supports a card detect callback to inform the SPI-based
+ * MMC/SD drvier when an SD card is inserted or removed, then
+ * CONFIG_SPI_CALLBACK should be defined and the following function(s) must
+ * must be implemented. These functiosn implements the registercallback
+ * method of the SPI interface (see include/nuttx/spi/spi.h for details)
+ *
+ * Input Parameters:
+ * dev - Device-specific state data
+ * callback - The funtion to call on the media change
+ * arg - A caller provided value to return with the callback
+ *
+ * Returned Value:
+ * 0 on success; negated errno on failure.
+ *
+ ************************************************************************************/
+
+#ifdef CONFIG_SPI_CALLBACK
+#ifdef CONFIG_LPC17_SSP0
+ /* If there were any CD detect pins on the LPC1766-STK, this is how the
+ * would be configured.
+ */
+
+int lpc17_ssp0register(FAR struct spi_dev_s *dev, spi_mediachange_t callback, void *arg)
+{
+ /* Save the callback information */
+
+#if 0
+ g_ssp0callback.callback = callback;
+ g_ssp0callback.arg = arg;
+
+ /* Setup the interrupt */
+
+ spi_cdirqsetup(LPC1766STK_SPICD_IRQ, ssp0_cdinterrupt);
+#endif
+ return OK;
+}
+#endif
+
+#ifdef CONFIG_LPC17_SSP1
+int lpc17_ssp1register(FAR struct spi_dev_s *dev, spi_mediachange_t callback, void *arg)
+{
+ /* Save the callback information */
+
+#if 0
+ g_ssp1callback.callback = callback;
+ g_ssp1callback.arg = arg;
+
+ /* Setup the interrupt */
+
+ spi_cdirqsetup(LPC1766STK_SPICD_IRQ, ssp1_cdinterrupt);
+#endif
+ return OK;
+}
+#endif
+#endif
+
+#endif /* CONFIG_LPC17_SSP0 || CONFIG_LPC17_SSP1 */
diff --git a/nuttx/configs/olimex-lpc1766stk/src/lpc17_usbmsc.c b/nuttx/configs/olimex-lpc1766stk/src/lpc17_usbmsc.c
new file mode 100644
index 000000000..221ed41b4
--- /dev/null
+++ b/nuttx/configs/olimex-lpc1766stk/src/lpc17_usbmsc.c
@@ -0,0 +1,155 @@
+/****************************************************************************
+ * configs/olimex-lpc1766stk/src/lpc17_usbmsc.c
+ *
+ * Copyright (C) 2010 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Configure and register the LPC17xx MMC/SD SPI block driver.
+ *
+ * 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 <stdio.h>
+#include <debug.h>
+#include <errno.h>
+
+#include <nuttx/spi/spi.h>
+#include <nuttx/mmcsd.h>
+
+#include "lpc17_gpio.h"
+#include "lpc1766stk.h"
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+/* Configuration ************************************************************/
+
+#ifndef CONFIG_SYSTEM_USBMSC_DEVMINOR1
+# define CONFIG_SYSTEM_USBMSC_DEVMINOR1 0
+#endif
+
+/* PORT and SLOT number probably depend on the board configuration */
+
+#ifdef CONFIG_ARCH_BOARD_LPC1766STK
+# undef LPC17XX_MMCSDSPIPORTNO
+# define LPC17XX_MMCSDSPIPORTNO 1
+# undef LPC17XX_MMCSDSLOTNO
+# define LPC17XX_MMCSDSLOTNO 0
+#else
+ /* Add configuration for new LPC17xx boards here */
+# error "Unrecognized LPC17xx board"
+#endif
+
+/* Debug ********************************************************************/
+
+#ifdef CONFIG_CPP_HAVE_VARARGS
+# ifdef CONFIG_DEBUG
+# define message(...) lowsyslog(__VA_ARGS__)
+# define msgflush()
+# else
+# define message(...) printf(__VA_ARGS__)
+# define msgflush() fflush(stdout)
+# endif
+#else
+# ifdef CONFIG_DEBUG
+# define message lowsyslog
+# define msgflush()
+# else
+# define message printf
+# define msgflush() fflush(stdout)
+# endif
+#endif
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: usbmsc_archinitialize
+ *
+ * Description:
+ * Perform architecture specific initialization
+ *
+ ****************************************************************************/
+
+int usbmsc_archinitialize(void)
+{
+ FAR struct spi_dev_s *spi;
+ int ret;
+
+ /* Enable power to the SD/MMC via a GPIO. LOW enables SD/MMC. */
+
+ lpc17_gpiowrite(LPC1766STK_MMC_PWR, false);
+
+ /* Get the SPI port */
+
+ message("usbmsc_archinitialize: Initializing SPI port %d\n",
+ LPC17XX_MMCSDSPIPORTNO);
+
+ spi = lpc17_sspinitialize(LPC17XX_MMCSDSPIPORTNO);
+ if (!spi)
+ {
+ message("usbmsc_archinitialize: Failed to initialize SPI port %d\n",
+ LPC17XX_MMCSDSPIPORTNO);
+ ret = -ENODEV;
+ goto errout;
+ }
+
+ message("usbmsc_archinitialize: Successfully initialized SPI port %d\n",
+ LPC17XX_MMCSDSPIPORTNO);
+
+ /* Bind the SPI port to the slot */
+
+ message("usbmsc_archinitialize: Binding SPI port %d to MMC/SD slot %d\n",
+ LPC17XX_MMCSDSPIPORTNO, LPC17XX_MMCSDSLOTNO);
+
+ ret = mmcsd_spislotinitialize(CONFIG_SYSTEM_USBMSC_DEVMINOR1, LPC17XX_MMCSDSLOTNO, spi);
+ if (ret < 0)
+ {
+ message("usbmsc_archinitialize: Failed to bind SPI port %d to MMC/SD slot %d: %d\n",
+ LPC17XX_MMCSDSPIPORTNO, LPC17XX_MMCSDSLOTNO, ret);
+ goto errout;
+ }
+
+ message("usbmsc_archinitialize: Successfuly bound SPI port %d to MMC/SD slot %d\n",
+ LPC17XX_MMCSDSPIPORTNO, LPC17XX_MMCSDSLOTNO);
+ return OK;
+
+ /* Disable power to the SD/MMC via a GPIO. HIGH disables SD/MMC. */
+
+errout:
+ lpc17_gpiowrite(LPC1766STK_MMC_PWR, true);
+ return ret;}