diff --git a/nuttx/arch/arm/src/lpc43xx/Make.defs b/nuttx/arch/arm/src/lpc43xx/Make.defs index ea86ed1a48..33fbbb5b52 100644 --- a/nuttx/arch/arm/src/lpc43xx/Make.defs +++ b/nuttx/arch/arm/src/lpc43xx/Make.defs @@ -33,35 +33,39 @@ # ############################################################################ -HEAD_ASRC = +HEAD_ASRC = -CMN_ASRCS = up_saveusercontext.S up_fullcontextrestore.S up_switchcontext.S -CMN_CSRCS = up_assert.c up_blocktask.c up_copystate.c \ - up_createstack.c up_mdelay.c up_udelay.c up_exit.c \ - up_initialize.c up_initialstate.c up_interruptcontext.c \ - up_memfault.c up_modifyreg8.c up_modifyreg16.c up_modifyreg32.c \ - up_releasepending.c up_releasestack.c up_reprioritizertr.c \ - up_schedulesigaction.c up_sigdeliver.c up_unblocktask.c \ - up_usestack.c up_doirq.c up_hardfault.c up_svcall.c +CMN_ASRCS = up_saveusercontext.S up_fullcontextrestore.S up_switchcontext.S +CMN_CSRCS += up_assert.c up_blocktask.c up_copystate.c +CMN_CSRCS += up_createstack.c up_mdelay.c up_udelay.c up_exit.c +CMN_CSRCS += up_initialize.c up_initialstate.c up_interruptcontext.c +CMN_CSRCS += up_memfault.c up_modifyreg8.c up_modifyreg16.c up_modifyreg32.c +CMN_CSRCS += up_releasepending.c up_releasestack.c up_reprioritizertr.c +CMN_CSRCS += up_schedulesigaction.c up_sigdeliver.c up_unblocktask.c +CMN_CSRCS += up_usestack.c up_doirq.c up_hardfault.c up_svcall.c ifeq ($(CONFIG_ARMV7M_CMNVECTOR),y) -CMN_ASRCS += up_exception.S -CMN_CSRCS += up_vectors.c +CMN_ASRCS += up_exception.S +CMN_CSRCS += up_vectors.c endif ifeq ($(CONFIG_DEBUG_STACK),y) -CMN_CSRCS += up_checkstack.c +CMN_CSRCS += up_checkstack.c endif ifeq ($(CONFIG_ARCH_FPU),y) -CMN_ASRCS += up_fpu.S +CMN_ASRCS += up_fpu.S endif -CHIP_ASRCS = -CHIP_CSRCS = lpc43_irq.c lpc43_start.c +CHIP_ASRCS = +CHIP_CSRCS = lpc43_clrpend.c lpc43_gpio.c lpc43_irq.c lpc43_lowputc.c +CHIP_CSRCS += lpc43_pinconfig.c lpc43_start.c lpc43_timerisr.c ifneq ($(CONFIG_IDLE_CUSTOM),y) -CHIP_CSRCS += lpc43_idle.c +CHIP_CSRCS += lpc43_idle.c endif +ifneq ($(CONFIG_DEBUG),y) +CHIP_CSRCS += lpc43_debug.c +endif diff --git a/nuttx/arch/arm/src/lpc43xx/lpc43_clrpend.c b/nuttx/arch/arm/src/lpc43xx/lpc43_clrpend.c new file mode 100644 index 0000000000..ca7189103e --- /dev/null +++ b/nuttx/arch/arm/src/lpc43xx/lpc43_clrpend.c @@ -0,0 +1,99 @@ +/**************************************************************************** + * arch/arm/src/lpc43/lpc43_clrpend.c + * arch/arm/src/chip/lpc43_clrpend.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 "nvic.h" +#include "up_arch.h" + +#include "lpc43_irq.h" + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: lpc43_clrpend + * + * Description: + * Clear a pending interrupt at the NVIC. This does not seem to be required + * for most interrupts. Don't know why... but the LPC4366 Ethernet EMAC + * interrupt definitely needs it! + * + * This function is logically a part of lpc43_irq.c, but I will keep it in + * a separate file so that it will not increase the footprint on LPC43xx + * platforms that do not need this function. + * + ****************************************************************************/ + +void lpc43_clrpend(int irq) +{ + /* Check for external interrupt */ + + if (irq >= LPC43_IRQ_EXTINT) + { + if (irq < (LPC43_IRQ_EXTINT + 32)) + { + putreg32(1 << (irq - LPC43_IRQ_EXTINT), NVIC_IRQ0_31_CLRPEND); + } + else if (irq < LPC43M4_IRQ_NIRQS) + { + putreg32(1 << (irq - LPC43_IRQ_EXTINT - 32), NVIC_IRQ32_63_CLRPEND); + } + } +} diff --git a/nuttx/arch/arm/src/lpc43xx/lpc43_debug.c b/nuttx/arch/arm/src/lpc43xx/lpc43_debug.c new file mode 100644 index 0000000000..94237ab09c --- /dev/null +++ b/nuttx/arch/arm/src/lpc43xx/lpc43_debug.c @@ -0,0 +1,94 @@ +/**************************************************************************** + * arch/arm/src/lpc43/lpc43_pinconfig.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 "lpc43_pinconfig.h" + +#ifdef CONFIG_DEBUG + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ +/**************************************************************************** + * Function: lpc43_dumppinconfig + * + * Description: + * Dump all pin configuration registers associated with the provided pin + * configuration + * + ****************************************************************************/ + +int lpc43_dumppinconfig(uint32_t pinconf, const char *msg) +{ +#warning "Missing logic" + return -ENOSYS; +} + +/******************************************************************************************** + * Function: lpc43_dumpgpio + * + * Description: + * Dump all pin configuration registers associated with the provided base address + * + ********************************************************************************************/ + +int lpc43_dumpgpio(uint16_t gpiocfg, const char *msg) +{ +#warning "Missing logic" + return -ENOSYS; +} + +#endif /* CONFIG_DEBUG */ diff --git a/nuttx/arch/arm/src/lpc43xx/lpc43_gpio.c b/nuttx/arch/arm/src/lpc43xx/lpc43_gpio.c new file mode 100644 index 0000000000..36983b8eca --- /dev/null +++ b/nuttx/arch/arm/src/lpc43xx/lpc43_gpio.c @@ -0,0 +1,115 @@ +/**************************************************************************** + * arch/arm/src/lpc43/lpc43_gpio.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 "lpc43_pinconfig.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: lpc43_gpioconfig + * + * Description: + * Configure a GPIO based on bit-encoded description of the pin. + * + * Returned Value: + * OK on success; A negated errno value on failure. + * + ****************************************************************************/ + +int lpc43_gpioconfig(uint16_t gpiocfg) +{ +#warning "Missing logic" + return -ENOSYS; +} + +/**************************************************************************** + * Name: lpc43_gpiowrite + * + * Description: + * Write one or zero to the selected GPIO pin + * + * Returned Value: + * None + * + ****************************************************************************/ + +void lpc43_gpiowrite(uint16_t gpiocfg, bool value) +{ +#warning "Missing logic" +} + +/**************************************************************************** + * Name: lpc43_gpioread + * + * Description: + * Read one or zero from the selected GPIO pin + * + * Returned Value: + * The boolean state of the input pin + * + ****************************************************************************/ + +bool lpc43_gpioread(uint16_t gpiocfg) +{ +#warning "Missing logic" + return false; +} + + + diff --git a/nuttx/arch/arm/src/lpc43xx/lpc43_gpio.h b/nuttx/arch/arm/src/lpc43xx/lpc43_gpio.h index 1ceb3f4f0c..d7615efa00 100644 --- a/nuttx/arch/arm/src/lpc43xx/lpc43_gpio.h +++ b/nuttx/arch/arm/src/lpc43xx/lpc43_gpio.h @@ -249,11 +249,11 @@ EXTERN const uint32_t g_gpiobase[NUM_GPIO_PORTS]; * Returned Value: * OK on success; A negated errno value on failure. * - ************************************************************************************/ + ********************************************************************************************/ EXTERN int lpc43_gpioconfig(uint16_t gpiocfg); -/************************************************************************************ +/******************************************************************************************** * Name: lpc43_gpiowrite * * Description: @@ -262,11 +262,11 @@ EXTERN int lpc43_gpioconfig(uint16_t gpiocfg); * Returned Value: * None * - ************************************************************************************/ + ********************************************************************************************/ EXTERN void lpc43_gpiowrite(uint16_t gpiocfg, bool value); -/************************************************************************************ +/******************************************************************************************** * Name: lpc43_gpioread * * Description: @@ -275,11 +275,11 @@ EXTERN void lpc43_gpiowrite(uint16_t gpiocfg, bool value); * Returned Value: * The boolean state of the input pin * - ************************************************************************************/ + ********************************************************************************************/ EXTERN bool lpc43_gpioread(uint16_t gpiocfg); -/************************************************************************************ +/******************************************************************************************** * Name: lpc43_gpioattach * * Description: @@ -296,17 +296,17 @@ EXTERN bool lpc43_gpioread(uint16_t gpiocfg); * for example, be used to restore the previous handler when multiple handlers are * used. * - ************************************************************************************/ + ********************************************************************************************/ EXTERN xcpt_t lpc43_gpioattach(uint16_t gpiocfg, xcpt_t func); -/************************************************************************************ +/******************************************************************************************** * Function: lpc43_dumpgpio * * Description: * Dump all pin configuration registers associated with the provided base address * - ************************************************************************************/ + ********************************************************************************************/ #ifdef CONFIG_DEBUG EXTERN int lpc43_dumpgpio(uint16_t gpiocfg, const char *msg); diff --git a/nuttx/arch/arm/src/lpc43xx/lpc43_irq.c b/nuttx/arch/arm/src/lpc43xx/lpc43_irq.c index 40c1496f81..73a0c92e99 100644 --- a/nuttx/arch/arm/src/lpc43xx/lpc43_irq.c +++ b/nuttx/arch/arm/src/lpc43xx/lpc43_irq.c @@ -53,6 +53,8 @@ #include "os_internal.h" #include "up_internal.h" +#include "lpc43_irq.h" + /**************************************************************************** * Definitions ****************************************************************************/ diff --git a/nuttx/arch/arm/src/lpc43xx/lpc43_irq.h b/nuttx/arch/arm/src/lpc43xx/lpc43_irq.h new file mode 100644 index 0000000000..201081169b --- /dev/null +++ b/nuttx/arch/arm/src/lpc43xx/lpc43_irq.h @@ -0,0 +1,92 @@ +/**************************************************************************** + * arch/arm/src/lpc43xx/lpc43_irq.h + * + * 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. + * + ****************************************************************************/ + +#ifndef __ARCH_ARM_SRC_LPC43XX_LPC43_IRQ_H +#define __ARCH_ARM_SRC_LPC43XX_LPC43_IRQ_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +#ifndef __ASSEMBLY__ + +#undef EXTERN +#if defined(__cplusplus) +#define EXTERN extern "C" +extern "C" { +#else +#define EXTERN extern +#endif + +/**************************************************************************** + * Inline Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: lpc43_clrpend + * + * Description: + * Clear a pending interrupt at the NVIC. This does not seem to be + * required for most interrupts. + * + ****************************************************************************/ + +EXTERN void lpc43_clrpend(int irq); + +#undef EXTERN +#if defined(__cplusplus) +} +#endif + +#endif /* __ASSEMBLY__ */ +#endif /* __ARCH_ARM_SRC_LPC43XX_LPC43_IRQ_H */ diff --git a/nuttx/arch/arm/src/lpc43xx/lpc43_lowputc.c b/nuttx/arch/arm/src/lpc43xx/lpc43_lowputc.c new file mode 100644 index 0000000000..2e45f9855c --- /dev/null +++ b/nuttx/arch/arm/src/lpc43xx/lpc43_lowputc.c @@ -0,0 +1,422 @@ +/************************************************************************** + * arch/arm/src/lpc43xx/lpc43_lowputc.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 "up_internal.h" +#include "up_arch.h" + +#include "chip.h" +#include "lpc43_config.h" +#include "lpc43_pinconfig.h" +#include "chip/lpc43_uart.h" + +#include "lpc43_lowputc.h" + +/************************************************************************** + * Private Definitions + **************************************************************************/ + +/* Select UART parameters for the selected console */ + +#if defined(CONFIG_USART0_SERIAL_CONSOLE) +# define CONSOLE_BASE LPC43_USART0_BASE +# define CONSOLE_BAUD CONFIG_USART0_BAUD +# define CONSOLE_BITS CONFIG_USART0_BITS +# define CONSOLE_PARITY CONFIG_USART0_PARITY +# define CONSOLE_2STOP CONFIG_USART0_2STOP +#elif defined(CONFIG_UART1_SERIAL_CONSOLE) +# define CONSOLE_BASE LPC43_UART1_BASE +# define CONSOLE_BAUD CONFIG_UART1_BAUD +# define CONSOLE_BITS CONFIG_UART1_BITS +# define CONSOLE_PARITY CONFIG_UART1_PARITY +# define CONSOLE_2STOP CONFIG_UART1_2STOP +#elif defined(CONFIG_USART2_SERIAL_CONSOLE) +# define CONSOLE_BASE LPC43_USART2_BASE +# define CONSOLE_BAUD CONFIG_USART2_BAUD +# define CONSOLE_BITS CONFIG_USART2_BITS +# define CONSOLE_PARITY CONFIG_USART2_PARITY +# define CONSOLE_2STOP CONFIG_USART2_2STOP +#elif defined(CONFIG_USART3_SERIAL_CONSOLE) +# define CONSOLE_BASE LPC43_USART3_BASE +# define CONSOLE_BAUD CONFIG_USART3_BAUD +# define CONSOLE_BITS CONFIG_USART3_BITS +# define CONSOLE_PARITY CONFIG_USART3_PARITY +# define CONSOLE_2STOP CONFIG_USART3_2STOP +#elif defined(HAVE_CONSOLE) +# error "No CONFIG_UARTn_SERIAL_CONSOLE Setting" +#endif + +/* Get word length setting for the console */ + +#if CONSOLE_BITS == 5 +# define CONSOLE_LCR_WLS UART_LCR_WLS_5BIT +#elif CONSOLE_BITS == 6 +# define CONSOLE_LCR_WLS UART_LCR_WLS_6BIT +#elif CONSOLE_BITS == 7 +# define CONSOLE_LCR_WLS UART_LCR_WLS_7BIT +#elif CONSOLE_BITS == 8 +# define CONSOLE_LCR_WLS UART_LCR_WLS_8BIT +#elif defined(HAVE_CONSOLE) +# error "Invalid CONFIG_UARTn_BITS setting for console " +#endif + +/* Get parity setting for the console */ + +#if CONSOLE_PARITY == 0 +# define CONSOLE_LCR_PAR 0 +#elif CONSOLE_PARITY == 1 +# define CONSOLE_LCR_PAR (UART_LCR_PE|UART_LCR_PS_ODD) +#elif CONSOLE_PARITY == 2 +# define CONSOLE_LCR_PAR (UART_LCR_PE|UART_LCR_PS_EVEN) +#elif CONSOLE_PARITY == 3 +# define CONSOLE_LCR_PAR (UART_LCR_PE|UART_LCR_PS_STICK1) +#elif CONSOLE_PARITY == 4 +# define CONSOLE_LCR_PAR (UART_LCR_PE|UART_LCR_PS_STICK0) +#elif defined(HAVE_CONSOLE) +# error "Invalid CONFIG_UARTn_PARITY setting for CONSOLE" +#endif + +/* Get stop-bit setting for the console and USART0/2/3, UART1 */ + +#if CONSOLE_2STOP != 0 +# define CONSOLE_LCR_STOP UART_LCR_STOP +#else +# define CONSOLE_LCR_STOP 0 +#endif + +/* LCR and FCR values for the console */ + +#define CONSOLE_LCR_VALUE (CONSOLE_LCR_WLS | CONSOLE_LCR_PAR | CONSOLE_LCR_STOP) +#define CONSOLE_FCR_VALUE (UART_FCR_RXTRIGGER_8 | UART_FCR_TXRST |\ + UART_FCR_RXRST | UART_FCR_FIFOEN) + +/* We cannot allow the DLM/DLL divisor to become to small or will will lose too + * much accuracy. This following is a "fudge factor" that represents the minimum + * value of the divisor that we will permit. + */ + +#define UART_MINDL 32 + +/* Select a CCLK divider to produce the UART PCLK. The strategy is to select the + * smallest divisor that results in an solution within range of the 16-bit + * DLM and DLL divisor: + * + * BAUD = PCLK / (16 * DL), or + * DL = PCLK / BAUD / 16 + * + * Where: + * + * PCLK = CCLK / divisor + * + * Ignoring the fractional divider for now. + * + * Check divisor == 1. This works if the upper limit is met + * + * DL < 0xffff, or + * PCLK / BAUD / 16 < 0xffff, or + * CCLK / BAUD / 16 < 0xffff, or + * CCLK < BAUD * 0xffff * 16 + * BAUD > CCLK / 0xffff / 16 + * + * And the lower limit is met (we can't allow DL to get very close to one). + * + * DL >= MinDL + * CCLK / BAUD / 16 >= MinDL, or + * BAUD <= CCLK / 16 / MinDL + */ + +#if CONSOLE_BAUD < (LPC43_CCLK / 16 / UART_MINDL) +# define CONSOLE_CCLKDIV SYSCON_PCLKSEL_CCLK +# define CONSOLE_NUMERATOR (LPC43_CCLK) + +/* Check divisor == 2. This works if: + * + * 2 * CCLK / BAUD / 16 < 0xffff, or + * BAUD > CCLK / 0xffff / 8 + * + * And + * + * 2 * CCLK / BAUD / 16 >= MinDL, or + * BAUD <= CCLK / 8 / MinDL + */ + +#elif CONSOLE_BAUD < (LPC43_CCLK / 8 / UART_MINDL) +# define CONSOLE_CCLKDIV SYSCON_PCLKSEL_CCLK2 +# define CONSOLE_NUMERATOR (LPC43_CCLK / 2) + +/* Check divisor == 4. This works if: + * + * 4 * CCLK / BAUD / 16 < 0xffff, or + * BAUD > CCLK / 0xffff / 4 + * + * And + * + * 4 * CCLK / BAUD / 16 >= MinDL, or + * BAUD <= CCLK / 4 / MinDL + */ + +#elif CONSOLE_BAUD < (LPC43_CCLK / 4 / UART_MINDL) +# define CONSOLE_CCLKDIV SYSCON_PCLKSEL_CCLK4 +# define CONSOLE_NUMERATOR (LPC43_CCLK / 4) + +/* Check divisor == 8. This works if: + * + * 8 * CCLK / BAUD / 16 < 0xffff, or + * BAUD > CCLK / 0xffff / 2 + * + * And + * + * 8 * CCLK / BAUD / 16 >= MinDL, or + * BAUD <= CCLK / 2 / MinDL + */ + +#else /* if CONSOLE_BAUD < (LPC43_CCLK / 2 / UART_MINDL) */ +# define CONSOLE_CCLKDIV SYSCON_PCLKSEL_CCLK8 +# define CONSOLE_NUMERATOR (LPC43_CCLK / 8) +#endif + +/* Then this is the value to use for the DLM and DLL registers */ + +#define CONSOLE_DL (CONSOLE_NUMERATOR / (CONSOLE_BAUD << 4)) + +/************************************************************************** + * Private Types + **************************************************************************/ + +/************************************************************************** + * Private Function Prototypes + **************************************************************************/ + +/************************************************************************** + * Global Variables + **************************************************************************/ + +/************************************************************************** + * Private Variables + **************************************************************************/ + +/************************************************************************** + * Private Functions + **************************************************************************/ + +/************************************************************************** + * Public Functions + **************************************************************************/ + +/************************************************************************** + * Name: up_lowputc + * + * Description: + * Output one byte on the serial console + * + **************************************************************************/ + +void up_lowputc(char ch) +{ +#if defined HAVE_UART && defined HAVE_CONSOLE + /* Wait for the transmitter to be available */ + + while ((getreg32(CONSOLE_BASE+LPC43_UART_LSR_OFFSET) & UART_LSR_THRE) == 0); + + /* Send the character */ + + putreg32((uint32_t)ch, CONSOLE_BASE+LPC43_UART_THR_OFFSET); +#endif +} + +/************************************************************************** + * Name: lpc43_lowsetup + * + * Description: + * This performs basic initialization of the UART used for the serial + * console. Its purpose is to get the console output availabe as soon + * as possible. + * + * The USART0/2/3 and UART1 peripherals are configured using the following registers: + * 1. Power: In the PCONP register, set bits PCUSART0/1/2/3. + * On reset, USART0 and UART 1 are enabled (PCUSART0 = 1 and PCUART1 = 1) + * and USART2/3 are disabled (PCUART1 = 0 and PCUSART3 = 0). + * 2. Peripheral clock: In the PCLKSEL0 register, select PCLK_USART0 and + * PCLK_UART1; in the PCLKSEL1 register, select PCLK_USART2 and PCLK_USART3. + * 3. Baud rate: In the LCR register, set bit DLAB = 1. This enables access + * to registers DLL and DLM for setting the baud rate. Also, if needed, + * set the fractional baud rate in the fractional divider + * 4. UART FIFO: Use bit FIFO enable (bit 0) in FCR register to + * enable FIFO. + * 5. Pins: Select UART pins through the PINSEL registers and pin modes + * through the PINMODE registers. UART receive pins should not have + * pull-down resistors enabled. + * 6. Interrupts: To enable UART interrupts set bit DLAB = 0 in the LCRF + * register. This enables access to IER. Interrupts are enabled + * in the NVIC using the appropriate Interrupt Set Enable register. + * 7. DMA: UART transmit and receive functions can operate with the + * GPDMA controller. + * + **************************************************************************/ + +void lpc43_lowsetup(void) +{ +#ifdef HAVE_UART + uint32_t regval; + + /* Step 1: Enable power for all console UART and disable power for + * other UARTs + * + * USART0/2/3 clocking and power control: + * + * ----------------------------------- -------------- -------------- + * BASE CLOCK BRANCH CLOCK + * ----------------------------------- -------------- -------------- + * USART0 clock to register interface BASE_M4_CLK CLK_M4_USART0 + * USART0 peripheral clock (PCLK) BASE_UART0_CLK CLK_APB0_UART0 + * UART1 clock to register interface BASE_M4_CLK CLK_M4_UART1 + * UART1 peripheral clock (PCLK) BASE_UART1_CLK CLK_APB0_UART1 + * USART2 clock to register interface BASE_M4_CLK CLK_M4_USART2 + * USART2 peripheral clock (PCLK) BASE_UART2_CLK CLK_APB2_UART2 + * USART3 clock to register interface BASE_M4_CLK CLK_M4_USART3 + * USART3 peripheral clock (PCLK) BASE_UART3_CLK CLK_APB2_UART3 + * ----------------------------------- -------------- -------------- + */ + +#warning "Missing logic" +#if 0 + regval = getreg32(LPC43_SYSCON_PCONP); + regval &= ~(SYSCON_PCONP_PCUSART0|SYSCON_PCONP_PCUART1| + SYSCON_PCONP_PCUSART2|SYSCON_PCONP_PCUSART3); +#if defined(CONFIG_USART0_SERIAL_CONSOLE) + regval |= SYSCON_PCONP_PCUSART0; +#elif defined(CONFIG_UART1_SERIAL_CONSOLE) + regval |= SYSCON_PCONP_PCUART1; +#elif defined(CONFIG_USART2_SERIAL_CONSOLE) + regval |= SYSCON_PCONP_PCUSART2; +#elif defined(CONFIG_USART3_SERIAL_CONSOLE) + regval |= SYSCON_PCONP_PCUSART3; +#endif + putreg32(regval, LPC43_SYSCON_PCONP); + +/* Step 2: Enable peripheral clocking for the console UART and disable + * clocking for all other UARTs + */ + + regval = getreg32(LPC43_SYSCON_PCLKSEL0); + regval &= ~(SYSCON_PCLKSEL0_USART0_MASK|SYSCON_PCLKSEL0_UART1_MASK); +#if defined(CONFIG_USART0_SERIAL_CONSOLE) + regval |= (CONSOLE_CCLKDIV << SYSCON_PCLKSEL0_USART0_SHIFT); +#elif defined(CONFIG_UART1_SERIAL_CONSOLE) + regval |= (CONSOLE_CCLKDIV << SYSCON_PCLKSEL0_UART1_SHIFT); +#endif + putreg32(regval, LPC43_SYSCON_PCLKSEL0); + + regval = getreg32(LPC43_SYSCON_PCLKSEL1); + regval &= ~(SYSCON_PCLKSEL1_USART2_MASK|SYSCON_PCLKSEL1_USART3_MASK); +#if defined(CONFIG_USART2_SERIAL_CONSOLE) + regval |= (CONSOLE_CCLKDIV << SYSCON_PCLKSEL1_USART2_SHIFT); +#elif defined(CONFIG_USART3_SERIAL_CONSOLE) + regval |= (CONSOLE_CCLKDIV << SYSCON_PCLKSEL1_USART3_SHIFT); +#endif + putreg32(regval, LPC43_SYSCON_PCLKSEL1); +#endif + + /* Configure UART pins for the selected CONSOLE. Definitions are + * required in the board.h header file in order to map pins to the + * correct pin and GPIO configuration. + */ + +#if defined(CONFIG_USART0_SERIAL_CONSOLE) + lpc43_pinconfig(PINCONF_U0_TXD); + lpc43_pinconfig(PINCONF_U0_RXD); +#elif defined(CONFIG_UART1_SERIAL_CONSOLE) + lpc43_pinconfig(PINCONF_U1_TXD); + lpc43_pinconfig(PINCONF_U1_RXD); +#ifdef CONFIG_UART1_FLOWCONTROL + lpc43_pinconfig(PINCONF_U1_CTS); + lpc43_pinconfig(PINCONF_U1_DCD); + lpc43_pinconfig(PINCONF_U1_DSR); + lpc43_pinconfig(PINCONF_U1_DTR); + lpc43_pinconfig(PINCONF_U1_RI); + lpc43_pinconfig(PINCONF_U1_RTS); +#endif +#elif defined(CONFIG_USART2_SERIAL_CONSOLE) + lpc43_pinconfig(PINCONF_U2_TXD); + lpc43_pinconfig(PINCONF_U2_RXD); +#elif defined(CONFIG_USART3_SERIAL_CONSOLE) + lpc43_pinconfig(PINCONF_U3_TXD); + lpc43_pinconfig(PINCONF_U3_RXD); +#endif + + /* Configure the console (only) */ + +#if defined(HAVE_CONSOLE) && !defined(CONFIG_SUPPRESS_UART_CONFIG) + + /* Clear fifos */ + + putreg32(UART_FCR_RXRST|UART_FCR_TXRST, CONSOLE_BASE+LPC43_UART_FCR_OFFSET); + + /* Set trigger */ + + putreg32(UART_FCR_FIFOEN|UART_FCR_RXTRIGGER_8, CONSOLE_BASE+LPC43_UART_FCR_OFFSET); + + /* Set up the LCR and set DLAB=1 */ + + putreg32(CONSOLE_LCR_VALUE|UART_LCR_DLAB, CONSOLE_BASE+LPC43_UART_LCR_OFFSET); + + /* Set the BAUD divisor */ + + putreg32(CONSOLE_DL >> 8, CONSOLE_BASE+LPC43_UART_DLM_OFFSET); + putreg32(CONSOLE_DL & 0xff, CONSOLE_BASE+LPC43_UART_DLL_OFFSET); + + /* Clear DLAB */ + + putreg32(CONSOLE_LCR_VALUE, CONSOLE_BASE+LPC43_UART_LCR_OFFSET); + + /* Configure the FIFOs */ + + putreg32(UART_FCR_RXTRIGGER_8|UART_FCR_TXRST|UART_FCR_RXRST|UART_FCR_FIFOEN, + CONSOLE_BASE+LPC43_UART_FCR_OFFSET); +#endif +#endif /* HAVE_UART */ +} + + diff --git a/nuttx/arch/arm/src/lpc43xx/lpc43_lowputc.h b/nuttx/arch/arm/src/lpc43xx/lpc43_lowputc.h index ee5e630f46..b15c9411c9 100644 --- a/nuttx/arch/arm/src/lpc43xx/lpc43_lowputc.h +++ b/nuttx/arch/arm/src/lpc43xx/lpc43_lowputc.h @@ -1,4 +1,4 @@ -/************************************************************************************ +/**************************************************************************** * arch/arm/src/lpc43xx/lpc43_lowputc.h * * Copyright (C) 2012 Gregory Nutt. All rights reserved. @@ -31,28 +31,28 @@ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. * - ************************************************************************************/ + ****************************************************************************/ #ifndef __ARCH_ARM_SRC_LPC43XX_LOWSETUP_H #define __ARCH_ARM_SRC_LPC43XX_LOWSETUP_H -/************************************************************************************ +/**************************************************************************** * Included Files - ************************************************************************************/ + ****************************************************************************/ #include -/************************************************************************************ +/**************************************************************************** * Pre-processor Definitions - ************************************************************************************/ + ****************************************************************************/ -/************************************************************************************ +/**************************************************************************** * Public Types - ************************************************************************************/ + ****************************************************************************/ -/************************************************************************************ +/**************************************************************************** * Public Data - ************************************************************************************/ + ****************************************************************************/ #ifndef __ASSEMBLY__ @@ -64,18 +64,18 @@ extern "C" { #define EXTERN extern #endif -/************************************************************************************ +/**************************************************************************** * Public Functions - ************************************************************************************/ + ****************************************************************************/ -/************************************************************************************ +/**************************************************************************** * Name: lpc43_lowsetup * * Description: - * Called at the very beginning of _start. Performs low level initialization - * of serial console. + * Called at the very beginning of _start. Performs low level + * initialization of the serial console. * - ************************************************************************************/ + ****************************************************************************/ EXTERN void lpc43_lowsetup(void); diff --git a/nuttx/arch/arm/src/lpc43xx/lpc43_pinconfig.c b/nuttx/arch/arm/src/lpc43xx/lpc43_pinconfig.c new file mode 100644 index 0000000000..d41d6f5884 --- /dev/null +++ b/nuttx/arch/arm/src/lpc43xx/lpc43_pinconfig.c @@ -0,0 +1,82 @@ +/**************************************************************************** + * arch/arm/src/lpc43/lpc43_pinconfig.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 "lpc43_pinconfig.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: lpc43_pinconfig + * + * Description: + * Configure a pin based on bit-encoded description of the pin. + * + * Input Value: + * 20-bit encoded value describing the pin. + * + * Returned Value: + * OK on success; A negated errno value on failure. + * + ****************************************************************************/ + +int lpc43_pinconfig(uint32_t pinconf) +{ +#warning "Missing logic" + return -ENOSYS; +} diff --git a/nuttx/arch/arm/src/lpc43xx/lpc43_pinconfig.h b/nuttx/arch/arm/src/lpc43xx/lpc43_pinconfig.h index 42ab5eb72d..27769f4b4a 100644 --- a/nuttx/arch/arm/src/lpc43xx/lpc43_pinconfig.h +++ b/nuttx/arch/arm/src/lpc43xx/lpc43_pinconfig.h @@ -265,17 +265,17 @@ extern "C" { * Returned Value: * OK on success; A negated errno value on failure. * - ************************************************************************************/ + ********************************************************************************************/ EXTERN int lpc43_pinconfig(uint32_t pinconf); -/************************************************************************************ +/******************************************************************************************** * Function: lpc43_dumppinconfig * * Description: - * Dump all pin configuration registers associated with the provided base address + * Dump all pin configuration registers associated with the provided pin configuration * - ************************************************************************************/ + ********************************************************************************************/ #ifdef CONFIG_DEBUG EXTERN int lpc43_dumppinconfig(uint32_t pinconf, const char *msg); diff --git a/nuttx/arch/arm/src/lpc43xx/lpc43_serial.h b/nuttx/arch/arm/src/lpc43xx/lpc43_serial.h new file mode 100644 index 0000000000..6d9a507937 --- /dev/null +++ b/nuttx/arch/arm/src/lpc43xx/lpc43_serial.h @@ -0,0 +1,65 @@ +/**************************************************************************** + * arch/arm/src/lpc43xx/lpc43_serial.h + * + * 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. + * + ****************************************************************************/ + +#ifndef __ARCH_ARM_SRC_LPC43XX_LPC43_SERIAL_H +#define __ARCH_ARM_SRC_LPC43XX_LPC43_SERIAL_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/**************************************************************************** + * Inline Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +#endif /* __ARCH_ARM_SRC_LPC43XX_LPC43_SERIAL_H */ diff --git a/nuttx/arch/arm/src/lpc43xx/lpc43_timerisr.c b/nuttx/arch/arm/src/lpc43xx/lpc43_timerisr.c new file mode 100644 index 0000000000..83a64e34f7 --- /dev/null +++ b/nuttx/arch/arm/src/lpc43xx/lpc43_timerisr.c @@ -0,0 +1,151 @@ +/**************************************************************************** + * arch/arm/src/lpc43xx/lpc43_timerisr.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 + +#include "nvic.h" +#include "clock_internal.h" +#include "up_internal.h" +#include "up_arch.h" + +#include "chip.h" + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/* The desired timer interrupt frequency is provided by the definition + * CLK_TCK (see include/time.h). CLK_TCK defines the desired number of + * system clock ticks per second. That value is a user configurable setting + * that defaults to 100 (100 ticks per second = 10 MS interval). + * + * The Clock Source: Either the internal CCLK or external STCLK (P3.26) clock + * as the source in the STCTRL register. This file alwyays configures the + * timer to use CCLK as its source. + */ + +#define SYSTICK_RELOAD ((LPC43_CCLK / CLK_TCK) - 1) + +/* The size of the reload field is 24 bits. Verify that the reload value + * will fit in the reload register. + */ + +#if SYSTICK_RELOAD > 0x00ffffff +# error SYSTICK_RELOAD exceeds the range of the RELOAD register +#endif + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Global Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: up_timerisr + * + * Description: + * The timer ISR will perform a variety of services for various portions + * of the systems. + * + ****************************************************************************/ + +int up_timerisr(int irq, uint32_t *regs) +{ + /* Process timer interrupt */ + + sched_process_timer(); + return 0; +} + +/**************************************************************************** + * Function: up_timerinit + * + * Description: + * This function is called during start-up to initialize + * the timer interrupt. + * + ****************************************************************************/ + +void up_timerinit(void) +{ + uint32_t regval; + + /* Set the SysTick interrupt to the default priority */ + + regval = getreg32(NVIC_SYSH12_15_PRIORITY); + regval &= ~NVIC_SYSH_PRIORITY_PR15_MASK; + regval |= (LPC43M4_SYSH_PRIORITY_DEFAULT << NVIC_SYSH_PRIORITY_PR15_SHIFT); + putreg32(regval, NVIC_SYSH12_15_PRIORITY); + + /* Make sure that the SYSTICK clock source is set to use the LPC43xx CCLK */ + + regval = getreg32(NVIC_SYSTICK_CTRL); + regval |= NVIC_SYSTICK_CTRL_CLKSOURCE; + putreg32(regval, NVIC_SYSTICK_CTRL); + + /* Configure SysTick to interrupt at the requested rate */ + + putreg32(SYSTICK_RELOAD, NVIC_SYSTICK_RELOAD); + + /* Attach the timer interrupt vector */ + + (void)irq_attach(LPC43_IRQ_SYSTICK, (xcpt_t)up_timerisr); + + /* Enable SysTick interrupts */ + + putreg32((NVIC_SYSTICK_CTRL_CLKSOURCE|NVIC_SYSTICK_CTRL_TICKINT| + NVIC_SYSTICK_CTRL_ENABLE), NVIC_SYSTICK_CTRL); + + /* And enable the timer interrupt */ + + up_enable_irq(LPC43_IRQ_SYSTICK); +} diff --git a/nuttx/configs/lpc4330-xplorer/README.txt b/nuttx/configs/lpc4330-xplorer/README.txt index 86e3f2f9ff..d1fcd7fb9e 100644 --- a/nuttx/configs/lpc4330-xplorer/README.txt +++ b/nuttx/configs/lpc4330-xplorer/README.txt @@ -12,7 +12,7 @@ Contents - GNU Toolchain Options - IDEs - NuttX buildroot Toolchain - - USB Device Controller Functions + - Serial Console - FPU - LPC4330-Xplorer Configuration Options - USB Host Configuration @@ -234,6 +234,22 @@ NuttX buildroot Toolchain NOTE: This is an OABI toolchain. +Serial Console +============== + +The LPC4330 Xplorer does not have RS-232 drivers or serial connectors on board. +USART0 and UART1 are available on J8 as follows: + + ------ ------ ----------------------- + SIGNAL J8 PIN LPC4330FET100 PIN + (TFBGA100 package) + ------ ------ ----------------------- + U0_TXD pin 9 F6 P6_4 U0_TXD=Alt 2 + U0_RXD pin 10 F9 P6_5 U0_RXD=Alt 2 + U1_TXD pin 13 H8 P1_13 U1_TXD=Alt 1 + U1_RXD pin 14 J8 P1_14 U1_RXD=Alt 1 + ------ ------ ----------------------- + FPU === diff --git a/nuttx/configs/lpc4330-xplorer/include/board.h b/nuttx/configs/lpc4330-xplorer/include/board.h index a8b926bfd0..6a3f36158b 100644 --- a/nuttx/configs/lpc4330-xplorer/include/board.h +++ b/nuttx/configs/lpc4330-xplorer/include/board.h @@ -170,26 +170,30 @@ #define LED_ASSERTION 2 /* NC ON NC OFF */ #define LED_PANIC 2 /* NC ON NC OFF */ -/* After the system is booted, this logic will no longer use LEDs 1 & 2. - * They are available for use the application software using lpc43_led - * (prototyped below) +/* UART Pins ****************************************************************/ +/* The LPC4330 Xplorer does not have RS-232 drivers or serial connectors on + * board. USART0 and UART1 are available on J8 as follows: + * + * ------ ------ ----------------------- + * SIGNAL J8 PIN LPC4330FET100 PIN + * (TFBGA100 package) + * ------ ------ ----------------------- + * U0_TXD pin 9 F6 P6_4 U0_TXD=Alt 2 + * U0_RXD pin 10 F9 P6_5 U0_RXD=Alt 2 + * U1_TXD pin 13 H8 P1_13 U1_TXD=Alt 1 + * U1_RXD pin 14 J8 P1_14 U1_RXD=Alt 1 + * ------ ------ ----------------------- + * + * The following definitions must be provided so that the LPC43 serial + * driver can set up the U[S]ART for the serial console properly (see the + * file arch/arc/src/lpc43xx/lpc4310203050_pinconf.h for more info). */ -#define GPIO_SSP0_SCK GPIO_SSP0_SCK_1 -#define GPIO_SSP0_SSEL GPIO_SSP0_SSEL_1 -#define GPIO_SSP0_MISO GPIO_SSP0_MISO_1 -#define GPIO_SSP0_MOSI GPIO_SSP0_MOSI_1 +#define PINCONF_U0_TXD PINCONF_U0_TXD_3 +#define PINCONF_U0_RXD PINCONF_U0_RXD_3 -/* We need to redefine USB_PWRD as GPIO to get USB Host working - * Also remember to add 2 resistors of 15K to D+ and D- pins. - */ - -#ifdef CONFIG_USBHOST -# ifdef GPIO_USB_PWRD -# undef GPIO_USB_PWRD -# define GPIO_USB_PWRD (GPIO_INPUT | GPIO_PORT1 | GPIO_PIN22) -# endif -#endif +#define PINCONF_U1_TXD PINCONF_U1_TXD_1 +#define PINCONF_U1_RXD PINCONF_U1_RXD_1 /**************************************************************************** * Public Types diff --git a/nuttx/configs/lpc4330-xplorer/ostest/defconfig b/nuttx/configs/lpc4330-xplorer/ostest/defconfig index 782a4931e3..6d6bd7b67f 100644 --- a/nuttx/configs/lpc4330-xplorer/ostest/defconfig +++ b/nuttx/configs/lpc4330-xplorer/ostest/defconfig @@ -82,8 +82,8 @@ CONFIG_ARCH_CHIP_LPC4330FET100=y CONFIG_ARCH_BOARD=lpc4330-xplorer CONFIG_ARCH_BOARD_LPC4330_XPLORER=y CONFIG_BOARD_LOOPSPERMSEC=7982 -CONFIG_DRAM_SIZE=(128*1024) -CONFIG_DRAM_START=0x10000000 +CONFIG_DRAM_SIZE=(72*1024) +CONFIG_DRAM_START=0x10080000 CONFIG_DRAM_END=(CONFIG_DRAM_START+CONFIG_DRAM_SIZE) CONFIG_ARCH_IRQPRIO=y CONFIG_ARCH_FPU=n @@ -94,6 +94,7 @@ CONFIG_ARCH_LEDS=y CONFIG_ARCH_BUTTONS=n CONFIG_ARCH_CALIBRATION=n CONFIG_ARCH_DMA=n +CONFIG_ARMV7M_CMNVECTOR=y # # Identify toolchain and linker options diff --git a/nuttx/configs/lpc4330-xplorer/src/xplorer_internal.h b/nuttx/configs/lpc4330-xplorer/src/xplorer_internal.h index 45c972a757..886382c651 100644 --- a/nuttx/configs/lpc4330-xplorer/src/xplorer_internal.h +++ b/nuttx/configs/lpc4330-xplorer/src/xplorer_internal.h @@ -85,6 +85,22 @@ #define LPC4330_XPLORER_BUT1_IRQ LPC43_IRQ_P0p23 +#define GPIO_SSP0_SCK GPIO_SSP0_SCK_1 +#define GPIO_SSP0_SSEL GPIO_SSP0_SSEL_1 +#define GPIO_SSP0_MISO GPIO_SSP0_MISO_1 +#define GPIO_SSP0_MOSI GPIO_SSP0_MOSI_1 + +/* We need to redefine USB_PWRD as GPIO to get USB Host working + * Also remember to add 2 resistors of 15K to D+ and D- pins. + */ + +#ifdef CONFIG_USBHOST +# ifdef GPIO_USB_PWRD +# undef GPIO_USB_PWRD +# define GPIO_USB_PWRD (GPIO_INPUT | GPIO_PORT1 | GPIO_PIN22) +# endif +#endif + /**************************************************************************** * Public Types ****************************************************************************/