This adds basic architectural support for the LPC546xx family and includes support for the LPCXpresso-LPC54628 board. The basic NSH port is almost complete... still lacking GPIO support and LED support. There are still no significant drivers available.

Squashed commit of the following:

    arch/arm/src/lpc54xx:  Finish off some missing logic.  Complete now execpt for GPIO and LED support.
    arch/arm/src/lpc54xx:  Add lpc54_clrpend.c
    arch/arm/src/lpc54xx:  Serial driver is complete and compiles.
    arch/arm/src/lpc54xx:  Add beginning of a serial driver (still missing some logic)
    arch/arm/src/lpc54xx:  Fleshes out low level USART intialization.
    arch/arm/src/lpc546xx/Kconfig: Add hooks to integrate with common seril upper half.
    arch/arm/src/lpc54xx:  Beginning of USART console support.
    arch/arm/src/lpc54xx: Completes very basic clock configuration.
    arch/arm/src/lpc54xx:  Add clocking logic (still not complete)
    arch/arm/src/lpc54xx:  Beginning of PLL configuration logic.
    arch/arm/src/lpc54xx:  Fix a few things from first compile attempt.  Compilation cannot work until I at least finish the clock configuration logic.
    arch/arm/src/lpc54xx: Addes some SysTick logic.
    arch/arm/src/lpc54xx:  Completes basic startup logic (sans clock configuration) and interrupt configuration.
     arch/arm/src/lpc54xx:  Add generic ARMv7-M start-up logic (needs LPC54628 customizations); add emtpy file that will eventually hold the clock configuration logic.
    arch/arm/src/lpc54xx:  Add (incomplete) SYSCON register definition header file.
    arch/arm/src/lpc54xx:  Add FLEXCOMM header file.
    arch/arm/src/lpc54xx:  Bring in tickless clock logic from LPC43; configs/lpcxpresso-lpc54628: mount procfs if enabled.
    arch/arm/src/lpc54xx: Add RIT clock definitions; add SysTick initialization (not finished)
    LPC54xx and LPCXpresso-LPC54628: add more boilerplate files and stubbed out files.
    arch/arm/src/lpc54xx:  Add (incomplete) USART header file.
    Add another condition to a Kconfig; refresh a defconfig.
    arch/arm/src/lpc54xx/chip: Add LPC54628 memory map header files.
    configs/lpcxpresso-lpc54628:  Add basic build files for the LPCXpresso-LPC54628
    arch/: Basic build directory structure for the LPC54628
This commit is contained in:
Gregory Nutt 2017-12-07 13:30:02 -06:00
parent ba64499bc7
commit 8bc90a1899
50 changed files with 9557 additions and 19 deletions

View file

@ -171,6 +171,17 @@ config ARCH_CHIP_LPC43XX
---help---
NPX LPC43XX architectures (ARM Cortex-M4).
config ARCH_CHIP_LPC54XX
bool "NXP LPC54XX"
select ARCH_CORTEXM4
select ARCH_HAVE_CMNVECTOR
select ARMV7M_CMNVECTOR
select ARCH_HAVE_MPU
select ARM_HAVE_MPU_UNIFIED
select ARCH_HAVE_FPU
---help---
NPX LPC54XX architectures (ARM Cortex-M4).
config ARCH_CHIP_MOXART
bool "MoxART"
select ARCH_ARM7TDMI
@ -522,6 +533,7 @@ config ARCH_CHIP
default "lpc2378" if ARCH_CHIP_LPC2378
default "lpc31xx" if ARCH_CHIP_LPC31XX
default "lpc43xx" if ARCH_CHIP_LPC43XX
default "lpc54xx" if ARCH_CHIP_LPC54XX
default "moxart" if ARCH_CHIP_MOXART
default "nuc1xx" if ARCH_CHIP_NUC1XX
default "sama5" if ARCH_CHIP_SAMA5
@ -763,6 +775,9 @@ endif
if ARCH_CHIP_LPC43XX
source arch/arm/src/lpc43xx/Kconfig
endif
if ARCH_CHIP_LPC54XX
source arch/arm/src/lpc54xx/Kconfig
endif
if ARCH_CHIP_MOXART
source arch/arm/src/moxart/Kconfig
endif

View file

@ -0,0 +1,134 @@
/************************************************************************************
* arch/arm/include/lpc54xx/chip.h
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
************************************************************************************/
#ifndef __ARCH_ARM_INCLUDE_LPC54XX_CHIP_H
#define __ARCH_ARM_INCLUDE_LPC54XX_CHIP_H
/************************************************************************************
* Included Files
************************************************************************************/
#include <nuttx/config.h>
/************************************************************************************
* Pre-processor Definitions
***********************************************************************************
/* LPC546xx Family Options.
*
* Family CPU Flash SRAM FS HS Ether- CAN CAN LCD Package
* MHz (Kb) (Kb) USB USB net 2.0 FD
* LPC54628 220 512 200 X X X X X X BGA180
* LPC54618 180 <=512 <=200 X X X X X X BGA180, LQFP208
* LPC54616 180 <=512 <=200 X X X X X BGA100, BGA180, LQFP100, LQFP208
* LPC54608 180 512 200 X X X X X BGA180, LQFP208
* LPC54607 180 <=512 <=200 X X X BGA180, LQFP208
* LPC54606 180 <=512 <=200 X X X X BGA100, BGA180, LQFP100, LQFP208
* LPC54605 180 <=512 <=200 X X BGA180
*/
/* NVIC priority levels *************************************************************/
/* Each priority field holds a priority value, 0-31. The lower the value, the greater
* the priority of the corresponding interrupt.
*
* The Cortex-M4 core supports 8 programmable interrupt priority levels.
*/
#define NVIC_SYSH_PRIORITY_MIN 0xe0 /* All bits[7:5] set is minimum priority */
#define NVIC_SYSH_PRIORITY_DEFAULT 0x80 /* Midpoint is the default */
#define NVIC_SYSH_PRIORITY_MAX 0x00 /* Zero is maximum priority */
#define NVIC_SYSH_PRIORITY_STEP 0x20 /* Steps between priorities */
/* If CONFIG_ARMV7M_USEBASEPRI is selected, then interrupts will be disabled
* by setting the BASEPRI register to NVIC_SYSH_DISABLE_PRIORITY so that most
* interrupts will not have execution priority. SVCall must have execution
* priority in all cases.
*
* In the normal cases, interrupts are not nest-able and all interrupts run
* at an execution priority between NVIC_SYSH_PRIORITY_MIN and
* NVIC_SYSH_PRIORITY_MAX (with NVIC_SYSH_PRIORITY_MAX reserved for SVCall).
*
* If, in addition, CONFIG_ARCH_HIPRI_INTERRUPT is defined, then special
* high priority interrupts are supported. These are not "nested" in the
* normal sense of the word. These high priority interrupts can interrupt
* normal processing but execute outside of OS (although they can "get back
* into the game" via a PendSV interrupt).
*
* In the normal course of things, interrupts must occasionally be disabled
* using the up_irq_save() inline function to prevent contention in use of
* resources that may be shared between interrupt level and non-interrupt
* level logic. Now the question arises, if CONFIG_ARCH_HIPRI_INTERRUPT,
* do we disable all interrupts (except SVCall), or do we only disable the
* "normal" interrupts. Since the high priority interrupts cannot interact
* with the OS, you may want to permit the high priority interrupts even if
* interrupts are disabled. The setting CONFIG_ARCH_INT_DISABLEALL can be
* used to select either behavior:
*
* ----------------------------+--------------+----------------------------
* CONFIG_ARCH_HIPRI_INTERRUPT | NO | YES
* ----------------------------+--------------+--------------+-------------
* CONFIG_ARCH_INT_DISABLEALL | N/A | YES | NO
* ----------------------------+--------------+--------------+-------------
* | | | SVCall
* | SVCall | SVCall | HIGH
* Disable here and below --------> MAXNORMAL ---> HIGH --------> MAXNORMAL
* | | MAXNORMAL |
* ----------------------------+--------------+--------------+-------------
*/
#if defined(CONFIG_ARCH_HIPRI_INTERRUPT) && defined(CONFIG_ARCH_INT_DISABLEALL)
# define NVIC_SYSH_MAXNORMAL_PRIORITY (NVIC_SYSH_PRIORITY_MAX + 2*NVIC_SYSH_PRIORITY_STEP)
# define NVIC_SYSH_HIGH_PRIORITY (NVIC_SYSH_PRIORITY_MAX + NVIC_SYSH_PRIORITY_STEP)
# define NVIC_SYSH_DISABLE_PRIORITY NVIC_SYSH_HIGH_PRIORITY
# define NVIC_SYSH_SVCALL_PRIORITY NVIC_SYSH_PRIORITY_MAX
#else
# define NVIC_SYSH_MAXNORMAL_PRIORITY (NVIC_SYSH_PRIORITY_MAX + NVIC_SYSH_PRIORITY_STEP)
# define NVIC_SYSH_HIGH_PRIORITY NVIC_SYSH_PRIORITY_MAX
# define NVIC_SYSH_DISABLE_PRIORITY NVIC_SYSH_MAXNORMAL_PRIORITY
# define NVIC_SYSH_SVCALL_PRIORITY NVIC_SYSH_PRIORITY_MAX
#endif
/************************************************************************************
* Public Types
************************************************************************************/
/************************************************************************************
* Public Data
************************************************************************************/
/************************************************************************************
* Public Functions
************************************************************************************/
#endif /* __ARCH_ARM_INCLUDE_LPC43XX_CHIP_H */

View file

@ -0,0 +1,112 @@
/********************************************************************************************
* arch/arm/include/lpc54xxx/irq.h
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
********************************************************************************************/
/* This file should never be included directed but, rather,
* only indirectly through nuttx/irq.h
*/
#ifndef __ARCH_ARM_INCLUDE_LPC54XX_IRQ_H
#define __ARCH_ARM_INCLUDE_LPC54XX_IRQ_H
/********************************************************************************************
* Included Files
********************************************************************************************/
#ifndef __ASSEMBLY__
# include <stdint.h>
#endif
/********************************************************************************************
* Pre-processor Definitions
********************************************************************************************/
/* IRQ numbers. The IRQ number corresponds vector number and hence map directly to bits in
* the NVIC. This does, however, waste several words of memory in the IRQ to handle mapping
* tables.
*/
/* Processor Exceptions (vectors 0-15) */
#define LPC54_IRQ_RESERVED (0) /* Reserved vector (only used with CONFIG_DEBUG_FEATURES) */
/* Vector 0: Reset stack pointer value */
/* Vector 1: Reset (not handler as an IRQ) */
#define LPC54_IRQ_NMI (2) /* Vector 2: Non-Maskable Interrupt (NMI) */
#define LPC54_IRQ_HARDFAULT (3) /* Vector 3: Hard fault */
#define LPC54_IRQ_MEMFAULT (4) /* Vector 4: Memory management (MPU) */
#define LPC54_IRQ_BUSFAULT (5) /* Vector 5: Bus fault */
#define LPC54_IRQ_USAGEFAULT (6) /* Vector 6: Usage fault */
#define LPC54_IRQ_SIGNVALUE (7) /* Vector 7: Sign value */
#define LPC54_IRQ_SVCALL (11) /* Vector 11: SVC call */
#define LPC54_IRQ_DBGMONITOR (12) /* Vector 12: Debug Monitor */
/* Vector 13: Reserved */
#define LPC54_IRQ_PENDSV (14) /* Vector 14: Pendable system service request */
#define LPC54_IRQ_SYSTICK (15) /* Vector 15: System tick */
#define LPC54_IRQ_EXTINT (16) /* Vector 16: Vector number of the first external interrupt */
/* Cortex-M4 External interrupts (vectors >= 16) */
#if defined(CONFIG_ARCH_FAMILY_LPC546XX)
# include <arch/lpc54xx/lpc546x_irq.h>
#else
# error "Unsupported LPC54 MCU"
#endif
/********************************************************************************************
* Public Types
********************************************************************************************/
#ifndef __ASSEMBLY__
typedef void (*vic_vector_t)(uint32_t *regs);
/********************************************************************************************
* Public Function Prototypes
********************************************************************************************/
#ifdef __cplusplus
#define EXTERN extern "C"
extern "C"
{
#else
#define EXTERN extern
#endif
#undef EXTERN
#ifdef __cplusplus
}
#endif
#endif
#endif /* __ARCH_ARM_INCLUDE_LPC54XX_IRQ_H */

View file

@ -0,0 +1,115 @@
/****************************************************************************************************
* arch/arm/include/lpc54xxx/lpc546x_irq.h
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************************************/
#ifndef __ARCH_ARM_INCLUDE_LPC54XX_LPC543X_IRQ_H
#define __ARCH_ARM_INCLUDE_LPC54XX_LPC543X_IRQ_H
/****************************************************************************************************
* Included Files
****************************************************************************************************/
/****************************************************************************************************
* Pre-processor Definitions
****************************************************************************************************/
/* Cortex-M4 External interrupts (vectors >= 16) */
#define LPC54_IRQ_WDT (LPC54_IRQ_EXTINT+0) /* VOD Windowed watchdog timer, Brownout detect */
#define LPC54_IRQ_DMA (LPC54_IRQ_EXTINT+1) /* DMA controller */
#define LPC54_IRQ_GINT0 (LPC54_IRQ_EXTINT+2) /* GPIO group 0 */
#define LPC54_IRQ_GINT1 (LPC54_IRQ_EXTINT+3) /* GPIO group 1 */
#define LPC54_IRQ_PININT0 (LPC54_IRQ_EXTINT+4) /* Pin interrupt 0 or pattern match engine slice 0 */
#define LPC54_IRQ_PININT1 (LPC54_IRQ_EXTINT+5) /* Pin interrupt 1or pattern match engine slice 1 */
#define LPC54_IRQ_PININT2 (LPC54_IRQ_EXTINT+6) /* Pin interrupt 2 or pattern match engine slice 2 */
#define LPC54_IRQ_PININT3 (LPC54_IRQ_EXTINT+7) /* Pin interrupt 3 or pattern match engine slice 3 */
#define LPC54_IRQ_UTICK (LPC54_IRQ_EXTINT+8) /* Micro-tick Timer */
#define LPC54_IRQ_MRT (LPC54_IRQ_EXTINT+9) /* Multi-rate timer */
#define LPC54_IRQ_CTIMER0 (LPC54_IRQ_EXTINT+10) /* Standard counter/timer CTIMER0 */
#define LPC54_IRQ_CTIMER1 (LPC54_IRQ_EXTINT+11) /* Standard counter/timer CTIMER1 */
#define LPC54_IRQ_SCTIMER (LPC54_IRQ_EXTINT+12) /* SCTimer/PWM0 */
#define LPC54_IRQ_PWM0 (LPC54_IRQ_EXTINT+12) /* SCTimer/PWM0 */
#define LPC54_IRQ_CTIMER3 (LPC54_IRQ_EXTINT+13) /* CTIMER3 Standard counter/timer CTIMER3 */
#define LPC54_IRQ_FLEXCOMM0 (LPC54_IRQ_EXTINT+14) /* Flexcomm Interface 0 (USART, SPI, I2C) */
#define LPC54_IRQ_FLEXCOMM1 (LPC54_IRQ_EXTINT+15) /* Flexcomm Interface 1 (USART, SPI, I2C) */
#define LPC54_IRQ_FLEXCOMM2 (LPC54_IRQ_EXTINT+16) /* Flexcomm Interface 2 (USART, SPI, I2C) */
#define LPC54_IRQ_FLEXCOMM3 (LPC54_IRQ_EXTINT+17) /* Flexcomm Interface 3 (USART, SPI, I2C) */
#define LPC54_IRQ_FLEXCOMM4 (LPC54_IRQ_EXTINT+18) /* Flexcomm Interface 4 (USART, SPI, I2C) */
#define LPC54_IRQ_FLEXCOMM5 (LPC54_IRQ_EXTINT+19) /* Flexcomm Interface 5 (USART, SPI, I2C) */
#define LPC54_IRQ_FLEXCOMM6 (LPC54_IRQ_EXTINT+20) /* Flexcomm Interface 6 (USART, SPI, I2C, I2S) */
#define LPC54_IRQ_FLEXCOMM7 (LPC54_IRQ_EXTINT+21) /* Flexcomm Interface 7 (USART, SPI, I2C, I2S) */
#define LPC54_IRQ_ADC0SEQA (LPC54_IRQ_EXTINT+22) /* ADC0 sequence A completion */
#define LPC54_IRQ_ADC0SEQB (LPC54_IRQ_EXTINT+23) /* ADC0 sequence B completion */
#define LPC54_IRQ_ADC0THCMP (LPC54_IRQ_EXTINT+24) /* ADC0 threshold compare and error */
#define LPC54_IRQ_DMIC (LPC54_IRQ_EXTINT+25) /* Digital microphone and audio subsystem */
#define LPC54_IRQ_HWVAD (LPC54_IRQ_EXTINT+26) /* Hardware Voice Activity Detection */
#define LPC54_IRQ_USB0NEEDCLK (LPC54_IRQ_EXTINT+27) /* USB0 Activity Interrupt */
#define LPC54_IRQ_USB0 (LPC54_IRQ_EXTINT+28) /* USB0 host and device */
#define LPC54_IRQ_RTC (LPC54_IRQ_EXTINT+29) /* RTC alarm and wake-up interrupts */
/* 30-31 Reserved */
#define LPC54_IRQ_PININT4 (LPC54_IRQ_EXTINT+32) /* Pin interrupt 4 or pattern match engine slice 4 */
#define LPC54_IRQ_PININT5 (LPC54_IRQ_EXTINT+33) /* Pin interrupt 5 or pattern match engine slice 5 */
#define LPC54_IRQ_PININT6 (LPC54_IRQ_EXTINT+34) /* Pin interrupt 6 or pattern match engine slice 6 */
#define LPC54_IRQ_PININT7 (LPC54_IRQ_EXTINT+35) /* Pin interrupt 7 or pattern match engine slice 7 */
#define LPC54_IRQ_CTIMER2 (LPC54_IRQ_EXTINT+36) /* Standard counter/timer CTIMER2 */
#define LPC54_IRQ_CTIMER4 (LPC54_IRQ_EXTINT+37) /* Standard counter/timer CTIMER4 */
#define LPC54_IRQ_RIT (LPC54_IRQ_EXTINT+38) /* Repetitive Interrupt Timer */
#define LPC54_IRQ_SPIFI (LPC54_IRQ_EXTINT+39) /* SPI flash interface */
#define LPC54_IRQ_FLEXCOMM8 (LPC54_IRQ_EXTINT+40) /* Flexcomm Interface 8 (USART, SPI, I2C) */
#define LPC54_IRQ_FLEXCOMM9 (LPC54_IRQ_EXTINT+41) /* Flexcomm Interface 9 (USART, SPI, I2C) */
#define LPC54_IRQ_SDIO (LPC54_IRQ_EXTINT+42) /* SD/MMC interrupt */
#define LPC54_IRQ_CAN0IRQ0 (LPC54_IRQ_EXTINT+43) /* CAN0 interrupt 0 */
#define LPC54_IRQ_CAN0IRQ1 (LPC54_IRQ_EXTINT+44) /* CAN0 interrupt 1 */
#define LPC54_IRQ_CAN1IRQ0 (LPC54_IRQ_EXTINT+45) /* CAN1 interrupt 0 */
#define LPC54_IRQ_CAN1IRQ1 (LPC54_IRQ_EXTINT+46) /* CAN1 interrupt 1 */
#define LPC54_IRQ_USB1 (LPC54_IRQ_EXTINT+47) /* USB1 interrupt */
#define LPC54_IRQ_USB1NEEDCLK (LPC54_IRQ_EXTINT+48) /* USB1 activity */
#define LPC54_IRQ_ETHERNET (LPC54_IRQ_EXTINT+49) /* Ethernet */
#define LPC54_IRQ_ETHERNETPMT (LPC54_IRQ_EXTINT+50) /* Ethernet power management interrupt */
#define LPC54_IRQ_ETHERNETMACLP (LPC54_IRQ_EXTINT+51) /* Ethernet MAC interrupt */
#define LPC54_IRQ_EEPROM (LPC54_IRQ_EXTINT+52) /* EEPROM interrupt */
#define LPC54_IRQ_LCD (LPC54_IRQ_EXTINT+53) /* LCD interrupt */
#define LPC54_IRQ_SHA (LPC54_IRQ_EXTINT+54) /* SHA interrupt */
#define LPC54_IRQ_SMARTCARD0 (LPC54_IRQ_EXTINT+55) /* Smart card 0 interrupt */
#define LPC54_IRQ_SMARTCARD1 (LPC54_IRQ_EXTINT+56) /* Smart card 1 interrupt */
#define LPC54_IRQ_NEXTINT (57)
#define LPC54_IRQ_NIRQS (LPC54_IRQ_EXTINT+LPC54_IRQ_NEXTINT)
/* Total number of IRQ numbers */
#define NR_VECTORS LPC54_IRQ_NIRQS
#define NR_IRQS LPC54_IRQ_NIRQS
#endif /* __ARCH_ARM_INCLUDE_LPC54XX_LPC543X_IRQ_H */

View file

@ -1,6 +1,5 @@
/****************************************************************************
* 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 <gnutt@nuttx.org>

View file

@ -197,7 +197,7 @@ static inline bool lpc43_tl_get_interrupt(void)
/* Converters */
static uint32_t commonDev(uint32_t a, uint32_t b)
static uint32_t common_dev(uint32_t a, uint32_t b)
{
while (b != 0)
{
@ -449,17 +449,17 @@ static void lpc43_tl_looped_forced_set_compare(void)
static bool lpc43_tl_set_calc_arm(uint32_t curr, uint32_t to_set, bool arm)
{
uint32_t calcTime;
uint32_t calc_time;
if (curr < TO_RESET_NEXT)
{
calcTime = min(TO_RESET_NEXT, to_set);
calc_time = min(TO_RESET_NEXT, to_set);
}
else
{
if (curr < TO_END)
{
calcTime = min(curr + RESET_TICKS, to_set);
calc_time = min(curr + RESET_TICKS, to_set);
}
else
{
@ -468,9 +468,9 @@ static bool lpc43_tl_set_calc_arm(uint32_t curr, uint32_t to_set, bool arm)
}
}
bool set = lpc43_tl_set_safe_compare(calcTime);
bool set = lpc43_tl_set_safe_compare(calc_time);
if (arm && set && (calcTime == to_set))
if (arm && set && (calc_time == to_set))
{
armed = true;
}
@ -557,17 +557,17 @@ static int lpc43_tl_isr(int irq, FAR void *context, FAR void *arg)
{
if (alarm_time_set) /* need to set alarm time */
{
uint32_t toSet = lpc43_tl_calc_to_set();
uint32_t toset = lpc43_tl_calc_to_set();
if (toSet > curr)
if (toset > curr)
{
if (toSet > TO_END)
if (toset > TO_END)
{
lpc43_tl_set_default_compare(curr);
}
else
{
bool set = lpc43_tl_set_calc_arm(curr, toSet, true);
bool set = lpc43_tl_set_calc_arm(curr, toset, true);
if (!set)
{
lpc43_tl_alarm(curr);
@ -605,7 +605,7 @@ void arm_timer_initialize(void)
mask_cache = getreg32(LPC43_RIT_MASK);
compare_cache = getreg32(LPC43_RIT_COMPVAL);
COMMON_DEV = commonDev(NSEC_PER_SEC, LPC43_CCLK);
COMMON_DEV = common_dev(NSEC_PER_SEC, LPC43_CCLK);
MIN_TICKS = LPC43_CCLK/COMMON_DEV;
MIN_NSEC = NSEC_PER_SEC/COMMON_DEV;
@ -651,16 +651,16 @@ int up_timer_gettime(FAR struct timespec *ts)
if (lpc43_tl_get_reset_on_match())
{
bool resetAfter = lpc43_tl_get_interrupt();
bool reset_after = lpc43_tl_get_interrupt();
/* Was a reset during processing? get new counter */
if (reset != resetAfter)
if (reset != reset_after)
{
count = lpc43_tl_get_counter();
}
if (resetAfter)
if (reset_after)
{
/* Count should be smaller then UINT32_MAX-TO_END -> no overflow */
@ -710,19 +710,19 @@ int up_alarm_start(FAR const struct timespec *ts)
alarm_time_ts.tv_sec = ts->tv_sec;
alarm_time_ts.tv_nsec = ts->tv_nsec;
uint32_t toSet = lpc43_tl_calc_to_set();
uint32_t toset = lpc43_tl_calc_to_set();
uint32_t curr = lpc43_tl_get_counter();
if (toSet > curr)
if (toset > curr)
{
if (toSet > TO_END) /* Future set */
if (toset > TO_END) /* Future set */
{
lpc43_tl_set_default_compare(curr);
}
else
{
bool set = lpc43_tl_set_calc_arm(curr, toSet, true);
bool set = lpc43_tl_set_calc_arm(curr, toset, true);
if (!set) /* Signal call, force interrupt handler */
{
call = true;

View file

@ -0,0 +1,228 @@
#
# For a description of the syntax of this configuration file,
# see the file kconfig-language.txt in the NuttX tools repository.
#
comment "LPC54xx Configuration Options"
choice
prompt "LPC54XX Chip Selection"
default ARCH_CHIP_LPC54628
depends on ARCH_CHIP_LPC54XX
config ARCH_CHIP_LPC54628
bool "LPC54628"
select ARCH_FAMILY_LPC546XX
select ARCH_LPC54_HAVE_FSUSB
select ARCH_LPC54_HAVE_HSUSB
select ARCH_LPC54_HAVE_ETHERNET
select ARCH_LPC54_HAVE_CAN20
select ARCH_LPC54_HAVE_CANFD
select ARCH_LPC54_HAVE_LCD
select ARCH_LPC54_HAVE_SHA
config ARCH_CHIP_LPC54618
bool "LPC54618"
select ARCH_FAMILY_LPC546XX
select ARCH_LPC54_HAVE_FSUSB
select ARCH_LPC54_HAVE_HSUSB
select ARCH_LPC54_HAVE_ETHERNET
select ARCH_LPC54_HAVE_CAN20
select ARCH_LPC54_HAVE_CANFD
select ARCH_LPC54_HAVE_LCD
config ARCH_CHIP_LPC54616
bool "LPC54616"
select ARCH_FAMILY_LPC546XX
select ARCH_LPC54_HAVE_FSUSB
select ARCH_LPC54_HAVE_HSUSB
select ARCH_LPC54_HAVE_ETHERNET
select ARCH_LPC54_HAVE_CAN20
select ARCH_LPC54_HAVE_CANFD
config ARCH_CHIP_LPC54608
bool "LPC54608"
select ARCH_FAMILY_LPC546XX
select ARCH_LPC54_HAVE_FSUSB
select ARCH_LPC54_HAVE_ETHERNET
select ARCH_LPC54_HAVE_CAN20
select ARCH_LPC54_HAVE_LCD
config ARCH_CHIP_LPC54607
bool "LPC54607"
select ARCH_FAMILY_LPC546XX
select ARCH_LPC54_HAVE_FSUSB
select ARCH_LPC54_HAVE_HSUSB
select ARCH_LPC54_HAVE_ETHERNET
config ARCH_CHIP_LPC54606
bool "LPC54606"
select ARCH_FAMILY_LPC546XX
select ARCH_LPC54_HAVE_FSUSB
select ARCH_LPC54_HAVE_HSUSB
select ARCH_LPC54_HAVE_ETHERNET
select ARCH_LPC54_HAVE_CAN20
config ARCH_CHIP_LPC54605
bool "LPC54605"
select ARCH_FAMILY_LPC546XX
select ARCH_LPC54_HAVE_FSUSB
select ARCH_LPC54_HAVE_HSUSB
endchoice # LPC54XX Chip Selection
# LPC54xx Families
config ARCH_FAMILY_LPC546XX
bool
default n
# Peripheral support
config ARCH_LPC54_HAVE_FSUSB
bool
default n
config ARCH_LPC54_HAVE_HSUSB
bool
default n
config ARCH_LPC54_HAVE_ETHERNET
bool
default n
config ARCH_LPC54_HAVE_CAN20
bool
default n
config ARCH_LPC54_HAVE_CANFD
bool
default n
config ARCH_LPC54_HAVE_LCD
bool
default n
config ARCH_LPC54_HAVE_SHA
bool
default n
# Peripheral Selection
config LPC54_HAVE_FLEXCOMM
bool
default n
config LPC54_FLEXCOMM0
bool
default n
select LPC54_HAVE_FLEXCOMM
config LPC54_FLEXCOMM1
bool
default n
select LPC54_HAVE_FLEXCOMM
config LPC54_FLEXCOMM2
bool
default n
select LPC54_HAVE_FLEXCOMM
config LPC54_FLEXCOMM3
bool
default n
select LPC54_HAVE_FLEXCOMM
config LPC54_FLEXCOMM4
bool
default n
select LPC54_HAVE_FLEXCOMM
config LPC54_FLEXCOMM5
bool
default n
select LPC54_HAVE_FLEXCOMM
config LPC54_FLEXCOMM6
bool
default n
select LPC54_HAVE_FLEXCOMM
config LPC54_FLEXCOMM7
bool
default n
select LPC54_HAVE_FLEXCOMM
config LPC54_FLEXCOMM8
bool
default n
select LPC54_HAVE_FLEXCOMM
config LPC54_FLEXCOMM9
bool
default n
select LPC54_HAVE_FLEXCOMM
menu "LPC54xx Peripheral Selection"
config LPC54_USART0
bool "USART0"
default n
select LPC54_FLEXCOMM0
select USART0_SERIALDRIVER
config LPC54_USART1
bool "USART1"
default n
select LPC54_FLEXCOMM1
select USART1_SERIALDRIVER
config LPC54_USART2
bool "USART2"
default n
select LPC54_FLEXCOMM2
select USART2_SERIALDRIVER
config LPC54_USART3
bool "USART3"
default n
select LPC54_FLEXCOMM3
select USART3_SERIALDRIVER
config LPC54_USART4
bool "USART4"
default n
select LPC54_FLEXCOMM4
select USART4_SERIALDRIVER
config LPC54_USART5
bool "USART5"
default n
select LPC54_FLEXCOMM5
select USART5_SERIALDRIVER
config LPC54_USART6
bool "USART6"
default n
select LPC54_FLEXCOMM6
select USART6_SERIALDRIVER
config LPC54_USART7
bool "USART7"
default n
select LPC54_FLEXCOMM7
select USART7_SERIALDRIVER
config LPC54_USART8
bool "USART8"
default n
select LPC54_FLEXCOMM8
select USART8_SERIALDRIVER
config LPC54_USART9
bool "USART9"
default n
select LPC54_FLEXCOMM9
select USART9_SERIALDRIVER
endmenu # LPC54xx Peripheral Selection

View file

@ -0,0 +1,98 @@
############################################################################
# arch/arm/src/lpc54xx/Make.defs
#
# Copyright (C) 2017 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <gnutt@nuttx.org>
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name NuttX nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
HEAD_ASRC =
CMN_ASRCS = up_saveusercontext.S up_fullcontextrestore.S up_switchcontext.S
CMN_ASRCS += up_testset.S vfork.S
CMN_CSRCS = up_assert.c up_blocktask.c up_copyfullstate.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_stackframe.c
CMN_CSRCS += up_unblocktask.c up_usestack.c up_doirq.c up_hardfault.c
CMN_CSRCS += up_svcall.c up_vfork.c
ifeq ($(CONFIG_ARMV7M_LAZYFPU),y)
CMN_ASRCS += up_lazyexception.S
else
CMN_ASRCS += up_exception.S
endif
CMN_CSRCS += up_vectors.c
ifeq ($(CONFIG_ARCH_RAMVECTORS),y)
CMN_CSRCS += up_ramvec_initialize.c up_ramvec_attach.c
endif
ifeq ($(CONFIG_BUILD_PROTECTED),y)
CMN_CSRCS += up_mpu.c up_task_start.c up_pthread_start.c
ifneq ($(CONFIG_DISABLE_SIGNALS),y)
CMN_CSRCS += up_signal_dispatch.c
CMN_UASRCS += up_signal_handler.S
endif
endif
ifeq ($(CONFIG_STACK_COLORATION),y)
CMN_CSRCS += up_checkstack.c
endif
ifeq ($(CONFIG_ARCH_FPU),y)
CMN_ASRCS += up_fpu.S
ifneq ($(CONFIG_ARMV7M_CMNVECTOR),y)
CMN_CSRCS += up_copyarmstate.c
else ifeq ($(CONFIG_ARMV7M_LAZYFPU),y)
CMN_CSRCS += up_copyarmstate.c
endif
endif
CHIP_ASRCS =
CHIP_CSRCS = lpc54_start.c lpc54_clockconfig.c lpc54_irq.c lpc54_clrpend.c
CHIP_CSRCS += lpc54_allocateheap.c lpc54_lowputc.c lpc54_serial.c
ifneq ($(CONFIG_SCHED_TICKLESS),y)
CHIP_CSRCS += lpc54_timerisr.c
else
CHIP_CSRCS += lpc54_tickless.c
endif
ifeq ($(CONFIG_BUILD_PROTECTED),y)
CHIP_CSRCS += lpc54_userspace.c lpc54_mpuinit.c
endif
ifneq ($(CONFIG_ARCH_IDLE_CUSTOM),y)
CHIP_CSRCS += lpc54_idle.c
endif

View file

@ -0,0 +1,77 @@
/************************************************************************************
* arch/arm/src/lpc54xx/chip.h
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
************************************************************************************/
#ifndef __ARCH_ARM_SRC_LPC54XX_CHIP_H
#define __ARCH_ARM_SRC_LPC54XX_CHIP_H
/************************************************************************************
* Included Files
************************************************************************************/
#include <nuttx/config.h>
/* Include the memory map and the chip definitions file. Other chip hardware files
* should then include this file for the proper setup.
*/
#include <arch/irq.h>
#include <arch/lpc54xx/chip.h>
#include "chip/lpc54_memorymap.h"
/* If the common ARMv7-M vector handling logic is used, then it expects the
* following definition in this file that provides the number of supported external
* interrupts which, for this architecture, is provided in the arch/lpc54xx/chip.h
* header file.
*/
#define ARMV7M_PERIPHERAL_INTERRUPTS LPC54_IRQ_NEXTINT
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
/************************************************************************************
* Public Types
************************************************************************************/
/************************************************************************************
* Public Data
************************************************************************************/
/************************************************************************************
* Public Functions
************************************************************************************/
#endif /* __ARCH_ARM_SRC_LPC54XX_CHIP_H */

View file

@ -0,0 +1,153 @@
/****************************************************************************************************
* arch/arm/src/lpc54xx/chip/lpc546x_memorymap.h
*
* Copyright (C) 2016 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************************************/
#ifndef __ARCH_ARM_SRC_LPC54XX_CHIP_LPC546X_MEMORYMAP_H
#define __ARCH_ARM_SRC_LPC54XX_CHIP_LPC546X_MEMORYMAP_H
/****************************************************************************************************
* Included Files
****************************************************************************************************/
#include <nuttx/config.h>
/****************************************************************************************************
* Pre-processor Definitions
****************************************************************************************************/
/* Memory Map */
#define LPC54_FLASH_BASE 0x00000000 /* Flash memory (512 KB) */
#define LPC54_BOOTROM_BASE 0x03000000 /* Boot ROM with flash services in a 64 KB space. */
#define LPC54_SRAMX_BASE 0x04000000 /* I&D SRAM bank (32 KB) */
#define LPC54_SPIFLASH_BASE 0x10000000 /* SPIFI memory mapped access space (128 MB). */
#define LPC54_SRAM_BASE 0x20000000 /* SRAM banks (160 KB) */
#define LPC54_SRAMBB_BASE 0x22000000 /* SRAM bit band alias addressing (32 MB) */
#define LPC54_APB0_BASE 0x40000000 /* APB slave group 0 (128 KB) */
#define LPC54_APB1_BASE 0x40020000 /* APB slave group 1 (128 KB) */
#define LPC54_APB2_BASE 0x40040000 /* APB slave group 2 (128 KB) */
#define LPC54_AHB_BASE 0x40080000 /* AHB peripherals (256 KB) */
#define LPC54_USBSRAM_BASE 0x40100000 /* USB SRAM (8 KB) */
#define LPC54_PERIPHBB_BASE 0x42000000 /* Peripheral bit band alias addressing (32 MB) */
#define LPC54_SRAMCS0_BASE 0x80000000 /* Static memory chip select 0 (<=64MB) */
#define LPC54_SRAMCS1_BASE 0x88000000 /* Static memory chip select 1 (<=64MB) */
#define LPC54_SRAMCS2_BASE 0x90000000 /* Static memory chip select 2 (<=64MB) */
#define LPC54_SRAMCS3_BASE 0x98000000 /* Static memory chip select 3 (<=64MB) */
#define LPC54_DRAMCS0_BASE 0xa0000000 /* Dynamic memory chip select 0 (<=256MB) */
#define LPC54_DRAMCS1_BASE 0xa8000000 /* Dynamic memory chip select 1 (<=256MB) */
#define LPC54_DRAMCS2_BASE 0xb0000000 /* Dynamic memory chip select 2 (<=256MB) */
#define LPC54_DRAMCS3_BASE 0xb8000000 /* Dynamic memory chip select 3 (<=256MB) */
#define LPC54_CORTEXM4_BASE 0xe0000000 /* Cortex-M4 Private Peripheral Bus */
/* AHB Peripherals */
#define LPC54_SPIFI_BASE 0x40080000 /* SPIFI registers */
#define LPC54_EMC_BASE 0x40081000 /* EMC registers */
#define LPC54_DMA_BASE 0x40082000 /* DMA registers */
#define LPC54_LCD_BASE 0x40083000 /* LCD registers */
#define LPC54_FSUSB_BASE 0x40084000 /* FS USB device registers */
#define LPC54_SCTPWM_BASE 0x40085000 /* SC Timer / PWM */
#define LPC54_FLEXCOMM0_BASE 0x40086000 /* Flexcomm 0 */
#define LPC54_FLEXCOMM1_BASE 0x40087000 /* Flexcomm 1 */
#define LPC54_FLEXCOMM2_BASE 0x40088000 /* Flexcomm 2 */
#define LPC54_FLEXCOMM3_BASE 0x40089000 /* Flexcomm 3 */
#define LPC54_FLEXCOMM4_BASE 0x4008a000 /* Flexcomm 4 */
#define LPC54_GPIO_BASE 0x4008c000 /* High Speed GPIO */
#define LPC54_DMIC_BASE 0x40090000 /* D-Mic interface */
#define LPC54_ETHERNET_BASE 0x40092000 /* Ethernet */
#define LPC54_HSUSB_BASE 0x40094000 /* HS USB device */
#define LPC54_CRC_BASE 0x40095000 /* CRC engine */
#define LPC54_FLEXCOMM5_BASE 0x40096000 /* Flexcomm 5 */
#define LPC54_FLEXCOMM6_BASE 0x40097000 /* Flexcomm 6 */
#define LPC54_FLEXCOMM7_BASE 0x40098000 /* Flexcomm 7 */
#define LPC54_FLEXCOMM8_BASE 0x40099000 /* Flexcomm 8 */
#define LPC54_FLEXCOMM9_BASE 0x4009a000 /* Flexcomm 9 */
#define LPC54_SDIO_BASE 0x4009b000 /* SDIO */
#define LPC54_ISPAP_BASE 0x4009c000 /* ISP-AP interface */
#define LPC54_CAN0_BASE 0x4009d000 /* CAN 0 */
#define LPC54_CAN1_BASE 0x4009e000 /* CAN 1 */
#define LPC54_ADC_BASE 0x400a0000 /* ADC */
#define LPC54_SHA_BASE 0x400a1000 /* SHA registers */
#define LPC54_FSUSBHOST_BASE 0x400a2000 /* FS USB host registers */
#define LPC54_HSUSBHOST_BASE 0x400a3000 /* HS USB host registers */
#define LPC54_USBSRAM_BASE 0x40100000 /* USB SRAM (8 kB) */
#define LPC54_EPROM_BASE 0x40108000 /* EPROM (16 kB) */
/* APB Bridge 0 */
#define LP54_SYSCON_BASE 0x40000000 /* Syscon */
#define LP54_IOCON_BASE 0x40001000 /* IOCON */
#define LP54_GINT0_BASE 0x40002000 /* GINT0 */
#define LP54_GINT1_BASE 0x40003000 /* GINT1 */
#define LP54_PINT_BASE 0x40004000 /* Pin Interrupts (PINT) */
#define LP54_MUX_BASE 0x40005000 /* Input muxes */
#define LP54_CTIMER0_BASE 0x40008000 /* CTIMER0 */
#define LP54_CTIMER1_BASE 0x40009000 /* CTIMER1 */
#define LP54_WDT_BASE 0x4000c000 /* WDT */
#define LP54_MRT_BASE 0x4000d000 /* MRT */
#define LP54_MTICK_BASE 0x4000e000 /* Micro-Tick */
#define LP54_EEPROMC_BASE 0x40014000 /* EEPROM controller */
#define LP54_OTP_BASE 0x40016000 /* OTP controller */
/* APB Bridge 1 */
#define LP54_OSYSCON_BASE 0x40020000 /* Other system registers */
#define LP54_CTIMER2_BASE 0x40028000 /* CTIMER2 */
#define LP54_RTC_BASE 0x4002c000 /* RTC */
#define LP54_RIT_BASE 0x4002d000 /* RIT */
#define LP54_FLASHC_BASE 0x40034000 /* Flash controller */
#define LP54_SMARCARD0_BASE 0x40036000 /* Smart card 0 */
#define LP54_SMARCARD1_BASE 0x40037000 /* Smart card 1 */
#define LP54_RNG_BASE 0x4003a000 /* RNG */
/* Asynchronous APB bridge */
#define LP54_ASYSCON_BASE 0x40040000 /* Asynchronous Syscon */
#define LP54_CTIMER3_BASE 0x40048000 /* CTIMER3 */
#define LP54_CTIMER4_BASE 0x40049000 /* CTIMER4 */
/****************************************************************************************************
* Public Types
****************************************************************************************************/
/****************************************************************************************************
* Public Data
****************************************************************************************************/
/****************************************************************************************************
* Public Functions
****************************************************************************************************/
#endif /* __ARCH_ARM_SRC_LPC54XX_CHIP_LPC546X_MEMORYMAP_H */

View file

@ -0,0 +1,112 @@
/************************************************************************************
* arch/arm/src/lpc54xx/chip/lpc54_flexcomm.h
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
************************************************************************************/
#ifndef __ARCH_ARM_SRC_LPC54XX_CHIP_LPC54_FLEXCOMM_H
#define __ARCH_ARM_SRC_LPC54XX_CHIP_LPC54_FLEXCOMM_H
/************************************************************************************
* Included Files
************************************************************************************/
#include <nuttx/config.h>
#include "chip/lpc54_memorymap.h"
/* Register offsets *****************************************************************/
#define LPC54_FLEXCOMM_PSELID_OFFSET 0x0ff8 /* Peripheral Select /Flexcomm Interface ID */
#define LPC54_FLEXCOMM_PID_OFFSET 0x0ffc /* Peripheral identification register */
/* Register addresses ***************************************************************/
#define LPC54_FLEXCOMM0_PSELID (LPC54_FLEXCOMM0_BASE+LPC54_FLEXCOMM_PSELID_OFFSET)
#define LPC54_FLEXCOMM0_PID (LPC54_FLEXCOMM0_BASE+LPC54_FLEXCOMM_PID_OFFSET)
#define LPC54_FLEXCOMM1_PSELID (LPC54_FLEXCOMM1_BASE+LPC54_FLEXCOMM_PSELID_OFFSET)
#define LPC54_FLEXCOMM1_PID (LPC54_FLEXCOMM1_BASE+LPC54_FLEXCOMM_PID_OFFSET)
#define LPC54_FLEXCOMM2_PSELID (LPC54_FLEXCOMM2_BASE+LPC54_FLEXCOMM_PSELID_OFFSET)
#define LPC54_FLEXCOMM2_PID (LPC54_FLEXCOMM2_BASE+LPC54_FLEXCOMM_PID_OFFSET)
#define LPC54_FLEXCOMM3_PSELID (LPC54_FLEXCOMM3_BASE+LPC54_FLEXCOMM_PSELID_OFFSET)
#define LPC54_FLEXCOMM3_PID (LPC54_FLEXCOMM3_BASE+LPC54_FLEXCOMM_PID_OFFSET)
#define LPC54_FLEXCOMM4_PSELID (LPC54_FLEXCOMM4_BASE+LPC54_FLEXCOMM_PSELID_OFFSET)
#define LPC54_FLEXCOMM4_PID (LPC54_FLEXCOMM4_BASE+LPC54_FLEXCOMM_PID_OFFSET)
#define LPC54_FLEXCOMM5_PSELID (LPC54_FLEXCOMM5_BASE+LPC54_FLEXCOMM_PSELID_OFFSET)
#define LPC54_FLEXCOMM5_PID (LPC54_FLEXCOMM5_BASE+LPC54_FLEXCOMM_PID_OFFSET)
#define LPC54_FLEXCOMM6_PSELID (LPC54_FLEXCOMM6_BASE+LPC54_FLEXCOMM_PSELID_OFFSET)
#define LPC54_FLEXCOMM6_PID (LPC54_FLEXCOMM6_BASE+LPC54_FLEXCOMM_PID_OFFSET)
#define LPC54_FLEXCOMM7_PSELID (LPC54_FLEXCOMM7_BASE+LPC54_FLEXCOMM_PSELID_OFFSET)
#define LPC54_FLEXCOMM7_PID (LPC54_FLEXCOMM7_BASE+LPC54_FLEXCOMM_PID_OFFSET)
#define LPC54_FLEXCOMM8_PSELID (LPC54_FLEXCOMM8_BASE+LPC54_FLEXCOMM_PSELID_OFFSET)
#define LPC54_FLEXCOMM8_PID (LPC54_FLEXCOMM8_BASE+LPC54_FLEXCOMM_PID_OFFSET)
#define LPC54_FLEXCOMM9_PSELID (LPC54_FLEXCOMM9_BASE+LPC54_FLEXCOMM_PSELID_OFFSET)
#define LPC54_FLEXCOMM9_PID (LPC54_FLEXCOMM9_BASE+LPC54_FLEXCOMM_PID_OFFSET)
/* Register bit definitions *********************************************************/
/* Peripheral Select /Flexcomm Interface ID */
#define FLEXCOMM_PSELID_PERSEL_SHIFT (0) /* Bits 0-2: Peripheral Select */
#define FLEXCOMM_PSELID_PERSEL_MASK (7 << FLEXCOMM_PSELID_PERSEL_SHIFT)
# define FLEXCOMM_PSELID_PERSEL_NONE (0 << FLEXCOMM_PSELID_PERSEL_SHIFT) /* No peripheral selected */
# define FLEXCOMM_PSELID_PERSEL_USART (1 << FLEXCOMM_PSELID_PERSEL_SHIFT) /* USART function selected */
# define FLEXCOMM_PSELID_PERSEL_SPI (2 << FLEXCOMM_PSELID_PERSEL_SHIFT) /* SPI function selected */
# define FLEXCOMM_PSELID_PERSEL_I2C (3 << FLEXCOMM_PSELID_PERSEL_SHIFT) /* I2C function selected */
# define FLEXCOMM_PSELID_PERSEL_I2STX (4 << FLEXCOMM_PSELID_PERSEL_SHIFT) /* I2S transmit function */
# define FLEXCOMM_PSELID_PERSEL_I2SRX (5 << FLEXCOMM_PSELID_PERSEL_SHIFT) /* I2S receive function */
#define FLEXCOMM_PSELID_LOCK (1 << 3) /* Bit 3: Lock the peripheral select */
#define FLEXCOMM_PSELID_USARTPRESENT (1 << 4) /* Bit 4: USART present indicator */
#define FLEXCOMM_PSELID_SPIPRESENT (1 << 5) /* Bit 5: SPI present indicator */
#define FLEXCOMM_PSELID_I2CPRESENT (1 << 6) /* Bit 6: I2C present indicator */
#define FLEXCOMM_PSELID_I2SPRESENT (1 << 7) /* Bit 7: I2S present indicator */
#define FLEXCOMM_PSELID_ID_SHIFT (12) /* Bits 12-31: Flexcomm Interface ID */
#define FLEXCOMM_PSELID_ID_MASK (0xfffff << FLEXCOMM_PSELID_ID_SHIFT)
/* Peripheral identification register */
#define FLEXCOMM_PID_MINOR_SHIFT (8) /* Bits 8-11: Minor revision number */
#define FLEXCOMM_PID_MINOR_MASK (15 << FLEXCOMM_PID_MINOR_SHIFT)
#define FLEXCOMM_PID_MAJOR_SHIFT (12) /* Bits 12-15: Major revision number */
#define FLEXCOMM_PID_MAJOR_MASK (15 << FLEXCOMM_PID_MAJOR_SHIFT)
#define FLEXCOMM_PID_ID_SHIFT (16) /* Bits 15-31: Module ID for selected function */
#define FLEXCOMM_PID_ID_MASK (0xffff << FLEXCOMM_PID_ID_SHIFT)
#endif /* __ARCH_ARM_SRC_LPC54XX_CHIP_LPC54_FLEXCOMM_H */

View file

@ -0,0 +1,52 @@
/************************************************************************************
* arch/arm/src/lpc54xx/chip/lpc54_memorymap.h
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
************************************************************************************/
#ifndef __ARCH_ARM_SRC_LPC54XX_CHIP_LPC54_MEMORYMAP_H
#define __ARCH_ARM_SRC_LPC54XX_CHIP_LPC54_MEMORYMAP_H
/************************************************************************************
* Included Files
************************************************************************************/
#include <nuttx/config.h>
#if defined(CONFIG_ARCH_FAMILY_LPC546XX)
# include "chip/lpc546x_memorymap.h"
#else
# error "Unsupported LPC54 memory map"
#endif
#endif /* __ARCH_ARM_SRC_LPC54XX_CHIP_LPC54_MEMORYMAP_H */

View file

@ -0,0 +1,99 @@
/************************************************************************************
* arch/arm/src/lpc54xx/lpc54_rit.h
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
************************************************************************************/
#ifndef __ARCH_ARM_SRC_LPC54XX_CHIP_LPC54_RIT_H
#define __ARCH_ARM_SRC_LPC54XX_CHIP_LPC54_RIT_H
/************************************************************************************
* Included Files
************************************************************************************/
#include <nuttx/config.h>
#include "chip/lpc54_memorymap.h"
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
/* Register offsets *****************************************************************/
#define LPC54_RIT_COMPVAL_OFFSET 0x0000 /* LS 48-bit Compare register */
#define LPC54_RIT_MASK_OFFSET 0x0004 /* LS 48-bit Mask register */
#define LPC54_RIT_CTRL_OFFSET 0x0008 /* Control register */
#define LPC54_RIT_COUNTER_OFFSET 0x000c /* LS 48-bit counter */
#define LPC54_RIT_COMPVALH_OFFSET 0x0010 /* MS 48-bit Compare register */
#define LPC54_RIT_MASKH_OFFSET 0x0014 /* MS 48-bit Mask register */
#define LPC54_RIT_COUNTERH_OFFSET 0x001c /* MS 48-bit counter */
/* Register addresses ***************************************************************/
#define LPC54_RIT_COMPVAL (LPC54_RIT_BASE+LPC54_RIT_COMPVAL_OFFSET)
#define LPC54_RIT_MASK (LPC54_RIT_BASE+LPC54_RIT_MASK_OFFSET)
#define LPC54_RIT_CTRL (LPC54_RIT_BASE+LPC54_RIT_CTRL_OFFSET)
#define LPC54_RIT_COUNTER (LPC54_RIT_BASE+LPC54_RIT_COUNTER_OFFSET)
#define LPC54_RIT_COMPVALH (LPC54_RIT_BASE+LPC54_RIT_COMPVALH_OFFSET)
#define LPC54_RIT_MASKH (LPC54_RIT_BASE+LPC54_RIT_MASKH_OFFSET)
#define LPC54_RIT_COUNTERH (LPC54_RIT_BASE+LPC54_RIT_COUNTERH_OFFSET)
/* Register bit definitions *********************************************************/
/* LS Compare register (Bits 0-31: value compared to the counter) */
/* MS Compare register (Bits 21-47: value compared to the counter) */
/* LS Mask register (Bits 0-31: 32-bit mask value) */
/* MS Mask register (Bits 32-47: 16-bit mask value) */
/* Control register */
#define RIT_CTRL_INT (1 << 0) /* Bit 0: Interrupt flag */
#define RIT_CTRL_ENCLR (1 << 1) /* Bit 1: Timer enable clear */
#define RIT_CTRL_ENBR (1 << 2) /* Bit 2: Timer enable for debug */
#define RIT_CTRL_EN (1 << 3) /* Bit 3: Timer enable */
/* Bits 4-31: Reserved */
/* LS 48-bit counter (Bits 0-31: 48-bit up counter) */
/* MS 48-bit counter (Bits 32-47: 48-bit up counter) */
/************************************************************************************
* Public Types
************************************************************************************/
/************************************************************************************
* Public Data
************************************************************************************/
/************************************************************************************
* Public Functions
************************************************************************************/
#endif /* __ARCH_ARM_SRC_LPC54XX_CHIP_LPC54_RIT_H */

View file

@ -0,0 +1,763 @@
/********************************************************************************************
* arch/arm/src/lpc54xx/chip/lpc54_syscon.h
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
********************************************************************************************/
#ifndef __ARCH_ARM_SRC_LPC54XX_CHIP_LPC54_SYSCON_H
#define __ARCH_ARM_SRC_LPC54XX_CHIP_LPC54_SYSCON_H
/********************************************************************************************
* Included Files
********************************************************************************************/
#include <nuttx/config.h>
#include "chip/lpc54_memorymap.h"
/* Register offsets *************************************************************************/
/* Main system configuration */
#define LPC54_SYSCON_AHBMATPRIO_OFFSET 0x0010 /* AHB multilayer matrix priority control */
#define LPC54_SYSCON_SYSTCKCAL_OFFSET 0x0040 /* System tick counter calibration */
#define LPC54_SYSCON_NMISRC_OFFSET 0x0048 /* NMI source select */
#define LPC54_SYSCON_ASYNCAPBCTRL_OFFSET 0x004c /* Asynchronous APB control */
#define LPC54_SYSCON_PIOPORCAP0_OFFSET 0x00c0 /* POR captured value of port 0 */
#define LPC54_SYSCON_PIOPORCAP1_OFFSET 0x00c4 /* POR captured value of port 1 */
#define LPC54_SYSCON_PIORESCAP0_OFFSET 0x00d0 /* Reset captured value of port 0 */
#define LPC54_SYSCON_PIORESCAP1_OFFSET 0x00d4 /* Reset captured value of port 1 */
#define LPC54_SYSCON_PRESETCTRL0_OFFSET 0x0100 /* Peripheral reset control 0 */
#define LPC54_SYSCON_PRESETCTRL1_OFFSET 0x0104 /* Peripheral reset control 1 */
#define LPC54_SYSCON_PRESETCTRL2_OFFSET 0x0108 /* Peripheral reset control 2 */
#define LPC54_SYSCON_PRESETCTRLSET0_OFFSET 0x0120 /* Set bits in PRESETCTRL0 */
#define LPC54_SYSCON_PRESETCTRLSET1_OFFSET 0x0124 /* Set bits in PRESETCTRL1 */
#define LPC54_SYSCON_PRESETCTRLSET2_OFFSET 0x0128 /* Set bits in PRESETCTRL2 */
#define LPC54_SYSCON_PRESETCTRLCLR0_OFFSET 0x0140 /* Clear bits in PRESETCTRL0 */
#define LPC54_SYSCON_PRESETCTRLCLR1_OFFSET 0x0144 /* Clear bits in PRESETCTRL1 */
#define LPC54_SYSCON_PRESETCTRLCLR2_OFFSET 0x0148 /* Clear bits in PRESETCTRL2 */
#define LPC54_SYSCON_SYSRSTSTAT_OFFSET 0x01f0 /* System reset status register */
#define LPC54_SYSCON_AHBCLKCTRL0_OFFSET 0x0200 /* AHB Clock control 0 */
#define LPC54_SYSCON_AHBCLKCTRL1_OFFSET 0x0204 /* AHB Clock control 1 */
#define LPC54_SYSCON_AHBCLKCTRL2_OFFSET 0x0208 /* AHB Clock control 2 */
#define LPC54_SYSCON_AHBCLKCTRLSET0_OFFSET 0x0220 /* Set bits in AHBCLKCTRL0 */
#define LPC54_SYSCON_AHBCLKCTRLSET1_OFFSET 0x0224 /* Set bits in AHBCLKCTRL1 */
#define LPC54_SYSCON_AHBCLKCTRLSET2_OFFSET 0x0228 /* Set bits in AHBCLKCTRL2 */
#define LPC54_SYSCON_AHBCLKCTRLCLR0_OFFSET 0x0240 /* Clear bits in AHBCLKCTRL0 */
#define LPC54_SYSCON_AHBCLKCTRLCLR1_OFFSET 0x0244 /* Clear bits in AHBCLKCTRL1 */
#define LPC54_SYSCON_AHBCLKCTRLCLR2_OFFSET 0x0248 /* Clear bits in AHBCLKCTRL2 */
#define LPC54_SYSCON_MAINCLKSELA_OFFSET 0x0280 /* Main clock source select A */
#define LPC54_SYSCON_MAINCLKSELB_OFFSET 0x0284 /* Main clock source select B */
#define LPC54_SYSCON_CLKOUTSELA_OFFSET 0x0288 /* CLKOUT clock source select */
#define LPC54_SYSCON_SYSPLLCLKSEL_OFFSET 0x0290 /* PLL clock source select */
#define LPC54_SYSCON_AUDPLLCLKSEL_OFFSET 0x0298 /* Audio PLL clock source select */
#define LPC54_SYSCON_SPIFICLKSEL_OFFSET 0x02a0 /* SPIFI clock source select */
#define LPC54_SYSCON_ADCCLKSEL_OFFSET 0x02a4 /* ADC clock source select */
#define LPC54_SYSCON_USB0CLKSEL_OFFSET 0x02a8 /* USB0 clock source select */
#define LPC54_SYSCON_USB1CLKSEL_OFFSET 0x02ac /* USB1 clock source select */
#define LPC54_SYSCON_FCLKSEL0_OFFSET 0x02b0 /* Flexcomm Interface 0 clock source select */
#define LPC54_SYSCON_FCLKSEL1_OFFSET 0x02b4 /* Flexcomm Interface 1 clock source select */
#define LPC54_SYSCON_FCLKSEL2_OFFSET 0x02b8 /* Flexcomm Interface 2 clock source select */
#define LPC54_SYSCON_FCLKSEL3_OFFSET 0x02bc /* Flexcomm Interface 3 clock source select */
#define LPC54_SYSCON_FCLKSEL4_OFFSET 0x02c0 /* Flexcomm Interface 4 clock source select */
#define LPC54_SYSCON_FCLKSEL5_OFFSET 0x02c4 /* Flexcomm Interface 5 clock source select */
#define LPC54_SYSCON_FCLKSEL6_OFFSET 0x02c8 /* Flexcomm Interface 6 clock source select */
#define LPC54_SYSCON_FCLKSEL7_OFFSET 0x02cc /* Flexcomm Interface 7 clock source select */
#define LPC54_SYSCON_FCLKSEL8_OFFSET 0x02d0 /* Flexcomm Interface 8 clock source select */
#define LPC54_SYSCON_FCLKSEL9_OFFSET 0x02d4 /* Flexcomm Interface 9 clock source select */
#define LPC54_SYSCON_MCLKCLKSEL_OFFSET 0x02e0 /* MCLK clock source select */
#define LPC54_SYSCON_FRGCLKSEL_OFFSET 0x02e8 /* Fractional Rate Generator clock source select */
#define LPC54_SYSCON_DMICCLKSEL_OFFSET 0x02ec /* Digital microphone (DMIC) subsystem clock select */
#define LPC54_SYSCON_SCTCLKSEL_OFFSET 0x02f0 /* SCTimer/PWM clock source select */
#define LPC54_SYSCON_LCDCLKSEL_OFFSET 0x02f4 /* LCD clock source select */
#define LPC54_SYSCON_SDIOCLKSEL_OFFSET 0x02f8 /* SDIO clock source select */
#define LPC54_SYSCON_SYSTICKCLKDIV_OFFSET 0x0300 /* SYSTICK clock divider */
#define LPC54_SYSCON_ARMTRCLKDIV_OFFSET 0x0304 /* ARM Trace clock divider */
#define LPC54_SYSCON_CAN0CLKDIV_OFFSET 0x0308 /* MCAN0 clock divider */
#define LPC54_SYSCON_CAN1CLKDIV_OFFSET 0x030c /* MCAN1 clock divider */
#define LPC54_SYSCON_SC0CLKDIV_OFFSET 0x0310 /* Smartcard0 clock divider */
#define LPC54_SYSCON_SC1CLKDIV_OFFSET 0x0314 /* Smartcard1 clock divider */
#define LPC54_SYSCON_AHBCLKDIV_OFFSET 0x0380 /* System clock divider */
#define LPC54_SYSCON_CLKOUTDIV_OFFSET 0x0384 /* CLKOUT clock divider */
#define LPC54_SYSCON_FROHFDIV_OFFSET 0x0388 /* FROHF clock divider */
#define LPC54_SYSCON_SPIFICLKDIV_OFFSET 0x0390 /* SPIFI clock divider */
#define LPC54_SYSCON_ADCCLKDIV_OFFSET 0x0394 /* ADC clock divider */
#define LPC54_SYSCON_USB0CLKDIV_OFFSET 0x0398 /* USB0 clock divider */
#define LPC54_SYSCON_USB1CLKDIV_OFFSET 0x039c /* USB1 clock divider */
#define LPC54_SYSCON_FRGCTRL_OFFSET 0x03a0 /* Fractional rate divider */
#define LPC54_SYSCON_DMICCLKDIV_OFFSET 0x03a8 /* DMIC clock divider */
#define LPC54_SYSCON_MCLKDIV_OFFSET 0x03ac /* I2S MCLK clock divider */
#define LPC54_SYSCON_LCDCLKDIV_OFFSET 0x03b0 /* LCD clock divider */
#define LPC54_SYSCON_SCTCLKDIV_OFFSET 0x03b4 /* SCT/PWM clock divider */
#define LPC54_SYSCON_EMCCLKDIV_OFFSET 0x03b8 /* EMC clock divider */
#define LPC54_SYSCON_SDIOCLKDIV_OFFSET 0x03bc /* SDIO clock divider */
#define LPC54_SYSCON_FLASHCFG_OFFSET 0x0400 /* Flash wait states configuration */
#define LPC54_SYSCON_USB0CLKCTRL_OFFSET 0x040c /* USB0 clock control */
#define LPC54_SYSCON_USB0CLKSTAT_OFFSET 0x0410 /* USB0 clock status */
#define LPC54_SYSCON_FREQMECTRL_OFFSET 0x0418 /* Frequency measure register */
#define LPC54_SYSCON_MCLKIO_OFFSET 0x0420 /* MCLK input/output control */
#define LPC54_SYSCON_USB1CLKCTRL_OFFSET 0x0424 /* USB1 clock control */
#define LPC54_SYSCON_USB1CLKSTAT_OFFSET 0x0428 /* USB1 clock status */
#define LPC54_SYSCON_EMCSYSCTRL_OFFSET 0x0444 /* EMC system control */
#define LPC54_SYSCON_EMCDLYCTRL_OFFSET 0x0448 /* EMC clock delay control */
#define LPC54_SYSCON_EMCDLYCAL_OFFSET 0x044c /* EMC delay chain calibration control */
#define LPC54_SYSCON_ETHPHYSEL_OFFSET 0x0450 /* Ethernet PHY selection */
#define LPC54_SYSCON_ETHSBDCTRL_OFFSET 0x0454 /* Ethernet SBD flow control */
#define LPC54_SYSCON_SDIOCLKCTRL_OFFSET 0x0460 /* SDIO CCLKIN phase and delay control */
#define LPC54_SYSCON_FROCTRL_OFFSET 0x0500 /* FRO oscillator control */
#define LPC54_SYSCON_SYSOSCCTRL_OFFSET 0x0504 /* System oscillator control */
#define LPC54_SYSCON_WDTOSCCTRL_OFFSET 0x0508 /* Watchdog oscillator control */
#define LPC54_SYSCON_RTCOSCCTRL_OFFSET 0x050c /* RTC oscillator 32 kHz output control */
#define LPC54_SYSCON_USBPLLCTRL_OFFSET 0x051c /* USB PLL control */
#define LPC54_SYSCON_USBPLLSTAT_OFFSET 0x0520 /* USB PLL status */
#define LPC54_SYSCON_SYSPLLCTRL_OFFSET 0x0580 /* System PLL control */
#define LPC54_SYSCON_SYSPLLSTAT_OFFSET 0x0584 /* PLL status */
#define LPC54_SYSCON_SYSPLLNDEC_OFFSET 0x0588 /* PLL N divider */
#define LPC54_SYSCON_SYSPLLPDEC_OFFSET 0x058c /* PLL P divider */
#define LPC54_SYSCON_SYSPLLMDEC_OFFSET 0x0590 /* System PLL M divider */
#define LPC54_SYSCON_AUDPLLCTRL_OFFSET 0x05a0 /* Audio PLL control */
#define LPC54_SYSCON_AUDPLLSTAT_OFFSET 0x05a4 /* Audio PLL status */
#define LPC54_SYSCON_AUDPLLNDEC_OFFSET 0x05a8 /* Audio PLL N divider */
#define LPC54_SYSCON_AUDPLLPDEC_OFFSET 0x05ac /* Audio PLL P divider */
#define LPC54_SYSCON_AUDPLLMDEC_OFFSET 0x05b0 /* Audio PLL M divider */
#define LPC54_SYSCON_AUDPLLFRAC_OFFSET 0x05b4 /* Audio PLL fractional divider control */
#define LPC54_SYSCON_PDSLEEPCFG0_OFFSET 0x0600 /* Sleep configuration register 0 */
#define LPC54_SYSCON_PDSLEEPCFG1_OFFSET 0x0604 /* Sleep configuration register 1 */
#define LPC54_SYSCON_PDRUNCFG0_OFFSET 0x0610 /* Power configuration register 0 */
#define LPC54_SYSCON_PDRUNCFG1_OFFSET 0x0614 /* Power configuration register 1 */
#define LPC54_SYSCON_PDRUNCFGSET0_OFFSET 0x0620 /* Set bits in PDRUNCFG0 */
#define LPC54_SYSCON_PDRUNCFGSET1_OFFSET 0x0624 /* Set bits in PDRUNCFG1 */
#define LPC54_SYSCON_PDRUNCFGCLR0_OFFSET 0x0630 /* Clear bits in PDRUNCFG0 */
#define LPC54_SYSCON_PDRUNCFGCLR1_OFFSET 0x0634 /* Clear bits in PDRUNCFG1 */
#define LPC54_SYSCON_STARTER0_OFFSET 0x0680 /* Start logic 0 wake-up enable register */
#define LPC54_SYSCON_STARTER1_OFFSET 0x0684 /* Start logic 1 wake-up enable register */
#define LPC54_SYSCON_STARTERSET0_OFFSET 0x06a0 /* Set bits in STARTER0 */
#define LPC54_SYSCON_STARTERSET1_OFFSET 0x06a4 /* Set bits in STARTER1 */
#define LPC54_SYSCON_STARTERCLR0_OFFSET 0x06c0 /* Clear bits in STARTER0 */
#define LPC54_SYSCON_STARTERCLR1_OFFSET 0x06c4 /* Clear bits in STARTER1 */
#define LPC54_SYSCON_HWWAKE_OFFSET 0x0780 /* Configures special cases of hardware wake-up */
#define LPC54_SYSCON_AUTOCGOR_OFFSET 0x0e04 /* Auto clock-gate override */
#define LPC54_SYSCON_JTAGIDCODE_OFFSET 0x0ff4 /* JTAG ID code */
#define LPC54_SYSCON_DEVICE_ID0_OFFSET 0x0ff8 /* Part ID */
#define LPC54_SYSCON_DEVICE_ID1_OFFSET 0x0ffc /* Boot ROM and die revision */
/* Asynchronous system configuration */
#define LPC54_SYSCON_ASYNCPRESETCTRL_OFFSET 0x0000 /* Async peripheral reset control */
#define LPC54_SYSCON_ASYNCPRESETCTRLSET_OFFSET 0x0004 /* Set bits in ASYNCPRESETCTRL */
#define LPC54_SYSCON_ASYNCPRESETCTRLCLR_OFFSET 0x0008 /* Clear bits in ASYNCPRESETCTRL */
#define LPC54_SYSCON_ASYNCAPBCLKCTRL_OFFSET 0x0010 /* Async peripheral clock control */
#define LPC54_SYSCON_ASYNCAPBCLKCTRLSET_OFFSET 0x0014 /* Set bits in ASYNCAPBCLKCTRL */
#define LPC54_SYSCON_ASYNCAPBCLKCTRLCLR_OFFSET 0x0018 /* Clear bits in ASYNCAPBCLKCTRL */
#define LPC54_SYSCON_ASYNCAPBCLKSELA_OFFSET 0x0020 /* Async APB clock source select A */
/* Other system configuration */
#define LPC54_SYSCON_BODCTRL_OFFSET 0x0044 /* Brown-Out Detect control */
/* Register addresses ***********************************************************************/
/* Main system configuration */
#define LPC54_SYSCON_AHBMATPRIO (LP54_SYSCON_BASE+LPC54_SYSCON_AHBMATPRIO_OFFSET)
#define LPC54_SYSCON_SYSTCKCAL (LP54_SYSCON_BASE+LPC54_SYSCON_SYSTCKCAL_OFFSET)
#define LPC54_SYSCON_NMISRC (LP54_SYSCON_BASE+LPC54_SYSCON_NMISRC_OFFSET)
#define LPC54_SYSCON_ASYNCAPBCTRL (LP54_SYSCON_BASE+LPC54_SYSCON_ASYNCAPBCTRL_OFFSET)
#define LPC54_SYSCON_PIOPORCAP0 (LP54_SYSCON_BASE+LPC54_SYSCON_PIOPORCAP0_OFFSET)
#define LPC54_SYSCON_PIOPORCAP1 (LP54_SYSCON_BASE+LPC54_SYSCON_PIOPORCAP1_OFFSET)
#define LPC54_SYSCON_PIORESCAP0 (LP54_SYSCON_BASE+LPC54_SYSCON_PIORESCAP0_OFFSET)
#define LPC54_SYSCON_PIORESCAP1 (LP54_SYSCON_BASE+LPC54_SYSCON_PIORESCAP1_OFFSET)
#define LPC54_SYSCON_PRESETCTRL0 (LP54_SYSCON_BASE+LPC54_SYSCON_PRESETCTRL0_OFFSET)
#define LPC54_SYSCON_PRESETCTRL1 (LP54_SYSCON_BASE+LPC54_SYSCON_PRESETCTRL1_OFFSET)
#define LPC54_SYSCON_PRESETCTRL2 (LP54_SYSCON_BASE+LPC54_SYSCON_PRESETCTRL2_OFFSET)
#define LPC54_SYSCON_PRESETCTRLSET0 (LP54_SYSCON_BASE+LPC54_SYSCON_PRESETCTRLSET0_OFFSET)
#define LPC54_SYSCON_PRESETCTRLSET1 (LP54_SYSCON_BASE+LPC54_SYSCON_PRESETCTRLSET1_OFFSET)
#define LPC54_SYSCON_PRESETCTRLSET2 (LP54_SYSCON_BASE+LPC54_SYSCON_PRESETCTRLSET2_OFFSET)
#define LPC54_SYSCON_PRESETCTRLCLR0 (LP54_SYSCON_BASE+LPC54_SYSCON_PRESETCTRLCLR0_OFFSET)
#define LPC54_SYSCON_PRESETCTRLCLR1 (LP54_SYSCON_BASE+LPC54_SYSCON_PRESETCTRLCLR1_OFFSET)
#define LPC54_SYSCON_PRESETCTRLCLR2 (LP54_SYSCON_BASE+LPC54_SYSCON_PRESETCTRLCLR2_OFFSET)
#define LPC54_SYSCON_SYSRSTSTAT (LP54_SYSCON_BASE+LPC54_SYSCON_SYSRSTSTAT_OFFSET)
#define LPC54_SYSCON_AHBCLKCTRL0 (LP54_SYSCON_BASE+LPC54_SYSCON_AHBCLKCTRL0_OFFSET)
#define LPC54_SYSCON_AHBCLKCTRL1 (LP54_SYSCON_BASE+LPC54_SYSCON_AHBCLKCTRL1_OFFSET)
#define LPC54_SYSCON_AHBCLKCTRL2 (LP54_SYSCON_BASE+LPC54_SYSCON_AHBCLKCTRL2_OFFSET)
#define LPC54_SYSCON_AHBCLKCTRLSET0 (LP54_SYSCON_BASE+LPC54_SYSCON_AHBCLKCTRLSET0_OFFSET)
#define LPC54_SYSCON_AHBCLKCTRLSET1 (LP54_SYSCON_BASE+LPC54_SYSCON_AHBCLKCTRLSET1_OFFSET)
#define LPC54_SYSCON_AHBCLKCTRLSET2 (LP54_SYSCON_BASE+LPC54_SYSCON_AHBCLKCTRLSET2_OFFSET)
#define LPC54_SYSCON_AHBCLKCTRLCLR0 (LP54_SYSCON_BASE+LPC54_SYSCON_AHBCLKCTRLCLR0_OFFSET)
#define LPC54_SYSCON_AHBCLKCTRLCLR1 (LP54_SYSCON_BASE+LPC54_SYSCON_AHBCLKCTRLCLR1_OFFSET)
#define LPC54_SYSCON_AHBCLKCTRLCLR2 (LP54_SYSCON_BASE+LPC54_SYSCON_AHBCLKCTRLCLR2_OFFSET)
#define LPC54_SYSCON_MAINCLKSELA (LP54_SYSCON_BASE+LPC54_SYSCON_MAINCLKSELA_OFFSET)
#define LPC54_SYSCON_MAINCLKSELB (LP54_SYSCON_BASE+LPC54_SYSCON_MAINCLKSELB_OFFSET)
#define LPC54_SYSCON_CLKOUTSELA (LP54_SYSCON_BASE+LPC54_SYSCON_CLKOUTSELA_OFFSET)
#define LPC54_SYSCON_SYSPLLCLKSEL (LP54_SYSCON_BASE+LPC54_SYSCON_SYSPLLCLKSEL_OFFSET)
#define LPC54_SYSCON_AUDPLLCLKSEL (LP54_SYSCON_BASE+LPC54_SYSCON_AUDPLLCLKSEL_OFFSET)
#define LPC54_SYSCON_SPIFICLKSEL (LP54_SYSCON_BASE+LPC54_SYSCON_SPIFICLKSEL_OFFSET)
#define LPC54_SYSCON_ADCCLKSEL (LP54_SYSCON_BASE+LPC54_SYSCON_ADCCLKSEL_OFFSET)
#define LPC54_SYSCON_USB0CLKSEL (LP54_SYSCON_BASE+LPC54_SYSCON_USB0CLKSEL_OFFSET)
#define LPC54_SYSCON_USB1CLKSEL (LP54_SYSCON_BASE+LPC54_SYSCON_USB1CLKSEL_OFFSET)
#define LPC54_SYSCON_FCLKSEL0 (LP54_SYSCON_BASE+LPC54_SYSCON_FCLKSEL0_OFFSET)
#define LPC54_SYSCON_FCLKSEL1 (LP54_SYSCON_BASE+LPC54_SYSCON_FCLKSEL1_OFFSET)
#define LPC54_SYSCON_FCLKSEL2 (LP54_SYSCON_BASE+LPC54_SYSCON_FCLKSEL2_OFFSET)
#define LPC54_SYSCON_FCLKSEL3 (LP54_SYSCON_BASE+LPC54_SYSCON_FCLKSEL3_OFFSET)
#define LPC54_SYSCON_FCLKSEL4 (LP54_SYSCON_BASE+LPC54_SYSCON_FCLKSEL4_OFFSET)
#define LPC54_SYSCON_FCLKSEL5 (LP54_SYSCON_BASE+LPC54_SYSCON_FCLKSEL5_OFFSET)
#define LPC54_SYSCON_FCLKSEL6 (LP54_SYSCON_BASE+LPC54_SYSCON_FCLKSEL6_OFFSET)
#define LPC54_SYSCON_FCLKSEL7 (LP54_SYSCON_BASE+LPC54_SYSCON_FCLKSEL7_OFFSET)
#define LPC54_SYSCON_FCLKSEL8 (LP54_SYSCON_BASE+LPC54_SYSCON_FCLKSEL8_OFFSET)
#define LPC54_SYSCON_FCLKSEL9 (LP54_SYSCON_BASE+LPC54_SYSCON_FCLKSEL9_OFFSET)
#define LPC54_SYSCON_MCLKCLKSEL (LP54_SYSCON_BASE+LPC54_SYSCON_MCLKCLKSEL_OFFSET)
#define LPC54_SYSCON_FRGCLKSEL (LP54_SYSCON_BASE+LPC54_SYSCON_FRGCLKSEL_OFFSET)
#define LPC54_SYSCON_DMICCLKSEL (LP54_SYSCON_BASE+LPC54_SYSCON_DMICCLKSEL_OFFSET)
#define LPC54_SYSCON_SCTCLKSEL (LP54_SYSCON_BASE+LPC54_SYSCON_SCTCLKSEL_OFFSET)
#define LPC54_SYSCON_LCDCLKSEL (LP54_SYSCON_BASE+LPC54_SYSCON_LCDCLKSEL_OFFSET)
#define LPC54_SYSCON_SDIOCLKSEL (LP54_SYSCON_BASE+LPC54_SYSCON_SDIOCLKSEL_OFFSET)
#define LPC54_SYSCON_SYSTICKCLKDIV (LP54_SYSCON_BASE+LPC54_SYSCON_SYSTICKCLKDIV_OFFSET)
#define LPC54_SYSCON_ARMTRCLKDIV (LP54_SYSCON_BASE+LPC54_SYSCON_ARMTRCLKDIV_OFFSET)
#define LPC54_SYSCON_CAN0CLKDIV (LP54_SYSCON_BASE+LPC54_SYSCON_CAN0CLKDIV_OFFSET)
#define LPC54_SYSCON_CAN1CLKDIV (LP54_SYSCON_BASE+LPC54_SYSCON_CAN1CLKDIV_OFFSET)
#define LPC54_SYSCON_SC0CLKDIV (LP54_SYSCON_BASE+LPC54_SYSCON_SC0CLKDIV_OFFSET)
#define LPC54_SYSCON_SC1CLKDIV (LP54_SYSCON_BASE+LPC54_SYSCON_SC1CLKDIV_OFFSET)
#define LPC54_SYSCON_AHBCLKDIV (LP54_SYSCON_BASE+LPC54_SYSCON_AHBCLKDIV_OFFSET)
#define LPC54_SYSCON_CLKOUTDIV (LP54_SYSCON_BASE+LPC54_SYSCON_CLKOUTDIV_OFFSET)
#define LPC54_SYSCON_FROHFDIV (LP54_SYSCON_BASE+LPC54_SYSCON_FROHFDIV_OFFSET)
#define LPC54_SYSCON_SPIFICLKDIV (LP54_SYSCON_BASE+LPC54_SYSCON_SPIFICLKDIV_OFFSET)
#define LPC54_SYSCON_ADCCLKDIV (LP54_SYSCON_BASE+LPC54_SYSCON_ADCCLKDIV_OFFSET)
#define LPC54_SYSCON_USB0CLKDIV (LP54_SYSCON_BASE+LPC54_SYSCON_USB0CLKDIV_OFFSET)
#define LPC54_SYSCON_USB1CLKDIV (LP54_SYSCON_BASE+LPC54_SYSCON_USB1CLKDIV_OFFSET)
#define LPC54_SYSCON_FRGCTRL (LP54_SYSCON_BASE+LPC54_SYSCON_FRGCTRL_OFFSET)
#define LPC54_SYSCON_DMICCLKDIV (LP54_SYSCON_BASE+LPC54_SYSCON_DMICCLKDIV_OFFSET)
#define LPC54_SYSCON_MCLKDIV (LP54_SYSCON_BASE+LPC54_SYSCON_MCLKDIV_OFFSET)
#define LPC54_SYSCON_LCDCLKDIV (LP54_SYSCON_BASE+LPC54_SYSCON_LCDCLKDIV_OFFSET)
#define LPC54_SYSCON_SCTCLKDIV (LP54_SYSCON_BASE+LPC54_SYSCON_SCTCLKDIV_OFFSET)
#define LPC54_SYSCON_EMCCLKDIV (LP54_SYSCON_BASE+LPC54_SYSCON_EMCCLKDIV_OFFSET)
#define LPC54_SYSCON_SDIOCLKDIV (LP54_SYSCON_BASE+LPC54_SYSCON_SDIOCLKDIV_OFFSET)
#define LPC54_SYSCON_FLASHCFG (LP54_SYSCON_BASE+LPC54_SYSCON_FLASHCFG_OFFSET)
#define LPC54_SYSCON_USB0CLKCTRL (LP54_SYSCON_BASE+LPC54_SYSCON_USB0CLKCTRL_OFFSET)
#define LPC54_SYSCON_USB0CLKSTAT (LP54_SYSCON_BASE+LPC54_SYSCON_USB0CLKSTAT_OFFSET)
#define LPC54_SYSCON_FREQMECTRL (LP54_SYSCON_BASE+LPC54_SYSCON_FREQMECTRL_OFFSET)
#define LPC54_SYSCON_MCLKIO (LP54_SYSCON_BASE+LPC54_SYSCON_MCLKIO_OFFSET)
#define LPC54_SYSCON_USB1CLKCTRL (LP54_SYSCON_BASE+LPC54_SYSCON_USB1CLKCTRL_OFFSET)
#define LPC54_SYSCON_USB1CLKSTAT (LP54_SYSCON_BASE+LPC54_SYSCON_USB1CLKSTAT_OFFSET)
#define LPC54_SYSCON_EMCSYSCTRL (LP54_SYSCON_BASE+LPC54_SYSCON_EMCSYSCTRL_OFFSET)
#define LPC54_SYSCON_EMCDLYCTRL (LP54_SYSCON_BASE+LPC54_SYSCON_EMCDLYCTRL_OFFSET)
#define LPC54_SYSCON_EMCDLYCAL (LP54_SYSCON_BASE+LPC54_SYSCON_EMCDLYCAL_OFFSET)
#define LPC54_SYSCON_ETHPHYSEL (LP54_SYSCON_BASE+LPC54_SYSCON_ETHPHYSEL_OFFSET)
#define LPC54_SYSCON_ETHSBDCTRL (LP54_SYSCON_BASE+LPC54_SYSCON_ETHSBDCTRL_OFFSET)
#define LPC54_SYSCON_SDIOCLKCTRL (LP54_SYSCON_BASE+LPC54_SYSCON_SDIOCLKCTRL_OFFSET)
#define LPC54_SYSCON_FROCTRL (LP54_SYSCON_BASE+LPC54_SYSCON_FROCTRL_OFFSET)
#define LPC54_SYSCON_SYSOSCCTRL (LP54_SYSCON_BASE+LPC54_SYSCON_SYSOSCCTRL_OFFSET)
#define LPC54_SYSCON_WDTOSCCTRL (LP54_SYSCON_BASE+LPC54_SYSCON_WDTOSCCTRL_OFFSET)
#define LPC54_SYSCON_RTCOSCCTRL_ (LP54_SYSCON_BASE+LPC54_SYSCON_RTCOSCCTRL_OFFSET)
#define LPC54_SYSCON_USBPLLCTRL (LP54_SYSCON_BASE+LPC54_SYSCON_USBPLLCTRL_OFFSET)
#define LPC54_SYSCON_USBPLLSTAT (LP54_SYSCON_BASE+LPC54_SYSCON_USBPLLSTAT_OFFSET)
#define LPC54_SYSCON_SYSPLLCTRL (LP54_SYSCON_BASE+LPC54_SYSCON_SYSPLLCTRL_OFFSET)
#define LPC54_SYSCON_SYSPLLSTAT (LP54_SYSCON_BASE+LPC54_SYSCON_SYSPLLSTAT_OFFSET)
#define LPC54_SYSCON_SYSPLLNDEC (LP54_SYSCON_BASE+LPC54_SYSCON_SYSPLLNDEC_OFFSET)
#define LPC54_SYSCON_SYSPLLPDEC (LP54_SYSCON_BASE+LPC54_SYSCON_SYSPLLPDEC_OFFSET)
#define LPC54_SYSCON_SYSPLLMDEC (LP54_SYSCON_BASE+LPC54_SYSCON_SYSPLLMDEC_OFFSET)
#define LPC54_SYSCON_AUDPLLCTRL (LP54_SYSCON_BASE+LPC54_SYSCON_AUDPLLCTRL_OFFSET)
#define LPC54_SYSCON_AUDPLLSTAT (LP54_SYSCON_BASE+LPC54_SYSCON_AUDPLLSTAT_OFFSET)
#define LPC54_SYSCON_AUDPLLNDEC (LP54_SYSCON_BASE+LPC54_SYSCON_AUDPLLNDEC_OFFSET)
#define LPC54_SYSCON_AUDPLLPDEC (LP54_SYSCON_BASE+LPC54_SYSCON_AUDPLLPDEC_OFFSET)
#define LPC54_SYSCON_AUDPLLMDEC (LP54_SYSCON_BASE+LPC54_SYSCON_AUDPLLMDEC_OFFSET)
#define LPC54_SYSCON_AUDPLLFRAC (LP54_SYSCON_BASE+LPC54_SYSCON_AUDPLLFRAC_OFFSET)
#define LPC54_SYSCON_PDSLEEPCFG0 (LP54_SYSCON_BASE+LPC54_SYSCON_PDSLEEPCFG0_OFFSET)
#define LPC54_SYSCON_PDSLEEPCFG1 (LP54_SYSCON_BASE+LPC54_SYSCON_PDSLEEPCFG1_OFFSET)
#define LPC54_SYSCON_PDRUNCFG0 (LP54_SYSCON_BASE+LPC54_SYSCON_PDRUNCFG0_OFFSET)
#define LPC54_SYSCON_PDRUNCFG1 (LP54_SYSCON_BASE+LPC54_SYSCON_PDRUNCFG1_OFFSET)
#define LPC54_SYSCON_PDRUNCFGSET0 (LP54_SYSCON_BASE+LPC54_SYSCON_PDRUNCFGSET0_OFFSET)
#define LPC54_SYSCON_PDRUNCFGSET1 (LP54_SYSCON_BASE+LPC54_SYSCON_PDRUNCFGSET1_OFFSET)
#define LPC54_SYSCON_PDRUNCFGCLR0 (LP54_SYSCON_BASE+LPC54_SYSCON_PDRUNCFGCLR0_OFFSET)
#define LPC54_SYSCON_PDRUNCFGCLR1 (LP54_SYSCON_BASE+LPC54_SYSCON_PDRUNCFGCLR1_OFFSET)
#define LPC54_SYSCON_STARTER0 (LP54_SYSCON_BASE+LPC54_SYSCON_STARTER0_OFFSET)
#define LPC54_SYSCON_STARTER1 (LP54_SYSCON_BASE+LPC54_SYSCON_STARTER1_OFFSET)
#define LPC54_SYSCON_STARTERSET0 (LP54_SYSCON_BASE+LPC54_SYSCON_STARTERSET0_OFFSET)
#define LPC54_SYSCON_STARTERSET1 (LP54_SYSCON_BASE+LPC54_SYSCON_STARTERSET1_OFFSET)
#define LPC54_SYSCON_STARTERCLR0 (LP54_SYSCON_BASE+LPC54_SYSCON_STARTERCLR0_OFFSET)
#define LPC54_SYSCON_STARTERCLR1 (LP54_SYSCON_BASE+LPC54_SYSCON_STARTERCLR1_OFFSET)
#define LPC54_SYSCON_HWWAKE (LP54_SYSCON_BASE+LPC54_SYSCON_HWWAKE_OFFSET)
#define LPC54_SYSCON_AUTOCGOR (LP54_SYSCON_BASE+LPC54_SYSCON_AUTOCGOR_OFFSET)
#define LPC54_SYSCON_JTAGIDCODE (LP54_SYSCON_BASE+LPC54_SYSCON_JTAGIDCODE_OFFSET)
#define LPC54_SYSCON_DEVICE_ID0 (LP54_SYSCON_BASE+LPC54_SYSCON_DEVICE_ID0_OFFSET)
#define LPC54_SYSCON_DEVICE_ID1 (LP54_SYSCON_BASE+LPC54_SYSCON_DEVICE_ID1_OFFSET)
/* Asynchronous system configuration */
#define LPC54_SYSCON_ASYNCPRESETCTRL (LP54_ASYSCON_BASE+LPC54_SYSCON_ASYNCPRESETCTRL_OFFSET)
#define LPC54_SYSCON_ASYNCPRESETCTRLSET (LP54_ASYSCON_BASE+LPC54_SYSCON_ASYNCPRESETCTRLSET_OFFSET)
#define LPC54_SYSCON_ASYNCPRESETCTRLCLR (LP54_ASYSCON_BASE+LPC54_SYSCON_ASYNCPRESETCTRLCLR_OFFSET)
#define LPC54_SYSCON_ASYNCAPBCLKCTRL (LP54_ASYSCON_BASE+LPC54_SYSCON_ASYNCAPBCLKCTRL_OFFSET)
#define LPC54_SYSCON_ASYNCAPBCLKCTRLSET (LP54_ASYSCON_BASE+LPC54_SYSCON_ASYNCAPBCLKCTRLSET_OFFSET)
#define LPC54_SYSCON_ASYNCAPBCLKCTRLCLR (LP54_ASYSCON_BASE+LPC54_SYSCON_ASYNCAPBCLKCTRLCLR_OFFSET)
#define LPC54_SYSCON_ASYNCAPBCLKSELA (LP54_ASYSCON_BASE+LPC54_SYSCON_ASYNCAPBCLKSELA_OFFSET)
/* Other system configuration */
#define LPC54_SYSCON_BODCTRL (LP54_OSYSCON_BASE+LPC54_SYSCON_BODCTRL_OFFSET)
/* Register bit definitions *****************************************************************/
/* Main system configuration */
/* AHB multilayer matrix priority control */
#define SYSCON_AHBMATPRIO_
/* System tick counter calibration */
#define SYSCON_SYSTCKCAL_
/* NMI source select */
#define SYSCON_NMISRC_
/* Asynchronous APB control */
#define SYSCON_ASYNCAPBCTRL_
/* POR captured value of port 0 */
#define SYSCON_PIOPORCAP0_
/* POR captured value of port 1 */
#define SYSCON_PIOPORCAP1_
/* Reset captured value of port 0 */
#define SYSCON_PIORESCAP0_
/* Reset captured value of port 1 */
#define SYSCON_PIORESCAP1_
/* Peripheral reset control 0 */
#define SYSCON_PRESETCTRL0_
/* Peripheral reset control 1 */
#define SYSCON_PRESETCTRL1_
/* Peripheral reset control 2 */
#define SYSCON_PRESETCTRL2_
/* Set bits in PRESETCTRL0 */
#define SYSCON_PRESETCTRLSET0_
/* Set bits in PRESETCTRL1 */
#define SYSCON_PRESETCTRLSET1_
/* Set bits in PRESETCTRL2 */
#define SYSCON_PRESETCTRLSET2_
/* Clear bits in PRESETCTRL0 */
#define SYSCON_PRESETCTRLCLR0_
/* Clear bits in PRESETCTRL1 */
#define SYSCON_PRESETCTRLCLR1_
/* Clear bits in PRESETCTRL2 */
#define SYSCON_PRESETCTRLCLR2_
/* System reset status register */
#define SYSCON_SYSRSTSTAT_
/* AHB Clock control 0: AHBCLKCTRL0, AHBCLKCTRLCLR0, and AHBCLKCTRLSET0 */
#define SYSCON_AHBCLKCTRL0_ROM (1 << 1) /* Bit 1: Enables the clock for the Boot ROM */
#define SYSCON_AHBCLKCTRL0_SRAM1 (1 << 3) /* Bit 3: Enables the clock for SRAM1 */
#define SYSCON_AHBCLKCTRL0_SRAM2 (1 << 4) /* Bit 4: Enables the clock for SRAM2 */
#define SYSCON_AHBCLKCTRL0_SRAM3 (1 << 5) /* Bit 5: Enables the clock for SRAM3 */
#define SYSCON_AHBCLKCTRL0_FLASH (1 << 7) /* Bit 7: Enables the clock for the flash controller */
#define SYSCON_AHBCLKCTRL0_FMC (1 << 8) /* Bit 8: Enables the clock for the Flash accelerator */
#define SYSCON_AHBCLKCTRL0_EEPROM (1 << 9) /* Bit 9: Enables the clock for EEPROM */
#define SYSCON_AHBCLKCTRL0_SPIFI (1 << 10) /* Bit 10: Enables the clock for the SPIFI */
#define SYSCON_AHBCLKCTRL0_INPUTMUX (1 << 11) /* Bit 11: Enables the clock for the input muxes */
#define SYSCON_AHBCLKCTRL0_IOCON (1 << 13) /* Bit 13: Enables the clock for the IOCON block */
#define SYSCON_AHBCLKCTRL0_GPIO0 (1 << 14) /* Bit 14: Enables the clock for the GPIO0 port registers */
#define SYSCON_AHBCLKCTRL0_GPIO1 (1 << 15) /* Bit 15: Enables the clock for the GPIO1 port registers */
#define SYSCON_AHBCLKCTRL0_GPIO2 (1 << 16) /* Bit 16: Enables the clock for the GPIO2 port registers */
#define SYSCON_AHBCLKCTRL0_GPIO3 (1 << 17) /* Bit 17: Enables the clock for the GPIO3 port registers */
#define SYSCON_AHBCLKCTRL0_PINT (1 << 18) /* Bit 18: Enables the clock for the pin interrupt block */
#define SYSCON_AHBCLKCTRL0_GINT (1 << 19) /* Bit 19: Enables the clock for the grouped pin interrupt block */
#define SYSCON_AHBCLKCTRL0_DMA (1 << 20) /* Bit 20: Enables the clock for the DMA controller */
#define SYSCON_AHBCLKCTRL0_CRC (1 << 21) /* Bit 21: Enables the clock for the CRC engine */
#define SYSCON_AHBCLKCTRL0_WWDT (1 << 22) /* Bit 22: Enables the clock for the Watchdog Timer */
#define SYSCON_AHBCLKCTRL0_RTC (1 << 23) /* Bit 23: Enables the bus clock for the RTC */
#define SYSCON_AHBCLKCTRL0_ADC0 (1 << 27) /* Bit 27: Enables the clock for the ADC0 register interface */
/* AHB Clock control 1: AHBCLKCTRL1, AHBCLKCTRLCLR1, and AHBCLKCTRLSET1 */
#define SYSCON_AHBCLKCTRL1_MRT (1 << 0) /* Bit 0: Enables the clock for the Multi-Rate Timer */
#define SYSCON_AHBCLKCTRL1_RIT (1 << 1) /* Bit 1: Enables the clock for the Repetitive Interrupt Timer */
#define SYSCON_AHBCLKCTRL1_SCT0 (1 << 2) /* Bit 2: Enables the clock for SCT0 */
#define SYSCON_AHBCLKCTRL1_MCAN0 (1 << 7) /* Bit 7: Enables the clock for MCAN0 */
#define SYSCON_AHBCLKCTRL1_MCAN1 (1 << 8) /* Bit 8: Enables the clock for MCAN1 */
#define SYSCON_AHBCLKCTRL1_UTICK (1 << 10) /* Bit 10: Enables the clock for the Micro-tick Timer */
#define SYSCON_AHBCLKCTRL1_FLEXCOMM0 (1 << 11) /* Bit 11: Enables the clock for Flexcomm Interface 0 */
#define SYSCON_AHBCLKCTRL1_FLEXCOMM1 (1 << 12) /* Bit 12: Enables the clock for Flexcomm Interface 1 */
#define SYSCON_AHBCLKCTRL1_FLEXCOMM2 (1 << 13) /* Bit 13: Enables the clock for Flexcomm Interface 2 */
#define SYSCON_AHBCLKCTRL1_FLEXCOMM3 (1 << 14) /* Bit 14: Enables the clock for Flexcomm Interface 3 */
#define SYSCON_AHBCLKCTRL1_FLEXCOMM4 (1 << 15) /* Bit 15: Enables the clock for Flexcomm Interface 4 */
#define SYSCON_AHBCLKCTRL1_FLEXCOMM5 (1 << 16) /* Bit 16: Enables the clock for Flexcomm Interface 5 */
#define SYSCON_AHBCLKCTRL1_FLEXCOMM6 (1 << 17) /* Bit 17: Enables the clock for Flexcomm Interface 6 */
#define SYSCON_AHBCLKCTRL1_FLEXCOMM7 (1 << 18) /* Bit 18: Enables the clock for Flexcomm Interface 7 */
#define SYSCON_AHBCLKCTRL1_DMIC (1 << 19) /* Bit 19: Enables the clock for the digital microphone interface */
#define SYSCON_AHBCLKCTRL1_CTIMER2 (1 << 22) /* Bit 22: Enables the clock for CTIMER 2 */
#define SYSCON_AHBCLKCTRL1_USB0D (1 << 25) /* Bit 25: Enables the clock for the USB0 device interface */
#define SYSCON_AHBCLKCTRL1_CTIMER0 (1 << 26) /* Bit 26: Enables the clock for timer CTIMER0 */
#define SYSCON_AHBCLKCTRL1_CTIMER1 (1 << 27) /* Bit 27: Enables the clock for timer CTIMER1 */
/* AHB Clock control 2: AHBCLKCTRL2, AHBCLKCTRLCLR2, and AHBCLKCTRLSET2 */
#define SYSCON_AHBCLKCTRL2_LCD (1 << 2) /* Bit 2: Enables the clock for the LCD interface */
#define SYSCON_AHBCLKCTRL2_SDIO (1 << 3) /* Bit 3: Enables the clock for the SDIO interface */
#define SYSCON_AHBCLKCTRL2_USB1H (1 << 4) /* Bit 4: Enables the clock for the USB1 host interface */
#define SYSCON_AHBCLKCTRL2_USB1D (1 << 5) /* Bit 5: Enables the clock for the USB1 device interface */
#define SYSCON_AHBCLKCTRL2_USB1RAM (1 << 6) /* Bit 6: Enables the clock for the USB1 RAM interface */
#define SYSCON_AHBCLKCTRL2_EMC (1 << 7) /* Bit 7: Enables the clock for the EMC interface */
#define SYSCON_AHBCLKCTRL2_ETH (1 << 8) /* Bit 8: Enables the clock for the ethernet interface */
#define SYSCON_AHBCLKCTRL2_GPIO4 (1 << 9) /* Bit 9: Enables the clock for the GPIO4 interface */
#define SYSCON_AHBCLKCTRL2_GPIO5 (1 << 10) /* Bit 10: Enables the clock for the GPIO5 interface */
#define SYSCON_AHBCLKCTRL2_OTP (1 << 12) /* Bit 12: Enables the clock for the OTP interface */
#define SYSCON_AHBCLKCTRL2_RNG (1 << 13) /* Bit 13: Enables the clock for the RNG interface */
#define SYSCON_AHBCLKCTRL2_FLEXCOMM8 (1 << 14) /* Bit 14: Enables the clock for the Flexcomm Interface 8 */
#define SYSCON_AHBCLKCTRL2_FLEXCOMM9 (1 << 15) /* Bit 15: Enables the clock for the Flexcomm Interface 9 */
#define SYSCON_AHBCLKCTRL2_USB0HMR (1 << 16) /* Bit 16: Enables the clock for the USB host master interface */
#define SYSCON_AHBCLKCTRL2_USB0HSL (1 << 17) /* Bit 17: Enables the clock for the USB host slave interface */
#define SYSCON_AHBCLKCTRL2_SHA (1 << 18) /* Bit 18: Enables the clock for the SHA interface */
#define SYSCON_AHBCLKCTRL2_SC0 (1 << 19) /* Bit 19: Enables the clock for the Smart card0 interface */
#define SYSCON_AHBCLKCTRL2_SC1 (1 << 20) /* Bit 20: Enables the clock for the Smart card1 interface */
/* Main clock source select A */
#define SYSCON_MAINCLKSELA_SHIFT (0) /* Bits 0-1: Clock source for main clock */
#define SYSCON_MAINCLKSELA_MASK (3 << SYSCON_MAINCLKSELA_SHIFT)
# define SYSCON_MAINCLKSELA_FRO12 (0 << SYSCON_MAINCLKSELA_SHIFT) /* FRO 12 MHz (fro_12m) */
# define SYSCON_MAINCLKSELA_CLKIN (1 << SYSCON_MAINCLKSELA_SHIFT) /* CLKIN (clk_in) */
# define SYSCON_MAINCLKSELA_WDTCLK (2 << SYSCON_MAINCLKSELA_SHIFT) /* Watchdog oscillator (wdt_clk) */
# define SYSCON_MAINCLKSELA_FROHF (3 << SYSCON_MAINCLKSELA_SHIFT) /* FRO 96 or 48 MHz (fro_hf) */
/* Main clock source select B */
#define SYSCON_MAINCLKSELB_SHIFT (0) /* Bits 0-1: Clock source for main clock */
#define SYSCON_MAINCLKSELB_MASK (3 << SYSCON_MAINCLKSELB_SHIFT)
# define SYSCON_MAINCLKSELB_MAINCLKSELA (0 << SYSCON_MAINCLKSELB_SHIFT) /* Use MAINCLKSELA selection */
# define SYSCON_MAINCLKSELB_PLLCLK (2 << SYSCON_MAINCLKSELB_SHIFT) /* System PLL output (pll_clk) */
# define SYSCON_MAINCLKSELB_32KCLK (3 << SYSCON_MAINCLKSELB_SHIFT) /* RTC oscillator 32 kHz output (32k_clk) */
/* CLKOUT clock source select */
#define SYSCON_CLKOUTSELA_
/* PLL clock source select */
#define SYSCON_SYSPLLCLKSEL_SHIFT (0) /* Bits 0-2: System PLL clock source selection */
#define SYSCON_SYSPLLCLKSEL_MASK (7 << SYSCON_SYSPLLCLKSEL_SHIFT)
# define SYSCON_SYSPLLCLKSEL_FFRO (0 << SYSCON_SYSPLLCLKSEL_SHIFT) /* FRO 12 MHz (fro_12m) */
# define SYSCON_SYSPLLCLKSEL_CLKIN (1 << SYSCON_SYSPLLCLKSEL_SHIFT) /* CLKIN (clk_in) */
# define SYSCON_SYSPLLCLKSEL_RTC (3 << SYSCON_SYSPLLCLKSEL_SHIFT) /* RTC oscillator 32 KHz ouput */
# define SYSCON_SYSPLLCLKSEL_NONE (7 << SYSCON_SYSPLLCLKSEL_SHIFT) /* None */
/* Audio PLL clock source select */
#define SYSCON_AUDPLLCLKSEL_
/* SPIFI clock source select */
#define SYSCON_SPIFICLKSEL_
/* ADC clock source select */
#define SYSCON_ADCCLKSEL_
/* USB0 clock source select */
#define SYSCON_USB0CLKSEL_
/* USB1 clock source select */
#define SYSCON_USB1CLKSEL_
/* Flexcomm Interface 0..9 clock source select */
#define SYSCON_FCLKSEL_SHIFT (0) /* Bits 0-2: Flexcomm Interface clock source selection */
#define SYSCON_FCLKSEL_MASK (7 << SYSCON_FCLKSEL_SHIFT)
# define SYSCON_FCLKSEL_FRO12M (0 << SYSCON_FCLKSEL_SHIFT) /* FRO 12 MHz (fro_12m) */
# define SYSCON_FCLKSEL_FROHFDIV (1 << SYSCON_FCLKSEL_SHIFT) /* FRO 96 or 48 MHz divided (fro_hf_div) */
# define SYSCON_FCLKSEL_AUDPLLCLK (2 << SYSCON_FCLKSEL_SHIFT) /* Audio PLL clock (audio_pll_clk) */
# define SYSCON_FCLKSEL_MCLK (3 << SYSCON_FCLKSEL_SHIFT) /* MCK */
# define SYSCON_FCLKSEL_FRG (4 << SYSCON_FCLKSEL_SHIFT) /* FRG clock */
# define SYSCON_FCLKSEL_NONE (7 << SYSCON_FCLKSEL_SHIFT) /* None */
/* MCLK clock source select */
#define SYSCON_MCLKCLKSEL_SHIFT (0) /* Bits 0-2: MCLK source select */
#define SYSCON_MCLKCLKSEL_MASK (7 << SYSCON_MCLKCLKSEL_SHIFT)
# define SYSCON_MCLKCLKSEL_FROHFDIV (0 << SYSCON_MCLKCLKSEL_SHIFT) /* FRO 96 or 48 MHz divided (fro_hf_div) */
# define SYSCON_MCLKCLKSEL_AUDPLLCLK (1 << SYSCON_MCLKCLKSEL_SHIFT) /* Audio PLL clock (audio_pll_clk) */
# define SYSCON_MCLKCLKSEL_NONE (7 << SYSCON_MCLKCLKSEL_SHIFT) /* None */
/* Fractional Rate Generator clock source select */
#define SYSCON_FRGCLKSEL_SHIFT (0) /* Bits 0-2: Fractional Rate Generator clock source */
#define SYSCON_FRGCLKSEL_MASK (7 << SYSCON_FRGCLKSEL_SHIFT)
# define SYSCON_FRGCLKSEL_MAINCLK (0 << SYSCON_FRGCLKSEL_SHIFT) /* Main clock (main_clk) */
# define SYSCON_FRGCLKSEL_PLLCLK (1 << SYSCON_FRGCLKSEL_SHIFT) /* System PLL output (pll_clk) */
# define SYSCON_FRGCLKSEL_FRO12M (2 << SYSCON_FRGCLKSEL_SHIFT) /* FRO 12 MHz (fro_12m) */
# define SYSCON_FRGCLKSEL_FROHF (3 << SYSCON_FRGCLKSEL_SHIFT) /* FRO 96 or 48 MHz (fro_hf) */
# define SYSCON_FRGCLKSEL_NONE (7 << SYSCON_FRGCLKSEL_SHIFT) /* None */
/* Digital microphone (DMIC) subsystem clock select */
#define SYSCON_DMICCLKSEL_
/* SCTimer/PWM clock source select */
#define SYSCON_SCTCLKSEL_
/* LCD clock source select */
#define SYSCON_LCDCLKSEL_
/* SDIO clock source select */
#define SYSCON_SDIOCLKSEL_
/* SYSTICK clock divider */
#define SYSCON_SYSTICKCLKDIV_DIV_SHIFT (0) /* Bits 0-7: Clock divider value */
#define SYSCON_SYSTICKCLKDIV_DIV_MASK (0xff << SYSCON_SYSTICKCLKDIV_DIV_SHIFT)
# define SYSCON_SYSTICKCLKDIV_DIV(n) ((uint32_t)((n)-1) << SYSCON_SYSTICKCLKDIV_DIV_SHIFT)
#define SYSCON_SYSTICKCLKDIV_RESET (1 << 29) /* Bit 29: Resets the divider counter */
#define SYSCON_SYSTICKCLKDIV_HALT (1 << 30) /* Bit 30: Halts the divider counter */
#define SYSCON_SYSTICKCLKDIV_REQFLAG (1 << 31) /* Bit 31: Divider status flag */
/* ARM Trace clock divider */
#define SYSCON_ARMTRCLKDIV_
/* MCAN0 clock divider */
#define SYSCON_CAN0CLKDIV_
/* MCAN1 clock divider */
#define SYSCON_CAN1CLKDIV_
/* Smartcard0 clock divider */
#define SYSCON_SC0CLKDIV_
/* Smartcard1 clock divider */
#define SYSCON_SC1CLKDIV_
/* System clock divider */
#define SYSCON_AHBCLKDIV_DIV_SHIFT (0) /* Bits 0-7: Clock divider value */
#define SYSCON_AHBCLKDIV_DIV_MASK (0xff << SYSCON_AHBCLKDIV_DIV_SHIFT)
# define SYSCON_AHBCLKDIV_DIV(n) ((uint32_t)((n)-1) << SYSCON_AHBCLKDIV_DIV_SHIFT)
#define SYSCON_AHBCLKDIV_REQFLAG (1 << 31) /* Bit 32: Divider status flag */
/* CLKOUT clock divider */
#define SYSCON_CLKOUTDIV_
/* FROHF clock divider */
#define SYSCON_FROHFDIV_
/* SPIFI clock divider */
#define SYSCON_SPIFICLKDIV_
/* ADC clock divider */
#define SYSCON_ADCCLKDIV_
/* USB0 clock divider */
#define SYSCON_USB0CLKDIV_
/* USB1 clock divider */
#define SYSCON_USB1CLKDIV_
/* Fractional rate divider */
#define SYSCON_FRGCTRL_DIV_SHIFT (0) /* Bits 0-7: Denominator of the fractional divider */
#define SYSCON_FRGCTRL_DIV_MASK (0xff << SYSCON_FRGCTRL_DIV_SHIFT)
# define SYSCON_FRGCTRL_DIV(n) ((uint32_t)((n)-1) << SYSCON_FRGCTRL_DIV_SHIFT)
#define SYSCON_FRGCTRL_MULT_SHIFT (8) /* Bit 8-15: Numerator of the fractional divider */
#define SYSCON_FRGCTRL_MULT_MASK (0xff << SYSCON_FRGCTRL_MULT_SHIFT)
# define SYSCON_FRGCTRL_MULT(n) ((uint32_t)(n) << SYSCON_FRGCTRL_MULT_SHIFT)
/* DMIC clock divider */
#define SYSCON_DMICCLKDIV_
/* I2S MCLK clock divider */
#define SYSCON_MCLKDIV_
/* LCD clock divider */
#define SYSCON_LCDCLKDIV_
/* SCT/PWM clock divider */
#define SYSCON_SCTCLKDIV_
/* EMC clock divider */
#define SYSCON_EMCCLKDIV_
/* SDIO clock divider */
#define SYSCON_SDIOCLKDIV_
/* Flash wait states configuration */
#define SYSCON_FLASHCFG_FETCHCFG_SHIFT (0) /* Bits 0-1: Instruction fetch configuration */
#define SYSCON_FLASHCFG_FETCHCFG_MASK (3 << SYSCON_FLASHCFG_FETCHCFG_SHIFT)
# define SYSCON_FLASHCFG_FETCHCFG_NONE (0 << SYSCON_FLASHCFG_FETCHCFG_SHIFT) /* Instruction fetches not buffered */
# define SYSCON_FLASHCFG_FETCHCFG_ONE (1 << SYSCON_FLASHCFG_FETCHCFG_SHIFT) /* One buffer used for instruction fetches */
# define SYSCON_FLASHCFG_FETCHCFG_ALL (2 << SYSCON_FLASHCFG_FETCHCFG_SHIFT) /* All buffers used for instruction fetches */
#define SYSCON_FLASHCFG_DATACFG_SHIFT (2) /* Bit 2-3: Data read configuration */
#define SYSCON_FLASHCFG_DATACFG_MASK (3 << SYSCON_FLASHCFG_DATACFG_SHIFT)
# define SYSCON_FLASHCFG_DATACFG_NONE (0 << SYSCON_FLASHCFG_DATACFG_SHIFT) /* Data accesses from flash not buffered */
# define SYSCON_FLASHCFG_DATACFG_ONE (1 << SYSCON_FLASHCFG_DATACFG_SHIFT) /* One buffer used for data accesses */
# define SYSCON_FLASHCFG_DATACFG_ALL (2 << SYSCON_FLASHCFG_DATACFG_SHIFT) /* All buffers used for data accesses */
#define SYSCON_FLASHCFG_ACCEL (1 << 4) /* Bit 4: Acceleration enable */
#define SYSCON_FLASHCFG_PREFEN (1 << 5) /* Bit 5: Prefetch enable */
#define SYSCON_FLASHCFG_PREFOVR (1 << 6) /* Bit 6: Prefetch override */
#define SYSCON_FLASHCFG_FLASHTIM_SHIFT (12) /* Bits 12-15: Flash memory access time */
#define SYSCON_FLASHCFG_FLASHTIM_MASK (15 << SYSCON_FLASHCFG_FLASHTIM_SHIFT)
# define SYSCON_FLASHCFG_FLASHTIM(n) ((uint32_t)((n)-1) << SYSCON_FLASHCFG_FLASHTIM_SHIFT)
/* USB0 clock control */
#define SYSCON_USB0CLKCTRL_
/* USB0 clock status */
#define SYSCON_USB0CLKSTAT_
/* Frequency measure register */
#define SYSCON_FREQMECTRL_
/* MCLK input/output control */
#define SYSCON_MCLKIO_
/* USB1 clock control */
#define SYSCON_USB1CLKCTRL_
/* USB1 clock status */
#define SYSCON_USB1CLKSTAT_
/* EMC system control */
#define SYSCON_EMCSYSCTRL_
/* EMC clock delay control */
#define SYSCON_EMCDLYCTRL_
/* EMC delay chain calibration control */
#define SYSCON_EMCDLYCAL_
/* Ethernet PHY selection */
#define SYSCON_ETHPHYSEL_
/* Ethernet SBD flow control */
#define SYSCON_ETHSBDCTRL_
/* SDIO CCLKIN phase and delay control */
#define SYSCON_SDIOCLKCTRL_
/* FRO oscillator control */
#define SYSCON_FROCTRL_
/* System oscillator control */
#define SYSCON_SYSOSCCTRL_
/* Watchdog oscillator control */
#define SYSCON_WDTOSCCTRL_
/* RTC oscillator 32 kHz output control */
#define SYSCON_RTCOSCCTRL_
/* USB PLL control */
#define SYSCON_USBPLLCTRL_
/* USB PLL status */
#define SYSCON_USBPLLSTAT_
/* System PLL control */
#define SYSCON_SYSPLLCTRL_SELR_SHIFT (0) /* Bits 0-3: Bandwidth select R value */
#define SYSCON_SYSPLLCTRL_SELR_MASK (15 << SYSCON_SYSPLLCTRL_SELR_SHIFT)
# define SYSCON_SYSPLLCTRL_SELR(n) ((uint32_t)((n)-1) << SYSCON_SYSPLLCTRL_SELR_SHIFT)
#define SYSCON_SYSPLLCTRL_SELI_SHIFT (4) /* Bits 4-9: Bandwidth select I value */
#define SYSCON_SYSPLLCTRL_SELI_MASK (0x3f << SYSCON_SYSPLLCTRL_SELI_SHIFT)
# define SYSCON_SYSPLLCTRL_SELI(n) ((uint32_t)((n)-1) << SYSCON_SYSPLLCTRL_SELI_SHIFT)
#define SYSCON_SYSPLLCTRL_SELP_SHIFT (10) /* Bits 10-14: Bandwidth select P value */
#define SYSCON_SYSPLLCTRL_SELP_MASK (0x1f << SYSCON_SYSPLLCTRL_SELP_SHIFT)
# define SYSCON_SYSPLLCTRL_SELP(n) ((uint32_t)((n)-1) << SYSCON_SYSPLLCTRL_SELP_SHIFT)
#define SYSCON_SYSPLLCTRL_BYPASS (1 << 15) /* Bit 15: PLL bypass control */
#define SYSCON_SYSPLLCTRL_UPLIMOFF (1 << 17) /* Bit 17: Disable upper frequency limiter */
#define SYSCON_SYSPLLCTRL_DIRECTI (1 << 19) /* Bit 19: PLL direct input enable */
#define SYSCON_SYSPLLCTRL_DIRECTO (1 << 10) /* Bit 20: PLL direct output enable */
/* PLL status */
#define SYSCON_SYSPLLSTAT_LOCK (1 << 0) /* Bit 0: LOCK PLL lock indicator */
/* PLL N divider */
#define SYSCON_SYSPLLNDEC_NDEC_SHIFT (0) /* Bits 0-9: Decoded N-divider coefficient */
#define SYSCON_SYSPLLNDEC_NDEC_MASK (0x3ff << SYSCON_SYSPLLNDEC_NDEC_SHIFT)
# define SYSCON_SYSPLLNDEC_NDEC(n) ((uint32_t)((n)-1) << SYSCON_SYSPLLNDEC_NDEC_SHIFT)
#define SYSCON_SYSPLLNDEC_NREQ (1 << 10) /* Bit 10: NDEC reload request */
/* PLL P divider */
#define SYSCON_SYSPLLPDEC_PDEC_SHIFT (0) /* Bits 0-6: Decoded P-divider coefficient */
#define SYSCON_SYSPLLPDEC_PDEC_MASK (0x7f << SYSCON_SYSPLLPDEC_PDEC_SHIFT)
# define SYSCON_SYSPLLPDEC_PDEC(n) ((uint32_t)((n)-1) << SYSCON_SYSPLLPDEC_PDEC_SHIFT)
#define SYSCON_SYSPLLPDEC_PREQ (1 << 7) /* Bit 7: PDEC reload request */
/* System PLL M divider */
#define SYSCON_SYSPLLMDEC_MDEC_SHIFT (0) /* Bits 0-16: Decoded M-divider coefficient */
#define SYSCON_SYSPLLMDEC_MDEC_MASK (0xffff << SYSCON_SYSPLLMDEC_MDEC_SHIFT)
# define SYSCON_SYSPLLMDEC_MDEC(n) ((uint32_t)((n)-1) << SYSCON_SYSPLLMDEC_MDEC_SHIFT)
#define SYSCON_SYSPLLMDEC_MREQ (1 << 17) /* Bit 17: MDEC reload request */
/* Audio PLL control */
#define SYSCON_AUDPLLCTRL_
/* Audio PLL status */
#define SYSCON_AUDPLLSTAT_
/* Audio PLL N divider */
#define SYSCON_AUDPLLNDEC_
/* Audio PLL P divider */
#define SYSCON_AUDPLLPDEC_
/* Audio PLL M divider */
#define SYSCON_AUDPLLMDEC_
/* Audio PLL fractional divider control */
#define SYSCON_AUDPLLFRAC_
/* Sleep configuration register 0 */
#define SYSCON_PDSLEEPCFG0_
/* Sleep configuration register 1 */
#define SYSCON_PDSLEEPCFG1_
/* Power configuration register 0 (also corresponding set/clear registers) */
#define SYSCON_PDRUNCFG0_FRO (1 << 4) /* Bit 4: FRO oscillator */
#define SYSCON_PDRUNCFG0_TS (1 << 6) /* Bit 6: Temp sensor */
#define SYSCON_PDRUNCFG0_BODRST (1 << 7) /* Bit 7: Brown-out Detect reset */
#define SYSCON_PDRUNCFG0_BODINTR (1 << 8) /* Bit 8: Brown-out Detect interrupt */
#define SYSCON_PDRUNCFG0_VD2ANA (1 << 9) /* Bit 9: Analog supply for System Oscillator */
#define SYSCON_PDRUNCFG0_ADC0 (1 << 10) /* Bit 10: ADC power */
#define SYSCON_PDRUNCFG0_SRAMX (1 << 13) /* Bit 13: Controls SRAMX */
#define SYSCON_PDRUNCFG0_SRAM0 (1 << 14) /* Bit 14: Controls SRAM0 */
#define SYSCON_PDRUNCFG0_SRAM123 (1 << 15) /* Bit 15: Controls SRAM1, SRAM2, and SRAM3 */
#define SYSCON_PDRUNCFG0_USBRAM (1 << 16) /* Bit 16: Controls USB_RAM */
#define SYSCON_PDRUNCFG0_VDDA (1 << 19) /* Bit 19: VDDA to the ADC */
#define SYSCON_PDRUNCFG0_WDTOSC (1 << 20) /* Bit 20: Watchdog oscillator */
#define SYSCON_PDRUNCFG0_USB0PHY (1 << 21) /* Bit 21: USB0 PHY power */
#define SYSCON_PDRUNCFG0_SYSPLL (1 << 22) /* Bit 22: System PLL power */
#define SYSCON_PDRUNCFG0_VREFP (1 << 23) /* Bit 23: VREFP to the ADC */
#define SYSCON_PDRUNCFG0_VD3 (1 << 26) /* Bit 26: Power control for all PLLs */
#define SYSCON_PDRUNCFG0_VD4 (1 << 27) /* Bit 27: Power control for all SRAMs and ROM */
#define SYSCON_PDRUNCFG0_VD5 (1 << 28) /* Bit 28: Power control both USB0 PHY and USB1 PHY */
#define SYSCON_PDRUNCFG0_VD6 (1 << 29) /* Bit 29 Power control for EEPROM */
/* Power configuration register 1 (also corresponding set/clear registers)*/
#define SYSCON_PDRUNCFG1_USB1PHY (1 << 0) /* Bit 0: USB1 high speed PHY */
#define SYSCON_PDRUNCFG1_USB1PLL (1 << 1) /* Bit 1: USB PLL power */
#define SYSCON_PDRUNCFG1_AUDPLL (1 << 2) /* Bit 2: Audio PLL power and fractional divider */
#define SYSCON_PDRUNCFG1_SYSOSC (1 << 3) /* Bit 3: System Oscillator Power */
#define SYSCON_PDRUNCFG1_EEPROM (1 << 5) /* Bit 5: EEPROM power */
#define SYSCON_PDRUNCFG1_RNG (1 << 7) /* Bit 7: Random Number Generator Power */
/* Start logic 0 wake-up enable register */
#define SYSCON_STARTER0_
/* Start logic 1 wake-up enable register */
#define SYSCON_STARTER1_
/* Set bits in STARTER0 */
#define SYSCON_STARTERSET0_
/* Set bits in STARTER1 */
#define SYSCON_STARTERSET1_
/* Clear bits in STARTER0 */
#define SYSCON_STARTERCLR0_
/* Clear bits in STARTER1 */
#define SYSCON_STARTERCLR1_
/* Configures special cases of hardware wake-up */
#define SYSCON_HWWAKE_
/* Auto clock-gate override */
#define SYSCON_AUTOCGOR_
/* JTAG ID code */
#define SYSCON_JTAGIDCODE_
/* Part ID */
#define SYSCON_DEVICE_ID0_
/* Boot ROM and die revision */
#define SYSCON_DEVICE_ID1_
/* Asynchronous system configuration */
/* Async peripheral reset control */
#define SYSCON_ASYNCPRESETCTRL_
/* Set bits in ASYNCPRESETCTRL */
#define SYSCON_ASYNCPRESETCTRLSET_
/* Clear bits in ASYNCPRESETCTRL */
#define SYSCON_ASYNCPRESETCTRLCLR_
/* Async peripheral clock control */
#define SYSCON_ASYNCAPBCLKCTRL_
/* Set bits in ASYNCAPBCLKCTRL */
#define SYSCON_ASYNCAPBCLKCTRLSET_
/* Clear bits in ASYNCAPBCLKCTRL */
#define SYSCON_ASYNCAPBCLKCTRLCLR_
/* Async APB clock source select A */
#define SYSCON_ASYNCAPBCLKSELA_
/* Other system configuration */
/* Brown-Out Detect control */
#define SYSCON_BODCTRL_
#endif /* __ARCH_ARM_SRC_LPC54XX_CHIP_LPC54_SYSCON_H */

View file

@ -0,0 +1,420 @@
/*****************************************************************************************************
* arch/arm/src/lpc54xx/chip/lpc54_usart.h
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
*****************************************************************************************************/
#ifndef __ARCH_ARM_SRC_LPC54XX_CHIP_LPC54_USART_H
#define __ARCH_ARM_SRC_LPC54XX_CHIP_LPC54_USART_H
/*****************************************************************************************************
* Included Files
*****************************************************************************************************/
#include <nuttx/config.h>
#include "chip/lpc54_memorymap.h"
/*****************************************************************************************************
* Pre-processor Definitions
*****************************************************************************************************/
#define LPC54_USART_FIFO_DEPTH 8 /* All FIFOs are 16x8-bits */
/* USART Register Offsets ***************************************************************************/
/* Registers for the USART function: */
#define LPC54_USART_CFG_OFFSET 0x0000 /* USART Configuration register */
#define LPC54_USART_CTL_OFFSET 0x0004 /* USART Control register */
#define LPC54_USART_STAT_OFFSET 0x0008 /* USART Status register */
#define LPC54_USART_INTENSET_OFFSET 0x000c /* USART Interrupt Enable read and Set register */
#define LPC54_USART_INTENCLR_OFFSET 0x0010 /* USART Interrupt Enable Clear register */
#define LPC54_USART_BRG_OFFSET 0x0020 /* USART Baud Rate Generator register */
#define LPC54_USART_INTSTAT_OFFSET 0x0024 /* USART Interrupt status register */
#define LPC54_USART_OSR_OFFSET 0x0028 /* USART Oversample selection register */
/* Registers for FIFO control and data access: */
#define LPC54_USART_FIFOCFG_OFFSET 0x0e00 /* FIFO configuration and enable register */
#define LPC54_USART_FIFOSTAT_OFFSET 0x0e04 /* FIFO status register */
#define LPC54_USART_FIFOTRIG_OFFSET 0x0e08 /* FIFO trigger settings for interrupt and DMA request */
#define LPC54_USART_FIFOINTENSET_OFFSET 0x0e10 /* FIFO interrupt enable set (enable) and read register */
#define LPC54_USART_FIFOINTENCLR_OFFSET 0x0e14 /* FIFO interrupt enable clear (disable) and read register */
#define LPC54_USART_FIFOINTSTAT_OFFSET 0x0e18 /* FIFO interrupt status register */
#define LPC54_USART_FIFOWR_OFFSET 0x0e20 /* FIFO write data */
#define LPC54_USART_FIFORD_OFFSET 0x0e30 /* FIFO read data */
#define LPC54_USART_FIFORDNOPOP_OFFSET 0x0e40 /* FIFO data read with no FIFO pop */
/* ID register: */
#define LPC54_USART_ID_OFFSET 0x0ffc /* USART module Identification */
/* USART Register Adreesses **************************************************************************/
#define LPC54_USART0_CFG (LPC54_FLEXCOMM0_BASE+LPC54_USART_CFG_OFFSET)
#define LPC54_USART0_CTL (LPC54_FLEXCOMM0_BASE+LPC54_USART_CTL_OFFSET)
#define LPC54_USART0_STAT (LPC54_FLEXCOMM0_BASE+LPC54_USART_STAT_OFFSET)
#define LPC54_USART0_INTENSET (LPC54_FLEXCOMM0_BASE+LPC54_USART_INTENSET_OFFSET)
#define LPC54_USART0_INTENCLR (LPC54_FLEXCOMM0_BASE+LPC54_USART_INTENCLR_OFFSET)
#define LPC54_USART0_BRG (LPC54_FLEXCOMM0_BASE+LPC54_USART_BRG_OFFSET)
#define LPC54_USART0_INTSTAT (LPC54_FLEXCOMM0_BASE+LPC54_USART_INTSTAT_OFFSET)
#define LPC54_USART0_OSR (LPC54_FLEXCOMM0_BASE+LPC54_USART_OSR_OFFSET)
#define LPC54_USART0_FIFOCFG (LPC54_FLEXCOMM0_BASE+LPC54_USART_FIFOCFG_OFFSET)
#define LPC54_USART0_FIFOSTAT (LPC54_FLEXCOMM0_BASE+LPC54_USART_FIFOSTAT_OFFSET)
#define LPC54_USART0_FIFOTRIG (LPC54_FLEXCOMM0_BASE+LPC54_USART_FIFOTRIG_OFFSET)
#define LPC54_USART0_FIFOINTENSET (LPC54_FLEXCOMM0_BASE+LPC54_USART_FIFOINTENSET_OFFSET)
#define LPC54_USART0_FIFOINTENCLR (LPC54_FLEXCOMM0_BASE+LPC54_USART_FIFOINTENCLR_OFFSET)
#define LPC54_USART0_FIFOINTSTAT (LPC54_FLEXCOMM0_BASE+LPC54_USART_FIFOINTSTAT_OFFSET)
#define LPC54_USART0_FIFOWR (LPC54_FLEXCOMM0_BASE+LPC54_USART_FIFOWR_OFFSET)
#define LPC54_USART0_FIFORD (LPC54_FLEXCOMM0_BASE+LPC54_USART_FIFORD_OFFSET)
#define LPC54_USART0_FIFORDNOPOP (LPC54_FLEXCOMM0_BASE+LPC54_USART_FIFORDNOPOP_OFFSET)
#define LPC54_USART0_ID (LPC54_FLEXCOMM0_BASE+LPC54_USART_ID_OFFSET)
#define LPC54_USART1_CFG (LPC54_FLEXCOMM1_BASE+LPC54_USART_CFG_OFFSET)
#define LPC54_USART1_CTL (LPC54_FLEXCOMM1_BASE+LPC54_USART_CTL_OFFSET)
#define LPC54_USART1_STAT (LPC54_FLEXCOMM1_BASE+LPC54_USART_STAT_OFFSET)
#define LPC54_USART1_INTENSET (LPC54_FLEXCOMM1_BASE+LPC54_USART_INTENSET_OFFSET)
#define LPC54_USART1_INTENCLR (LPC54_FLEXCOMM1_BASE+LPC54_USART_INTENCLR_OFFSET)
#define LPC54_USART1_BRG (LPC54_FLEXCOMM1_BASE+LPC54_USART_BRG_OFFSET)
#define LPC54_USART1_INTSTAT (LPC54_FLEXCOMM1_BASE+LPC54_USART_INTSTAT_OFFSET)
#define LPC54_USART1_OSR (LPC54_FLEXCOMM1_BASE+LPC54_USART_OSR_OFFSET)
#define LPC54_USART1_FIFOCFG (LPC54_FLEXCOMM1_BASE+LPC54_USART_FIFOCFG_OFFSET)
#define LPC54_USART1_FIFOSTAT (LPC54_FLEXCOMM1_BASE+LPC54_USART_FIFOSTAT_OFFSET)
#define LPC54_USART1_FIFOTRIG (LPC54_FLEXCOMM1_BASE+LPC54_USART_FIFOTRIG_OFFSET)
#define LPC54_USART1_FIFOINTENSET (LPC54_FLEXCOMM1_BASE+LPC54_USART_FIFOINTENSET_OFFSET)
#define LPC54_USART1_FIFOINTENCLR (LPC54_FLEXCOMM1_BASE+LPC54_USART_FIFOINTENCLR_OFFSET)
#define LPC54_USART1_FIFOINTSTAT (LPC54_FLEXCOMM1_BASE+LPC54_USART_FIFOINTSTAT_OFFSET)
#define LPC54_USART1_FIFOWR (LPC54_FLEXCOMM1_BASE+LPC54_USART_FIFOWR_OFFSET)
#define LPC54_USART1_FIFORD (LPC54_FLEXCOMM1_BASE+LPC54_USART_FIFORD_OFFSET)
#define LPC54_USART1_FIFORDNOPOP (LPC54_FLEXCOMM1_BASE+LPC54_USART_FIFORDNOPOP_OFFSET)
#define LPC54_USART1_ID (LPC54_FLEXCOMM1_BASE+LPC54_USART_ID_OFFSET)
#define LPC54_USART2_CFG (LPC54_FLEXCOMM2_BASE+LPC54_USART_CFG_OFFSET)
#define LPC54_USART2_CTL (LPC54_FLEXCOMM2_BASE+LPC54_USART_CTL_OFFSET)
#define LPC54_USART2_STAT (LPC54_FLEXCOMM2_BASE+LPC54_USART_STAT_OFFSET)
#define LPC54_USART2_INTENSET (LPC54_FLEXCOMM2_BASE+LPC54_USART_INTENSET_OFFSET)
#define LPC54_USART2_INTENCLR (LPC54_FLEXCOMM2_BASE+LPC54_USART_INTENCLR_OFFSET)
#define LPC54_USART2_BRG (LPC54_FLEXCOMM2_BASE+LPC54_USART_BRG_OFFSET)
#define LPC54_USART2_INTSTAT (LPC54_FLEXCOMM2_BASE+LPC54_USART_INTSTAT_OFFSET)
#define LPC54_USART2_OSR (LPC54_FLEXCOMM2_BASE+LPC54_USART_OSR_OFFSET)
#define LPC54_USART2_FIFOCFG (LPC54_FLEXCOMM2_BASE+LPC54_USART_FIFOCFG_OFFSET)
#define LPC54_USART2_FIFOSTAT (LPC54_FLEXCOMM2_BASE+LPC54_USART_FIFOSTAT_OFFSET)
#define LPC54_USART2_FIFOTRIG (LPC54_FLEXCOMM2_BASE+LPC54_USART_FIFOTRIG_OFFSET)
#define LPC54_USART2_FIFOINTENSET (LPC54_FLEXCOMM2_BASE+LPC54_USART_FIFOINTENSET_OFFSET)
#define LPC54_USART2_FIFOINTENCLR (LPC54_FLEXCOMM2_BASE+LPC54_USART_FIFOINTENCLR_OFFSET)
#define LPC54_USART2_FIFOINTSTAT (LPC54_FLEXCOMM2_BASE+LPC54_USART_FIFOINTSTAT_OFFSET)
#define LPC54_USART2_FIFOWR (LPC54_FLEXCOMM2_BASE+LPC54_USART_FIFOWR_OFFSET)
#define LPC54_USART2_FIFORD (LPC54_FLEXCOMM2_BASE+LPC54_USART_FIFORD_OFFSET)
#define LPC54_USART2_FIFORDNOPOP (LPC54_FLEXCOMM2_BASE+LPC54_USART_FIFORDNOPOP_OFFSET)
#define LPC54_USART2_ID (LPC54_FLEXCOMM2_BASE+LPC54_USART_ID_OFFSET)
#define LPC54_USART3_CFG (LPC54_FLEXCOMM3_BASE+LPC54_USART_CFG_OFFSET)
#define LPC54_USART3_CTL (LPC54_FLEXCOMM3_BASE+LPC54_USART_CTL_OFFSET)
#define LPC54_USART3_STAT (LPC54_FLEXCOMM3_BASE+LPC54_USART_STAT_OFFSET)
#define LPC54_USART3_INTENSET (LPC54_FLEXCOMM3_BASE+LPC54_USART_INTENSET_OFFSET)
#define LPC54_USART3_INTENCLR (LPC54_FLEXCOMM3_BASE+LPC54_USART_INTENCLR_OFFSET)
#define LPC54_USART3_BRG (LPC54_FLEXCOMM3_BASE+LPC54_USART_BRG_OFFSET)
#define LPC54_USART3_INTSTAT (LPC54_FLEXCOMM3_BASE+LPC54_USART_INTSTAT_OFFSET)
#define LPC54_USART3_OSR (LPC54_FLEXCOMM3_BASE+LPC54_USART_OSR_OFFSET)
#define LPC54_USART3_FIFOCFG (LPC54_FLEXCOMM3_BASE+LPC54_USART_FIFOCFG_OFFSET)
#define LPC54_USART3_FIFOSTAT (LPC54_FLEXCOMM3_BASE+LPC54_USART_FIFOSTAT_OFFSET)
#define LPC54_USART3_FIFOTRIG (LPC54_FLEXCOMM3_BASE+LPC54_USART_FIFOTRIG_OFFSET)
#define LPC54_USART3_FIFOINTENSET (LPC54_FLEXCOMM3_BASE+LPC54_USART_FIFOINTENSET_OFFSET)
#define LPC54_USART3_FIFOINTENCLR (LPC54_FLEXCOMM3_BASE+LPC54_USART_FIFOINTENCLR_OFFSET)
#define LPC54_USART3_FIFOINTSTAT (LPC54_FLEXCOMM3_BASE+LPC54_USART_FIFOINTSTAT_OFFSET)
#define LPC54_USART3_FIFOWR (LPC54_FLEXCOMM3_BASE+LPC54_USART_FIFOWR_OFFSET)
#define LPC54_USART3_FIFORD (LPC54_FLEXCOMM3_BASE+LPC54_USART_FIFORD_OFFSET)
#define LPC54_USART3_FIFORDNOPOP (LPC54_FLEXCOMM3_BASE+LPC54_USART_FIFORDNOPOP_OFFSET)
#define LPC54_USART3_ID (LPC54_FLEXCOMM3_BASE+LPC54_USART_ID_OFFSET)
#define LPC54_USART4_CFG (LPC54_FLEXCOMM4_BASE+LPC54_USART_CFG_OFFSET)
#define LPC54_USART4_CTL (LPC54_FLEXCOMM4_BASE+LPC54_USART_CTL_OFFSET)
#define LPC54_USART4_STAT (LPC54_FLEXCOMM4_BASE+LPC54_USART_STAT_OFFSET)
#define LPC54_USART4_INTENSET (LPC54_FLEXCOMM4_BASE+LPC54_USART_INTENSET_OFFSET)
#define LPC54_USART4_INTENCLR (LPC54_FLEXCOMM4_BASE+LPC54_USART_INTENCLR_OFFSET)
#define LPC54_USART4_BRG (LPC54_FLEXCOMM4_BASE+LPC54_USART_BRG_OFFSET)
#define LPC54_USART4_INTSTAT (LPC54_FLEXCOMM4_BASE+LPC54_USART_INTSTAT_OFFSET)
#define LPC54_USART4_OSR (LPC54_FLEXCOMM4_BASE+LPC54_USART_OSR_OFFSET)
#define LPC54_USART4_FIFOCFG (LPC54_FLEXCOMM4_BASE+LPC54_USART_FIFOCFG_OFFSET)
#define LPC54_USART4_FIFOSTAT (LPC54_FLEXCOMM4_BASE+LPC54_USART_FIFOSTAT_OFFSET)
#define LPC54_USART4_FIFOTRIG (LPC54_FLEXCOMM4_BASE+LPC54_USART_FIFOTRIG_OFFSET)
#define LPC54_USART4_FIFOINTENSET (LPC54_FLEXCOMM4_BASE+LPC54_USART_FIFOINTENSET_OFFSET)
#define LPC54_USART4_FIFOINTENCLR (LPC54_FLEXCOMM4_BASE+LPC54_USART_FIFOINTENCLR_OFFSET)
#define LPC54_USART4_FIFOINTSTAT (LPC54_FLEXCOMM4_BASE+LPC54_USART_FIFOINTSTAT_OFFSET)
#define LPC54_USART4_FIFOWR (LPC54_FLEXCOMM4_BASE+LPC54_USART_FIFOWR_OFFSET)
#define LPC54_USART4_FIFORD (LPC54_FLEXCOMM4_BASE+LPC54_USART_FIFORD_OFFSET)
#define LPC54_USART4_FIFORDNOPOP (LPC54_FLEXCOMM4_BASE+LPC54_USART_FIFORDNOPOP_OFFSET)
#define LPC54_USART4_ID (LPC54_FLEXCOMM4_BASE+LPC54_USART_ID_OFFSET)
#define LPC54_USART5_CFG (LPC54_FLEXCOMM5_BASE+LPC54_USART_CFG_OFFSET)
#define LPC54_USART5_CTL (LPC54_FLEXCOMM5_BASE+LPC54_USART_CTL_OFFSET)
#define LPC54_USART5_STAT (LPC54_FLEXCOMM5_BASE+LPC54_USART_STAT_OFFSET)
#define LPC54_USART5_INTENSET (LPC54_FLEXCOMM5_BASE+LPC54_USART_INTENSET_OFFSET)
#define LPC54_USART5_INTENCLR (LPC54_FLEXCOMM5_BASE+LPC54_USART_INTENCLR_OFFSET)
#define LPC54_USART5_BRG (LPC54_FLEXCOMM5_BASE+LPC54_USART_BRG_OFFSET)
#define LPC54_USART5_INTSTAT (LPC54_FLEXCOMM5_BASE+LPC54_USART_INTSTAT_OFFSET)
#define LPC54_USART5_OSR (LPC54_FLEXCOMM5_BASE+LPC54_USART_OSR_OFFSET)
#define LPC54_USART5_FIFOCFG (LPC54_FLEXCOMM5_BASE+LPC54_USART_FIFOCFG_OFFSET)
#define LPC54_USART5_FIFOSTAT (LPC54_FLEXCOMM5_BASE+LPC54_USART_FIFOSTAT_OFFSET)
#define LPC54_USART5_FIFOTRIG (LPC54_FLEXCOMM5_BASE+LPC54_USART_FIFOTRIG_OFFSET)
#define LPC54_USART5_FIFOINTENSET (LPC54_FLEXCOMM5_BASE+LPC54_USART_FIFOINTENSET_OFFSET)
#define LPC54_USART5_FIFOINTENCLR (LPC54_FLEXCOMM5_BASE+LPC54_USART_FIFOINTENCLR_OFFSET)
#define LPC54_USART5_FIFOINTSTAT (LPC54_FLEXCOMM5_BASE+LPC54_USART_FIFOINTSTAT_OFFSET)
#define LPC54_USART5_FIFOWR (LPC54_FLEXCOMM5_BASE+LPC54_USART_FIFOWR_OFFSET)
#define LPC54_USART5_FIFORD (LPC54_FLEXCOMM5_BASE+LPC54_USART_FIFORD_OFFSET)
#define LPC54_USART5_FIFORDNOPOP (LPC54_FLEXCOMM5_BASE+LPC54_USART_FIFORDNOPOP_OFFSET)
#define LPC54_USART5_ID (LPC54_FLEXCOMM5_BASE+LPC54_USART_ID_OFFSET)
#define LPC54_USART6_CFG (LPC54_FLEXCOMM6_BASE+LPC54_USART_CFG_OFFSET)
#define LPC54_USART6_CTL (LPC54_FLEXCOMM6_BASE+LPC54_USART_CTL_OFFSET)
#define LPC54_USART6_STAT (LPC54_FLEXCOMM6_BASE+LPC54_USART_STAT_OFFSET)
#define LPC54_USART6_INTENSET (LPC54_FLEXCOMM6_BASE+LPC54_USART_INTENSET_OFFSET)
#define LPC54_USART6_INTENCLR (LPC54_FLEXCOMM6_BASE+LPC54_USART_INTENCLR_OFFSET)
#define LPC54_USART6_BRG (LPC54_FLEXCOMM6_BASE+LPC54_USART_BRG_OFFSET)
#define LPC54_USART6_INTSTAT (LPC54_FLEXCOMM6_BASE+LPC54_USART_INTSTAT_OFFSET)
#define LPC54_USART6_OSR (LPC54_FLEXCOMM6_BASE+LPC54_USART_OSR_OFFSET)
#define LPC54_USART6_FIFOCFG (LPC54_FLEXCOMM6_BASE+LPC54_USART_FIFOCFG_OFFSET)
#define LPC54_USART6_FIFOSTAT (LPC54_FLEXCOMM6_BASE+LPC54_USART_FIFOSTAT_OFFSET)
#define LPC54_USART6_FIFOTRIG (LPC54_FLEXCOMM6_BASE+LPC54_USART_FIFOTRIG_OFFSET)
#define LPC54_USART6_FIFOINTENSET (LPC54_FLEXCOMM6_BASE+LPC54_USART_FIFOINTENSET_OFFSET)
#define LPC54_USART6_FIFOINTENCLR (LPC54_FLEXCOMM6_BASE+LPC54_USART_FIFOINTENCLR_OFFSET)
#define LPC54_USART6_FIFOINTSTAT (LPC54_FLEXCOMM6_BASE+LPC54_USART_FIFOINTSTAT_OFFSET)
#define LPC54_USART6_FIFOWR (LPC54_FLEXCOMM6_BASE+LPC54_USART_FIFOWR_OFFSET)
#define LPC54_USART6_FIFORD (LPC54_FLEXCOMM6_BASE+LPC54_USART_FIFORD_OFFSET)
#define LPC54_USART6_FIFORDNOPOP (LPC54_FLEXCOMM6_BASE+LPC54_USART_FIFORDNOPOP_OFFSET)
#define LPC54_USART6_ID (LPC54_FLEXCOMM6_BASE+LPC54_USART_ID_OFFSET)
#define LPC54_USART7_CFG (LPC54_FLEXCOMM7_BASE+LPC54_USART_CFG_OFFSET)
#define LPC54_USART7_CTL (LPC54_FLEXCOMM7_BASE+LPC54_USART_CTL_OFFSET)
#define LPC54_USART7_STAT (LPC54_FLEXCOMM7_BASE+LPC54_USART_STAT_OFFSET)
#define LPC54_USART7_INTENSET (LPC54_FLEXCOMM7_BASE+LPC54_USART_INTENSET_OFFSET)
#define LPC54_USART7_INTENCLR (LPC54_FLEXCOMM7_BASE+LPC54_USART_INTENCLR_OFFSET)
#define LPC54_USART7_BRG (LPC54_FLEXCOMM7_BASE+LPC54_USART_BRG_OFFSET)
#define LPC54_USART7_INTSTAT (LPC54_FLEXCOMM7_BASE+LPC54_USART_INTSTAT_OFFSET)
#define LPC54_USART7_OSR (LPC54_FLEXCOMM7_BASE+LPC54_USART_OSR_OFFSET)
#define LPC54_USART7_FIFOCFG (LPC54_FLEXCOMM7_BASE+LPC54_USART_FIFOCFG_OFFSET)
#define LPC54_USART7_FIFOSTAT (LPC54_FLEXCOMM7_BASE+LPC54_USART_FIFOSTAT_OFFSET)
#define LPC54_USART7_FIFOTRIG (LPC54_FLEXCOMM7_BASE+LPC54_USART_FIFOTRIG_OFFSET)
#define LPC54_USART7_FIFOINTENSET (LPC54_FLEXCOMM7_BASE+LPC54_USART_FIFOINTENSET_OFFSET)
#define LPC54_USART7_FIFOINTENCLR (LPC54_FLEXCOMM7_BASE+LPC54_USART_FIFOINTENCLR_OFFSET)
#define LPC54_USART7_FIFOINTSTAT (LPC54_FLEXCOMM7_BASE+LPC54_USART_FIFOINTSTAT_OFFSET)
#define LPC54_USART7_FIFOWR (LPC54_FLEXCOMM7_BASE+LPC54_USART_FIFOWR_OFFSET)
#define LPC54_USART7_FIFORD (LPC54_FLEXCOMM7_BASE+LPC54_USART_FIFORD_OFFSET)
#define LPC54_USART7_FIFORDNOPOP (LPC54_FLEXCOMM7_BASE+LPC54_USART_FIFORDNOPOP_OFFSET)
#define LPC54_USART7_ID (LPC54_FLEXCOMM7_BASE+LPC54_USART_ID_OFFSET)
#define LPC54_USART8_CFG (LPC54_FLEXCOMM8_BASE+LPC54_USART_CFG_OFFSET)
#define LPC54_USART8_CTL (LPC54_FLEXCOMM8_BASE+LPC54_USART_CTL_OFFSET)
#define LPC54_USART8_STAT (LPC54_FLEXCOMM8_BASE+LPC54_USART_STAT_OFFSET)
#define LPC54_USART8_INTENSET (LPC54_FLEXCOMM8_BASE+LPC54_USART_INTENSET_OFFSET)
#define LPC54_USART8_INTENCLR (LPC54_FLEXCOMM8_BASE+LPC54_USART_INTENCLR_OFFSET)
#define LPC54_USART8_BRG (LPC54_FLEXCOMM8_BASE+LPC54_USART_BRG_OFFSET)
#define LPC54_USART8_INTSTAT (LPC54_FLEXCOMM8_BASE+LPC54_USART_INTSTAT_OFFSET)
#define LPC54_USART8_OSR (LPC54_FLEXCOMM8_BASE+LPC54_USART_OSR_OFFSET)
#define LPC54_USART8_FIFOCFG (LPC54_FLEXCOMM8_BASE+LPC54_USART_FIFOCFG_OFFSET)
#define LPC54_USART8_FIFOSTAT (LPC54_FLEXCOMM8_BASE+LPC54_USART_FIFOSTAT_OFFSET)
#define LPC54_USART8_FIFOTRIG (LPC54_FLEXCOMM8_BASE+LPC54_USART_FIFOTRIG_OFFSET)
#define LPC54_USART8_FIFOINTENSET (LPC54_FLEXCOMM8_BASE+LPC54_USART_FIFOINTENSET_OFFSET)
#define LPC54_USART8_FIFOINTENCLR (LPC54_FLEXCOMM8_BASE+LPC54_USART_FIFOINTENCLR_OFFSET)
#define LPC54_USART8_FIFOINTSTAT (LPC54_FLEXCOMM8_BASE+LPC54_USART_FIFOINTSTAT_OFFSET)
#define LPC54_USART8_FIFOWR (LPC54_FLEXCOMM8_BASE+LPC54_USART_FIFOWR_OFFSET)
#define LPC54_USART8_FIFORD (LPC54_FLEXCOMM8_BASE+LPC54_USART_FIFORD_OFFSET)
#define LPC54_USART8_FIFORDNOPOP (LPC54_FLEXCOMM8_BASE+LPC54_USART_FIFORDNOPOP_OFFSET)
#define LPC54_USART8_ID (LPC54_FLEXCOMM8_BASE+LPC54_USART_ID_OFFSET)
#define LPC54_USART9_CFG (LPC54_FLEXCOMM9_BASE+LPC54_USART_CFG_OFFSET)
#define LPC54_USART9_CTL (LPC54_FLEXCOMM9_BASE+LPC54_USART_CTL_OFFSET)
#define LPC54_USART9_STAT (LPC54_FLEXCOMM9_BASE+LPC54_USART_STAT_OFFSET)
#define LPC54_USART9_INTENSET (LPC54_FLEXCOMM9_BASE+LPC54_USART_INTENSET_OFFSET)
#define LPC54_USART9_INTENCLR (LPC54_FLEXCOMM9_BASE+LPC54_USART_INTENCLR_OFFSET)
#define LPC54_USART9_BRG (LPC54_FLEXCOMM9_BASE+LPC54_USART_BRG_OFFSET)
#define LPC54_USART9_INTSTAT (LPC54_FLEXCOMM9_BASE+LPC54_USART_INTSTAT_OFFSET)
#define LPC54_USART9_OSR (LPC54_FLEXCOMM9_BASE+LPC54_USART_OSR_OFFSET)
#define LPC54_USART9_FIFOCFG (LPC54_FLEXCOMM9_BASE+LPC54_USART_FIFOCFG_OFFSET)
#define LPC54_USART9_FIFOSTAT (LPC54_FLEXCOMM9_BASE+LPC54_USART_FIFOSTAT_OFFSET)
#define LPC54_USART9_FIFOTRIG (LPC54_FLEXCOMM9_BASE+LPC54_USART_FIFOTRIG_OFFSET)
#define LPC54_USART9_FIFOINTENSET (LPC54_FLEXCOMM9_BASE+LPC54_USART_FIFOINTENSET_OFFSET)
#define LPC54_USART9_FIFOINTENCLR (LPC54_FLEXCOMM9_BASE+LPC54_USART_FIFOINTENCLR_OFFSET)
#define LPC54_USART9_FIFOINTSTAT (LPC54_FLEXCOMM9_BASE+LPC54_USART_FIFOINTSTAT_OFFSET)
#define LPC54_USART9_FIFOWR (LPC54_FLEXCOMM9_BASE+LPC54_USART_FIFOWR_OFFSET)
#define LPC54_USART9_FIFORD (LPC54_FLEXCOMM9_BASE+LPC54_USART_FIFORD_OFFSET)
#define LPC54_USART9_FIFORDNOPOP (LPC54_FLEXCOMM9_BASE+LPC54_USART_FIFORDNOPOP_OFFSET)
#define LPC54_USART9_ID (LPC54_FLEXCOMM9_BASE+LPC54_USART_ID_OFFSET)
/* USART Register Bitfield Definitions ***************************************************************/
/* USART Configuration register */
#define USART_CFG_ENABLE (1 << 0) /* Bit 0 USART Enable */
#define USART_CFG_DATALEN_SHIFT (2) /* Bits 2-3: Selects the data size for the USART */
#define USART_CFG_DATALEN_MASK (3 << USART_CFG_DATALEN_SHIFT)
# define USART_CFG_DATALEN_7BIT (0 << USART_CFG_DATALEN_SHIFT) /* 7 bit Data length */
# define USART_CFG_DATALEN_8BIT (1 << USART_CFG_DATALEN_SHIFT) /* 8 bit Data length */
# define USART_CFG_DATALEN_9BIT (2 << USART_CFG_DATALEN_SHIFT) /* 9 bit data lengt */
#define USART_CFG_PARITYSEL_SHIFT (4) /* Bits 4-5: Selects what type of parity is used by the USART */
#define USART_CFG_PARITYSEL_MASK (3 << USART_CFG_PARITYSEL_SHIFT)
# define USART_CFG_PARITYSEL_NONE (0 << USART_CFG_PARITYSEL_SHIFT) /* No parity */
# define USART_CFG_PARITYSEL_EVEN (2 << USART_CFG_PARITYSEL_SHIFT) /* Even parity */
# define USART_CFG_PARITYSEL_ODD (3 << USART_CFG_PARITYSEL_SHIFT) /* Odd parity */
#define USART_CFG_STOPLEN (1 << 6) /* Bit 6 Number of stop bits appended to transmitted data */
#define USART_CFG_MODE32K (1 << 7) /* Bit 7 Selects standard or 32 kHz clocking mode */
#define USART_CFG_LINMODE (1 << 8) /* Bit 8 LIN break mode enable */
#define USART_CFG_CTSEN (1 << 9) /* Bit 9 CTS Enable */
#define USART_CFG_SYNCEN (1 << 11) /* Bit 11 Selects synchronous or asynchronous operation */
#define USART_CFG_CLKPOL (1 << 12) /* Bit 12 Selects clock polarity and sampling edge of RX data */
#define USART_CFG_SYNCMST (1 << 14) /* Bit 14 Synchronous mode Master select */
#define USART_CFG_LOOP (1 << 15) /* Bit 15 Selects data loopback mode */
#define USART_CFG_OETA (1 << 18) /* Bit 18 Output Enable Turnaround time enable for RS-485 operation */
#define USART_CFG_AUTOADDR (1 << 19) /* Bit 19 Automatic Address matching enable */
#define USART_CFG_OESEL (1 << 20) /* Bit 20 Output Enable Select */
#define USART_CFG_OEPOL (1 << 21) /* Bit 21 Output Enable Polarity */
#define USART_CFG_RXPOL (1 << 22) /* Bit 22 Receive data polarity */
#define USART_CFG_TXPOL (1 << 23) /* Bit 23 Transmit data polarity */
/* USART Control register */
#define USART_CTL_TXBRKEN (1 << 1) /* Bit 1: Break Enable */
#define USART_CTL_ADDRDET (1 << 2) /* Bit 2: Enable address detect mode */
#define USART_CTL_TXDIS (1 << 6) /* Bit 6: Transmit Disable */
#define USART_CTL_CC (1 << 8) /* Bit 8: Continuous Clock generation */
#define USART_CTL_CLRCCONRX (1 << 9) /* Bit 9: Clear Continuous Clock */
#define USART_CTL_AUTOBAUD (1 << 16) /* Bit 16: Autobaud enable */
/* USART Status register, USART Interrupt Enable read and Set register, and USART Interrupt Enable Clear register */
#define USART_INTSTAT_RXIDLE (1 << 1) /* Bit 1: Receiver Idle (Status only) */
#define USART_INT_TXIDLE (1 << 3) /* Bit 3: Transmitter Idle */
#define USART_INTSTAT_CTS (1 << 4) /* Bit 4: State of the CTS signal (Status only) */
#define USART_INT_DELTACTS (1 << 5) /* Bit 5: Change in the state of CTS flag */
#define USART_INT_TXDIS (1 << 6) /* Bit 6: Transmitter Disabled Status flag */
#define USART_INTSTAT_RXBRK (1 << 10) /* Bit 10: Received Break (Status only) */
#define USART_INT_DELTARXBRK (1 << 11) /* Bit 11: Change in the state of receiver break detection */
#define USART_INT_START (1 << 12) /* Bit 12: Start detected on the receiver input */
#define USART_INT_FRAMERR (1 << 13) /* Bit 13: Framing Error interrupt flag */
#define USART_INT_PARITYER (1 << 14) /* Bit 14: Parity Error interrupt flag */
#define USART_INT_RXNOISE (1 << 15) /* Bit 15: Received Noise interrupt flag */
#define USART_INT_ABERR (1 << 16) /* Bit 16: Auto baud Error */
/* USART Baud Rate Generator register */
#define USART_BRG_SHIFT (0) /* Bits 0-15: BAUD rate divisor */
#define USART_BRG_MASK (0xffff << USART_OSR_SHIFT)
# define USART_BRG(n) ((uint32)((n)-1) << USART_OSR_SHIFT)
/* USART Oversample selection register */
#define USART_OSR_SHIFT (0) /* Bits 0-3: Oversample Selection Value. */
#define USART_OSR_MASK (15 << USART_OSR_SHIFT)
# define USART_OSR(n) ((uint32)((n)-1) << USART_OSR_SHIFT)
/* FIFO configuration and enable register */
#define USART_FIFOCFG_ENABLETX (1 << 0) /* Bit 0: Enable the transmit FIFO */
#define USART_FIFOCFG_ENABLERX (1 << 1) /* Bit 1: Enable the receive FIFO */
#define USART_FIFOCFG_SIZE_SHIFT (4) /* Bits 4-5: FIFO size configuration */
#define USART_FIFOCFG_SIZE_MASK (3 << USART_FIFOCFG_SIZE_SHIFT)
# define USART_FIFOCFG_SIZE_16x8 (0 << USART_FIFOCFG_SIZE_SHIFT) /* FIFO is 16 entries x 8 bits */
#define USART_FIFOCFG_DMATX (1 << 12) /* Bit 12: DMA configuration for transmit */
#define USART_FIFOCFG_DMARX (1 << 13) /* Bit 13: DMA configuration for receive */
#define USART_FIFOCFG_WAKETX (1 << 14) /* Bit 14: Wake-up for transmit FIFO level */
#define USART_FIFOCFG_WAKERX (1 << 15) /* Bit 15: Wake-up for receive FIFO level */
#define USART_FIFOCFG_EMPTYTX (1 << 16) /* Bit 16: Empty command for the transmit FIFO */
#define USART_FIFOCFG_EMPTYRX (1 << 17) /* Bit 17: Empty command for the receive FIFO */
/* FIFO status register */
#define USART_FIFOSTAT_TXERR (1 << 0) /* Bit 0 TX FIFO error */
#define USART_FIFOSTAT_RXERR (1 << 1) /* Bit 1 RX FIFO error */
#define USART_FIFOSTAT_PERINT (1 << 3) /* Bit 3 Peripheral interrupt */
#define USART_FIFOSTAT_TXEMPTY (1 << 4) /* Bit 4 Transmit FIFO empty */
#define USART_FIFOSTAT_TXNOTFULL (1 << 5) /* Bit 5 Transmit FIFO not full */
#define USART_FIFOSTAT_RXNOTEMPTY (1 << 6) /* Bit 6 Receive FIFO not empty */
#define USART_FIFOSTAT_RXFULL (1 << 7) /* Bit 7 Receive FIFO full */
#define USART_FIFOSTAT_TXLVL_SHIFT (8) /* Bits 8-12: Transmit FIFO current level */
#define USART_FIFOSTAT_TXLVL_MASK (31 << USART_FIFOSTAT_TXLVL_SHIFT)
#define USART_FIFOSTAT_RXLVL_SHIFT (16) /* Bits 16-20: Receive FIFO current level */
#define USART_FIFOSTAT_RXLVL_MASK (31 << USART_FIFOSTAT_RXLVL_SHIFT)
/* FIFO trigger settings for interrupt and DMA request */
#define USART_FIFOTRIG_TXLVLENA (1 << 0) /* Bit 0: Transmit FIFO level trigger enable */
#define USART_FIFOTRIG_RXLVLENA (1 << 1) /* Bit 1: Receive FIFO level trigger enable */
#define USART_FIFOTRIG_TXLVL_SHIFT (8) /* Bits 8-11: Transmit FIFO level trigger point */
#define USART_FIFOTRIG_TXLVL_MASK (15 << USART_FIFOTRIG_TXLVL_SHIFT)
# define USART_FIFOTRIG_TXLVL(n) ((uint32_t)(n) << USART_FIFOTRIG_TXLVL_SHIFT) /* Interrupt when n entries */
# define USART_FIFOTRIG_TXLVL_EMPTY USART_FIFOTRIG_TXLVL(0)
# define USART_FIFOTRIG_TXLVL_NOTFULL USART_FIFOTRIG_TXLVL(15)
#define USART_FIFOTRIG_RXLVL_SHIFT (16) /* Bits 16-19: Receive FIFO level trigger point */
#define USART_FIFOTRIG_RXLVL_MASK (15 << USART_FIFOTRIG_RXLVL_SHIFT)
# define USART_FIFOTRIG_RXLVL(n) ((uint32_t)(n) << USART_FIFOTRIG_RXLVL_SHIFT) /* Interrupt when n+1 entries */
# define USART_FIFOTRIG_RXLVL_NOTEMPY USART_FIFOTRIG_RXLVL(0)
# define USART_FIFOTRIG_RXLVL_FULL USART_FIFOTRIG_RXLVL(15)
/* FIFO interrupt status register, FIFO interrupt enable set (enable), and read register and FIFO interrupt enable
* clear (disable) and read register
*/
#define USART_FIFOINT_TXERR (1 << 0) /* Bit 0: Transmit FIFO error interrupt */
#define USART_FIFOINT_RXERR (1 << 2) /* Bit 1: Receive ERROR error interrupt */
#define USART_FIFOINT_TXLVL (1 << 3) /* Bit 2: Transmit FIFO level interrupt */
#define USART_FIFOINT_RXLVL (1 << 3) /* Bit 3: Receive FIFO level interrupt */
#define USART_FIFOINTSTAT_PERINT (1 << 4) /* Bit 4: Peripheral interrupt (Status only) */
#define USART_FIFOINT_ALL 0x0000000f
/* FIFO write data */
#define USART_FIFOWR_TXDATA_SHIFT (0) /* Bits 0-8: Transmit data to the FIFO */
#define USART_FIFOWR_TXDATA_MASK (0x1ff << USART_FIFOWR_TXDATA_SHIFT)
# define USART_FIFOWR_TXDATA(n) ((uint32_t)(n) << USART_FIFOWR_TXDATA_SHIFT)
/* FIFO read data register and FIFO data read with no FIFO pop register */
#define USART_FIFORD_RXDATA_SHIFT (0) /* Bits 0-8: Received data from the FIFO */
#define USART_FIFORD_RXDATA_MASK (0x1ff << USART_FIFOWR_TXDATA_SHIFT)
#define USART_FIFORD_FRAMERR (1 << 13) /* Bit 13: Framing Error status flag */
#define USART_FIFORD_PARITYERR (1 << 14) /* Bit 14: Parity Error status flag */
#define USART_FIFORD_RXNOISE (1 << 15) /* Bit 15: Received Noise flag */
/* USART module Identification */
#define USART_ID_APERTURE_SHIFT (0) /* Bits 0-7: Aperture encoded as (aperture size/4K) -1 */
#define USART_ID_APERTURE_MASKX (0xff << USART_ID_APERTURE_SHIFT)
#define USART_ID_MINOR_SHIFT (8) /* Bits 8-11: Minor revision of module implementation */
#define USART_ID_MINOR_MASKX (15 << USART_ID_MINOR_SHIFT)
#define USART_ID_MAJOR_SHIFT (12) /* Bits 12-15: Major revision of module implementation */
#define USART_ID_MAJOR_MASKX (15 << USART_ID_MAJOR_SHIFT)
#define USART_ID_ID_SHIFT (16) /* Bits 16-31: ID Unique module identifier for this IP block */
#define USART_ID_ID_MASKX (0xffff << USART_ID_ID_SHIFT)
#endif /* __ARCH_ARM_SRC_LPC54XX_CHIP_LPC54_USART_H */

View file

@ -0,0 +1,150 @@
/************************************************************************************
* arch/arm/src/lpc54xx/lpc546x_power.h
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
************************************************************************************/
#ifndef __ARCH_ARM_SRC_LPC54XX_LPC546X_PERIPHPOWER_H
#define __ARCH_ARM_SRC_LPC54XX_LPC546X_PERIPHPOWER_H
/************************************************************************************
* Included Files
************************************************************************************/
#include <nuttx/config.h>
#include "up_arch.h"
#include "chip/lpc54_syscon.h"
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
/* Setting the bit corresponding in the PDRUNCFGSET0/1 register powers down the
* selected component; clearling the bit enables it.
*/
#define lpc54_enable0(s) putreg32((s), LPC54_SYSCON_PDRUNCFGCLR0)
#define lpc54_enable1(s) putreg32((s), LPC54_SYSCON_PDRUNCFGCLR1)
#define lpc54_disable0(s) putreg32((s), LPC54_SYSCON_PDRUNCFGSET0)
#define lpc54_disable1(s) putreg32((s), LPC54_SYSCON_PDRUNCFGSET1)
#define lpc54_isenabled0(s) ((getreg32(LPC54_SYSCON_PDRUNCFG0) & (s)) == 0)
#define lpc54_isenabled1(s) ((getreg32(LPC54_SYSCON_PDRUNCFG1) & (s)) == 0)
/* Enable power */
#define lpc54_fro_enable() lpc54_enable0(SYSCON_PDRUNCFG0_FRO)
#define lpc54_ts_enable() lpc54_enable0(SYSCON_PDRUNCFG0_TS)
#define lpc54_bodrst_enable() lpc54_enable0(SYSCON_PDRUNCFG0_BODRST)
#define lpc54_bodintr_enable() lpc54_enable0(SYSCON_PDRUNCFG0_BODINTR)
#define lpc54_vd2ana_enable() lpc54_enable0(SYSCON_PDRUNCFG0_VD2ANA)
#define lpc54_adc0_enable() lpc54_enable0(SYSCON_PDRUNCFG0_ADC0)
#define lpc54_sramx_enable() lpc54_enable0(SYSCON_PDRUNCFG0_SRAMX)
#define lpc54_sam0_enable() lpc54_enable0(SYSCON_PDRUNCFG0_SRAM0)
#define lpc54_sram123_enable() lpc54_enable0(SYSCON_PDRUNCFG0_SRAM123)
#define lpc54_usbram_enable() lpc54_enable0(SYSCON_PDRUNCFG0_USBRAM)
#define lpc54_vdda_enable() lpc54_enable0(SYSCON_PDRUNCFG0_VDDA)
#define lpc54_wdtosc_enable() lpc54_enable0(SYSCON_PDRUNCFG0_WDTOSC)
#define lpc54_usb0phy_enable() lpc54_enable0(SYSCON_PDRUNCFG0_USB0PHY)
#define lpc54_syspll_enable() lpc54_enable0(SYSCON_PDRUNCFG0_SYSPLL)
#define lpc54_vrefp_enable() lpc54_enable0(SYSCON_PDRUNCFG0_VREFP)
#define lpc54_vd3_enable() lpc54_enable0(SYSCON_PDRUNCFG0_VD3)
#define lpc54_vd4_enable() lpc54_enable0(SYSCON_PDRUNCFG0_VD4)
#define lpc54_vd5_enable() lpc54_enable0(SYSCON_PDRUNCFG0_VD5)
#define lpc54_vd6_enable() lpc54_enable0(SYSCON_PDRUNCFG0_VD6)
#define lpc54_usb1phy_enable() lpc54_enable1(SYSCON_PDRUNCFG1_USB1PHY)
#define lpc54_usb1pll_enable() lpc54_enable1(SYSCON_PDRUNCFG1_USB1PLL)
#define lpc54_audpll_enable() lpc54_enable1(SYSCON_PDRUNCFG1_AUDPLL)
#define lpc54_sysosc_enable() lpc54_enable1(SYSCON_PDRUNCFG1_SYSOSC)
#define lpc54_eeprom_enable() lpc54_enable1(SYSCON_PDRUNCFG1_EEPROM)
#define lpc54_rng_enable() lpc54_enable1(SYSCON_PDRUNCFG1_RNG)
/* Disable power */
#define lpc54_fro_disable() lpc54_disable0(SYSCON_PDRUNCFG0_FRO)
#define lpc54_ts_disable() lpc54_disable0(SYSCON_PDRUNCFG0_TS)
#define lpc54_bodrst_disable() lpc54_disable0(SYSCON_PDRUNCFG0_BODRST)
#define lpc54_bodintr_disable() lpc54_disable0(SYSCON_PDRUNCFG0_BODINTR)
#define lpc54_vd2ana_disable() lpc54_disable0(SYSCON_PDRUNCFG0_VD2ANA)
#define lpc54_adc0_disable() lpc54_disable0(SYSCON_PDRUNCFG0_ADC0)
#define lpc54_sramx_disable() lpc54_disable0(SYSCON_PDRUNCFG0_SRAMX)
#define lpc54_sam0_disable() lpc54_disable0(SYSCON_PDRUNCFG0_SRAM0)
#define lpc54_sram123_disable() lpc54_disable0(SYSCON_PDRUNCFG0_SRAM123)
#define lpc54_usbram_disable() lpc54_disable0(SYSCON_PDRUNCFG0_USBRAM)
#define lpc54_vdda_disable() lpc54_disable0(SYSCON_PDRUNCFG0_VDDA)
#define lpc54_wdtosc_disable() lpc54_disable0(SYSCON_PDRUNCFG0_WDTOSC)
#define lpc54_usb0phy_disable() lpc54_disable0(SYSCON_PDRUNCFG0_USB0PHY)
#define lpc54_syspll_disable() lpc54_disable0(SYSCON_PDRUNCFG0_SYSPLL)
#define lpc54_vrefp_disable() lpc54_disable0(SYSCON_PDRUNCFG0_VREFP)
#define lpc54_vd3_disable() lpc54_disable0(SYSCON_PDRUNCFG0_VD3)
#define lpc54_vd4_disable() lpc54_disable0(SYSCON_PDRUNCFG0_VD4)
#define lpc54_vd5_disable() lpc54_disable0(SYSCON_PDRUNCFG0_VD5)
#define lpc54_vd6_disable() lpc54_disable0(SYSCON_PDRUNCFG0_VD6)
#define lpc54_usb1phy_disable() lpc54_disable1(SYSCON_PDRUNCFG1_USB1PHY)
#define lpc54_usb1pll_disable() lpc54_disable1(SYSCON_PDRUNCFG1_USB1PLL)
#define lpc54_audpll_disable() lpc54_disable1(SYSCON_PDRUNCFG1_AUDPLL)
#define lpc54_sysosc_disable() lpc54_disable1(SYSCON_PDRUNCFG1_SYSOSC)
#define lpc54_eeprom_disable() lpc54_disable1(SYSCON_PDRUNCFG1_EEPROM)
#define lpc54_rng_disable() lpc54_disable1(SYSCON_PDRUNCFG1_RNG)
/* Test if power is enabled */
#define lpc54_fro_isenabled() lpc54_isenabled0(SYSCON_PDRUNCFG0_FRO)
#define lpc54_ts_isenabled() lpc54_isenabled0(SYSCON_PDRUNCFG0_TS)
#define lpc54_bodrst_isenabled() lpc54_isenabled0(SYSCON_PDRUNCFG0_BODRST)
#define lpc54_bodintr_isenabled() lpc54_isenabled0(SYSCON_PDRUNCFG0_BODINTR)
#define lpc54_vd2ana_isenabled() lpc54_isenabled0(SYSCON_PDRUNCFG0_VD2ANA)
#define lpc54_adc0_isenabled() lpc54_isenabled0(SYSCON_PDRUNCFG0_ADC0)
#define lpc54_sramx_isenabled() lpc54_isenabled0(SYSCON_PDRUNCFG0_SRAMX)
#define lpc54_sam0_isenabled() lpc54_isenabled0(SYSCON_PDRUNCFG0_SRAM0)
#define lpc54_sram123_isenabled() lpc54_isenabled0(SYSCON_PDRUNCFG0_SRAM123)
#define lpc54_usbram_isenabled() lpc54_isenabled0(SYSCON_PDRUNCFG0_USBRAM)
#define lpc54_vdda_isenabled() lpc54_isenabled0(SYSCON_PDRUNCFG0_VDDA)
#define lpc54_wdtosc_isenabled() lpc54_isenabled0(SYSCON_PDRUNCFG0_WDTOSC)
#define lpc54_usb0phy_isenabled() lpc54_isenabled0(SYSCON_PDRUNCFG0_USB0PHY)
#define lpc54_syspll_isenabled() lpc54_isenabled0(SYSCON_PDRUNCFG0_SYSPLL)
#define lpc54_vrefp_isenabled() lpc54_isenabled0(SYSCON_PDRUNCFG0_VREFP)
#define lpc54_vd3_isenabled() lpc54_isenabled0(SYSCON_PDRUNCFG0_VD3)
#define lpc54_vd4_isenabled() lpc54_isenabled0(SYSCON_PDRUNCFG0_VD4)
#define lpc54_vd5_isenabled() lpc54_isenabled0(SYSCON_PDRUNCFG0_VD5)
#define lpc54_vd6_isenabled() lpc54_isenabled0(SYSCON_PDRUNCFG0_VD6)
#define lpc54_usb1phy_isenabled() lpc54_isenabled1(SYSCON_PDRUNCFG1_USB1PHY)
#define lpc54_usb1pll_isenabled() lpc54_isenabled1(SYSCON_PDRUNCFG1_USB1PLL)
#define lpc54_audpll_isenabled() lpc54_isenabled1(SYSCON_PDRUNCFG1_AUDPLL)
#define lpc54_sysosc_isenabled() lpc54_isenabled1(SYSCON_PDRUNCFG1_SYSOSC)
#define lpc54_eeprom_isenabled() lpc54_isenabled1(SYSCON_PDRUNCFG1_EEPROM)
#define lpc54_rng_isenabled() lpc54_isenabled1(SYSCON_PDRUNCFG1_RNG)
#endif /* __ARCH_ARM_SRC_LPC54XX_LPC546X_PERIPHPOWER_H */

View file

@ -0,0 +1,210 @@
/****************************************************************************
* arch/arm/src/lpc54xx/lpx54_allocateheap.c
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <sys/types.h>
#include <stdint.h>
#include <assert.h>
#include <debug.h>
#include <nuttx/arch.h>
#include <nuttx/board.h>
#include <nuttx/userspace.h>
#include <arch/board/board.h>
#include "up_arch.h"
#include "up_internal.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/* Configuration ************************************************************/
/* Terminology. In the flat build (CONFIG_BUILD_FLAT=y), there is only a
* single heap access with the standard allocations (malloc/free). This
* heap is referred to as the user heap. In the protected build
* (CONFIG_BUILD_PROTECTED=y) where an MPU is used to protect a region of
* otherwise flat memory, there will be two allocators: One that allocates
* protected (kernel) memory and one that allocates unprotected (user)
* memory. These are referred to as the kernel and user heaps,
* respectively.
*
* The ARMv7 has no MPU but does have an MMU. With this MMU, it can support
* the kernel build (CONFIG_BUILD_KERNEL=y). In this configuration, there
* is one kernel heap but multiple user heaps: One per task group. However,
* in this case, we need only be concerned about initializing the single
* kernel heap here.
*/
/****************************************************************************
* Public Data
****************************************************************************/
/* _sbss is the start of the BSS region (see the linker script) _ebss is the
* end of the BSS regsion (see the linker script). The idle task stack starts
* at the end of BSS and is of size CONFIG_IDLETHREAD_STACKSIZE. The IDLE
* thread is the thread that the system boots on and, eventually, becomes the
* idle, do nothing task that runs only when there is nothing else to run.
* The heap continues from there until the configured end of memory.
* g_idle_topstack is the beginning of this heap region (not necessarily
* aligned).
*/
const uint32_t g_idle_topstack = (uint32_t)&_ebss + CONFIG_IDLETHREAD_STACKSIZE;
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: up_allocate_heap/up_allocate_kheap
*
* Description:
* This function will be called to dynamically set aside the heap region.
*
* - For the normal "flat" build, this function returns the size of the
* single heap.
* - For the protected build (CONFIG_BUILD_PROTECTED=y) with both kernel-
* and user-space heaps (CONFIG_MM_KERNEL_HEAP=y), this function
* provides the size of the unprotected, user-space heap.
* - For the kernel build (CONFIG_BUILD_KERNEL=y), this function provides
* the size of the protected, kernel-space heap.
*
* If a protected kernel-space heap is provided, the kernel heap must be
* allocated by an analogous up_allocate_kheap(). A custom version of this
* file is needed if memory protection of the kernel heap is required.
*
* The following memory map is assumed for the flat build:
*
* .data region. Size determined at link time.
* .bss region Size determined at link time.
* IDLE thread stack. Size determined by CONFIG_IDLETHREAD_STACKSIZE.
* Heap. Extends to the end of SRAM.
*
* The following memory map is assumed for the kernel build:
*
* Kernel .data region. Size determined at link time.
* Kernel .bss region Size determined at link time.
* Kernel IDLE thread stack. Size determined by CONFIG_IDLETHREAD_STACKSIZE.
* Padding for alignment
* User .data region. Size determined at link time.
* User .bss region Size determined at link time.
* Kernel heap. Size determined by CONFIG_MM_KERNEL_HEAPSIZE.
* User heap. Extends to the end of SRAM.
*
****************************************************************************/
#ifdef CONFIG_BUILD_KERNEL
void up_allocate_kheap(FAR void **heap_start, size_t *heap_size)
#else
void up_allocate_heap(FAR void **heap_start, size_t *heap_size)
#endif
{
#if defined(CONFIG_BUILD_PROTECTED) && defined(CONFIG_MM_KERNEL_HEAP)
/* Get the unaligned size and position of the user-space heap.
* This heap begins after the user-space .bss section at an offset
* of CONFIG_MM_KERNEL_HEAPSIZE (subject to alignment).
*/
uintptr_t ubase = (uintptr_t)USERSPACE->us_bssend + CONFIG_MM_KERNEL_HEAPSIZE;
size_t usize = CONFIG_RAM_END - ubase;
DEBUGASSERT(ubase < (uintptr_t)CONFIG_RAM_END);
/* Return the user-space heap settings */
board_autoled_on(LED_HEAPALLOCATE);
*heap_start = (FAR void *)ubase;
*heap_size = usize;
#else
/* Return the heap settings */
board_autoled_on(LED_HEAPALLOCATE);
*heap_start = (FAR void *)g_idle_topstack;
*heap_size = CONFIG_RAM_END - g_idle_topstack;
#endif
}
/****************************************************************************
* Name: up_allocate_kheap
*
* Description:
* For the kernel build (CONFIG_BUILD_PROTECTED/KERNEL=y) with both kernel-
* and user-space heaps (CONFIG_MM_KERNEL_HEAP=y), this function allocates
* the kernel-space heap. A custom version of this function is needed if
* memory protection of the kernel heap is required.
*
****************************************************************************/
#if defined(CONFIG_BUILD_PROTECTED) && defined(CONFIG_MM_KERNEL_HEAP)
void up_allocate_kheap(FAR void **heap_start, size_t *heap_size)
{
/* Get the unaligned size and position of the user-space heap.
* This heap begins after the user-space .bss section at an offset
* of CONFIG_MM_KERNEL_HEAPSIZE (subject to alignment).
*/
uintptr_t ubase = (uintptr_t)USERSPACE->us_bssend + CONFIG_MM_KERNEL_HEAPSIZE;
DEBUGASSERT(ubase < (uintptr_t)CONFIG_RAM_END);
/* Return the kernel heap settings (i.e., the part of the heap region
* that was not dedicated to the user heap).
*/
*heap_start = (FAR void *)USERSPACE->us_bssend;
*heap_size = ubase - (uintptr_t)USERSPACE->us_bssend;
}
#endif
/****************************************************************************
* Name: up_addregion
*
* Description:
* Memory may be added in non-contiguous chunks. Additional chunks are
* added by calling this function.
*
****************************************************************************/
#if CONFIG_MM_REGIONS > 1
void up_addregion(void)
{
}
#endif

View file

@ -0,0 +1,303 @@
/****************************************************************************
* arch/arm/src/lpc54628/lpc54_clockconfig.c
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Parts of this file were adapted from sample code provided for the LPC54xx
* family from NXP which has a compatible BSD license.
*
* Copyright (c) 2016, Freescale Semiconductor, Inc.
* Copyright (c) 2016 - 2017 , NXP
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <stdint.h>
#include <debug.h>
#include <nuttx/arch.h>
#include <arch/board/board.h>
#include "up_arch.h"
#include "up_internal.h"
#include "chip/lpc54_syscon.h"
#include "lpc54_power.h"
#include "lpc54_clockconfig.h"
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Name: lpc54_setvoltage
*
* Description:
* Set voltage for PLL frequency.
*
****************************************************************************/
static void lpc54_setvoltage(uint32_t freq)
{
if (freq == 12000000)
{
putreg32(0x21e, 0x40020040);
putreg32(4, 0x40000620);
}
else if (freq == 48000000)
{
putreg32(0x31e, 0x40020040);
putreg32(4, 0x40000620);
}
else
{
putreg32(4, 0x40000630);
}
}
/****************************************************************************
* Name: lpc54_power_pll
*
* Description:
* Provide VD3 power to the PLL
*
****************************************************************************/
static void lpc54_power_pll(void)
{
putreg32(0x04000000, 0x40000630);
while ((getreg32(0x40020054) & (1 << 6)) == 0)
{
}
}
/****************************************************************************
* Name: lpc54_set_flash_waitstates
*
* Description:
* Set the FLASH wait states for the passed frequency
*
****************************************************************************/
static void lpc54_set_flash_waitstates(uint32_t freq)
{
uint32_t regval;
regval = getreg32(LPC54_SYSCON_FLASHCFG);
regval &= ~SYSCON_FLASHCFG_FLASHTIM_MASK;
if (freq <= 12000000)
{
regval |= SYSCON_FLASHCFG_FLASHTIM(1);
}
else if (freq <= 24000000)
{
regval |= SYSCON_FLASHCFG_FLASHTIM(2);
}
else if (freq <= 36000000)
{
regval |= SYSCON_FLASHCFG_FLASHTIM(3);
}
else if (freq <= 60000000)
{
regval |= SYSCON_FLASHCFG_FLASHTIM(4);
}
else if (freq <= 96000000)
{
regval |= SYSCON_FLASHCFG_FLASHTIM(5);
}
else if (freq <= 120000000)
{
regval |= SYSCON_FLASHCFG_FLASHTIM(6);
}
else if (freq <= 144000000)
{
regval |= SYSCON_FLASHCFG_FLASHTIM(7);
}
else if (freq <= 168000000)
{
regval |= SYSCON_FLASHCFG_FLASHTIM(8);
}
else
{
regval |= SYSCON_FLASHCFG_FLASHTIM(9);
}
putreg32(regval, LPC54_SYSCON_FLASHCFG);
}
/****************************************************************************
* Name: lpc54_configure_pll
*
* Description:
* Configure the PLL.
*
*****************************************************************************/
static void lpc54_configure_pll(FAR const struct pll_setup_s *pllsetup)
{
/* Enable power VD3 for PLLs */
lpc54_power_pll();
/* Power off PLL during setup changes */
lpc54_syspll_disable();
/* Write PLL setup data */
putreg32(pllsetup->pllctrl, LPC54_SYSCON_SYSPLLCTRL);
putreg32(pllsetup->pllndec, LPC54_SYSCON_SYSPLLNDEC);
putreg32(pllsetup->pllndec | SYSCON_SYSPLLNDEC_NREQ,
LPC54_SYSCON_SYSPLLNDEC);
putreg32(pllsetup->pllpdec, LPC54_SYSCON_SYSPLLPDEC);
putreg32(pllsetup->pllpdec | SYSCON_SYSPLLPDEC_PREQ,
LPC54_SYSCON_SYSPLLPDEC);
putreg32(pllsetup->pllmdec, LPC54_SYSCON_SYSPLLMDEC);
putreg32(pllsetup->pllmdec | SYSCON_SYSPLLMDEC_MREQ,
LPC54_SYSCON_SYSPLLMDEC);
/* Flags for lock or power on */
if ((pllsetup->pllflags & (PLL_SETUPFLAG_POWERUP | PLL_SETUPFLAG_WAITLOCK)) != 0)
{
/* If turning the PLL back on, perform the following sequence to
* accelerate PLL lock.
*/
volatile uint32_t delay;
uint32_t maxcco = (1 << 18) | 0x5dd2; /* CCO = 1.6Ghz + MDEC enabled*/
uint32_t ssctrl = getreg32(LPC54_SYSCON_SYSPLLMDEC) & ~SYSCON_SYSPLLMDEC_MREQ;
/* Initialize and power up PLL */
putreg32(maxcco, LPC54_SYSCON_SYSPLLMDEC);
lpc54_syspll_enable();
/* Set MREQ to activate */
putreg32(maxcco | SYSCON_SYSPLLMDEC_MREQ, LPC54_SYSCON_SYSPLLMDEC);
/* Delay for 72 uSec @ 12Mhz */
for (delay = 0; delay < 172; delay++)
{
}
/* Clear MREQ to prepare for restoring MREQ */
putreg32(ssctrl, LPC54_SYSCON_SYSPLLMDEC);
/* set original value back and activate */
putreg32(ssctrl | SYSCON_SYSPLLMDEC_MREQ, LPC54_SYSCON_SYSPLLMDEC);
/* Enable PLL */
lpc54_syspll_enable();
}
/* Wait for the lock? */
if ((pllsetup->pllflags & PLL_SETUPFLAG_WAITLOCK) != 0)
{
while ((getreg32(LPC54_SYSCON_SYSPLLSTAT) & SYSCON_SYSPLLSTAT_LOCK) == 0)
{
}
}
}
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: lpc54_clockconfig
*
* Description:
* Called to initialize the LPC54628. This does whatever setup is needed
* to put the MCU in a usable state. This includes the initialization of
* clocking using the settings in board.h. This function also performs
* other low-level chip as necessary.
*
*****************************************************************************/
void lpc54_clockconfig(FAR const struct pll_setup_s *pllsetup)
{
/* Set up the clock sources */
/* Power up the FRO 12MHz clock source */
lpc54_fro_enable();
/* Switch to FRO 12MHz first to ensure we can change voltage without
* accidentally being below the voltage for current speed.
*/
putreg32(SYSCON_MAINCLKSELA_FRO12, LPC54_SYSCON_MAINCLKSELA);
putreg32(SYSCON_MAINCLKSELB_MAINCLKSELA, LPC54_SYSCON_MAINCLKSELB);
/* Set the voltage for the find PLL output frequency. This assumes
* that the PLL output frequncy is >=12MHz.
*/
lpc54_setvoltage(pllsetup->pllfout);
/* Set up the FLASH wait states for the core
*
* REVISIT: Should this be the PLL output frequency (Main clock) or
* the AHB clock?
*/
lpc54_set_flash_waitstates(pllsetup->pllfout);
/* Set up the PLL clock source to FRO 12MHz */
putreg32(pllsetup->pllclksel, LPC54_SYSCON_SYSPLLCLKSEL);
/* Configure the PLL */
lpc54_configure_pll(pllsetup);
/* Set up the AHB/CPU clock divider */
putreg32(pllsetup->ahbdiv, LPC54_SYSCON_AHBCLKDIV);
/* Switch System clock to SYS PLL */
putreg32(SYSCON_MAINCLKSELB_PLLCLK, LPC54_SYSCON_MAINCLKSELB);
putreg32(SYSCON_MAINCLKSELA_FRO12, LPC54_SYSCON_MAINCLKSELA);
}

View file

@ -0,0 +1,139 @@
/****************************************************************************
* arch/arm/src/lpc64628/lpc54_clockconfig.h
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Parts of this file were adapted from sample code provided for the LPC54xx
* family from NXP which has a compatible BSD license.
*
* Copyright (c) 2016, Freescale Semiconductor, Inc.
* Copyright (c) 2016 - 2017 , NXP
* All rights reserved.
*
* 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_SRCLPC54628_LPC54_CLOCKCONFIG_H
#define __ARCH_ARM_SRCLPC54628_LPC54_CLOCKCONFIG_H
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/* Frequencies of internal clocks */
#define LPC54_SYSTEM_CLOCK 12000000 /* Default System clock value */
#define LPC54_RTC_CLOCK 32768 /* RTC oscillator 32 kHz output (32k_clk )*/
#define LPC54_FRO_12MHZ 12000000 /* FRO 12 MHz (fro_12m) */
#define LPC54_FRO_48MHZ 48000000 /* FRO 48 MHz (fro_48m) */
#define LPC54_FRO_96MHZ 96000000 /* FRO 96 MHz (fro_96m) */
#define LPC54_CLKIN 0 /* CLKIN pin clock */
/* PLL setup structure flags for pllflags field. These flags control how
* the PLL setup function sets up the PLL
*/
#define PLL_SETUPFLAG_POWERUP (1 << 0) /* Power on the PLL after setup */
#define PLL_SETUPFLAG_WAITLOCK (1 << 1) /* Wait for PLL lock and power on */
#define PLL_SETUPFLAG_ADGVOLT (1 << 2) /* Optimize system voltage for PLL rate */
/****************************************************************************
* Public Types
****************************************************************************/
/* PLL setup structure.
*
* This structure can be used to define a PLL configuration. If powering
* up or waiting for PLL lock, the PLL input clock source should be
* configured prior to PLL setup.
*/
struct pll_setup_s
{
uint32_t pllclksel; /* PLL clock source register SYSPLLCLKSEL */
uint32_t pllctrl; /* PLL control register SYSPLLCTRL */
uint32_t pllndec; /* PLL NDEC register SYSPLLNDEC */
uint32_t pllpdec; /* PLL PDEC register SYSPLLPDEC */
uint32_t pllmdec; /* PLL MDEC registers SYSPLLPDEC */
uint32_t pllfout; /* Actual PLL output frequency */
uint32_t pllfrac; /* Only aduio PLL has this function*/
uint32_t pllflags; /* PLL setup flags */
uint32_t ahbdiv; /* AHB divider */
};
/****************************************************************************
* Inline Functions
****************************************************************************/
#ifndef __ASSEMBLY__
/****************************************************************************
* Public Data
****************************************************************************/
#undef EXTERN
#if defined(__cplusplus)
#define EXTERN extern "C"
extern "C"
{
#else
#define EXTERN extern
#endif
/****************************************************************************
* Public Function Prototypes
****************************************************************************/
/****************************************************************************
* Name: lpc54_clockconfig
*
* Description:
* Called to initialize the LPC54628. This does whatever setup is needed
* to put the MCU in a usable state. This includes the initialization of
* clocking using the settings in board.h. This function also performs
* other low-level chip as necessary.
*
*****************************************************************************/
void lpc54_clockconfig(FAR const struct pll_setup_s *pllsetup);
#undef EXTERN
#if defined(__cplusplus)
}
#endif
#endif /* __ASSEMBLY__ */
#endif /* __ARCH_ARM_SRCLPC54628_LPC54_CLOCKCONFIG_H */

View file

@ -0,0 +1,82 @@
/****************************************************************************
* arch/arm/src/lpc54/lpc54_clrpend.c
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <arch/irq.h>
#include "nvic.h"
#include "up_arch.h"
#include "lpc54_irq.h"
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: lpc54_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 LPC54xx Ethernet EMAC
* interrupt definitely needs it!
*
* This function is logically a part of lpc54_irq.c, but I will keep it in
* a separate file so that it will not increase the footprint on LPC54xx
* platforms that do not need this function.
*
****************************************************************************/
void lpc54_clrpend(int irq)
{
/* Check for external interrupt */
if (irq >= LPC54_IRQ_EXTINT)
{
if (irq < (LPC54_IRQ_EXTINT + 32))
{
putreg32(1 << (irq - LPC54_IRQ_EXTINT), NVIC_IRQ0_31_CLRPEND);
}
else if (irq < LPC54_IRQ_NIRQS)
{
putreg32(1 << (irq - LPC54_IRQ_EXTINT - 32), NVIC_IRQ32_63_CLRPEND);
}
}
}

View file

@ -0,0 +1,289 @@
/************************************************************************************
* arch/arm/src/lpc54xx/lpc54_config.h
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
************************************************************************************/
#ifndef __ARCH_ARM_SRC_LPC54XX_LPC54_CONFIG_H
#define __ARCH_ARM_SRC_LPC54XX_LPC54_CONFIG_H
/************************************************************************************
* Included Files
************************************************************************************/
#include <nuttx/config.h>
#include <arch/board/board.h>
#include "chip.h"
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
/* Configuration *********************************************************************/
/* Make sure that no unsupported UARTs are enabled */
#ifndef CONFIG_LPC54_FLEXCOMM0
# undef CONFIG_LPC54_USART0
#endif
#ifndef CONFIG_LPC54_FLEXCOMM1
# undef CONFIG_LPC54_USART1
#endif
#ifndef CONFIG_LPC54_FLEXCOMM2
# undef CONFIG_LPC54_USART2
#endif
#ifndef CONFIG_LPC54_FLEXCOMM3
# undef CONFIG_LPC54_USART3
#endif
#ifndef CONFIG_LPC54_FLEXCOMM4
# undef CONFIG_LPC54_USART4
#endif
#ifndef CONFIG_LPC54_FLEXCOMM5
# undef CONFIG_LPC54_USART5
#endif
#ifndef CONFIG_LPC54_FLEXCOMM6
# undef CONFIG_LPC54_USART6
#endif
#ifndef CONFIG_LPC54_FLEXCOMM7
# undef CONFIG_LPC54_USART7
#endif
#ifndef CONFIG_LPC54_FLEXCOMM8
# undef CONFIG_LPC54_USART8
#endif
#ifndef CONFIG_LPC54_FLEXCOMM9
# undef CONFIG_LPC54_USART9
#endif
/* Map logical UART names (Just for simplicity of naming) */
#undef HAVE_USART0
#undef HAVE_USART1
#undef HAVE_USART2
#undef HAVE_USART3
#undef HAVE_USART4
#undef HAVE_USART5
#undef HAVE_USART6
#undef HAVE_USART7
#undef HAVE_USART8
#undef HAVE_USART9
#ifdef CONFIG_LPC54_USART0
# define HAVE_USART0
#endif
#ifdef CONFIG_LPC54_USART1
# define HAVE_USART1
#endif
#ifdef CONFIG_LPC54_USART2
# define HAVE_USART2
#endif
#ifdef CONFIG_LPC54_USART3
# define HAVE_USART3
#endif
#ifdef CONFIG_LPC54_USART4
# define HAVE_USART4
#endif
#ifdef CONFIG_LPC54_USART5
# define HAVE_USART5
#endif
#ifdef CONFIG_LPC54_USART6
# define HAVE_USART6
#endif
#ifdef CONFIG_LPC54_USART7
# define HAVE_USART7
#endif
#ifdef CONFIG_LPC54_USART8
# define HAVE_USART8
#endif
#ifdef CONFIG_LPC54_USART9
# define HAVE_USART9
#endif
/* Are any UARTs enabled? */
#undef HAVE_USART_DEVICE
#if defined(HAVE_USART0) || defined(HAVE_USART1) || defined(HAVE_USART2) || \
defined(HAVE_USART3) || defined(HAVE_USART4) || defined(HAVE_USART5) || \
defined(HAVE_USART6) || defined(HAVE_USART7) || defined(HAVE_USART8) || \
defined(HAVE_USART9)
# define HAVE_USART_DEVICE 1
#endif
/* Is there a serial console? There should be at most one defined. It could be on
* any UARTn, n=0,1,2,3,4,5
*/
#undef HAVE_USART_CONSOLE
#if defined(CONFIG_USART0_SERIAL_CONSOLE) && defined(HAVE_USART0)
# undef CONFIG_USART1_SERIAL_CONSOLE
# undef CONFIG_USART2_SERIAL_CONSOLE
# undef CONFIG_USART3_SERIAL_CONSOLE
# undef CONFIG_USART4_SERIAL_CONSOLE
# undef CONFIG_USART5_SERIAL_CONSOLE
# undef CONFIG_USART6_SERIAL_CONSOLE
# undef CONFIG_USART7_SERIAL_CONSOLE
# undef CONFIG_USART8_SERIAL_CONSOLE
# undef CONFIG_USART9_SERIAL_CONSOLE
# define HAVE_USART_CONSOLE 1
#elif defined(CONFIG_USART1_SERIAL_CONSOLE) && defined(HAVE_USART1)
# undef CONFIG_USART0_SERIAL_CONSOLE
# undef CONFIG_USART2_SERIAL_CONSOLE
# undef CONFIG_USART3_SERIAL_CONSOLE
# undef CONFIG_USART4_SERIAL_CONSOLE
# undef CONFIG_USART5_SERIAL_CONSOLE
# undef CONFIG_USART6_SERIAL_CONSOLE
# undef CONFIG_USART7_SERIAL_CONSOLE
# undef CONFIG_USART8_SERIAL_CONSOLE
# undef CONFIG_USART9_SERIAL_CONSOLE
# define HAVE_USART_CONSOLE 1
#elif defined(CONFIG_USART2_SERIAL_CONSOLE) && defined(HAVE_USART2)
# undef CONFIG_USART0_SERIAL_CONSOLE
# undef CONFIG_USART1_SERIAL_CONSOLE
# undef CONFIG_USART3_SERIAL_CONSOLE
# undef CONFIG_USART4_SERIAL_CONSOLE
# undef CONFIG_USART5_SERIAL_CONSOLE
# undef CONFIG_USART6_SERIAL_CONSOLE
# undef CONFIG_USART7_SERIAL_CONSOLE
# undef CONFIG_USART8_SERIAL_CONSOLE
# undef CONFIG_USART9_SERIAL_CONSOLE
# define HAVE_USART_CONSOLE 1
#elif defined(CONFIG_USART3_SERIAL_CONSOLE) && defined(HAVE_USART3)
# undef CONFIG_USART0_SERIAL_CONSOLE
# undef CONFIG_USART1_SERIAL_CONSOLE
# undef CONFIG_USART2_SERIAL_CONSOLE
# undef CONFIG_USART4_SERIAL_CONSOLE
# undef CONFIG_USART5_SERIAL_CONSOLE
# undef CONFIG_USART6_SERIAL_CONSOLE
# undef CONFIG_USART7_SERIAL_CONSOLE
# undef CONFIG_USART8_SERIAL_CONSOLE
# undef CONFIG_USART9_SERIAL_CONSOLE
# define HAVE_USART_CONSOLE 1
#elif defined(CONFIG_USART4_SERIAL_CONSOLE) && defined(HAVE_USART4)
# undef CONFIG_USART0_SERIAL_CONSOLE
# undef CONFIG_USART1_SERIAL_CONSOLE
# undef CONFIG_USART2_SERIAL_CONSOLE
# undef CONFIG_USART3_SERIAL_CONSOLE
# undef CONFIG_USART5_SERIAL_CONSOLE
# undef CONFIG_USART6_SERIAL_CONSOLE
# undef CONFIG_USART7_SERIAL_CONSOLE
# undef CONFIG_USART8_SERIAL_CONSOLE
# undef CONFIG_USART9_SERIAL_CONSOLE
# define HAVE_USART_CONSOLE 1
#elif defined(CONFIG_USART5_SERIAL_CONSOLE) && defined(HAVE_USART5)
# undef CONFIG_USART0_SERIAL_CONSOLE
# undef CONFIG_USART1_SERIAL_CONSOLE
# undef CONFIG_USART2_SERIAL_CONSOLE
# undef CONFIG_USART3_SERIAL_CONSOLE
# undef CONFIG_USART4_SERIAL_CONSOLE
# undef CONFIG_USART6_SERIAL_CONSOLE
# undef CONFIG_USART7_SERIAL_CONSOLE
# undef CONFIG_USART8_SERIAL_CONSOLE
# undef CONFIG_USART9_SERIAL_CONSOLE
# define HAVE_USART_CONSOLE 1
#elif defined(CONFIG_USART6_SERIAL_CONSOLE) && defined(HAVE_USART6)
# undef CONFIG_USART0_SERIAL_CONSOLE
# undef CONFIG_USART1_SERIAL_CONSOLE
# undef CONFIG_USART2_SERIAL_CONSOLE
# undef CONFIG_USART3_SERIAL_CONSOLE
# undef CONFIG_USART4_SERIAL_CONSOLE
# undef CONFIG_USART5_SERIAL_CONSOLE
# undef CONFIG_USART7_SERIAL_CONSOLE
# undef CONFIG_USART8_SERIAL_CONSOLE
# undef CONFIG_USART9_SERIAL_CONSOLE
# define HAVE_USART_CONSOLE 1
#elif defined(CONFIG_USART7_SERIAL_CONSOLE) && defined(HAVE_USART7)
# undef CONFIG_USART0_SERIAL_CONSOLE
# undef CONFIG_USART1_SERIAL_CONSOLE
# undef CONFIG_USART2_SERIAL_CONSOLE
# undef CONFIG_USART3_SERIAL_CONSOLE
# undef CONFIG_USART4_SERIAL_CONSOLE
# undef CONFIG_USART5_SERIAL_CONSOLE
# undef CONFIG_USART6_SERIAL_CONSOLE
# undef CONFIG_USART8_SERIAL_CONSOLE
# undef CONFIG_USART9_SERIAL_CONSOLE
# define HAVE_USART_CONSOLE 1
#elif defined(CONFIG_USART8_SERIAL_CONSOLE) && defined(HAVE_USART8)
# undef CONFIG_USART0_SERIAL_CONSOLE
# undef CONFIG_USART1_SERIAL_CONSOLE
# undef CONFIG_USART2_SERIAL_CONSOLE
# undef CONFIG_USART3_SERIAL_CONSOLE
# undef CONFIG_USART4_SERIAL_CONSOLE
# undef CONFIG_USART5_SERIAL_CONSOLE
# undef CONFIG_USART6_SERIAL_CONSOLE
# undef CONFIG_USART7_SERIAL_CONSOLE
# undef CONFIG_USART9_SERIAL_CONSOLE
# define HAVE_USART_CONSOLE 1
#elif defined(CONFIG_USART9_SERIAL_CONSOLE) && defined(HAVE_USART9)
# undef CONFIG_USART0_SERIAL_CONSOLE
# undef CONFIG_USART1_SERIAL_CONSOLE
# undef CONFIG_USART2_SERIAL_CONSOLE
# undef CONFIG_USART3_SERIAL_CONSOLE
# undef CONFIG_USART4_SERIAL_CONSOLE
# undef CONFIG_USART5_SERIAL_CONSOLE
# undef CONFIG_USART6_SERIAL_CONSOLE
# undef CONFIG_USART7_SERIAL_CONSOLE
# undef CONFIG_USART8_SERIAL_CONSOLE
# define HAVE_USART_CONSOLE 1
#else
# ifdef CONFIG_DEV_CONSOLE
# warning "No valid CONFIG_[LP]UART[n]_SERIAL_CONSOLE Setting"
# endif
# undef CONFIG_USART0_SERIAL_CONSOLE
# undef CONFIG_USART1_SERIAL_CONSOLE
# undef CONFIG_USART2_SERIAL_CONSOLE
# undef CONFIG_USART3_SERIAL_CONSOLE
# undef CONFIG_USART4_SERIAL_CONSOLE
# undef CONFIG_USART5_SERIAL_CONSOLE
# undef CONFIG_USART6_SERIAL_CONSOLE
# undef CONFIG_USART7_SERIAL_CONSOLE
# undef CONFIG_USART8_SERIAL_CONSOLE
# undef CONFIG_USART9_SERIAL_CONSOLE
#endif
/* Check UART flow control (Not yet supported) */
# undef CONFIG_USART0_FLOWCONTROL
# undef CONFIG_USART1_FLOWCONTROL
# undef CONFIG_USART2_FLOWCONTROL
# undef CONFIG_USART3_FLOWCONTROL
# undef CONFIG_USART4_FLOWCONTROL
# undef CONFIG_USART5_FLOWCONTROL
# undef CONFIG_USART6_FLOWCONTROL
# undef CONFIG_USART7_FLOWCONTROL
# undef CONFIG_USART8_FLOWCONTROL
# undef CONFIG_USART9_FLOWCONTROL
/************************************************************************************
* Public Functions
************************************************************************************/
#endif /* __ARCH_ARM_SRC_LPC54XX_LPC54_CONFIG_H */

View file

@ -0,0 +1,186 @@
/****************************************************************************
* arch/arm/src/lpc54/lpc54_idle.c
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <arch/board/board.h>
#include <nuttx/config.h>
#include <nuttx/arch.h>
#include <nuttx/board.h>
#include <nuttx/power/pm.h>
#include <nuttx/irq.h>
#include "up_internal.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/* Does the board support an IDLE LED to indicate that the board is in the
* IDLE state?
*/
#if defined(CONFIG_ARCH_LEDS) && defined(LED_IDLE)
# define BEGIN_IDLE() board_autoled_on(LED_IDLE)
# define END_IDLE() board_autoled_off(LED_IDLE)
#else
# define BEGIN_IDLE()
# define END_IDLE()
#endif
#define PM_IDLE_DOMAIN 0 /* Revisit */
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Name: up_idlepm
*
* Description:
* Perform IDLE state power management.
*
****************************************************************************/
#ifdef CONFIG_PM
static void up_idlepm(void)
{
static enum pm_state_e oldstate = PM_NORMAL;
enum pm_state_e newstate;
irqstate_t flags;
int ret;
/* Decide, which power saving level can be obtained */
newstate = pm_checkstate(PM_IDLE_DOMAIN);
/* Check for state changes */
if (newstate != oldstate)
{
flags = enter_critical_section();
/* Perform board-specific, state-dependent logic here */
_info("newstate= %d oldstate=%d\n", newstate, oldstate);
/* Then force the global state change */
ret = pm_changestate(PM_IDLE_DOMAIN, newstate);
if (ret < 0)
{
/* The new state change failed, revert to the preceding state */
(void)pm_changestate(PM_IDLE_DOMAIN, oldstate);
}
else
{
/* Save the new state */
oldstate = newstate;
}
/* MCU-specific power management logic */
switch (newstate)
{
case PM_NORMAL:
break;
case PM_IDLE:
break;
case PM_STANDBY:
lpc54_pmstandby(true);
break;
case PM_SLEEP:
(void)lpc54_pmsleep();
break;
default:
break;
}
leave_critical_section(flags);
}
}
#else
# define up_idlepm()
#endif
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: up_idle
*
* Description:
* up_idle() is the logic that will be executed when their is no other
* ready-to-run task. This is processor idle time and will continue until
* some interrupt occurs to cause a context switch from the idle task.
*
* Processing in this state may be processor-specific. e.g., this is where
* power management operations might be performed.
*
****************************************************************************/
void up_idle(void)
{
#if defined(CONFIG_SUPPRESS_INTERRUPTS) || defined(CONFIG_SUPPRESS_TIMER_INTS)
/* If the system is idle and there are no timer interrupts, then process
* "fake" timer interrupts. Hopefully, something will wake up.
*/
sched_process_timer();
#else
/* Perform IDLE mode power management */
up_idlepm();
/* Sleep until an interrupt occurs to save power */
BEGIN_IDLE();
asm("WFI");
END_IDLE();
#endif
}

View file

@ -0,0 +1,554 @@
/****************************************************************************
* arch/arm/src/lpc54/lpc54_irq.c
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <stdint.h>
#include <debug.h>
#include <nuttx/irq.h>
#include <nuttx/arch.h>
#include <arch/irq.h>
#include "chip.h"
#include "nvic.h"
#include "ram_vectors.h"
#include "up_arch.h"
#include "up_internal.h"
#include "lpc54_irq.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/* Get a 32-bit version of the default priority */
#define DEFPRIORITY32 \
(NVIC_SYSH_PRIORITY_DEFAULT << 24 | NVIC_SYSH_PRIORITY_DEFAULT << 16 | \
NVIC_SYSH_PRIORITY_DEFAULT << 8 | NVIC_SYSH_PRIORITY_DEFAULT)
/* Given the address of a NVIC ENABLE register, this is the offset to
* the corresponding CLEAR ENABLE register.
*/
#define NVIC_ENA_OFFSET (0)
#define NVIC_CLRENA_OFFSET (NVIC_IRQ0_31_CLEAR - NVIC_IRQ0_31_ENABLE)
/****************************************************************************
* Public Data
****************************************************************************/
/* g_current_regs[] holds a references to the current interrupt level
* register storage structure. If is non-NULL only during interrupt
* processing. Access to g_current_regs[] must be through the macro
* CURRENT_REGS for portability.
*/
volatile uint32_t *g_current_regs[1];
/* This is the address of the exception vector table (determined by the
* linker script).
*/
extern uint32_t _vectors[];
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Name: lpc54_dumpnvic
*
* Description:
* Dump some interesting NVIC registers
*
****************************************************************************/
#if defined(CONFIG_DEBUG_IRQ_INFO)
static void lpc54_dumpnvic(const char *msg, int irq)
{
irqstate_t flags;
flags = enter_critical_section();
irqinfo("NVIC (%s, irq=%d):\n", msg, irq);
irqinfo(" INTCTRL: %08x VECTAB: %08x\n",
getreg32(NVIC_INTCTRL), getreg32(NVIC_VECTAB));
#if 0
irqinfo(" SYSH ENABLE MEMFAULT: %08x BUSFAULT: %08x USGFAULT: %08x SYSTICK: %08x\n",
getreg32(NVIC_SYSHCON_MEMFAULTENA), getreg32(NVIC_SYSHCON_BUSFAULTENA),
getreg32(NVIC_SYSHCON_USGFAULTENA), getreg32(NVIC_SYSTICK_CTRL_ENABLE));
#endif
irqinfo(" IRQ ENABLE: %08x %08x\n",
getreg32(NVIC_IRQ0_31_ENABLE), getreg32(NVIC_IRQ32_63_ENABLE));
irqinfo(" SYSH_PRIO: %08x %08x %08x\n",
getreg32(NVIC_SYSH4_7_PRIORITY), getreg32(NVIC_SYSH8_11_PRIORITY),
getreg32(NVIC_SYSH12_15_PRIORITY));
irqinfo(" IRQ PRIO: %08x %08x %08x %08x\n",
getreg32(NVIC_IRQ0_3_PRIORITY), getreg32(NVIC_IRQ4_7_PRIORITY),
getreg32(NVIC_IRQ8_11_PRIORITY), getreg32(NVIC_IRQ12_15_PRIORITY));
irqinfo(" %08x %08x %08x %08x\n",
getreg32(NVIC_IRQ16_19_PRIORITY), getreg32(NVIC_IRQ20_23_PRIORITY),
getreg32(NVIC_IRQ24_27_PRIORITY), getreg32(NVIC_IRQ28_31_PRIORITY));
irqinfo(" %08x %08x %08x %08x\n",
getreg32(NVIC_IRQ32_35_PRIORITY), getreg32(NVIC_IRQ36_39_PRIORITY),
getreg32(NVIC_IRQ40_43_PRIORITY), getreg32(NVIC_IRQ44_47_PRIORITY));
irqinfo(" %08x %08x %08x\n",
getreg32(NVIC_IRQ48_51_PRIORITY), getreg32(NVIC_IRQ52_55_PRIORITY),
getreg32(NVIC_IRQ56_59_PRIORITY));
leave_critical_section(flags);
}
#else
# define lpc54_dumpnvic(msg, irq)
#endif
/****************************************************************************
* Name: lpc54_nmi, lpc54_busfault, lpc54_usagefault, lpc54_pendsv,
* lpc54_dbgmonitor, lpc54_pendsv, lpc54_reserved
*
* Description:
* Handlers for various exceptions. None are handled and all are fatal
* error conditions. The only advantage these provided over the default
* unexpected interrupt handler is that they provide a diagnostic output.
*
****************************************************************************/
#ifdef CONFIG_DEBUG_FEATURES
static int lpc54_nmi(int irq, FAR void *context, FAR void *arg)
{
(void)up_irq_save();
_err("PANIC!!! NMI received\n");
PANIC();
return 0;
}
static int lpc54_busfault(int irq, FAR void *context, FAR void *arg)
{
(void)up_irq_save();
_err("PANIC!!! Bus fault recived\n");
PANIC();
return 0;
}
static int lpc54_usagefault(int irq, FAR void *context, FAR void *arg)
{
(void)up_irq_save();
_err("PANIC!!! Usage fault received\n");
PANIC();
return 0;
}
static int lpc54_pendsv(int irq, FAR void *context, FAR void *arg)
{
(void)up_irq_save();
_err("PANIC!!! PendSV received\n");
PANIC();
return 0;
}
static int lpc54_dbgmonitor(int irq, FAR void *context, FAR void *arg)
{
(void)up_irq_save();
_err("PANIC!!! Debug Monitor received\n");
PANIC();
return 0;
}
static int lpc54_reserved(int irq, FAR void *context, FAR void *arg)
{
(void)up_irq_save();
_err("PANIC!!! Reserved interrupt\n");
PANIC();
return 0;
}
#endif
/****************************************************************************
* Name: lpc54_prioritize_syscall
*
* Description:
* Set the priority of an exception. This function may be needed
* internally even if support for prioritized interrupts is not enabled.
*
****************************************************************************/
#ifdef CONFIG_ARMV7M_USEBASEPRI
static inline void lpc54_prioritize_syscall(int priority)
{
uint32_t regval;
/* SVCALL is system handler 11 */
regval = getreg32(NVIC_SYSH8_11_PRIORITY);
regval &= ~NVIC_SYSH_PRIORITY_PR11_MASK;
regval |= (priority << NVIC_SYSH_PRIORITY_PR11_SHIFT);
putreg32(regval, NVIC_SYSH8_11_PRIORITY);
}
#endif
/****************************************************************************
* Name: lpc54_irqinfo
*
* Description:
* Given an IRQ number, provide the register and bit setting to enable or
* disable the irq.
*
****************************************************************************/
static int lpc54_irqinfo(int irq, uintptr_t *regaddr, uint32_t *bit,
uintptr_t offset)
{
int n;
DEBUGASSERT(irq >= LPC54_IRQ_NMI && irq < NR_IRQS);
/* Check for external interrupt */
if (irq >= LPC54_IRQ_EXTINT)
{
n = irq - LPC54_IRQ_EXTINT;
*regaddr = NVIC_IRQ_ENABLE(n) + offset;
*bit = (uint32_t)1 << (n & 0x1f);
}
/* Handle processor exceptions. Only a few can be disabled */
else
{
*regaddr = NVIC_SYSHCON;
if (irq == LPC54_IRQ_MEMFAULT)
{
*bit = NVIC_SYSHCON_MEMFAULTENA;
}
else if (irq == LPC54_IRQ_BUSFAULT)
{
*bit = NVIC_SYSHCON_BUSFAULTENA;
}
else if (irq == LPC54_IRQ_USAGEFAULT)
{
*bit = NVIC_SYSHCON_USGFAULTENA;
}
else if (irq == LPC54_IRQ_SYSTICK)
{
*regaddr = NVIC_SYSTICK_CTRL;
*bit = NVIC_SYSTICK_CTRL_ENABLE;
}
else
{
return ERROR; /* Invalid or unsupported exception */
}
}
return OK;
}
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: up_irqinitialize
*
* Description:
* Complete initialization of the interrupt system and enable normal,
* interrupt processing.
*
****************************************************************************/
void up_irqinitialize(void)
{
uint32_t regaddr;
#ifdef CONFIG_DEBUG_FEATURES
uint32_t regval;
#endif
int num_priority_registers;
int i;
/* Disable all interrupts */
for (i = 0; i < LPC54_IRQ_NEXTINT; i += 32)
{
putreg32(0xffffffff, NVIC_IRQ_CLEAR(i));
}
/* Make sure that we are using the correct vector table. The default
* vector address is 0x0000:0000 but if we are executing code that is
* positioned in SRAM or in external FLASH, then we may need to reset
* the interrupt vector so that it refers to the table in SRAM or in
* external FLASH.
*/
putreg32((uint32_t)_vectors, NVIC_VECTAB);
#ifdef CONFIG_ARCH_RAMVECTORS
/* If CONFIG_ARCH_RAMVECTORS is defined, then we are using a RAM-based
* vector table that requires special initialization.
*/
up_ramvec_initialize();
#endif
/* Set all interrupts (and exceptions) to the default priority */
putreg32(DEFPRIORITY32, NVIC_SYSH4_7_PRIORITY);
putreg32(DEFPRIORITY32, NVIC_SYSH8_11_PRIORITY);
putreg32(DEFPRIORITY32, NVIC_SYSH12_15_PRIORITY);
/* The NVIC ICTR register (bits 0-4) holds the number of of interrupt
* lines that the NVIC supports:
*
* 0 -> 32 interrupt lines, 8 priority registers
* 1 -> 64 " " " ", 16 priority registers
* 2 -> 96 " " " ", 32 priority registers
* ...
*/
num_priority_registers = (getreg32(NVIC_ICTR) + 1) * 8;
/* Now set all of the interrupt lines to the default priority */
regaddr = NVIC_IRQ0_3_PRIORITY;
while (num_priority_registers--)
{
putreg32(DEFPRIORITY32, regaddr);
regaddr += 4;
}
/* currents_regs is non-NULL only while processing an interrupt */
CURRENT_REGS = NULL;
/* Attach the SVCall and Hard Fault exception handlers. The SVCall
* exception is used for performing context switches; The Hard Fault
* must also be caught because a SVCall may show up as a Hard Fault
* under certain conditions.
*/
irq_attach(LPC54_IRQ_SVCALL, up_svcall, NULL);
irq_attach(LPC54_IRQ_HARDFAULT, up_hardfault, NULL);
/* Set the priority of the SVCall interrupt */
#ifdef CONFIG_ARCH_IRQPRIO
/* up_prioritize_irq(LPC54_IRQ_PENDSV, NVIC_SYSH_PRIORITY_MIN); */
#endif
#ifdef CONFIG_ARMV7M_USEBASEPRI
lpc54_prioritize_syscall(NVIC_SYSH_SVCALL_PRIORITY);
#endif
/* If the MPU is enabled, then attach and enable the Memory Management
* Fault handler.
*/
#ifdef CONFIG_ARM_MPU
irq_attach(LPC54_IRQ_MEMFAULT, up_memfault, NULL);
up_enable_irq(LPC54_IRQ_MEMFAULT);
#endif
/* Attach all other processor exceptions (except reset and sys tick) */
#ifdef CONFIG_DEBUG_FEATURES
irq_attach(LPC54_IRQ_NMI, lpc54_nmi, NULL);
#ifndef CONFIG_ARM_MPU
irq_attach(LPC54_IRQ_MEMFAULT, up_memfault, NULL);
#endif
irq_attach(LPC54_IRQ_BUSFAULT, lpc54_busfault, NULL);
irq_attach(LPC54_IRQ_USAGEFAULT, lpc54_usagefault, NULL);
irq_attach(LPC54_IRQ_PENDSV, lpc54_pendsv, NULL);
irq_attach(LPC54_IRQ_DBGMONITOR, lpc54_dbgmonitor, NULL);
irq_attach(LPC54_IRQ_RESERVED, lpc54_reserved, NULL);
#endif
lpc54_dumpnvic("initial", LPC54_IRQ_NIRQS);
/* If a debugger is connected, try to prevent it from catching hardfaults.
* If CONFIG_ARMV7M_USEBASEPRI, no hardfaults are expected in normal
* operation.
*/
#if defined(CONFIG_DEBUG_FEATURES) && !defined(CONFIG_ARMV7M_USEBASEPRI)
regval = getreg32(NVIC_DEMCR);
regval &= ~NVIC_DEMCR_VCHARDERR;
putreg32(regval, NVIC_DEMCR);
#endif
/* And finally, enable interrupts */
#ifndef CONFIG_SUPPRESS_INTERRUPTS
up_irq_enable();
#endif
}
/****************************************************************************
* Name: up_disable_irq
*
* Description:
* Disable the IRQ specified by 'irq'
*
****************************************************************************/
void up_disable_irq(int irq)
{
uintptr_t regaddr;
uint32_t regval;
uint32_t bit;
if (lpc54_irqinfo(irq, &regaddr, &bit, NVIC_CLRENA_OFFSET) == 0)
{
/* Modify the appropriate bit in the register to disable the interrupt.
* For normal interrupts, we need to set the bit in the associated
* Interrupt Clear Enable register. For other exceptions, we need to
* clear the bit in the System Handler Control and State Register.
*/
if (irq >= LPC54_IRQ_EXTINT)
{
putreg32(bit, regaddr);
}
else
{
regval = getreg32(regaddr);
regval &= ~bit;
putreg32(regval, regaddr);
}
}
lpc54_dumpnvic("disable", irq);
}
/****************************************************************************
* Name: up_enable_irq
*
* Description:
* Enable the IRQ specified by 'irq'
*
****************************************************************************/
void up_enable_irq(int irq)
{
uintptr_t regaddr;
uint32_t regval;
uint32_t bit;
if (lpc54_irqinfo(irq, &regaddr, &bit, NVIC_ENA_OFFSET) == 0)
{
/* Modify the appropriate bit in the register to enable the interrupt.
* For normal interrupts, we need to set the bit in the associated
* Interrupt Set Enable register. For other exceptions, we need to
* set the bit in the System Handler Control and State Register.
*/
if (irq >= LPC54_IRQ_EXTINT)
{
putreg32(bit, regaddr);
}
else
{
regval = getreg32(regaddr);
regval |= bit;
putreg32(regval, regaddr);
}
}
lpc54_dumpnvic("enable", irq);
}
/****************************************************************************
* Name: up_ack_irq
*
* Description:
* Acknowledge the IRQ
*
****************************************************************************/
void up_ack_irq(int irq)
{
lpc54_clrpend(irq);
}
/****************************************************************************
* Name: up_prioritize_irq
*
* Description:
* Set the priority of an IRQ.
*
* Since this API is not supported on all architectures, it should be
* avoided in common implementations where possible.
*
****************************************************************************/
#ifdef CONFIG_ARCH_IRQPRIO
int up_prioritize_irq(int irq, int priority)
{
uint32_t regaddr;
uint32_t regval;
int shift;
DEBUGASSERT(irq >= LPC54_IRQ_MEMFAULT && irq < NR_IRQS &&
(unsigned)priority <= NVIC_SYSH_PRIORITY_MIN);
if (irq < LPC54_IRQ_EXTINT)
{
/* NVIC_SYSH_PRIORITY() maps {0..15} to one of three priority
* registers (0-3 are invalid)
*/
regaddr = NVIC_SYSH_PRIORITY(irq);
irq -= 4;
}
else
{
/* NVIC_IRQ_PRIORITY() maps {0..} to one of many priority registers */
irq -= LPC54_IRQ_EXTINT;
regaddr = NVIC_IRQ_PRIORITY(irq);
}
regval = getreg32(regaddr);
shift = ((irq & 3) << 3);
regval &= ~(0xff << shift);
regval |= (priority << shift);
putreg32(regval, regaddr);
lpc54_dumpnvic("prioritize", irq);
return OK;
}
#endif

View file

@ -0,0 +1,60 @@
/****************************************************************************
* arch/arm/src/lpc54xx/lpc54_irq.h
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#ifndef __ARCH_ARM_SRC_LPC54XX_LPC54_IRQ_H
#define __ARCH_ARM_SRC_LPC54XX_LPC54_IRQ_H
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: lpc54_clrpend
*
* Description:
* Clear a pending interrupt at the NVIC. This does not seem to be
* required for most interrupts.
*
****************************************************************************/
void lpc54_clrpend(int irq);
#endif /* __ARCH_ARM_SRC_LPC54XX_LPC54_IRQ_H */

View file

@ -0,0 +1,707 @@
/************************************************************************************
* arch/arm/src/lpc54xx/lpc54_lowputc.c
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Parts of this file were adapted from sample code provided for the LPC54xx
* family from NXP which has a compatible BSD license.
*
* Copyright (c) 2016, Freescale Semiconductor, Inc.
* Copyright (c) 2016 - 2017 , NXP
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
************************************************************************************/
/************************************************************************************
* Included Files
************************************************************************************/
#include <nuttx/config.h>
#include <stdbool.h>
#include "up_arch.h"
#include "up_internal.h"
#include "chip/lpc54_memorymap.h"
#include "chip/lpc54_syscon.h"
#include "chip/lpc54_flexcomm.h"
#include "chip/lpc54_usart.h"
#include "lpc54_config.h"
#include "lpc54_clockconfig.h"
#include "lpc54_lowputc.h"
#include <arch/board/board.h>
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
#if defined(CONFIG_USART0_SERIAL_CONSOLE)
# define CONSOLE_BASE LPC54_FLEXCOMM0_BASE
# define CONSOLE_BAUD CONFIG_USART0_BAUD
# define CONSOLE_FCLK BOARD_FLEXCOMM0_FCLK
# define CONSOLE_PARITY CONFIG_USART0_PARITY
# define CONSOLE_BITS CONFIG_USART0_BITS
# ifdef CONFIG_USART0_2STOP
# define CONSOLE_STOPBITS2 true
# else
# define CONSOLE_STOPBITS2 false
# endif
# ifdef CONFIG_USART0_IFLOWCONTROL
# define CONSOLE_IFLOW true
# else
# define CONSOLE_IFLOW false
# endif
# ifdef CONFIG_USART0_OFLOWCONTROL
# define CONSOLE_OFLOW true
# else
# define CONSOLE_OFLOW false
# endif
#elif defined(CONFIG_USART1_SERIAL_CONSOLE)
# define CONSOLE_BASE LPC54_FLEXCOMM1_BASE
# define CONSOLE_BAUD CONFIG_USART1_BAUD
# define CONSOLE_FCLK BOARD_FLEXCOMM1_FCLK
# define CONSOLE_PARITY CONFIG_USART1_PARITY
# define CONSOLE_BITS CONFIG_USART1_BITS
# ifdef CONFIG_USART1_2STOP
# define CONSOLE_STOPBITS2 true
# else
# define CONSOLE_STOPBITS2 false
# endif
# ifdef CONFIG_USART1_IFLOWCONTROL
# define CONSOLE_IFLOW true
# else
# define CONSOLE_IFLOW false
# endif
# ifdef CONFIG_USART1_OFLOWCONTROL
# define CONSOLE_OFLOW true
# else
# define CONSOLE_OFLOW false
# endif
#elif defined(CONFIG_USART2_SERIAL_CONSOLE)
# define CONSOLE_BASE LPC54_FLEXCOMM2_BASE
# define CONSOLE_BAUD CONFIG_USART2_BAUD
# define CONSOLE_FCLK BOARD_FLEXCOMM2_FCLK
# define CONSOLE_PARITY CONFIG_USART2_PARITY
# define CONSOLE_BITS CONFIG_USART2_BITS
# ifdef CONFIG_USART2_2STOP
# define CONSOLE_STOPBITS2 true
# else
# define CONSOLE_STOPBITS2 false
# endif
# ifdef CONFIG_USART2_IFLOWCONTROL
# define CONSOLE_IFLOW true
# else
# define CONSOLE_IFLOW false
# endif
# ifdef CONFIG_USART2_OFLOWCONTROL
# define CONSOLE_OFLOW true
# else
# define CONSOLE_OFLOW false
# endif
#elif defined(CONFIG_USART3_SERIAL_CONSOLE)
# define CONSOLE_BASE LPC54_FLEXCOMM3_BASE
# define CONSOLE_BAUD CONFIG_USART3_BAUD
# define CONSOLE_FCLK BOARD_FLEXCOMM3_FCLK
# define CONSOLE_PARITY CONFIG_USART3_PARITY
# define CONSOLE_BITS CONFIG_USART3_BITS
# ifdef CONFIG_USART3_2STOP
# define CONSOLE_STOPBITS2 true
# else
# define CONSOLE_STOPBITS2 false
# endif
# ifdef CONFIG_USART3_IFLOWCONTROL
# define CONSOLE_IFLOW true
# else
# define CONSOLE_IFLOW false
# endif
# ifdef CONFIG_USART3_OFLOWCONTROL
# define CONSOLE_OFLOW true
# else
# define CONSOLE_OFLOW false
# endif
#elif defined(CONFIG_USART4_SERIAL_CONSOLE)
# define CONSOLE_BASE LPC54_FLEXCOMM4_BASE
# define CONSOLE_BAUD CONFIG_USART4_BAUD
# define CONSOLE_FCLK BOARD_FLEXCOMM4_FCLK
# define CONSOLE_PARITY CONFIG_USART4_PARITY
# define CONSOLE_BITS CONFIG_USART4_BITS
# ifdef CONFIG_USART4_2STOP
# define CONSOLE_STOPBITS2 true
# else
# define CONSOLE_STOPBITS2 false
# endif
# ifdef CONFIG_USART4_IFLOWCONTROL
# define CONSOLE_IFLOW true
# else
# define CONSOLE_IFLOW false
# endif
# ifdef CONFIG_USART4_OFLOWCONTROL
# define CONSOLE_OFLOW true
# else
# define CONSOLE_OFLOW false
# endif
#elif defined(CONFIG_USART5_SERIAL_CONSOLE)
# define CONSOLE_BASE LPC54_FLEXCOMM5_BASE
# define CONSOLE_BAUD CONFIG_USART5_BAUD
# define CONSOLE_FCLK BOARD_FLEXCOMM5_FCLK
# define CONSOLE_PARITY CONFIG_USART5_PARITY
# define CONSOLE_BITS CONFIG_USART5_BITS
# ifdef CONFIG_USART5_2STOP
# define CONSOLE_STOPBITS2 true
# else
# define CONSOLE_STOPBITS2 false
# endif
# ifdef CONFIG_USART5_IFLOWCONTROL
# define CONSOLE_IFLOW true
# else
# define CONSOLE_IFLOW false
# endif
# ifdef CONFIG_USART5_OFLOWCONTROL
# define CONSOLE_OFLOW true
# else
# define CONSOLE_OFLOW false
# endif
#elif defined(CONFIG_USART6_SERIAL_CONSOLE)
# define CONSOLE_BASE LPC54_FLEXCOMM6_BASE
# define CONSOLE_BAUD CONFIG_USART6_BAUD
# define CONSOLE_FCLK BOARD_FLEXCOMM6_FCLK
# define CONSOLE_PARITY CONFIG_USART6_PARITY
# define CONSOLE_BITS CONFIG_USART6_BITS
# ifdef CONFIG_USART6_2STOP
# define CONSOLE_STOPBITS2 true
# else
# define CONSOLE_STOPBITS2 false
# endif
# ifdef CONFIG_USART6_IFLOWCONTROL
# define CONSOLE_IFLOW true
# else
# define CONSOLE_IFLOW false
# endif
# ifdef CONFIG_USART6_OFLOWCONTROL
# define CONSOLE_OFLOW true
# else
# define CONSOLE_OFLOW false
# endif
#elif defined(CONFIG_USART7_SERIAL_CONSOLE)
# define CONSOLE_BASE LPC54_FLEXCOMM7_BASE
# define CONSOLE_BAUD CONFIG_USART7_BAUD
# define CONSOLE_FCLK BOARD_FLEXCOMM7_FCLK
# define CONSOLE_PARITY CONFIG_USART7_PARITY
# define CONSOLE_BITS CONFIG_USART7_BITS
# ifdef CONFIG_USART7_2STOP
# define CONSOLE_STOPBITS2 true
# else
# define CONSOLE_STOPBITS2 false
# endif
# ifdef CONFIG_USART7_IFLOWCONTROL
# define CONSOLE_IFLOW true
# else
# define CONSOLE_IFLOW false
# endif
# ifdef CONFIG_USART7_OFLOWCONTROL
# define CONSOLE_OFLOW true
# else
# define CONSOLE_OFLOW false
# endif
#elif defined(CONFIG_USART8_SERIAL_CONSOLE)
# define CONSOLE_BASE LPC54_FLEXCOMM8_BASE
# define CONSOLE_BAUD CONFIG_USART8_BAUD
# define CONSOLE_FCLK BOARD_FLEXCOMM8_FCLK
# define CONSOLE_PARITY CONFIG_USART8_PARITY
# define CONSOLE_BITS CONFIG_USART8_BITS
# ifdef CONFIG_USART8_2STOP
# define CONSOLE_STOPBITS2 true
# else
# define CONSOLE_STOPBITS2 false
# endif
# ifdef CONFIG_USART8_IFLOWCONTROL
# define CONSOLE_IFLOW true
# else
# define CONSOLE_IFLOW false
# endif
# ifdef CONFIG_USART8_OFLOWCONTROL
# define CONSOLE_OFLOW true
# else
# define CONSOLE_OFLOW false
# endif
#elif defined(CONFIG_USART9_SERIAL_CONSOLE)
# define CONSOLE_BASE LPC54_FLEXCOMM9_BASE
# define CONSOLE_BAUD CONFIG_USART9_BAUD
# define CONSOLE_FCLK BOARD_FLEXCOMM9_FCLK
# define CONSOLE_PARITY CONFIG_USART9_PARITY
# define CONSOLE_BITS CONFIG_USART9_BITS
# ifdef CONFIG_USART9_2STOP
# define CONSOLE_STOPBITS2 true
# else
# define CONSOLE_STOPBITS2 false
# endif
# ifdef CONFIG_USART9_IFLOWCONTROL
# define CONSOLE_IFLOW true
# else
# define CONSOLE_IFLOW false
# endif
# ifdef CONFIG_USART9_OFLOWCONTROL
# define CONSOLE_OFLOW true
# else
# define CONSOLE_OFLOW false
# endif
#endif
/************************************************************************************
* Private Data
************************************************************************************/
#ifdef HAVE_USART_CONSOLE
/* USART console configuration */
static const struct uart_config_s g_console_config=
{
.baud = CONSOLE_BAUD,
.fclk = CONSOLE_FCLK,
.parity = CONSOLE_PARITY,
.bits = CONSOLE_BITS,
.txlevel = LPC54_USART_FIFO_DEPTH / 2,
.rxlevel = LPC54_USART_FIFO_DEPTH - 1,
.stopbits2 = CONSOLE_STOPBITS2,
#ifdef CONFIG_SERIAL_IFLOWCONTROL
.iflow = CONSOLE_IFLOW,
#endif
#ifdef CONFIG_SERIAL_OFLOWCONTROL
.oflow = CONSOLE_OFLOW,
#endif
};
#endif /* HAVE_USART_CONSOLE */
/************************************************************************************
* Private Functions
************************************************************************************/
/************************************************************************************
* Name: lp54_setbaud
*
* Description:
* Configure the USART BAUD.
*
************************************************************************************/
#ifdef HAVE_USART_DEVICE
static void lp54_setbaud(uintptr_t base, FAR const struct uart_config_s *config)
{
uint32_t bestdiff = (uint32_t)-1;
uint32_t bestosr = 15;
uint32_t bestbrg = (uint32_t)-1;
uint32_t lastosr;
uint32_t lastbrg;
uint32_t osr;
uint32_t brg;
uint32_t diff;
uint32_t baud;
/* Smaller values of OSR can make the sampling position within a data bit less
* accurate and may potentially cause more noise errors or incorrect data.
*/
for (osr = bestosr; osr >= 8; osr--)
{
brg = (config->fclk / ((osr + 1) * config->baud)) - 1;
if (brg > 0xffff)
{
continue;
}
baud = config->fclk / ((osr + 1) * (brg + 1));
if (config->baud < baud)
{
diff = baud - config->baud;
}
else
{
diff = config->baud - baud;
}
if (diff < bestdiff)
{
bestdiff = diff;
bestosr = osr;
bestbrg = brg;
}
lastosr = osr;
lastbrg = brg;
}
/* Check for value over range */
if (bestbrg > 0xffff)
{
bestosr = lastosr;
bestbrg = lastbrg;
}
putreg32(bestosr, base + LPC54_USART_OSR_OFFSET);
putreg32(bestbrg, base + LPC54_USART_BRG_OFFSET);
}
#endif
/************************************************************************************
* Public Functions
************************************************************************************/
/************************************************************************************
* Name: lpc54_lowsetup
*
* Description:
* Called at the very beginning of _start. Performs low level initialization
* including setup of the console USART. This USART initialization is done
* early so that the serial console is available for debugging very early in
* the boot sequence.
*
************************************************************************************/
void lpc54_lowsetup(void)
{
/* TODO: Configure Fractional Rate Generate in case it is selected as a Flexcomm
* clock source.
*/
#ifdef HAVE_USART_DEVICE
#ifdef HAVE_USART0
/* Attach 12 MHz clock to FLEXCOMM0 */
putreg32(SYSCON_AHBCLKCTRL1_FLEXCOMM0, LPC54_SYSCON_AHBCLKCTRLSET1);
/* Set FLEXCOMM0 to the USART peripheral, locking that configuration in place. */
putreg32(FLEXCOMM_PSELID_PERSEL_USART | FLEXCOMM_PSELID_LOCK,
LPC54_FLEXCOMM0_PSELID);
/* Set up the FLEXCOMM0 function clock */
putreg32(BOARD_FLEXCOMM0_CLKSEL, LPC54_SYSCON_FCLKSEL0);
#endif
#ifdef HAVE_USART1
/* Attach 12 MHz clock to FLEXCOMM1 */
putreg32(SYSCON_AHBCLKCTRL1_FLEXCOMM1, LPC54_SYSCON_AHBCLKCTRLSET1);
/* Set FLEXCOMM1 to the USART peripheral, locking that configuration in place. */
putreg32(FLEXCOMM_PSELID_PERSEL_USART | FLEXCOMM_PSELID_LOCK,
LPC54_FLEXCOMM1_PSELID);
/* Set up the FLEXCOMM1 function clock */
putreg32(BOARD_FLEXCOMM1_CLKSEL, LPC54_SYSCON_FCLKSEL1);
#endif
#ifdef HAVE_USART2
/* Attach 12 MHz clock to FLEXCOMM2 */
putreg32(SYSCON_AHBCLKCTRL1_FLEXCOMM2, LPC54_SYSCON_AHBCLKCTRLSET1);
/* Set FLEXCOMM2 to the USART peripheral, locking that configuration in place. */
putreg32(FLEXCOMM_PSELID_PERSEL_USART | FLEXCOMM_PSELID_LOCK,
LPC54_FLEXCOMM2_PSELID);
/* Set up the FLEXCOMM0 function clock */
putreg32(BOARD_FLEXCOMM2_CLKSEL, LPC54_SYSCON_FCLKSEL2);
#endif
#ifdef HAVE_USART3
/* Attach 12 MHz clock to FLEXCOMM3 */
putreg32(SYSCON_AHBCLKCTRL1_FLEXCOMM3, LPC54_SYSCON_AHBCLKCTRLSET1);
/* Set FLEXCOMM3 to the USART peripheral, locking that configuration in place. */
putreg32(FLEXCOMM_PSELID_PERSEL_USART | FLEXCOMM_PSELID_LOCK,
LPC54_FLEXCOMM3_PSELID);
/* Set up the FLEXCOMM3 function clock */
putreg32(BOARD_FLEXCOMM3_CLKSEL, LPC54_SYSCON_FCLKSEL3);
#endif
#ifdef HAVE_USART4
/* Attach 12 MHz clock to FLEXCOMM4 */
putreg32(SYSCON_AHBCLKCTRL1_FLEXCOMM4, LPC54_SYSCON_AHBCLKCTRLSET1);
/* Set FLEXCOMM4 to the USART peripheral, locking that configuration in place. */
putreg32(FLEXCOMM_PSELID_PERSEL_USART | FLEXCOMM_PSELID_LOCK,
LPC54_FLEXCOMM4_PSELID);
/* Set up the FLEXCOMM4 function clock */
putreg32(BOARD_FLEXCOMM4_CLKSEL, LPC54_SYSCON_FCLKSEL4);
#endif
#ifdef HAVE_USART5
/* Attach 12 MHz clock to FLEXCOMM5 */
putreg32(SYSCON_AHBCLKCTRL1_FLEXCOMM5, LPC54_SYSCON_AHBCLKCTRLSET1);
/* Set FLEXCOMM5 to the USART peripheral, locking that configuration in place. */
putreg32(FLEXCOMM_PSELID_PERSEL_USART | FLEXCOMM_PSELID_LOCK,
LPC54_FLEXCOMM5_PSELID);
/* Set up the FLEXCOMM5 function clock */
putreg32(BOARD_FLEXCOMM5_CLKSEL, LPC54_SYSCON_FCLKSEL5);
#endif
#ifdef HAVE_USART6
/* Attach 12 MHz clock to FLEXCOMM6 */
putreg32(SYSCON_AHBCLKCTRL1_FLEXCOMM6, LPC54_SYSCON_AHBCLKCTRLSET1);
/* Set FLEXCOMM6 to the USART peripheral, locking that configuration in place. */
putreg32(FLEXCOMM_PSELID_PERSEL_USART | FLEXCOMM_PSELID_LOCK,
LPC54_FLEXCOMM6_PSELID);
/* Set up the FLEXCOMM6 function clock */
putreg32(BOARD_FLEXCOMM6_CLKSEL, LPC54_SYSCON_FCLKSEL6);
#endif
#ifdef HAVE_USART7
/* Attach 12 MHz clock to FLEXCOMM7 */
putreg32(SYSCON_AHBCLKCTRL1_FLEXCOMM7, LPC54_SYSCON_AHBCLKCTRLSET1);
/* Set FLEXCOMM7 to the USART peripheral, locking that configuration in place. */
putreg32(FLEXCOMM_PSELID_PERSEL_USART | FLEXCOMM_PSELID_LOCK,
LPC54_FLEXCOMM7_PSELID);
/* Set up the FLEXCOMM7 function clock */
putreg32(BOARD_FLEXCOMM7_CLKSEL, LPC54_SYSCON_FCLKSEL7);
#endif
#ifdef HAVE_USART8
/* Attach 12 MHz clock to FLEXCOMM8 */
putreg32(SYSCON_AHBCLKCTRL2_FLEXCOMM8, LPC54_SYSCON_AHBCLKCTRLSET2);
/* Set FLEXCOMM8 to the USART peripheral, locking that configuration in place. */
putreg32(FLEXCOMM_PSELID_PERSEL_USART | FLEXCOMM_PSELID_LOCK,
LPC54_FLEXCOMM8_PSELID);
/* Set up the FLEXCOMM0 function clock */
putreg32(BOARD_FLEXCOMM8_CLKSEL, LPC54_SYSCON_FCLKSEL8);
#endif
#ifdef HAVE_USART9
/* Attach 12 MHz clock to FLEXCOMM9 */
putreg32(SYSCON_AHBCLKCTRL2_FLEXCOMM9, LPC54_SYSCON_AHBCLKCTRLSET2);
/* Set FLEXCOMM9 to the USART peripheral, locking that configuration in place. */
putreg32(FLEXCOMM_PSELID_PERSEL_USART | FLEXCOMM_PSELID_LOCK,
LPC54_FLEXCOMM9_PSELID);
/* Set up the FLEXCOMM9 function clock */
putreg32(BOARD_FLEXCOMM9_CLKSEL, LPC54_SYSCON_FCLKSEL9);
#endif
#ifdef HAVE_USART_CONSOLE
/* Configure the console USART (if any) */
lpc54_usart_configure(CONSOLE_BASE, &g_console_config);
#endif /* HAVE_USART_CONSOLE */
#endif /* HAVE_USART_DEVICE */
}
/************************************************************************************
* Name: lpc54_usart_configure
*
* Description:
* Configure a UART for non-interrupt driven operation
*
************************************************************************************/
#ifdef HAVE_USART_DEVICE
void lpc54_usart_configure(uintptr_t base, FAR const struct uart_config_s *config)
{
uint32_t regval;
/* Configure baud */
lp54_setbaud(base, config);
/* Configure RX and TX FIFOs */
/* Empty and enable FIFOs */
regval = getreg32(base + LPC54_USART_FIFOCFG_OFFSET);
regval |= (USART_FIFOCFG_ENABLERX | USART_FIFOCFG_EMPTYRX);
regval |= (USART_FIFOCFG_ENABLETX | USART_FIFOCFG_EMPTYTX);
putreg32(regval, base + LPC54_USART_FIFOCFG_OFFSET);
/* Setup trigger level */
regval = getreg32(base + LPC54_USART_FIFOTRIG_OFFSET);
regval &= ~(USART_FIFOTRIG_TXLVL_MASK | USART_FIFOTRIG_RXLVL_MASK);
regval |= USART_FIFOTRIG_RXLVL(config->rxlevel);
regval |= USART_FIFOTRIG_TXLVL(config->txlevel);
putreg32(regval, base + LPC54_USART_FIFOTRIG_OFFSET);
/* Enable trigger events */
regval |= (USART_FIFOTRIG_RXLVLENA | USART_FIFOTRIG_TXLVLENA);
putreg32(regval, base + LPC54_USART_FIFOTRIG_OFFSET);
/* Setup configuration and enable USART */
regval = USART_CFG_ENABLE;
switch (config->bits)
{
case 7:
regval |= USART_CFG_DATALEN_7BIT;
break;
default:
case 8:
regval |= USART_CFG_DATALEN_8BIT;
break;
case 9:
regval |= USART_CFG_DATALEN_9BIT;
break;
}
switch (config->parity)
{
default:
case 0:
regval |= USART_CFG_PARITYSEL_NONE;
break;
case 1:
regval |= USART_CFG_PARITYSEL_ODD;
break;
case 2:
regval |= USART_CFG_PARITYSEL_EVEN;
break;
}
if (config->stopbits2)
{
regval |= USART_CFG_STOPLEN;
}
putreg32(regval, base + LPC54_USART_CFG_OFFSET);
}
#endif
/****************************************************************************
* Name: lpc54_usart_disable
*
* Description:
* Disable a USART. it will be necessary to again call
* lpc54_usart_configure() in order to use this USART channel again.
*
****************************************************************************/
#ifdef HAVE_USART_DEVICE
void lpc54_usart_disable(uintptr_t base)
{
/* Disable interrupts */
putreg32(USART_FIFOINT_ALL, base + LPC54_USART_FIFOINTENCLR_OFFSET);
/* Disable the UART */
putreg32(0, base + LPC54_USART_CFG_OFFSET);
/* Disable the FIFOs */
putreg32(0, base + LPC54_USART_FIFOCFG_OFFSET);
putreg32(0, base + LPC54_USART_FIFOTRIG_OFFSET);
}
#endif
/****************************************************************************
* Name: up_lowputc
*
* Description:
* Output one byte on the serial console
*
****************************************************************************/
void up_lowputc(char ch)
{
#ifdef HAVE_USART_CONSOLE
irqstate_t flags;
for (; ; )
{
/* Wait for the transmit FIFO to be not full */
while ((getreg32(CONSOLE_BASE + LPC54_USART_FIFOSTAT_OFFSET) &
USART_FIFOSTAT_TXNOTFULL) == 0)
{
}
/* Disable interrupts so that the fest test and the transmission are
* atomic.
*/
flags = enter_critical_section();
if ((getreg32(CONSOLE_BASE + LPC54_USART_FIFOSTAT_OFFSET) &
USART_FIFOSTAT_TXNOTFULL) != 0)
{
/* Send the character */
putreg32((uint32_t)ch, CONSOLE_BASE + LPC54_USART_FIFOWR_OFFSET);
leave_critical_section(flags);
return;
}
leave_critical_section(flags);
}
#endif
}

View file

@ -0,0 +1,115 @@
/************************************************************************************
* arch/arm/src/lpc54xx/lpc54_lowputc.h
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
************************************************************************************/
#ifndef __ARCH_ARM_SRC_LPC54XX_LPC54_LOWPUTC_H
#define __ARCH_ARM_SRC_LPC54XX_LPC54_LOWPUTC_H
/************************************************************************************
* Included Files
************************************************************************************/
#include <nuttx/config.h>
#include <stdint.h>
#include <stdbool.h>
/************************************************************************************
* Public Types
************************************************************************************/
#ifdef HAVE_USART_DEVICE
/* This structure describes the configuration of an UART */
struct uart_config_s
{
uint32_t baud; /* Configured baud */
uint32_t fclk; /* Input Flexcomm function clock frequency */
uint8_t parity; /* 0=none, 1=odd, 2=even */
uint8_t bits; /* Number of bits (5-9) */
uint8_t txlevel; /* TX level for event generation */
uint8_t rxlevel; /* RX level for event generation */
bool stopbits2; /* true: Configure with 2 stop bits instead of 1 */
#ifdef CONFIG_SERIAL_IFLOWCONTROL
bool iflow; /* true: Input flow control supported */
#endif
#ifdef CONFIG_SERIAL_OFLOWCONTROL
bool oflow; /* true: Output flow control supported. */
#endif
};
#endif
/************************************************************************************
* Public Functions
************************************************************************************/
/************************************************************************************
* Name: lpc54_lowsetup
*
* Description:
* Called at the very beginning of _start. Performs low level initialization
* including setup of the console USART. This USART initialization is done
* early so that the serial console is available for debugging very early in
* the boot sequence.
*
************************************************************************************/
void lpc54_lowsetup(void);
/************************************************************************************
* Name: lpc54_usart_configure
*
* Description:
* Configure a UART for non-interrupt driven operation
*
************************************************************************************/
#ifdef HAVE_USART_DEVICE
void lpc54_usart_configure(uintptr_t base, FAR const struct uart_config_s *config);
#endif
/****************************************************************************
* Name: lpc54_usart_disable
*
* Description:
* Disable a USART. it will be necessary to again call
* lpc54_usart_configure() in order to use this USART channel again.
*
****************************************************************************/
#ifdef HAVE_USART_DEVICE
void lpc54_usart_disable(uintptr_t base);
#endif
#endif /* __ARCH_ARM_SRC_LPC54XX_LPC54_LOWPUTC_H */

View file

@ -0,0 +1,116 @@
/****************************************************************************
* arch/arm/src/lpc54xx/lpc54_mpuinit.c
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <assert.h>
#include <nuttx/userspace.h>
#include "mpu.h"
#include "lpc54_mpuinit.h"
#if defined(CONFIG_BUILD_PROTECTED) && defined(CONFIG_ARM_MPU)
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
#ifndef MAX
# define MAX(a,b) a > b ? a : b
#endif
#ifndef MIN
# define MIN(a,b) a < b ? a : b
#endif
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: lpc54_mpuinitialize
*
* Description:
* Configure the MPU to permit user-space access to only restricted SAM3U
* resources.
*
****************************************************************************/
void lpc54_mpuinitialize(void)
{
uintptr_t datastart = MIN(USERSPACE->us_datastart, USERSPACE->us_bssstart);
uintptr_t dataend = MAX(USERSPACE->us_dataend, USERSPACE->us_bssend);
DEBUGASSERT(USERSPACE->us_textend >= USERSPACE->us_textstart &&
dataend >= datastart);
/* Show MPU information */
mpu_showtype();
/* Configure user flash and SRAM space */
mpu_user_flash(USERSPACE->us_textstart,
USERSPACE->us_textend - USERSPACE->us_textstart);
mpu_user_intsram(datastart, dataend - datastart);
/* Then enable the MPU */
mpu_control(true, false, true);
}
/****************************************************************************
* Name: lpc54_mpu_uheap
*
* Description:
* Map the user-heap region.
*
* This logic may need an extension to handle external SDRAM).
*
****************************************************************************/
void lpc54_mpu_uheap(uintptr_t start, size_t size)
{
mpu_user_intsram(start, size);
}
#endif /* CONFIG_BUILD_PROTECTED && CONFIG_ARM_MPU */

View file

@ -0,0 +1,78 @@
/************************************************************************************
* arch/arm/src/lpc54xx/lpc54_mpuinit.h
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
************************************************************************************/
#ifndef __ARCH_ARM_SRC_LPC54XX_LPC54_MPUINIT_H
#define __ARCH_ARM_SRC_LPC54XX_LPC54_MPUINIT_H
/************************************************************************************
* Included Files
************************************************************************************/
#include <nuttx/config.h>
/************************************************************************************
* Public Function Prototypes
************************************************************************************/
/****************************************************************************
* Name: lpc54_mpuinitialize
*
* Description:
* Configure the MPU to permit user-space access to only unrestricted MCU
* resources.
*
****************************************************************************/
#ifdef CONFIG_BUILD_PROTECTED
void lpc54_mpuinitialize(void);
#else
# define lpc54_mpuinitialize()
#endif
/****************************************************************************
* Name: lpc54_mpu_uheap
*
* Description:
* Map the user heap region.
*
****************************************************************************/
#ifdef CONFIG_BUILD_PROTECTED
void lpc54_mpu_uheap(uintptr_t start, size_t size);
#else
# define lpc54_mpu_uheap(start,size)
#endif
#endif /* __ARCH_ARM_SRC_LPC54XX_LPC54_MPUINIT_H */

View file

@ -0,0 +1,53 @@
/************************************************************************************
* arch/arm/src/lpc54xx/lpc54_power.h
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
************************************************************************************/
#ifndef __ARCH_ARM_SRC_LPC54XX_LPC54_PERIPHPOWER_H
#define __ARCH_ARM_SRC_LPC54XX_LPC54_PERIPHPOWER_H
/************************************************************************************
* Included Files
************************************************************************************/
#include <nuttx/config.h>
/* Include the correct logic for the configured chip */
#if defined(CONFIG_ARCH_FAMILY_LPC546XX)
# include "lpc546x_power.h"
#else
# error "Unsupported LPC54 architecture"
#endif
#endif /* __ARCH_ARM_SRC_LPC54XX_LPC54_PERIPHPOWER_H */

File diff suppressed because it is too large Load diff

View file

@ -0,0 +1,66 @@
/****************************************************************************
* arch/arm/src/lpc54xx/lpc54_serial.h
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#ifndef __ARCH_ARM_SRC_LPC54XX_LPC54_SERIAL_H
#define __ARCH_ARM_SRC_LPC54XX_LPC54_SERIAL_H
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include "lpc54_config.h"
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: lpc54_earlyserialinit
*
* Description:
* Performs the low level USART initialization early in debug so that the
* serial console will be available during bootup. This must be called
* before lpc54_serialinit. NOTE: This function depends on GPIO pin
* configuration performed in xmc_lowsetup() and main clock iniialization
* performed in xmc_clock_configure().
*
****************************************************************************/
#ifdef USE_EARLYSERIALINIT
void lpc54_earlyserialinit(void);
#endif
#endif /* __ARCH_ARM_SRC_LPC54XX_LPC54_SERIAL_H */

View file

@ -0,0 +1,283 @@
/****************************************************************************
* arch/arm/src/lpc54xx/lpc54_start.c
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#include <nuttx/config.h>
#include <stdint.h>
#include <assert.h>
#include <debug.h>
#include <nuttx/init.h>
#include <arch/board/board.h>
#include <arch/irq.h>
#include "up_arch.h"
#include "up_internal.h"
#include "nvic.h"
#include "chip/lpc54_syscon.h"
#include "lpc54_clockconfig.h"
#include "lpc54_userspace.h"
#include "lpc54_lowputc.h"
#include "lpc54_serial.h"
#include "lpc54_start.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/****************************************************************************
* Name: showprogress
*
* Description:
* Print a character on the UART to show boot status.
*
****************************************************************************/
#ifdef CONFIG_DEBUG_FEATURES
# define showprogress(c) up_lowputc(c)
#else
# define showprogress(c)
#endif
/****************************************************************************
* Private Data
****************************************************************************/
/* This describes the initial PLL configuration */
static const struct pll_setup_s g_initial_pll_setup =
{
.pllclksel = BOARD_PLL_CLKSEL,
.pllctrl = SYSCON_SYSPLLCTRL_SELR(BOARD_PLL_SELR) |
SYSCON_SYSPLLCTRL_SELI(BOARD_PLL_SELI) |
SYSCON_SYSPLLCTRL_SELP(BOARD_PLL_SELP),
.pllmdec = (SYSCON_SYSPLLMDEC_MDEC(BOARD_PLL_MDEC)),
.pllndec = (SYSCON_SYSPLLNDEC_NDEC(BOARD_PLL_NDEC)),
.pllpdec = (SYSCON_SYSPLLPDEC_PDEC(BOARD_PLL_PDEC)),
.pllfout = BOARD_PLL_FOUT,
.pllflags = PLL_SETUPFLAG_WAITLOCK | PLL_SETUPFLAG_POWERUP,
.ahbdiv = SYSCON_AHBCLKDIV_DIV(BOARD_AHBCLKDIV)
};
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Name: lpc54_fpuconfig
*
* Description:
* Configure the FPU. Relative bit settings:
*
* CPACR: Enables access to CP10 and CP11
* CONTROL.FPCA: Determines whether the FP extension is active in the
* current context:
* FPCCR.ASPEN: Enables automatic FP state preservation, then the
* processor sets this bit to 1 on successful completion of any FP
* instruction.
* FPCCR.LSPEN: Enables lazy context save of FP state. When this is
* done, the processor reserves space on the stack for the FP state,
* but does not save that state information to the stack.
*
* Software must not change the value of the ASPEN bit or LSPEN bit while either:
* - the CPACR permits access to CP10 and CP11, that give access to the FP
* extension, or
* - the CONTROL.FPCA bit is set to 1
*
****************************************************************************/
#ifdef CONFIG_ARCH_FPU
#if defined(CONFIG_ARMV7M_CMNVECTOR) && !defined(CONFIG_ARMV7M_LAZYFPU)
static inline void lpc54_fpuconfig(void)
{
uint32_t regval;
/* Set CONTROL.FPCA so that we always get the extended context frame
* with the volatile FP registers stacked above the basic context.
*/
regval = getcontrol();
regval |= (1 << 2);
setcontrol(regval);
/* Ensure that FPCCR.LSPEN is disabled, so that we don't have to contend
* with the lazy FP context save behaviour. Clear FPCCR.ASPEN since we
* are going to turn on CONTROL.FPCA for all contexts.
*/
regval = getreg32(NVIC_FPCCR);
regval &= ~((1 << 31) | (1 << 30));
putreg32(regval, NVIC_FPCCR);
/* Enable full access to CP10 and CP11 */
regval = getreg32(NVIC_CPACR);
regval |= ((3 << (2 * 10)) | (3 << (2 * 11)));
putreg32(regval, NVIC_CPACR);
}
#else
static inline void lpc54_fpuconfig(void)
{
uint32_t regval;
/* Clear CONTROL.FPCA so that we do not get the extended context frame
* with the volatile FP registers stacked in the saved context.
*/
regval = getcontrol();
regval &= ~(1 << 2);
setcontrol(regval);
/* Ensure that FPCCR.LSPEN is disabled, so that we don't have to contend
* with the lazy FP context save behaviour. Clear FPCCR.ASPEN since we
* are going to keep CONTROL.FPCA off for all contexts.
*/
regval = getreg32(NVIC_FPCCR);
regval &= ~((1 << 31) | (1 << 30));
putreg32(regval, NVIC_FPCCR);
/* Enable full access to CP10 and CP11 */
regval = getreg32(NVIC_CPACR);
regval |= ((3 << (2 * 10)) | (3 << (2 * 11)));
putreg32(regval, NVIC_CPACR);
}
#endif
#else
# define lpc54_fpuconfig()
#endif
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: _start
*
* Description:
* This is the reset entry point.
*
****************************************************************************/
void __start(void)
{
const uint32_t *src;
uint32_t *dest;
uint32_t regval;
/* Make sure that interrupts are disabled */
__asm__ __volatile__ ("\tcpsid i\n");
/* Enable the SRAM clock to make the stack usable */
regval = (SYSCON_AHBCLKCTRL0_SRAM1 | SYSCON_AHBCLKCTRL0_SRAM2 |
SYSCON_AHBCLKCTRL0_SRAM3);
putreg32(regval, LPC54_SYSCON_AHBCLKCTRLSET0);
/* Configure the clocking and the console uart so that we can get debug
* output as soon as possible. NOTE: That this logic must not assume that
* .bss or .data have beeninitialized.
*/
lpc54_clockconfig(&g_initial_pll_setup);
lpc54_lowsetup();
showprogress('A');
/* Clear .bss. We'll do this inline (vs. calling memset) just to be
* certain that there are no issues with the state of global variables.
*/
for (dest = &_sbss; dest < &_ebss; )
{
*dest++ = 0;
}
showprogress('B');
/* Move the initialized data section from his temporary holding spot in
* FLASH into the correct place in SRAM. The correct place in SRAM is
* give by _sdata and _edata. The temporary location is in FLASH at the
* end of all of the other read-only data (.text, .rodata) at _eronly.
*/
for (src = &_eronly, dest = &_sdata; dest < &_edata; )
{
*dest++ = *src++;
}
showprogress('C');
/* Initialize the FPU (if configured) */
lpc54_fpuconfig();
showprogress('D');
/* Perform early serial initialization */
#ifdef USE_EARLYSERIALINIT
lpc54_earlyserialinit();
#endif
showprogress('E');
/* For the case of the separate user-/kernel-space build, perform whatever
* platform specific initialization of the user memory is required.
* Normally this just means initializing the user space .data and .bss
* segments.
*/
#ifdef CONFIG_BUILD_PROTECTED
lpc54_userspace();
showprogress('F');
#endif
/* Initialize onboard resources */
lpc54_board_initialize();
showprogress('G');
/* Then start NuttX */
showprogress('\r');
showprogress('\n');
os_start();
/* Shouldn't get here */
for (; ; );
}

View file

@ -0,0 +1,88 @@
/************************************************************************************
* arch/arm/src/lpc54xx/lpc54_start.h
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
************************************************************************************/
#ifndef __ARCH_ARM_SRC_LPC54XX_LPC54_START_H
#define __ARCH_ARM_SRC_LPC54XX_LPC54_START_H
/************************************************************************************
* Included Files
************************************************************************************/
#include <nuttx/config.h>
#include <nuttx/compiler.h>
#include <sys/types.h>
#include <stdint.h>
#include <stdbool.h>
#include "up_internal.h"
#include "chip.h"
/************************************************************************************
* Public Data
************************************************************************************/
#ifndef __ASSEMBLY__
/* g_idle_topstack: _sbss is the start of the BSS region as defined by the linker
* script. _ebss lies at the end of the BSS region. The idle task stack starts at
* the end of BSS and is of size CONFIG_IDLETHREAD_STACKSIZE. The IDLE thread is
* the thread that the system boots on and, eventually, becomes the IDLE, do
* nothing task that runs only when there is nothing else to run. The heap
* continues from there until the end of memory. g_idle_topstack is a read-only
* variable the provides this computed address.
*/
extern const uintptr_t g_idle_topstack;
/************************************************************************************
* Public Function Prototypes
************************************************************************************/
/************************************************************************************
* Name: lpc54_board_initialize
*
* Description:
* All LPC54xx architectures must provide the following entry point. This entry
* point is called early in the initialization -- after clocking and memory have
* been configured but before caches have been enabled and before any devices have
* been initialized.
*
************************************************************************************/
void lpc54_board_initialize(void);
#endif /* __ASSEMBLY__ */
#endif /* __ARCH_ARM_SRC_LPC54XX_LPC54_START_H */

View file

@ -0,0 +1,802 @@
/****************************************************************************
* arch/arm/src/lpc54xx/lpc54_rit.c
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Derives from the LPC43xx tickless most logic
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <errno.h>
#include <time.h>
#include <nuttx/irq.h>
#include <nuttx/arch.h>
#include <nuttx/clock.h>
#include <arch/board/board.h>
#include "up_arch.h"
#include "chip.h"
#include "chip/lpc54_rit.h"
#ifdef CONFIG_SCHED_TICKLESS
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
#ifndef min
# define min(a,b) (a < b ? a : b)
#endif
#define COUNTER_MAX 0x0000ffffffffffffllu
/****************************************************************************
* Private Data
****************************************************************************/
static uint64_t g_to_reset = COUNTER_MAX / 2;
static uint64_t g_to_reset_next = COUNTER_MAX / 2 + COUNTER_MAX / 4;
static uint64_t g_to_end = COUNTER_MAX / 2 + COUNTER_MAX / 4 + COUNTER_MAX / 8; /* any alarm should no last more than COUNTER_MAX/8 */
static struct timespec g_max_ts;
static uint64_t g_common_div;
static uint64_t g_min_ticks;
static uint64_t g_min_nsec;
static uint64_t g_reset_ticks = 1000; /* Ticks to add to force a reset */
static struct timespec g_base_ts; /* Time base */
static uint64_t g_base_rest; /* Rest of ticks that is < g_min_ticks */
static struct timespec g_alarm_ts; /* alarm_time to set on next interrupt, used if not already g_armed */
static bool g_alarm_time_set = false; /* true if alarm_time set and need to be processed */
static bool g_call = false; /* true if callback should be called on next interrupt */
static bool g_forced_int = false; /* true if interrupt was forced with mask, no reset */
static bool g_armed = false; /* true if alarm is g_armed for next match */
static uint32_t g_synch = 0; /* Synch all calls, recursion is possible */
static irqstate_t g_flags;
static uint32_t g_cached_ctrl;
static uint64_t g_cached_mask;
static uint64_t g_cached_compare;
/****************************************************************************
* Private Functions
****************************************************************************/
/* Some timer HW functions */
static inline void lpc54_set_counter(uint64_t value)
{
putreg32(0, LPC54_RIT_COUNTER);
putreg16((uint32_t)(value >> 32), LPC54_RIT_COUNTERH);
putreg32((uint32_t)(value & 0xffffffffllu), LPC54_RIT_COUNTER);
}
static uint64_t lpc54_get_counter(void)
{
uint32_t ls;
uint16_t ms;
uint16_t verify;
do
{
ms = getreg16(LPC54_RIT_COUNTERH);
ls = getreg32(LPC54_RIT_COUNTER);
verify = getreg16(LPC54_RIT_COUNTERH);
}
while (verify != ms);
return (uint64_t)ms << 32 | (uint64_t)ls;
}
static void lpc54_set_compare(uint64_t value)
{
irqstate_t flags;
if (value != g_cached_compare)
{
g_cached_compare = value;
flags = enter_critical_section();
putreg32(0, LPC54_RIT_COMPVAL);
putreg16((uint32_t)(value >> 32), LPC54_RIT_COMPVALH);
putreg32((uint32_t)(value & 0xffffffffllu), LPC54_RIT_COMPVAL);
leave_critical_section();
}
}
static inline uint64_t lpc54_get_compare(void)
{
return g_cached_compare;
}
static void lpc54_set_mask(uint64_t value)
{
irqstate_t flags;
if (value != g_cached_mask)
{
g_cached_mask = value;
flags = enter_critical_section();
putreg32(0, LPC54_RIT_MASK);
putreg16((uint32_t)(value >> 32), LPC54_RIT_MASKH);
putreg32((uint32_t)(value & 0xffffffffllu), LPC54_RIT_MASK);
leave_critical_section();
putreg32(value, );
}
}
static inline uint64_t lpc54_get_mask(void)
{
return g_cached_mask;
}
static inline bool lpc54_get_ctrl_bit(uint32_t bit)
{
return (g_cached_ctrl & bit) != 0;
}
static inline void lpc54_set_ctrl_bit(uint32_t bit, bool value)
{
if (lpc54_get_ctrl_bit(bit) != value)
{
if (value)
{
g_cached_ctrl |= bit;
}
else
{
g_cached_ctrl &= ~bit;
}
putreg32(g_cached_ctrl, LPC54_RIT_CTRL);
}
}
static inline void lpc54_set_reset_on_match(bool value)
{
lpc54_set_ctrl_bit(RIT_CTRL_ENCLR, value);
}
static inline bool lpc54_get_reset_on_match(void)
{
return lpc54_get_ctrl_bit(RIT_CTRL_ENCLR);
}
static inline void lpc54_set_enable(bool value)
{
lpc54_set_ctrl_bit(RIT_CTRL_EN, value);
}
static inline bool lpc54_get_enable(void)
{
return lpc54_get_ctrl_bit(RIT_CTRL_EN);
}
static inline void lpc54_clear_interrupt(void)
{
putreg32(g_cached_ctrl | RIT_CTRL_INT, LPC54_RIT_CTRL);
}
static inline bool lpc54_get_interrupt(void)
{
return (getreg32(LPC54_RIT_CTRL) & RIT_CTRL_INT) != 0;
}
/* Converters */
static uint32_t common_div(uint32_t a, uint32_t b)
{
while (b != 0)
{
int h = a % b;
a = b;
b = h;
}
return a;
}
static void lpc54_ts_add(FAR const struct timespec *ts1,
FAR const struct timespec *ts2,
FAR struct timespec *ts3)
{
time_t sec = ts1->tv_sec + ts2->tv_sec;
long nsec = ts1->tv_nsec + ts2->tv_nsec;
if (nsec >= NSEC_PER_SEC)
{
nsec -= NSEC_PER_SEC;
sec++;
}
ts3->tv_sec = sec;
ts3->tv_nsec = nsec;
}
static void lpc54_ts_sub(FAR const struct timespec *ts1,
FAR const struct timespec *ts2,
FAR struct timespec *ts3)
{
time_t sec;
long nsec;
if (ts1->tv_sec < ts2->tv_sec)
{
sec = 0;
nsec = 0;
}
else if (ts1->tv_sec == ts2->tv_sec && ts1->tv_nsec <= ts2->tv_nsec)
{
sec = 0;
nsec = 0;
}
else
{
sec = ts1->tv_sec - ts2->tv_sec;
if (ts1->tv_nsec < ts2->tv_nsec)
{
nsec = (ts1->tv_nsec + NSEC_PER_SEC) - ts2->tv_nsec;
sec--;
}
else
{
nsec = ts1->tv_nsec - ts2->tv_nsec;
}
}
ts3->tv_sec = sec;
ts3->tv_nsec = nsec;
}
static inline uint64_t lpc54_ts2tick(FAR const struct timespec *ts)
{
return (uint64_t)ts->tv_sec * LPC54_CCLK +
((uint64_t)ts->tv_nsec / g_min_nsec * g_min_ticks));
}
static uint64_t lpc54_tick2ts(uint64_t ticks, FAR struct timespec *ts,
bool with_rest)
{
uint64_t ticks_whole;
uint64_t ticks_rest = 0;
if (with_rest)
{
uint64_t ticks_mult = ticks/g_min_ticks;
ticks_whole = ticks_mult*g_min_ticks;
ticks_rest = ticks - ticks_whole;
}
else
{
ticks_whole = ticks;
}
ts->tv_sec = ticks_whole/LPC54_CCLK;
ts->tv_nsec = ((ticks_whole % LPC54_CCLK) / g_min_ticks) * g_min_nsec;
return ticks_rest;
}
/* Logic functions */
static inline void lpc54_sync_up(void)
{
irqstate_t flags;
flags = enter_critical_section();
if (g_synch == 0)
{
g_flags = flags;
}
g_synch++;
}
static inline void lpc54_sync_down(void)
{
g_synch--;
if (g_synch == 0)
{
leave_critical_section(g_flags);
}
}
/* Assuming safe timer state, force interrupt, no reset possible */
static inline void lpc54_force_int(void)
{
g_forced_int = true;
lpc54_set_reset_on_match(false);
lpc54_set_mask(COUNTER_MAX);
lpc54_set_compare(COUNTER_MAX);
}
/* Init all vars, g_forced_int should not be cleared */
static inline void lpc54_init_timer_vars(void)
{
g_alarm_time_set = false;
g_call = false;
g_armed = false;
}
/* Calc g_reset_ticks and set compare to g_to_reset */
static void lpc54_calibrate_init(void)
{
uint64_t counter = lpc54_get_counter();
uint64_t counter_after = lpc54_get_counter();
counter_after = g_to_reset + counter;
counter_after = counter_after - counter;
/* Shift to to Reset */
lpc54_set_compare(counter_after);
counter_after = lpc54_get_counter();
g_reset_ticks = (counter_after - counter) * 2;
}
/* Process current and set timer in default safe state */
static void lpc54_save_timer(bool from_isr)
{
if (g_forced_int) /* special case of forced interrupt by mask */
{
g_forced_int = false;
lpc54_set_compare(COUNTER_MAX);
lpc54_set_mask(0);
lpc54_clear_interrupt();
}
else
{
/* Process reset if any */
uint64_t match = lpc54_get_compare();
/* Move to end, no resets during processing */
lpc54_set_compare(COUNTER_MAX);
lpc54_set_mask(0);
if (from_isr || lpc54_get_interrupt())
{
if (lpc54_get_reset_on_match()) /* Was reset? */
{
struct timespec match_ts;
g_base_rest = lpc54_tick2ts(match + g_base_rest,
&match_ts, true);
lpc54_ts_add(&g_base_ts, &match_ts, &g_base_ts);
}
lpc54_clear_interrupt();
}
}
}
/* Assuming safe timer state, true if set, false - time is in the past */
static bool lpc54_set_safe_compare(uint64_t compare_to_set)
{
uint64_t counter;
bool reset;
bool reset_after;
if (compare_to_set < g_to_reset)
{
lpc54_set_reset_on_match(false);
}
else
{
lpc54_set_reset_on_match(true);
}
lpc54_set_compare(compare_to_set);
/* Check if ok */
reset = lpc54_get_interrupt();
counter = lpc54_get_counter();
reset_after = lpc54_get_interrupt();
if (reset != reset_after)
{
/* Was a reset get new counter */
counter = lpc54_get_counter();
}
if (reset_after || (!reset_after && compare_to_set > counter))
{
return true;
}
else
{
lpc54_set_compare(COUNTER_MAX);
return false;
}
}
/* Assuming safe timer state, set_safe_compare in loop */
static void lpc54_looped_forced_set_compare(void)
{
uint32_t i = 1;
bool result =
lpc54_set_safe_compare(lpc54_get_counter() + g_reset_ticks);
while (!result)
{
i++;
result =
lpc54_set_safe_compare(lpc54_get_counter() + g_reset_ticks * i);
}
}
/* Assuming safe timer state, true if set, false - time is in the past */
static bool lpc54_set_calc_arm(uint64_t curr, uint64_t to_set, bool arm)
{
uint64_t calc_time;
bool set;
if (curr < g_to_reset_next)
{
calc_time = min(g_to_reset_next, to_set);
}
else
{
if (curr < g_to_end)
{
calc_time = min(curr + g_reset_ticks, to_set);
}
else
{
lpc54_looped_forced_set_compare();
return true;
}
}
set = lpc54_set_safe_compare(calc_time);
if (arm && set && (calc_time == to_set))
{
g_armed = true;
}
return set;
}
/* Assuming safe timer state, try to set compare for normal operation */
static void lpc54_set_default_compare(uint64_t curr)
{
bool result = lpc54_set_calc_arm(curr, COUNTER_MAX, false);
if (!result)
{
result = lpc54_set_calc_arm(lpc54_get_counter(), COUNTER_MAX,
false);
if (!result)
{
lpc54_looped_forced_set_compare();
}
}
}
/* Calculates ticks to set from g_alarm_ts and g_base_ts/g_base_rest,
* COUNTER_MAX if overflow.
*/
static inline uint64_t lpc54_calc_to_set(void)
{
struct timespec diff_ts;
struct timespec ovf_ts;
lpc54_ts_sub(&g_alarm_ts, &g_base_ts, &diff_ts);
lpc54_ts_sub(&diff_ts, &g_max_ts, &ovf_ts);
if (ovf_ts.tv_sec == 0 && ovf_ts.tv_nsec == 0) /* check overflow */
{
return (lpc54_ts2tick(&diff_ts) - g_base_rest);
}
else
{
return COUNTER_MAX;
}
}
/* Assuming safe timer state, used by isr: sets default compare,
* calls alarm.
*/
static inline void lpc54_tl_alarm(uint64_t curr)
{
lpc54_init_timer_vars();
lpc54_set_default_compare(curr);
#ifdef CONFIG_SCHED_TICKLESS_ALARM
struct timespec ts;
up_timer_gettime(&ts);
sched_alarm_expiration(&ts);
#else
sched_timer_expiration();
#endif
}
/* Interrupt handler */
static int lpc54_tl_isr(int irq, FAR void *context, FAR void *arg)
{
uint64_t curr;
lpc54_sync_up();
lpc54_save_timer(true);
curr = lpc54_get_counter();
if (g_call)
{
lpc54_tl_alarm(curr);
}
else
{
if (g_armed)
{
lpc54_tl_alarm(curr); /* g_armed - g_call alarm */
}
else
{
if (g_alarm_time_set) /* need to set alarm time */
{
uint64_t toset = lpc54_calc_to_set();
if (toset > curr)
{
if (toset > g_to_end)
{
lpc54_set_default_compare(curr);
}
else
{
bool set = lpc54_set_calc_arm(curr, toset, true);
if (!set)
{
lpc54_tl_alarm(curr);
}
}
}
else
{
lpc54_tl_alarm(curr);
}
}
else
{
lpc54_set_default_compare(curr);
}
}
}
lpc54_sync_down();
return OK;
}
/****************************************************************************
* Public Functions
****************************************************************************/
void arm_timer_initialize(void)
{
irqstate_t flags;
flags = enter_critical_section();
g_cached_ctrl = getreg32(LPC54_RIT_CTRL);
g_cached_ctrl &= ~RIT_CTRL_INT; /* Set interrupt to 0 */
g_cached_mask = getreg32(LPC54_RIT_MASK);
g_cached_compare = getreg32(LPC54_RIT_COMPVAL);
g_common_div = common_div(NSEC_PER_SEC, LPC54_CCLK);
g_min_ticks = LPC54_CCLK / g_common_div;
g_min_nsec = NSEC_PER_SEC / g_common_div;
g_base_ts.tv_sec = 0;
g_base_ts.tv_nsec = 0;
g_base_rest = 0;
lpc54_tick2ts(g_to_end, &g_max_ts, false);
lpc54_set_enable(false);
lpc54_set_compare(COUNTER_MAX);
lpc54_set_counter(0);
lpc54_set_mask(0);
lpc54_set_reset_on_match(false);
lpc54_clear_interrupt();
irq_attach(LPC54M4_IRQ_RITIMER, lpc54_tl_isr, NULL);
up_enable_irq(LPC54M4_IRQ_RITIMER);
lpc54_init_timer_vars();
lpc54_set_enable(true);
lpc54_calibrate_init();
leave_critical_section(flags);
}
/* No reg changes, only processing */
int up_timer_gettime(FAR struct timespec *ts)
{
struct timespec count_ts;
uint64_t count;
bool reset;
lpc54_sync_up();
/* Order of calls is important, reset can come during processing */
reset = lpc54_get_interrupt();
count = lpc54_get_counter();
/* Not processed reset can exist */
if (lpc54_get_reset_on_match())
{
bool reset_after = lpc54_get_interrupt();
/* Was a reset during processing? get new counter */
if (reset != reset_after)
{
count = lpc54_get_counter();
}
if (reset_after)
{
/* Count should be smaller then COUNTER_MAX-g_to_end -> no overflow */
count += lpc54_get_compare();
}
}
lpc54_tick2ts(count + g_base_rest, &count_ts, false);
lpc54_ts_add(&g_base_ts, &count_ts, ts);
lpc54_sync_down();
return OK;
}
int up_alarm_cancel(FAR struct timespec *ts)
{
lpc54_sync_up();
/* No reg changes, only variables logic */
if (ts != NULL)
{
up_timer_gettime(ts);
}
/* Let default setup will be done in interrupt handler or up_alarm_start */
lpc54_init_timer_vars();
lpc54_sync_down();
return OK;
}
int up_alarm_start(FAR const struct timespec *ts)
{
uint64_t toset;
uint64_t curr;
lpc54_sync_up();
lpc54_save_timer(false);
lpc54_init_timer_vars();
g_alarm_time_set = true;
g_alarm_ts.tv_sec = ts->tv_sec;
g_alarm_ts.tv_nsec = ts->tv_nsec;
toset = lpc54_calc_to_set();
curr = lpc54_get_counter();
if (toset > curr)
{
if (toset > g_to_end) /* Future set */
{
lpc54_set_default_compare(curr);
}
else
{
bool set = lpc54_set_calc_arm(curr, toset, true);
if (!set) /* Signal g_call, force interrupt handler */
{
g_call = true;
lpc54_force_int();
}
}
}
else /* Signal g_call, force interrupt handler */
{
g_call = true;
lpc54_force_int();
}
lpc54_sync_down();
return OK;
}
#ifndef CONFIG_SCHED_TICKLESS_ALARM
int up_timer_cancel(FAR struct timespec *ts)
{
lpc54_sync_up();
if (ts != NULL)
{
struct timespec abs_ts;
up_timer_gettime(&abs_ts);
lpc54_ts_sub(&g_alarm_ts, &abs_ts, ts);
}
lpc54_init_timer_vars();
lpc54_sync_down();
return OK;
}
int up_timer_start(FAR const struct timespec *ts)
{
lpc54_sync_up();
struct timespec abs_ts;
up_timer_gettime(&abs_ts);
lpc54_ts_add(&abs_ts, ts, &abs_ts);
up_alarm_start(&abs_ts);
lpc54_sync_down();
return OK;
}
#endif /* CONFIG_SCHED_TICKLESS_ALARM */
#endif /* CONFIG_SCHED_TICKLESS */

View file

@ -0,0 +1,171 @@
/****************************************************************************
* arch/arm/src/lpc54xx/lpc54_timerisr.c
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <stdint.h>
#include <time.h>
#include <debug.h>
#include <nuttx/arch.h>
#include <arch/board/board.h>
#include "nvic.h"
#include "clock/clock.h"
#include "up_internal.h"
#include "up_arch.h"
#include "chip/lpc54_syscon.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/* The SysTick clock may be clocked internally either by the by the system
* clock (CLKSOURCE==1) or by the SysTick function clock (CLKSOURCE==0).
* The SysTick Function clock is equal to:
*
* Fsystick = Fmainclk / SYSTICKCLKDIV
*
* Both the divider value (BOARD_SYSTICKCLKDIV) and the resulting SysTick
* function clock frequency (Fsystick, BOARD_SYSTICK_CLOCK)
*
* 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).
*
* reload = (Fsystick / CLK_TICK) - 1
*
* Tips for selecting BOARD_SYSTICKCLKDIV: The resulting reload value
* should be as large as possible, but must be less than 2^24:
*
* SYSTICKDIV > Fmainclk / CLK_TCK / 2^24
*/
#define SYSTICK_RELOAD ((BOARD_SYSTICK_CLOCK / 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 Functions
****************************************************************************/
/****************************************************************************
* Function: lpc54_timerisr
*
* Description:
* The timer ISR will perform a variety of services for various portions
* of the systems.
*
****************************************************************************/
static int lpc54_timerisr(int irq, uint32_t *regs, void *arg)
{
/* Process timer interrupt */
sched_process_timer();
return 0;
}
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Function: arm_timer_initialize
*
* Description:
* This function is called during start-up to initialize
* the timer interrupt.
*
****************************************************************************/
void arm_timer_initialize(void)
{
uint32_t regval;
/* May be clocked internally by the system clock or the SysTick function
* clock. Set the SysTick clock divider in the SYSCON_SYSTICK register.
* Since this function is called early after reset, it is safe to assume
* that the SysTick is disabled and so that no reset or halt actions are
* necessary.
*/
regval = (SYSCON_SYSTICKCLKDIV_DIV(BOARD_SYSTICKCLKDIV) |
SYSCON_SYSTICKCLKDIV_REQFLAG);
putreg32(regval, LPC54_SYSCON_SYSTICKCLKDIV);
/* The request flag will be cleared when the divider change is complete */
while ((getreg32(LPC54_SYSCON_SYSTICKCLKDIV) & SYSCON_SYSTICKCLKDIV_REQFLAG) != 0)
{
}
/* Make sure that the SYSTICK clock source is set to use the SysTick
* function clock (CLKSOURCE==0).
*/
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(LPC54_IRQ_SYSTICK, (xcpt_t)lpc54_timerisr, NULL);
/* 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(LPC54_IRQ_SYSTICK);
}

View file

@ -0,0 +1,107 @@
/****************************************************************************
* arch/arm/src/lpc54xx/lpc54_userspace.c
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <stdint.h>
#include <assert.h>
#include <nuttx/userspace.h>
#include "lpc54_mpuinit.h"
#include "lpc54_userspace.h"
#ifdef CONFIG_BUILD_PROTECTED
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: lpc54_userspace
*
* Description:
* For the case of the separate user-/kernel-space build, perform whatever
* platform specific initialization of the user memory is required.
* Normally this just means initializing the user space .data and .bss
* segments.
*
****************************************************************************/
void lpc54_userspace(void)
{
uint8_t *src;
uint8_t *dest;
uint8_t *end;
/* Clear all of user-space .bss */
DEBUGASSERT(USERSPACE->us_bssstart != 0 && USERSPACE->us_bssend != 0 &&
USERSPACE->us_bssstart <= USERSPACE->us_bssend);
dest = (uint8_t *)USERSPACE->us_bssstart;
end = (uint8_t *)USERSPACE->us_bssend;
while (dest != end)
{
*dest++ = 0;
}
/* Initialize all of user-space .data */
DEBUGASSERT(USERSPACE->us_datasource != 0 &&
USERSPACE->us_datastart != 0 && USERSPACE->us_dataend != 0 &&
USERSPACE->us_datastart <= USERSPACE->us_dataend);
src = (uint8_t *)USERSPACE->us_datasource;
dest = (uint8_t *)USERSPACE->us_datastart;
end = (uint8_t *)USERSPACE->us_dataend;
while (dest != end)
{
*dest++ = *src++;
}
/* Configure the MPU to permit user-space access to its FLASH and RAM */
lpc54_mpuinitialize();
}
#endif /* CONFIG_BUILD_PROTECTED */

View file

@ -0,0 +1,64 @@
/************************************************************************************
* arch/arm/src/lpc54xx/lpc54_userspace.h
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
************************************************************************************/
#ifndef __ARCH_ARM_SRC_LPC54XX_LPC54_USERSPACE_H
#define __ARCH_ARM_SRC_LPC54XX_LPC54_USERSPACE_H
/************************************************************************************
* Included Files
************************************************************************************/
#include <nuttx/config.h>
/************************************************************************************
* Public Function Prototypes
************************************************************************************/
/****************************************************************************
* Name: lpc54_userspace
*
* Description:
* For the case of the separate user-/kernel-space build, perform whatever
* platform specific initialization of the user memory is required.
* Normally this just means initializing the user space .data and .bss
* segments.
*
****************************************************************************/
#ifdef CONFIG_BUILD_PROTECTED
void lpc54_userspace(void);
#endif
#endif /* __ARCH_ARM_SRC_LPC54XX_LPC54_USERSPACE_H */

View file

@ -329,6 +329,13 @@ config ARCH_BOARD_LPCXPRESSO
Embedded Artists base board with NXP LPCExpresso LPC1768. This board
is based on the NXP LPC1768. The Code Red toolchain is used by default.
config ARCH_BOARD_LPCXPRESSO_LPC54628
bool "NXP LPCXpresso LPC54628"
depends on ARCH_CHIP_LPC54628
select ARCH_HAVE_LEDS
---help---
LPCXpresso LPC54626 board featuring the NXP LPC54628 MCU.
config ARCH_BOARD_BAMBINO_200E
bool "Micromint Bambino 200E"
depends on ARCH_CHIP_LPC4330FBD144
@ -1595,6 +1602,7 @@ config ARCH_BOARD
default "lpc4370-link2" if ARCH_BOARD_LPC4370_LINK2
default "lpcxpresso-lpc1115" if ARCH_BOARD_LPCXPRESSO_LPC1115
default "lpcxpresso-lpc1768" if ARCH_BOARD_LPCXPRESSO
default "lpcxpresso-lpc54628" if ARCH_BOARD_LPCXPRESSO_LPC54628
default "maple" if ARCH_BOARD_MAPLE
default "mbed" if ARCH_BOARD_MBED
default "mcb1700" if ARCH_BOARD_MCB1700
@ -1851,6 +1859,9 @@ endif
if ARCH_BOARD_LPCXPRESSO
source "configs/lpcxpresso-lpc1768/Kconfig"
endif
if ARCH_BOARD_LPCXPRESSO_LPC54628
source "configs/lpcxpresso-lpc54628/Kconfig"
endif
if ARCH_BOARD_MAPLE
source "configs/maple/Kconfig"
endif

View file

@ -314,6 +314,9 @@ configs/lpcxpresso-lpc1768
is based on the NXP LPC1768. The Code Red toolchain is used by default.
STATUS: Under development.
configs/lpcxpresso-lpc54628
NXP LPCExpresso LPC54628. This board is based on the NXP LPC54628.
configs/lpc4330-xplorer
NuttX port to the LPC4330-Xplorer board from NGX Technologies featuring
the NXP LPC4330FET100 MCU

View file

@ -0,0 +1,7 @@
#
# For a description of the syntax of this configuration file,
# see the file kconfig-language.txt in the NuttX tools repository.
#
if ARCH_BOARD_LPCXPRESSO
endif

View file

@ -0,0 +1,253 @@
/****************************************************************************
* configs/lpcxpresso-lpc54628/include/board.h
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#ifndef _CONFIGS_LPCXPRESSO_LPC54628_INCLUDE_BOARD_H
#define _CONFIGS_LPCXPRESSO_LPC54628_INCLUDE_BOARD_H
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/* Clocking ****************************************************************/
#undef BOARD_180MHz
#define BOARD_220MHz 1
/* System PLL
*
* Notation:
* Fin = the input to the PLL.
* Fout = the output of the PLL.
* Fref = the PLL reference frequency, the input to the phase frequency
* detector.
* N = optional pre-divider value.
* M = feedback divider value, which represents the multiplier for the
* PLL.
* P = optional post-divider value. An additional divide-by-2 is
* included in the post-divider path.
*
* In all variations of normal mode, the following requirements must be met:
*
* -275 MHz Fcco 550 MHz.
* 4 kHz Fin / N 25 MHz.
*
* Normal mode with optional pre-divide. In the equations, use N = 1 when
* the pre-divider is not used. The extra divide by 2 is in the feedback
* divider path:
*
* Fout = Fcco = 2 x M x Fin / N
*
* Normal mode with post-divide and optional pre-divide. In the equations,
* use N = 1 when the pre-divider is not used:
*
* Fout = Fcco / (2 x P) = M x Fin / (N x P)
*/
#define BOARD_PLL_SOURCE /* Select source FR0 12MHz */
#define BOARD_PLL_FIN LPC54_FRO_12MHZ /* PLL input frequency */
#ifdef BOARD_180MHz
/* PLL Clock Source: CLKIN
* Main Clock Source: PLL
* Fout: 220000000
*/
# define BOARD_PLL_CLKSEL SYSCON_SYSPLLCLKSEL_CLKIN
# define BOARD_PLL_SELI 32 /* Bandwidth select I value */
# define BOARD_PLL_SELP 16 /* Bandwidth select P value */
# define BOARD_PLL_SELR 0 /* Bandwidth select R value */
# define BOARD_PLL_MDEC 8191 /* Encoded M-divider coefficient */
# define BOARD_PLL_NDEC 770 /* Encoded N-divider coefficient */
# define BOARD_PLL_PDEC 98 /* Encoded P-divider coefficient */
# define BOARD_PLL_FOUT 180000000U /* Pll output frequency */
#else /* BOARD_220MHz */
/* PLL Clock Source: FRO 12MHz
* Main Clock Source: PLL
* Fout: 220000000
*/
# define BOARD_PLL_CLKSEL SYSCON_SYSPLLCLKSEL_FFRO
# define BOARD_PLL_SELI 34 /* Bandwidth select I value */
# define BOARD_PLL_SELP 31 /* Bandwidth select P value */
# define BOARD_PLL_SELR 0 /* Bandwidth select R value */
# define BOARD_PLL_MDEC 13243 /* Encoded M-divider coefficient */
# define BOARD_PLL_NDEC 1 /* Encoded N-divider coefficient */
# define BOARD_PLL_PDEC 98 /* Encoded P-divider coefficient */
# define BOARD_PLL_FOUT 220000000 /* Pll output frequency */
#endif
#define BOARD_MAIN_CLK BOARD_PLL_FOUT /* Main clock frequency */
/* CPU Clock:
*
* AHB Clock Divider: 1
* AHB Clock Frequency: 220,000,000
*/
#define BOARD_AHBCLKDIV 1
#define BOARD_AHB_FREQUENCY (BOARD_MAIN_CLK / BOARD_AHBCLKDIV)
#define BOARD_CPU_FREQUENCY BOARD_AHB_FREQUENCY
/* Fraction Rate Generator (FRG) Clock (Optional Flexcomm0 function clock)
*
* To use the fractional divider, the DIV value must be programmed with the
* fixed value of 256. Then:
*
* Ffrg = (Finput) / (1 + (MULT / DIV))
*
* Mainclock is used as the FRG clock source. Divider must be such that the
* FRG output frequency is less than equal to 48MHz
*
* MUL = (Finput - Ffrg) * 256) / Ffrg
*/
/* Revisit: FRGCLK <= 48MHz cannot be realized with the MainClk source */
#define BOARD FRGCLK_CLKSEL SYSCON_FRGCLKSEL_MAINCLK
#define BOARD_FRGCLK_INPUT BOARD_MAIN_CLK /* FRG input frequency */
#define BOARD_FRGCLK 48000000 /* May not be exact */
/* SysTick: The SysTick clock may be clocked internally either by the by the
* system clock (CLKSOURCE==1) or by the SysTick function clock (CLKSOURCE==0).
* The SysTick Function clock is equal to:
*
* Fsystick = Fmainclk / SYSTICKCLKDIV
*
* Tips for selecting BOARD_SYSTICKCLKDIV: The resulting SysTick reload value
* should be as large as possible, but must be less than 2^24:
*
* SYSTICKDIV > Fmainclk / CLK_TCK / 2^24
*
* The logic in lpc54_timerisr.c will always select the SysTick function clock
* as the source (CLKSOURCE==0). NOTE: When the system tick clock divider is
* selected as the clock source, the CPU clock must be at least 2.5 times
* faster than the divider output.
*
* SysTick Divider: (SYSTICKCLKDIV)
*/
#ifndef CONFIG_SCHED_TICKLESS
# if CONFIG_USEC_PER_TICK == 10000
# define BOARD_SYSTICKCLKDIV 1
# else
# error Missing SYSTICK divider
# endif
# define BOARD_SYSTICK_CLOCK (BOARD_AHB_FREQUENCY / BOARD_SYSTICKCLKDIV)
#endif
/* Flexcomm0: REVIST */
#define BOARD_FLEXCOMM0_CLKSEL SYSCON_FCLKSEL_FRO12M
#define BOARD_FLEXCOMM0_FCLK LPC54_FRO_12MHZ
/* LED definitions *********************************************************/
/* The LPCXpress-LPC54628 has three user LEDs: D9, D11, and D12. These
* LEDs are for application use. They are illuminated when the driving
* signal from the LPC546xx is low. The LEDs are driven by ports P2-2 (D9),
* P3-3 (D11) and P3-14 (D12).
*/
/* LED index values for use with board_userled() */
#define BOARD_D9 0
#define BOARD_D11 1
#define BOARD_D12 2
#define BOARD_NLEDS 3
/* LED bits for use with board_userled_all() */
#define BOARD_D9_BIT (1 << BOARD_D9)
#define BOARD_D11_BIT (1 << BOARD_D11)
#define BOARD_D12_BIT (1 << BOARD_D12)
/* These LEDs are not used by the NuttX port unless CONFIG_ARCH_LEDS is
* defined. In that case, the usage by the board port is defined in
* include/board.h and src/lpc54_autoleds.c. The LEDs are used to encode
* OS-related events as follows:
*/
/* D9 D11 D12 */
#define LED_STARTED 0 /* OFF OFF OFF */
#define LED_HEAPALLOCATE 1 /* ON OFF OFF */
#define LED_IRQSENABLED 2 /* OFF ON OFF */
#define LED_STACKCREATED 3 /* OFF OFF OFF */
#define LED_INIRQ 4 /* NC NC ON (momentary) */
#define LED_SIGNAL 4 /* NC NC ON (momentary) */
#define LED_ASSERTION 4 /* NC NC ON (momentary) */
#define LED_PANIC 4 /* NC NC ON (2Hz flashing) */
#undef LED_IDLE /* Sleep mode indication not supported */
/* Button definitions *******************************************************/
/* To be provided */
/* Pin Disambiguation *******************************************************/
/* To be provided */
/****************************************************************************
* Public Types
****************************************************************************/
#ifndef __ASSEMBLY__
/****************************************************************************
* Public Data
****************************************************************************/
#undef EXTERN
#if defined(__cplusplus)
#define EXTERN extern "C"
extern "C"
{
#else
#define EXTERN extern
#endif
/****************************************************************************
* Public Function Prototypes
****************************************************************************/
#undef EXTERN
#if defined(__cplusplus)
}
#endif
#endif /* __ASSEMBLY__ */
#endif /* _CONFIGS_LPCXPRESSO_LPC54628_INCLUDE_BOARD_H */

View file

@ -0,0 +1,42 @@
# CONFIG_ARCH_FPU is not set
# CONFIG_NSH_DISABLE_IFCONFIG is not set
# CONFIG_NSH_DISABLE_PS is not set
CONFIG_ARCH_BOARD_LPCXPRESSO_LPC54628=y
CONFIG_ARCH_BOARD="lpcxpresso-lpc54628"
CONFIG_ARCH_CHIP_LPC54628=y
CONFIG_ARCH_CHIP_LPC54XX=y
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_STDARG_H=y
CONFIG_ARCH="arm"
CONFIG_BOARD_LOOPSPERMSEC=18535
CONFIG_DEBUG_NOOPT=y
CONFIG_EXAMPLES_NSH=y
CONFIG_FAT_LCNAMES=y
CONFIG_FAT_LFN=y
CONFIG_FS_FAT=y
CONFIG_LPC54_USART0=y
CONFIG_MAX_TASKS=16
CONFIG_MAX_WDOGPARMS=2
CONFIG_MM_REGIONS=1
CONFIG_NFILE_DESCRIPTORS=8
CONFIG_NFILE_STREAMS=8
CONFIG_NSH_ARCHINIT=y
CONFIG_NSH_FILEIOSIZE=512
CONFIG_NSH_LINELEN=64
CONFIG_NSH_READLINE=y
CONFIG_PREALLOC_MQ_MSGS=4
CONFIG_PREALLOC_TIMERS=4
CONFIG_PREALLOC_WDOGS=4
CONFIG_RAM_SIZE=32768
CONFIG_RAM_START=0x10000000
CONFIG_RAW_BINARY=y
CONFIG_RR_INTERVAL=200
CONFIG_SCHED_WAITPID=y
CONFIG_SDCLONE_DISABLE=y
CONFIG_START_DAY=2
CONFIG_START_MONTH=12
CONFIG_SYMTAB_ORDEREDBYNAME=y
CONFIG_TASK_NAME_SIZE=0
CONFIG_USART0_SERIAL_CONSOLE=y
CONFIG_USER_ENTRYPOINT="nsh_main"
CONFIG_WDOG_INTRESERVE=0

View file

@ -0,0 +1,117 @@
############################################################################
# configs/lpcxpresso-lpc54628/scripts/Make.defs
#
# Copyright (C) 2017 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <gnutt@nuttx.org>
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name NuttX nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
include ${TOPDIR}/.config
include ${TOPDIR}/tools/Config.mk
include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs
# Setup for the kind of memory that we are executing from
LDSCRIPT = flash.ld
# Setup for Windows vs Linux/Cygwin/OSX environments
ifeq ($(WINTOOL),y)
# Windows-native toolchains
DIRLINK = $(TOPDIR)/tools/copydir.sh
DIRUNLINK = $(TOPDIR)/tools/unlink.sh
MKDEP = $(TOPDIR)/tools/mkwindeps.sh
ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}"
else
# Linux/Cygwin-native toolchain
MKDEP = $(TOPDIR)/tools/mkdeps$(HOSTEXEEXT)
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)
endif
CC = $(CROSSDEV)gcc
CXX = $(CROSSDEV)g++
CPP = $(CROSSDEV)gcc -E
LD = $(CROSSDEV)ld
AR = $(ARCROSSDEV)ar rcs
NM = $(ARCROSSDEV)nm
OBJCOPY = $(CROSSDEV)objcopy
OBJDUMP = $(CROSSDEV)objdump
ARCHCCVERSION = ${shell $(CC) -v 2>&1 | sed -n '/^gcc version/p' | sed -e 's/^gcc version \([0-9\.]\)/\1/g' -e 's/[-\ ].*//g' -e '1q'}
ARCHCCMAJOR = ${shell echo $(ARCHCCVERSION) | cut -d'.' -f1}
ifeq ($(CONFIG_DEBUG_SYMBOLS),y)
ARCHOPTIMIZATION = -g
endif
ifneq ($(CONFIG_DEBUG_NOOPT),y)
ARCHOPTIMIZATION += $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer
endif
ARCHCFLAGS = -fno-builtin
ARCHCXXFLAGS = -fno-builtin -fno-exceptions -fcheck-new -fno-rtti
ARCHWARNINGS = -Wall -Wstrict-prototypes -Wshadow -Wundef
ARCHWARNINGSXX = -Wall -Wshadow -Wundef
ARCHDEFINES =
ARCHPICFLAGS = -fpic -msingle-pic-base -mpic-register=r10
CFLAGS = $(ARCHCFLAGS) $(ARCHWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe
CPICFLAGS = $(ARCHPICFLAGS) $(CFLAGS)
CXXFLAGS = $(ARCHCXXFLAGS) $(ARCHWARNINGSXX) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHXXINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe
CXXPICFLAGS = $(ARCHPICFLAGS) $(CXXFLAGS)
CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES)
AFLAGS = $(CFLAGS) -D__ASSEMBLY__
NXFLATLDFLAGS1 = -r -d -warn-common
NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections
LDNXFLATFLAGS = -e main -s 2048
ASMEXT = .S
OBJEXT = .o
LIBEXT = .a
EXEEXT =
ifneq ($(CROSSDEV),arm-nuttx-elf-)
LDFLAGS += -nostartfiles -nodefaultlibs
endif
ifeq ($(CONFIG_DEBUG_SYMBOLS),y)
LDFLAGS += -g
endif
HOSTCC = gcc
HOSTINCLUDES = -I.
HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -Wundef -g -pipe
HOSTLDFLAGS =

View file

@ -0,0 +1,116 @@
/****************************************************************************
* configs/lpcxpresso-lpc54628/scripts/flash.ld
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/* The LPC54628 on the LPCXPressio has 512Kb of FLASH at address 0x0000:0000.
* The Main SRAM is comprised of up to a total 160 KB of contiguous, on-chip
* static RAM memory beginning at address 0x2000:0000 (this is in addition
* to SRAMX aso the total device SRAM can be up to 200 KB).
*/
MEMORY
{
progmem (rx) : ORIGIN = 0x00000000, LENGTH = 512K
datamem (rwx) : ORIGIN = 0x20000000, LENGTH = 160K
}
OUTPUT_ARCH(arm)
ENTRY(__start) /* Treat __start as the anchor for dead code stripping */
EXTERN(_vectors) /* Force the vectors to be included in the output */
SECTIONS
{
.text : {
_stext = ABSOLUTE(.);
*(.vectors)
*(.text .text.*)
*(.fixup)
*(.gnu.warning)
*(.rodata .rodata.*)
*(.gnu.linkonce.t.*)
*(.glue_7)
*(.glue_7t)
*(.got)
*(.gcc_except_table)
*(.gnu.linkonce.r.*)
_etext = ABSOLUTE(.);
} > progmem
.init_section : {
_sinit = ABSOLUTE(.);
*(.init_array .init_array.*)
_einit = ABSOLUTE(.);
} > progmem
.ARM.extab : {
*(.ARM.extab*)
} > progmem
__exidx_start = ABSOLUTE(.);
.ARM.exidx : {
*(.ARM.exidx*)
} > progmem
__exidx_end = ABSOLUTE(.);
_eronly = ABSOLUTE(.);
.data : {
_sdata = ABSOLUTE(.);
*(.data .data.*)
*(.gnu.linkonce.d.*)
CONSTRUCTORS
_edata = ABSOLUTE(.);
} > datamem AT > progmem
.bss : {
_sbss = ABSOLUTE(.);
*(.bss .bss.*)
*(.gnu.linkonce.b.*)
*(COMMON)
_ebss = ABSOLUTE(.);
} > datamem
/* Stabs debugging sections. */
.stab 0 : { *(.stab) }
.stabstr 0 : { *(.stabstr) }
.stab.excl 0 : { *(.stab.excl) }
.stab.exclstr 0 : { *(.stab.exclstr) }
.stab.index 0 : { *(.stab.index) }
.stab.indexstr 0 : { *(.stab.indexstr) }
.comment 0 : { *(.comment) }
.debug_abbrev 0 : { *(.debug_abbrev) }
.debug_info 0 : { *(.debug_info) }
.debug_line 0 : { *(.debug_line) }
.debug_pubnames 0 : { *(.debug_pubnames) }
.debug_aranges 0 : { *(.debug_aranges) }
}

View file

@ -0,0 +1,45 @@
############################################################################
# configs/lpcxpresso-lpc54628/src/Makefile
#
# Copyright (C) 2017 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <gnutt@nuttx.org>
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name NuttX nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
-include $(TOPDIR)/Make.defs
ASRCS =
CSRCS = lpc54_boot.c lpc54_bringup.c
ifeq ($(CONFIG_LIB_BOARDCTL),y)
CSRCS += lpc54_appinit.c
endif
include $(TOPDIR)/configs/Board.mk

View file

@ -0,0 +1,88 @@
/****************************************************************************
* config/lpcxpresso-lpc54628/src/lpc54_appinit.c
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <sys/types.h>
#include <nuttx/board.h>
#include "lpcxpresso-lpc54628.h"
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: board_app_initialize
*
* Description:
* Perform application specific initialization. This function is never
* called directly from application code, but only indirectly via the
* (non-standard) boardctl() interface using the command BOARDIOC_INIT.
*
* Input Parameters:
* arg - The boardctl() argument is passed to the board_app_initialize()
* implementation without modification. The argument has no
* meaning to NuttX; the meaning of the argument is a contract
* between the board-specific initalization logic and the
* matching application logic. The value cold be such things as a
* mode enumeration value, a set of DIP switch switch settings, a
* pointer to configuration data read from a file or serial FLASH,
* or whatever you would like to do with it. Every implementation
* should accept zero/NULL as a default configuration.
*
* Returned Value:
* Zero (OK) is returned on success; a negated errno value is returned on
* any failure to indicate the nature of the failure.
*
****************************************************************************/
int board_app_initialize(uintptr_t arg)
{
#ifdef CONFIG_BOARD_INITIALIZE
/* Board initialization already performed by board_initialize() */
return OK;
#else
/* Perform board-specific initialization */
return lpc54_bringup();
#endif
}

View file

@ -0,0 +1,85 @@
/************************************************************************************
* configs/lpcxpresso-lpc54628/src/lpc54_boot.c
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
************************************************************************************/
/************************************************************************************
* Included Files
************************************************************************************/
#include <nuttx/config.h>
#include <nuttx/board.h>
#include "lpcxpresso-lpc54628.h"
/************************************************************************************
* Public Functions
************************************************************************************/
/************************************************************************************
* Name: lpc54_board_initialize
*
* Description:
* All LPC54xx architectures must provide the following entry point. This entry
* point is called early in the initialization -- after clocking and memory have
* been configured but before caches have been enabled and before any devices have
* been initialized.
*
************************************************************************************/
void lpc54_board_initialize(void)
{
}
/****************************************************************************
* Name: board_initialize
*
* Description:
* If CONFIG_BOARD_INITIALIZE is selected, then an additional
* initialization call will be performed in the boot-up sequence to a
* function called board_initialize(). board_initialize() will be
* called immediately after up_initialize() is called and just before the
* initial application is started. This additional initialization phase
* may be used, for example, to initialize board-specific device drivers.
*
****************************************************************************/
#ifdef CONFIG_BOARD_INITIALIZE
void board_initialize(void)
{
/* Perform board-specific initialization */
(void)lpc54_bringup();
}
#endif

View file

@ -0,0 +1,82 @@
/****************************************************************************
* configs/lpcxpresso-lpc54628/src/lpc54_bringup.c
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <sys/types.h>
#include <sys/mount.h>
#include <syslog.h>
#include "lpcxpresso-lpc54628.h"
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: lpc54_bringup
*
* Description:
* Perform architecture-specific initialization
*
* CONFIG_BOARD_INITIALIZE=y :
* Called from board_initialize().
*
* CONFIG_BOARD_INITIALIZE=n && CONFIG_LIB_BOARDCTL=y :
* Called from the NSH library
*
****************************************************************************/
int lpc54_bringup(void)
{
int ret;
#ifdef CONFIG_FS_PROCFS
/* Mount the procfs file system */
ret = mount(NULL, "/proc", "procfs", 0, NULL);
if (ret < 0)
{
syslog(LOG_ERR, "ERROR: Failed to mount procfs at /proc: %d\n", ret);
}
#endif
UNUSED(ret);
return OK;
}

View file

@ -0,0 +1,86 @@
/****************************************************************************
* configs/lpcxpresso-lpc54628/src/lpcxpresso-lpc54628.h
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#ifndef _CONFIGS_LPCXPRESSO_LPC54628_SRC_LPCXPRESSO_LPC54628_H
#define _CONFIGS_LPCXPRESSO_LPC54628_SRC_LPCXPRESSO_LPC54628_H
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <nuttx/compiler.h>
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/* LED definitions **********************************************************/
/* to be provided */
/* Button definitions *******************************************************/
/* to be provided */
/****************************************************************************
* Public Types
****************************************************************************/
/****************************************************************************
* Public data
****************************************************************************/
#ifndef __ASSEMBLY__
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: lpc54_bringup
*
* Description:
* Perform architecture-specific initialization
*
* CONFIG_BOARD_INITIALIZE=y :
* Called from board_initialize().
*
* CONFIG_BOARD_INITIALIZE=n && CONFIG_LIB_BOARDCTL=y :
* Called from the NSH library
*
****************************************************************************/
int lpc54_bringup(void);
#endif /* __ASSEMBLY__ */
#endif /* _CONFIGS_LPCXPRESSO_LPC54628_SRC_LPCXPRESSO_LPC54628_H */

View file

@ -461,6 +461,11 @@ config USART8_SERIALDRIVER
default n
select MCU_SERIAL
config USART9_SERIALDRIVER
bool
default n
select MCU_SERIAL
config OTHER_UART_SERIALDRIVER
bool
default n
@ -667,6 +672,11 @@ config USART8_SERIAL_CONSOLE
depends on USART8_SERIALDRIVER
select SERIAL_CONSOLE
config USART9_SERIAL_CONSOLE
bool "USART8"
depends on USART9_SERIALDRIVER
select SERIAL_CONSOLE
config SCI0_SERIAL_CONSOLE
bool "SCI0"
depends on SCI0_SERIALDRIVER
@ -1924,6 +1934,71 @@ config UART8_DMA
endmenu
menu "USART9 Configuration"
depends on USART9_SERIALDRIVER
config USART9_RXBUFSIZE
int "Receive buffer size"
default 256
---help---
Characters are buffered as they are received. This specifies
the size of the receive buffer.
config USART9_TXBUFSIZE
int "Transmit buffer size"
default 256
---help---
Characters are buffered before being sent. This specifies
the size of the transmit buffer.
config USART9_BAUD
int "BAUD rate"
default 115200
---help---
The configured BAUD of the USART.
config USART9_BITS
int "Character size"
default 8
---help---
The number of bits. Must be either 7 or 8.
config USART9_PARITY
int "Parity setting"
default 0
range 0 2
---help---
0=no parity, 1=odd parity, 2=even parity
config USART9_2STOP
int "Uses 2 stop bits"
default 0
---help---
1=Two stop bits
config USART9_IFLOWCONTROL
bool "USART9 RTS flow control"
default n
select SERIAL_IFLOWCONTROL
---help---
Enable USART9 RTS flow control
config USART9_OFLOWCONTROL
bool "USART9 CTS flow control"
default n
select SERIAL_OFLOWCONTROL
---help---
Enable USART9 CTS flow control
config USART9_DMA
bool "USART9 DMA support"
default n
select SERIAL_DMA
---help---
Enable DMA transfers on USART9
endmenu
menu "SCI0 Configuration"
depends on SCI0_SERIALDRIVER