From 5bc024fdf6f8c21c164c6de5790c0c4d1d915d33 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Sat, 21 Mar 2015 10:24:24 -0600 Subject: Lincoln60: Rename files for better conformance to naming conventions --- nuttx/configs/lincoln60/src/Makefile | 30 +-- nuttx/configs/lincoln60/src/lincoln60_internal.h | 3 +- nuttx/configs/lincoln60/src/lpc17_boot.c | 81 ++++++++ nuttx/configs/lincoln60/src/lpc17_buttons.c | 226 +++++++++++++++++++++++ nuttx/configs/lincoln60/src/lpc17_leds.c | 215 +++++++++++++++++++++ nuttx/configs/lincoln60/src/lpc17_nsh.c | 68 +++++++ nuttx/configs/lincoln60/src/up_boot.c | 81 -------- nuttx/configs/lincoln60/src/up_buttons.c | 226 ----------------------- nuttx/configs/lincoln60/src/up_leds.c | 215 --------------------- nuttx/configs/lincoln60/src/up_nsh.c | 69 ------- 10 files changed, 606 insertions(+), 608 deletions(-) create mode 100644 nuttx/configs/lincoln60/src/lpc17_boot.c create mode 100644 nuttx/configs/lincoln60/src/lpc17_buttons.c create mode 100644 nuttx/configs/lincoln60/src/lpc17_leds.c create mode 100644 nuttx/configs/lincoln60/src/lpc17_nsh.c delete mode 100644 nuttx/configs/lincoln60/src/up_boot.c delete mode 100644 nuttx/configs/lincoln60/src/up_buttons.c delete mode 100644 nuttx/configs/lincoln60/src/up_leds.c delete mode 100644 nuttx/configs/lincoln60/src/up_nsh.c (limited to 'nuttx/configs/lincoln60') diff --git a/nuttx/configs/lincoln60/src/Makefile b/nuttx/configs/lincoln60/src/Makefile index 1fc01490a..a54083f1e 100644 --- a/nuttx/configs/lincoln60/src/Makefile +++ b/nuttx/configs/lincoln60/src/Makefile @@ -35,36 +35,36 @@ -include $(TOPDIR)/Make.defs -CFLAGS += -I$(TOPDIR)/sched +CFLAGS += -I$(TOPDIR)/sched -ASRCS = -CSRCS = up_boot.c up_leds.c +ASRCS = +CSRCS = lpc17_boot.c lpc17_leds.c ifeq ($(CONFIG_NSH_ARCHINIT),y) -CSRCS += up_nsh.c +CSRCS += lpc17_nsh.c endif ifeq ($(CONFIG_USBMSC),y) -CSRCS += up_usbmsc.c +CSRCS += lpc17_usbmsc.c endif ifeq ($(CONFIG_ARCH_BUTTONS),y) -CSRCS += up_buttons.c +CSRCS += lpc17_buttons.c endif -AOBJS = $(ASRCS:.S=$(OBJEXT)) -COBJS = $(CSRCS:.c=$(OBJEXT)) +AOBJS = $(ASRCS:.S=$(OBJEXT)) +COBJS = $(CSRCS:.c=$(OBJEXT)) -SRCS = $(ASRCS) $(CSRCS) -OBJS = $(AOBJS) $(COBJS) +SRCS = $(ASRCS) $(CSRCS) +OBJS = $(AOBJS) $(COBJS) -ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src +ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src ifeq ($(WINTOOL),y) - CFLAGS += -I "${shell cygpath -w $(ARCH_SRCDIR)/chip}" \ - -I "${shell cygpath -w $(ARCH_SRCDIR)/common}" \ - -I "${shell cygpath -w $(ARCH_SRCDIR)/armv7-m}" + CFLAGS += -I "${shell cygpath -w $(ARCH_SRCDIR)/chip}" \ + -I "${shell cygpath -w $(ARCH_SRCDIR)/common}" \ + -I "${shell cygpath -w $(ARCH_SRCDIR)/armv7-m}" else - CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common -I$(ARCH_SRCDIR)/armv7-m + CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common -I$(ARCH_SRCDIR)/armv7-m endif all: libboard$(LIBEXT) diff --git a/nuttx/configs/lincoln60/src/lincoln60_internal.h b/nuttx/configs/lincoln60/src/lincoln60_internal.h index 5f9891883..6d84d571f 100644 --- a/nuttx/configs/lincoln60/src/lincoln60_internal.h +++ b/nuttx/configs/lincoln60/src/lincoln60_internal.h @@ -1,6 +1,5 @@ /**************************************************************************** * configs/lincoln60/src/lincoln60_internal.h - * arch/arm/src/board/lincoln60_internal.n * * Copyright (C) 2012 Gregory Nutt. All rights reserved. * Author: Gregory Nutt @@ -45,7 +44,7 @@ #include /**************************************************************************** - * Definitions + * Pre-processor Definitions ****************************************************************************/ /**************************************************************************** diff --git a/nuttx/configs/lincoln60/src/lpc17_boot.c b/nuttx/configs/lincoln60/src/lpc17_boot.c new file mode 100644 index 000000000..bbaf0c178 --- /dev/null +++ b/nuttx/configs/lincoln60/src/lpc17_boot.c @@ -0,0 +1,81 @@ +/************************************************************************************ + * configs/lincoln60/src/lpc17_boot.c + * + * Copyright (C) 2012, 2015 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 + +#include + +#include +#include + +#include "up_arch.h" +#include "up_internal.h" + +#include "lincoln60_internal.h" + +/************************************************************************************ + * Pre-processor 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 on-board LEDs if LED support has been selected. */ + +#ifdef CONFIG_ARCH_LEDS + board_led_initialize(); +#endif +} diff --git a/nuttx/configs/lincoln60/src/lpc17_buttons.c b/nuttx/configs/lincoln60/src/lpc17_buttons.c new file mode 100644 index 000000000..38a2326a5 --- /dev/null +++ b/nuttx/configs/lincoln60/src/lpc17_buttons.c @@ -0,0 +1,226 @@ +/**************************************************************************** + * configs/lincoln60/src/lpc17_buttons.c + * + * Copyright (C) 2012-2013, 2015 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 + +#include +#include + +#include +#include +#include + +#include + +#include "lpc17_gpio.h" +#include "lincoln60_internal.h" + +#ifdef CONFIG_ARCH_BUTTONS + +/**************************************************************************** + * Pre-processor 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] = +{ + LINCOLN60_BUT1 +}; + +/* 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] = +{ + LINCOLN60_BUT1_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/lincoln60/src/lpc17_leds.c b/nuttx/configs/lincoln60/src/lpc17_leds.c new file mode 100644 index 000000000..47edb089e --- /dev/null +++ b/nuttx/configs/lincoln60/src/lpc17_leds.c @@ -0,0 +1,215 @@ +/**************************************************************************** + * configs/lincoln60/src/lpc17_leds.c + * + * Copyright (C) 2012-2013, 2015 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 + +#include +#include +#include + +#include +#include + +#include "chip.h" +#include "up_arch.h" +#include "up_internal.h" + +#include "lpc17_gpio.h" + +#include "lincoln60_internal.h" + +#ifdef CONFIG_ARCH_LEDS + +/**************************************************************************** + * Pre-processor 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(LINCOLN60_LED2, m) +#else +# define led_dumpgpio(m) +#endif + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/* LED definitions ****************************************************************** + +The Lincoln 60 has 2 LEDs along the bottom of the board. Green or off. +If CONFIG_ARCH_LEDS is defined, the LEDs will be controlled as follows for NuttX +debug functionality (where NC means "No Change"). + +During the boot phases. LED1 and LED2 will show boot status. + + LED1 LED2 +STARTED OFF OFF +HEAPALLOCATE BLUE OFF +IRQSENABLED OFF BLUE +STACKCREATED OFF OFF + +After the system is booted, this logic will no longer use LEDs 1 & 2. They +are available for use by applications using lpc17_led (prototyped below) +*/ + +static bool g_initialized; +static int g_nestcount; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: board_led_initialize + ****************************************************************************/ + +void board_led_initialize(void) +{ + /* Configure all LED GPIO lines */ + + led_dumpgpio("board_led_initialize() Entry)"); + + lpc17_configgpio(LINCOLN60_LED1); + lpc17_configgpio(LINCOLN60_LED2); + + led_dumpgpio("board_led_initialize() Exit"); +} + +/**************************************************************************** + * Name: board_led_on + ****************************************************************************/ + +void board_led_on(int led) +{ + /* We will control LED1 and LED2 not yet completed the boot sequence. */ + + if (!g_initialized) + { + int led1 = 0; + int led2 = 0; + switch (led) + { + case LED_STACKCREATED: + g_initialized = true; + case LED_STARTED: + default: + break; + + case LED_HEAPALLOCATE: + led1 = 1; + break; + + case LED_IRQSENABLED: + led2 = 1; + } + lpc17_led(LINCOLN60_LED1,led1); + lpc17_led(LINCOLN60_LED2,led2); + } + + /* We will always control the HB LED */ + + switch (led) + { + case LED_INIRQ: + case LED_SIGNAL: + case LED_ASSERTION: + case LED_PANIC: + lpc17_gpiowrite(LINCOLN60_HEARTBEAT, false); + g_nestcount++; + + default: + break; + } +} + +/**************************************************************************** + * Name: board_led_off + ****************************************************************************/ + +void board_led_off(int led) +{ + /* In all states, OFF can only mean turning off the HB LED */ + + if (g_nestcount <= 1) + { + lpc17_led(LINCOLN60_HEARTBEAT, true); + g_nestcount = 0; + } + else + { + g_nestcount--; + } +} + +/************************************************************************************ + * Name: lpc17_led + * + * Description: + * Once the system has booted, these functions can be used to control the LEDs + * + ************************************************************************************/ + +void lpc17_led(int lednum, int state) + +{ + lpc17_gpiowrite(lednum, state); +} +#endif /* CONFIG_ARCH_LEDS */ diff --git a/nuttx/configs/lincoln60/src/lpc17_nsh.c b/nuttx/configs/lincoln60/src/lpc17_nsh.c new file mode 100644 index 000000000..041a3345a --- /dev/null +++ b/nuttx/configs/lincoln60/src/lpc17_nsh.c @@ -0,0 +1,68 @@ +/**************************************************************************** + * config/lincoln60/src/lpc17_nsh.c + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 + +#include +#include +#include + +#include +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: nsh_archinitialize + * + * Description: + * Perform architecture specific initialization + * + ****************************************************************************/ + +int nsh_archinitialize(void) +{ + return OK; +} diff --git a/nuttx/configs/lincoln60/src/up_boot.c b/nuttx/configs/lincoln60/src/up_boot.c deleted file mode 100644 index c20295815..000000000 --- a/nuttx/configs/lincoln60/src/up_boot.c +++ /dev/null @@ -1,81 +0,0 @@ -/************************************************************************************ - * configs/lincoln60/src/up_boot.c - * - * Copyright (C) 2012, 2015 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * 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 - -#include - -#include -#include - -#include "up_arch.h" -#include "up_internal.h" - -#include "lincoln60_internal.h" - -/************************************************************************************ - * Pre-processor 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 on-board LEDs if LED support has been selected. */ - -#ifdef CONFIG_ARCH_LEDS - board_led_initialize(); -#endif -} diff --git a/nuttx/configs/lincoln60/src/up_buttons.c b/nuttx/configs/lincoln60/src/up_buttons.c deleted file mode 100644 index 610e2cab0..000000000 --- a/nuttx/configs/lincoln60/src/up_buttons.c +++ /dev/null @@ -1,226 +0,0 @@ -/**************************************************************************** - * configs/lincoln60/src/board_buttons.c - * - * Copyright (C) 2012-2013, 2015 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * 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 - -#include -#include - -#include -#include -#include - -#include - -#include "lpc17_gpio.h" -#include "lincoln60_internal.h" - -#ifdef CONFIG_ARCH_BUTTONS - -/**************************************************************************** - * Pre-processor 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] = -{ - LINCOLN60_BUT1 -}; - -/* 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] = -{ - LINCOLN60_BUT1_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/lincoln60/src/up_leds.c b/nuttx/configs/lincoln60/src/up_leds.c deleted file mode 100644 index d91cf407f..000000000 --- a/nuttx/configs/lincoln60/src/up_leds.c +++ /dev/null @@ -1,215 +0,0 @@ -/**************************************************************************** - * configs/lincoln60/src/up_leds.c - * - * Copyright (C) 2012-2013, 2015 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * 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 - -#include -#include -#include - -#include -#include - -#include "chip.h" -#include "up_arch.h" -#include "up_internal.h" - -#include "lpc17_gpio.h" - -#include "lincoln60_internal.h" - -#ifdef CONFIG_ARCH_LEDS - -/**************************************************************************** - * 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(LINCOLN60_LED2, m) -#else -# define led_dumpgpio(m) -#endif - -/**************************************************************************** - * Private Data - ****************************************************************************/ - -/* LED definitions ****************************************************************** - -The Lincoln 60 has 2 LEDs along the bottom of the board. Green or off. -If CONFIG_ARCH_LEDS is defined, the LEDs will be controlled as follows for NuttX -debug functionality (where NC means "No Change"). - -During the boot phases. LED1 and LED2 will show boot status. - - LED1 LED2 -STARTED OFF OFF -HEAPALLOCATE BLUE OFF -IRQSENABLED OFF BLUE -STACKCREATED OFF OFF - -After the system is booted, this logic will no longer use LEDs 1 & 2. They -are available for use by applications using lpc17_led (prototyped below) -*/ - -static bool g_initialized; -static int g_nestcount; - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: board_led_initialize - ****************************************************************************/ - -void board_led_initialize(void) -{ - /* Configure all LED GPIO lines */ - - led_dumpgpio("board_led_initialize() Entry)"); - - lpc17_configgpio(LINCOLN60_LED1); - lpc17_configgpio(LINCOLN60_LED2); - - led_dumpgpio("board_led_initialize() Exit"); -} - -/**************************************************************************** - * Name: board_led_on - ****************************************************************************/ - -void board_led_on(int led) -{ - /* We will control LED1 and LED2 not yet completed the boot sequence. */ - - if (!g_initialized) - { - int led1 = 0; - int led2 = 0; - switch (led) - { - case LED_STACKCREATED: - g_initialized = true; - case LED_STARTED: - default: - break; - - case LED_HEAPALLOCATE: - led1 = 1; - break; - - case LED_IRQSENABLED: - led2 = 1; - } - lpc17_led(LINCOLN60_LED1,led1); - lpc17_led(LINCOLN60_LED2,led2); - } - - /* We will always control the HB LED */ - - switch (led) - { - case LED_INIRQ: - case LED_SIGNAL: - case LED_ASSERTION: - case LED_PANIC: - lpc17_gpiowrite(LINCOLN60_HEARTBEAT, false); - g_nestcount++; - - default: - break; - } -} - -/**************************************************************************** - * Name: board_led_off - ****************************************************************************/ - -void board_led_off(int led) -{ - /* In all states, OFF can only mean turning off the HB LED */ - - if (g_nestcount <= 1) - { - lpc17_led(LINCOLN60_HEARTBEAT, true); - g_nestcount = 0; - } - else - { - g_nestcount--; - } -} - -/************************************************************************************ - * Name: lpc17_led - * - * Description: - * Once the system has booted, these functions can be used to control the LEDs - * - ************************************************************************************/ - -void lpc17_led(int lednum, int state) - -{ - lpc17_gpiowrite(lednum, state); -} -#endif /* CONFIG_ARCH_LEDS */ diff --git a/nuttx/configs/lincoln60/src/up_nsh.c b/nuttx/configs/lincoln60/src/up_nsh.c deleted file mode 100644 index d54c140c3..000000000 --- a/nuttx/configs/lincoln60/src/up_nsh.c +++ /dev/null @@ -1,69 +0,0 @@ -/**************************************************************************** - * config/lincoln60/src/up_nsh.c - * arch/arm/src/board/up_nsh.c - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * 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 - -#include -#include -#include - -#include -#include - -/**************************************************************************** - * Pre-Processor Definitions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: nsh_archinitialize - * - * Description: - * Perform architecture specific initialization - * - ****************************************************************************/ - -int nsh_archinitialize(void) -{ - return OK; -} -- cgit v1.2.3