From b9038dffaf17443479ca533e368ac871daff00a5 Mon Sep 17 00:00:00 2001 From: imi415 Date: Sat, 14 May 2022 23:06:41 +0800 Subject: [PATCH] Initial commit. --- .gitmodules | 3 + CMakeLists.txt | 137 +++++++++++++++++++++++++++++++++ LPC54102J512_M4F.mex | 176 +++++++++++++++++++++++++++++++++++++++++++ SDK | 1 + arm-none-eabi.cmake | 10 +++ board/board.c | 46 +++++++++++ board/board.h | 154 +++++++++++++++++++++++++++++++++++++ board/clock_config.c | 101 +++++++++++++++++++++++++ board/clock_config.h | 62 +++++++++++++++ board/peripherals.c | 93 +++++++++++++++++++++++ board/peripherals.h | 33 ++++++++ board/pin_mux.c | 83 ++++++++++++++++++++ board/pin_mux.h | 50 ++++++++++++ lib/.gitkeep | 0 src/main.c | 20 +++++ 15 files changed, 969 insertions(+) create mode 100644 .gitmodules create mode 100644 CMakeLists.txt create mode 100644 LPC54102J512_M4F.mex create mode 160000 SDK create mode 100644 arm-none-eabi.cmake create mode 100644 board/board.c create mode 100644 board/board.h create mode 100644 board/clock_config.c create mode 100644 board/clock_config.h create mode 100644 board/peripherals.c create mode 100644 board/peripherals.h create mode 100644 board/pin_mux.c create mode 100644 board/pin_mux.h create mode 100644 lib/.gitkeep create mode 100644 src/main.c diff --git a/.gitmodules b/.gitmodules new file mode 100644 index 0000000..d4d2fe2 --- /dev/null +++ b/.gitmodules @@ -0,0 +1,3 @@ +[submodule "SDK"] + path = SDK + url = https://git.minori.work/Embedded_SDK/MCUXpresso_LPC54102.git diff --git a/CMakeLists.txt b/CMakeLists.txt new file mode 100644 index 0000000..be0eab4 --- /dev/null +++ b/CMakeLists.txt @@ -0,0 +1,137 @@ +cmake_minimum_required(VERSION 3.10) + +project(lpc54102_hello) + +enable_language(CXX) +enable_language(ASM) + +# Different linker scripts +set(TARGET_LDSCRIPT_FLASH "${CMAKE_SOURCE_DIR}/SDK/devices/LPC54102/gcc/LPC54102J512_cm4_flash.ld") +set(TARGET_LDSCRIPT_RAM "${CMAKE_SOURCE_DIR}/SDK/devices/LPC54102/gcc/LPC54102J512_cm4_ram.ld") + +set(TARGET_SOURCES + "SDK/components/serial_manager/serial_manager.c" + "SDK/components/serial_manager/serial_port_uart.c" + "SDK/components/uart/vusart_adapter.c" + "SDK/devices/LPC54102/drivers/fsl_adc.c" + "SDK/devices/LPC54102/drivers/fsl_clock.c" + "SDK/devices/LPC54102/drivers/fsl_common.c" + "SDK/devices/LPC54102/drivers/fsl_crc.c" + "SDK/devices/LPC54102/drivers/fsl_ctimer.c" + "SDK/devices/LPC54102/drivers/fsl_dma.c" + "SDK/devices/LPC54102/drivers/fsl_flashiap.c" + "SDK/devices/LPC54102/drivers/fsl_fmeas.c" + "SDK/devices/LPC54102/drivers/fsl_gint.c" + "SDK/devices/LPC54102/drivers/fsl_gpio.c" + "SDK/devices/LPC54102/drivers/fsl_i2c.c" + "SDK/devices/LPC54102/drivers/fsl_i2c_dma.c" + "SDK/devices/LPC54102/drivers/fsl_iap.c" + "SDK/devices/LPC54102/drivers/fsl_inputmux.c" + "SDK/devices/LPC54102/drivers/fsl_mrt.c" + "SDK/devices/LPC54102/drivers/fsl_pint.c" + "SDK/devices/LPC54102/drivers/fsl_power.c" + "SDK/devices/LPC54102/drivers/fsl_reset.c" + "SDK/devices/LPC54102/drivers/fsl_rit.c" + "SDK/devices/LPC54102/drivers/fsl_rtc.c" + "SDK/devices/LPC54102/drivers/fsl_sctimer.c" + "SDK/devices/LPC54102/drivers/fsl_spi.c" + "SDK/devices/LPC54102/drivers/fsl_spi_dma.c" + "SDK/devices/LPC54102/drivers/fsl_usart.c" + "SDK/devices/LPC54102/drivers/fsl_usart_dma.c" + "SDK/devices/LPC54102/drivers/fsl_utick.c" + "SDK/devices/LPC54102/drivers/fsl_wwdt.c" + "SDK/devices/LPC54102/gcc/startup_LPC54102_cm4.S" + "SDK/devices/LPC54102/system_LPC54102_cm4.c" + "SDK/devices/LPC54102/utilities/debug_console/fsl_debug_console.c" + "SDK/devices/LPC54102/utilities/fsl_assert.c" + "SDK/devices/LPC54102/utilities/fsl_notifier.c" + "SDK/devices/LPC54102/utilities/fsl_sbrk.c" + "SDK/devices/LPC54102/utilities/str/fsl_str.c" + "board/board.c" + "board/clock_config.c" + "board/peripherals.c" + "board/pin_mux.c" + "src/main.c" +) + +set(TARGET_C_DEFINES + "CPU_LPC54102J256BD64" + "CPU_LPC54102J512BD64_cm4" + "MCUXPRESSO_SDK" + "SERIAL_PORT_TYPE_UART=1" + "__STARTUP_CLEAR_BSS" +) + +set(TARGET_C_INCLUDES + "SDK/CMSIS/Include" + "SDK/components/serial_manager" + "SDK/components/uart" + "SDK/devices/LPC54102" + "SDK/devices/LPC54102/drivers" + "SDK/devices/LPC54102/utilities/debug_console" + "SDK/devices/LPC54102/utilities/str" + "board" + "include" +) + +# Shared libraries linked with application +set(TARGET_LIBS + "power_cm4_hardabi" +) + +# Shared library and linker script search paths +set(TARGET_LIB_DIRECTORIES + "SDK/devices/LPC54102/gcc" +) + +# Device specific settings, goes to CFLAGS and LDFLAGS +set(TARGET_CFLAGS_HARDWARE "-mcpu=cortex-m33 -mthumb -mfloat-abi=hard -mfpu=fpv5-sp-d16") + +# Conditional flags +# DEBUG +set(CMAKE_C_FLAGS_DEBUG "-DDEBUG -Og -g") +set(CMAKE_CXX_FLAGS_DEBUG "-DDEBUG -Og -g") +set(CMAKE_ASM_FLAGS_DEBUG "-DDEBUG -Og -g") + +# RELEASE +set(CMAKE_C_FLAGS_RELEASE "-DNDEBUG -O2 -flto") +set(CMAKE_CXX_FLAGS_RELEASE "-DNDEBUG -O2 -flto") +set(CMAKE_ASM_FLAGS_RELEASE "-DNDEBUG -O2 -flto") +set(CMAKE_EXE_LINKER_FLAGS_RELEASE "-flto") + +# Final compiler flags +set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} ${TARGET_CFLAGS_HARDWARE} -Wall -fno-common -fno-builtin -ffreestanding -fdata-sections -ffunction-sections") +set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${TARGET_CFLAGS_HARDWARE} -Wall -fno-common -fno-builtin -ffreestanding -fdata-sections -ffunction-sections") +set(CMAKE_ASM_FLAGS "${CMAKE_ASM_FLAGS} ${CMAKE_C_FLAGS} -x assembler-with-cpp") +set(CMAKE_EXE_LINKER_FLAGS "-specs=nano.specs -specs=nosys.specs -Wl,--gc-sections -Wl,--print-memory-usage -lc -lm -lnosys ") + + +# Shared sources, includes and definitions +add_compile_definitions(${TARGET_C_DEFINES}) +include_directories(${TARGET_C_INCLUDES}) +link_directories(${TARGET_LIB_DIRECTORIES}) +link_libraries(${TARGET_LIBS}) + +# Main targets are added here + +# Create ELF +add_executable("${CMAKE_PROJECT_NAME}_FLASH.elf" ${TARGET_SOURCES}) +target_link_options("${CMAKE_PROJECT_NAME}_FLASH.elf" + PRIVATE "-T${TARGET_LDSCRIPT_FLASH}" +) +add_custom_command(OUTPUT "${CMAKE_PROJECT_NAME}_FLASH.hex" + COMMAND ${CMAKE_OBJCOPY} "-O" "ihex" "${CMAKE_PROJECT_NAME}_FLASH.elf" "${CMAKE_PROJECT_NAME}_FLASH.hex" + DEPENDS "${CMAKE_PROJECT_NAME}_FLASH.elf" +) +add_custom_target("${CMAKE_PROJECT_NAME}_FLASH_HEX" DEPENDS "${CMAKE_PROJECT_NAME}_FLASH.hex") + +# Create ELF +add_executable("${CMAKE_PROJECT_NAME}_RAM.elf" ${TARGET_SOURCES}) +target_link_options("${CMAKE_PROJECT_NAME}_RAM.elf" + PRIVATE "-T${TARGET_LDSCRIPT_RAM}" +) +add_custom_command(OUTPUT "${CMAKE_PROJECT_NAME}_RAM.hex" + COMMAND ${CMAKE_OBJCOPY} "-O" "ihex" "${CMAKE_PROJECT_NAME}_RAM.elf" "${CMAKE_PROJECT_NAME}_RAM.hex" + DEPENDS "${CMAKE_PROJECT_NAME}_RAM.elf" +) +add_custom_target("${CMAKE_PROJECT_NAME}_RAM_HEX" DEPENDS "${CMAKE_PROJECT_NAME}_RAM.hex") diff --git a/LPC54102J512_M4F.mex b/LPC54102J512_M4F.mex new file mode 100644 index 0000000..f3a6acb --- /dev/null +++ b/LPC54102J512_M4F.mex @@ -0,0 +1,176 @@ + + + + LPC54102J512 + LPC54102J512BD64 + ksdk2_0 + + + + + + + + true + false + false + true + false + + + + + + + + + 11.0.1 + + + + Configures pin routing and optionally pin electrical features. + + true + cm4 + true + + + + + true + + + + + true + + + + + + + + + + + + + + + + + 11.0.1 + + + + + + + + + true + + + + + true + + + + + true + + + + + true + + + + + true + + + + + true + + + + + + + + + + + + true + + + + + + + N/A + + + + + + + + + + 11.0.1 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + N/A + + + + \ No newline at end of file diff --git a/SDK b/SDK new file mode 160000 index 0000000..5540a4c --- /dev/null +++ b/SDK @@ -0,0 +1 @@ +Subproject commit 5540a4c296a16ba1fd7bbe78dec73165903fc94d diff --git a/arm-none-eabi.cmake b/arm-none-eabi.cmake new file mode 100644 index 0000000..ab16b40 --- /dev/null +++ b/arm-none-eabi.cmake @@ -0,0 +1,10 @@ +set(CMAKE_C_COMPILER arm-none-eabi-gcc) +set(CMAKE_CXX_COMPILER arm-none-eabi-g++) + +# Make CMake happy about those compilers +set(CMAKE_TRY_COMPILE_TARGET_TYPE "STATIC_LIBRARY") + +# Poor old Windows... +if(WIN32) + set(CMAKE_SYSTEM_NAME "Generic") +endif() \ No newline at end of file diff --git a/board/board.c b/board/board.c new file mode 100644 index 0000000..e390122 --- /dev/null +++ b/board/board.c @@ -0,0 +1,46 @@ +/* + * Copyright 2017-2018 NXP + * All rights reserved. + * + * SPDX-License-Identifier: BSD-3-Clause + */ + +#include +#include "fsl_common.h" +#include "clock_config.h" +#include "board.h" +#include "fsl_debug_console.h" + +/******************************************************************************* + * Variables + ******************************************************************************/ + +/* Clock rate on the CLKIN pin */ +const uint32_t ExtClockIn = BOARD_EXTCLKINRATE; + +/******************************************************************************* + * Code + ******************************************************************************/ +/* Initialize debug console. */ +status_t BOARD_InitDebugConsole(void) +{ + status_t result; + /* attach 12 MHz clock to USART0 (debug console) */ + CLOCK_AttachClk(BOARD_DEBUG_UART_CLK_ATTACH); + RESET_PeripheralReset(BOARD_DEBUG_UART_RST); + result = DbgConsole_Init(BOARD_DEBUG_UART_INSTANCE, BOARD_DEBUG_UART_BAUDRATE, BOARD_DEBUG_UART_TYPE, + BOARD_DEBUG_UART_CLK_FREQ); + assert(kStatus_Success == result); + return result; +} +status_t BOARD_InitDebugConsole_Core1(void) +{ + status_t result; + /* attach 12 MHz clock to USART2 (debug console) */ + CLOCK_AttachClk(BOARD_DEBUG_UART_CLK_ATTACH_CORE1); + RESET_PeripheralReset(BOARD_DEBUG_UART_RST_CORE1); + result = DbgConsole_Init(BOARD_DEBUG_UART_INSTANCE_CORE1, BOARD_DEBUG_UART_BAUDRATE_CORE1, + BOARD_DEBUG_UART_TYPE_CORE1, BOARD_DEBUG_UART_CLK_FREQ_CORE1); + assert(kStatus_Success == result); + return result; +} diff --git a/board/board.h b/board/board.h new file mode 100644 index 0000000..1c086d0 --- /dev/null +++ b/board/board.h @@ -0,0 +1,154 @@ +/* + * Copyright 2017-2018 NXP + * All rights reserved. + * + * SPDX-License-Identifier: BSD-3-Clause + */ + +#ifndef _BOARD_H_ +#define _BOARD_H_ + +#include "clock_config.h" +#include "fsl_common.h" +#include "fsl_gpio.h" + +/******************************************************************************* + * Definitions + ******************************************************************************/ +/*! @brief The board name */ +#define BOARD_NAME "LPCXPRESSO54102" + +#define BOARD_EXTCLKINRATE (0) + +/*! @brief The UART to use for debug messages. */ +#define BOARD_DEBUG_UART_TYPE kSerialPort_Uart +#define BOARD_DEBUG_UART_BASEADDR (uint32_t) USART0 +#define BOARD_DEBUG_UART_INSTANCE 0U +#define BOARD_DEBUG_UART_CLK_FREQ CLOCK_GetUsartClkFreq() +#define BOARD_DEBUG_UART_CLK_ATTACH kIRC12M_to_USART +#define BOARD_DEBUG_UART_RST kUSART0_RST_SHIFT_RSTn + +#define BOARD_DEBUG_UART_TYPE_CORE1 kSerialPort_Uart +#define BOARD_DEBUG_UART_BASEADDR_CORE1 (uint32_t) USART2 +#define BOARD_DEBUG_UART_INSTANCE_CORE1 2U +#define BOARD_DEBUG_UART_CLK_FREQ_CORE1 CLOCK_GetUsartClkFreq() +#define BOARD_DEBUG_UART_CLK_ATTACH_CORE1 kIRC12M_to_USART +#define BOARD_DEBUG_UART_RST_CORE1 kUSART2_RST_SHIFT_RSTn + +#define BOARD_DEBUG_SPI_CLK_FREQ 12000000 + +#ifndef BOARD_DEBUG_UART_BAUDRATE +#define BOARD_DEBUG_UART_BAUDRATE 115200 +#endif /* BOARD_DEBUG_UART_BAUDRATE */ + +#ifndef BOARD_DEBUG_UART_BAUDRATE_CORE1 +#define BOARD_DEBUG_UART_BAUDRATE_CORE1 115200 +#endif /* BOARD_DEBUG_UART_BAUDRATE_CORE1 */ + +#ifndef BOARD_LED_RED_GPIO +#define BOARD_LED_RED_GPIO GPIO +#endif +#define BOARD_LED_RED_GPIO_PORT 0U +#ifndef BOARD_LED_RED_GPIO_PIN +#define BOARD_LED_RED_GPIO_PIN 29U +#endif +#ifndef BOARD_LED_GREEN_GPIO +#define BOARD_LED_GREEN_GPIO GPIO +#endif +#define BOARD_LED_GREEN_GPIO_PORT 0U +#ifndef BOARD_LED_GREEN_GPIO_PIN +#define BOARD_LED_GREEN_GPIO_PIN 30U +#endif +#ifndef BOARD_LED_BLUE_GPIO +#define BOARD_LED_BLUE_GPIO GPIO +#endif +#define BOARD_LED_BLUE_GPIO_PORT 0U +#ifndef BOARD_LED_BLUE_GPIO_PIN +#define BOARD_LED_BLUE_GPIO_PIN 31U +#endif + +#ifndef BOARD_SW1_GPIO +#define BOARD_SW1_GPIO GPIO +#endif +#define BOARD_SW1_GPIO_PORT 0U +#ifndef BOARD_SW1_GPIO_PIN +#define BOARD_SW1_GPIO_PIN 24U +#endif +#define BOARD_SW1_NAME "SW1" +#define BOARD_SW1_IRQ PIN_INT0_IRQn +#define BOARD_SW1_IRQ_HANDLER PIN_INT0_IRQHandler + +#ifndef BOARD_SW2_GPIO +#define BOARD_SW2_GPIO GPIO +#endif +#define BOARD_SW2_GPIO_PORT 0U +#ifndef BOARD_SW2_GPIO_PIN +#define BOARD_SW2_GPIO_PIN 31U +#endif +#define BOARD_SW2_NAME "SW2" +#define BOARD_SW2_IRQ PIN_INT0_IRQn +#define BOARD_SW2_IRQ_HANDLER PIN_INT0_IRQHandler + +/* Board led color mapping */ +#define LOGIC_LED_ON 0U +#define LOGIC_LED_OFF 1U + +#define LED_RED_INIT(output) \ + GPIO_PinInit(BOARD_LED_RED_GPIO, BOARD_LED_RED_GPIO_PORT, BOARD_LED_RED_GPIO_PIN, \ + &(gpio_pin_config_t){kGPIO_DigitalOutput, (output)}) /*!< Enable target LED_RED */ +#define LED_RED_ON() \ + GPIO_PortClear(BOARD_LED_RED_GPIO, BOARD_LED_RED_GPIO_PORT, \ + 1U << BOARD_LED_RED_GPIO_PIN) /*!< Turn on target LED_RED */ +#define LED_RED_OFF() \ + GPIO_PortSet(BOARD_LED_RED_GPIO, BOARD_LED_RED_GPIO_PORT, \ + 1U << BOARD_LED_RED_GPIO_PIN) /*!< Turn off target LED_RED */ +#define LED_RED_TOGGLE() \ + GPIO_PortToggle(BOARD_LED_RED_GPIO, BOARD_LED_RED_GPIO_PORT, \ + 1U << BOARD_LED_RED_GPIO_PIN) /*!< Toggle on target LED_RED */ + +#define LED_GREEN_INIT(output) \ + GPIO_PinInit(BOARD_LED_GREEN_GPIO, BOARD_LED_GREEN_GPIO_PORT, BOARD_LED_GREEN_GPIO_PIN, \ + &(gpio_pin_config_t){kGPIO_DigitalOutput, (output)}) /*!< Enable target LED_GREEN */ +#define LED_GREEN_ON() \ + GPIO_PortClear(BOARD_LED_GREEN_GPIO, BOARD_LED_GREEN_GPIO_PORT, \ + 1U << BOARD_LED_GREEN_GPIO_PIN) /*!< Turn on target LED_GREEN */ +#define LED_GREEN_OFF() \ + GPIO_PortSet(BOARD_LED_GREEN_GPIO, BOARD_LED_GREEN_GPIO_PORT, \ + 1U << BOARD_LED_GREEN_GPIO_PIN) /*!< Turn off target LED_GREEN */ +#define LED_GREEN_TOGGLE() \ + GPIO_PortToggle(BOARD_LED_GREEN_GPIO, BOARD_LED_GREEN_GPIO_PORT, \ + 1U << BOARD_LED_GREEN_GPIO_PIN) /*!< Toggle on target LED_GREEN */ + +#define LED_BLUE_INIT(output) \ + GPIO_PinInit(BOARD_LED_BLUE_GPIO, BOARD_LED_BLUE_GPIO_PORT, BOARD_LED_BLUE_GPIO_PIN, \ + &(gpio_pin_config_t){kGPIO_DigitalOutput, (output)}) /*!< Enable target LED_BLUE */ +#define LED_BLUE_ON() \ + GPIO_PortClear(BOARD_LED_BLUE_GPIO, BOARD_LED_BLUE_GPIO_PORT, \ + 1U << BOARD_LED_BLUE_GPIO_PIN) /*!< Turn on target LED_BLUE */ +#define LED_BLUE_OFF() \ + GPIO_PortSet(BOARD_LED_BLUE_GPIO, BOARD_LED_BLUE_GPIO_PORT, \ + 1U << BOARD_LED_BLUE_GPIO_PIN) /*!< Turn off target LED_BLUE */ +#define LED_BLUE_TOGGLE() \ + GPIO_PortToggle(BOARD_LED_BLUE_GPIO, BOARD_LED_BLUE_GPIO_PORT, \ + 1U << BOARD_LED_BLUE_GPIO_PIN) /*!< Toggle on target LED_BLUE */ + +/* Display. */ +#define BOARD_LCD_DC_GPIO GPIO +#define BOARD_LCD_DC_GPIO_PORT 0U +#define BOARD_LCD_DC_GPIO_PIN 3U + +#if defined(__cplusplus) +extern "C" { +#endif /* __cplusplus */ + +/******************************************************************************* + * API + ******************************************************************************/ + +status_t BOARD_InitDebugConsole(void); +status_t BOARD_InitDebugConsole_Core1(void); +#if defined(__cplusplus) +} +#endif /* __cplusplus */ + +#endif /* _BOARD_H_ */ diff --git a/board/clock_config.c b/board/clock_config.c new file mode 100644 index 0000000..9eb75da --- /dev/null +++ b/board/clock_config.c @@ -0,0 +1,101 @@ +/*********************************************************************************************************************** + * This file was generated by the MCUXpresso Config Tools. Any manual edits made to this file + * will be overwritten if the respective MCUXpresso Config Tools is used to update this file. + **********************************************************************************************************************/ +/* + * How to set up clock using clock driver functions: + * + * 1. Setup clock sources. + * + * 2. Setup voltage for the fastest of the clock outputs + * + * 3. Set up wait states of the flash. + * + * 4. Set up all dividers. + * + * 5. Set up all selectors to provide selected clocks. + */ + +/* clang-format off */ +/* TEXT BELOW IS USED AS SETTING FOR TOOLS ************************************* +!!GlobalInfo +product: Clocks v9.0 +processor: LPC54102J512 +package_id: LPC54102J512BD64 +mcu_data: ksdk2_0 +processor_version: 11.0.1 + * BE CAREFUL MODIFYING THIS COMMENT - IT IS YAML SETTINGS FOR TOOLS **********/ +/* clang-format on */ + +#include "fsl_power.h" +#include "fsl_clock.h" +#include "clock_config.h" + +/******************************************************************************* + * Definitions + ******************************************************************************/ + +/******************************************************************************* + * Variables + ******************************************************************************/ +/* System clock frequency. */ +extern uint32_t SystemCoreClock; + +/******************************************************************************* + ************************ BOARD_InitBootClocks function ************************ + ******************************************************************************/ +void BOARD_InitBootClocks(void) +{ + BOARD_BootClockRUN(); +} + +/******************************************************************************* + ********************** Configuration BOARD_BootClockRUN *********************** + ******************************************************************************/ +/* clang-format off */ +/* TEXT BELOW IS USED AS SETTING FOR TOOLS ************************************* +!!Configuration +name: BOARD_BootClockRUN +called_from_default_init: true +outputs: +- {id: ASYNCAPB_clock.outFreq, value: 12 MHz} +- {id: FRG_clock.outFreq, value: 12 MHz} +- {id: MAIN_clock.outFreq, value: 12 MHz} +- {id: System_clock.outFreq, value: 12 MHz} + * BE CAREFUL MODIFYING THIS COMMENT - IT IS YAML SETTINGS FOR TOOLS **********/ +/* clang-format on */ + +/******************************************************************************* + * Variables for BOARD_BootClockRUN configuration + ******************************************************************************/ +/******************************************************************************* + * Code for BOARD_BootClockRUN configuration + ******************************************************************************/ +void BOARD_BootClockRUN(void) +{ + /*!< Set up the clock sources */ + /*!< Set up IRC */ + POWER_DisablePD(kPDRUNCFG_PD_IRC_OSC); /*!< Ensure IRC OSC is on */ + POWER_DisablePD(kPDRUNCFG_PD_IRC); /*!< Ensure IRC is on */ + CLOCK_AttachClk(kIRC12M_to_MAIN_CLK); /*!< Switch to IRC 12MHz first to ensure we can change voltage without accidentally + being below the voltage for current speed */ + + /*!< PLL is in power_down mode */ + + POWER_SetVoltageForFreq(12000000U); /*!< Set voltage for the one of the fastest clock outputs: System clock output */ + CLOCK_SetFLASHAccessCyclesForFreq(12000000U); /*!< Set FLASH wait states for core */ + + /*!< Set up dividers */ + CLOCK_SetClkDiv(kCLOCK_DivAhbClk, 1U, false); /*!< Set AHBCLKDIV divider to value 1 */ + SYSCON->ASYNCAPBCTRL = SYSCON_ASYNCAPBCTRL_ENABLE_MASK; /*!< Enable ASYNC APB subsystem */ + Clock_SetAsyncClkDiv(1U); /*!< Set ASYNCCLKDIV divider to value 1 */ + ASYNC_SYSCON->FRGCTRL = ((ASYNC_SYSCON->FRGCTRL & ~ASYNC_SYSCON_FRGCTRL_MULT_MASK) | ASYNC_SYSCON_FRGCTRL_MULT(0U)); /*!< Set FRG MULT to value 0 */ + ASYNC_SYSCON->ASYNCAPBCLKCTRL |= ASYNC_SYSCON_ASYNCAPBCLKCTRL_FRG0_MASK; /*!< Enable FRG clock */ + + /*!< Set up clock selectors - Attach clocks to the peripheries */ + CLOCK_AttachClk(kIRC12M_to_MAIN_CLK); /*!< Switch MAIN_CLK to IRC12M */ + + /*!< Set SystemCoreClock variable. */ + SystemCoreClock = BOARD_BOOTCLOCKRUN_CORE_CLOCK; +} + diff --git a/board/clock_config.h b/board/clock_config.h new file mode 100644 index 0000000..8212f14 --- /dev/null +++ b/board/clock_config.h @@ -0,0 +1,62 @@ +/*********************************************************************************************************************** + * This file was generated by the MCUXpresso Config Tools. Any manual edits made to this file + * will be overwritten if the respective MCUXpresso Config Tools is used to update this file. + **********************************************************************************************************************/ + +#ifndef _CLOCK_CONFIG_H_ +#define _CLOCK_CONFIG_H_ + +#include "fsl_common.h" + +/******************************************************************************* + * Definitions + ******************************************************************************/ +#define BOARD_XTAL0_CLK_HZ 12000000U /*!< Board xtal0 frequency in Hz */ +#define BOARD_XTAL32K_CLK_HZ 32768U /*!< Board xtal32K frequency in Hz */ + +/******************************************************************************* + ************************ BOARD_InitBootClocks function ************************ + ******************************************************************************/ + +#if defined(__cplusplus) +extern "C" { +#endif /* __cplusplus*/ + +/*! + * @brief This function executes default configuration of clocks. + * + */ +void BOARD_InitBootClocks(void); + +#if defined(__cplusplus) +} +#endif /* __cplusplus*/ + +/******************************************************************************* + ********************** Configuration BOARD_BootClockRUN *********************** + ******************************************************************************/ +/******************************************************************************* + * Definitions for BOARD_BootClockRUN configuration + ******************************************************************************/ +#define BOARD_BOOTCLOCKRUN_CORE_CLOCK 12000000U /*!< Core clock frequency: 12000000Hz */ + + +/******************************************************************************* + * API for BOARD_BootClockRUN configuration + ******************************************************************************/ +#if defined(__cplusplus) +extern "C" { +#endif /* __cplusplus*/ + +/*! + * @brief This function executes configuration of clocks. + * + */ +void BOARD_BootClockRUN(void); + +#if defined(__cplusplus) +} +#endif /* __cplusplus*/ + +#endif /* _CLOCK_CONFIG_H_ */ + diff --git a/board/peripherals.c b/board/peripherals.c new file mode 100644 index 0000000..1f9bd43 --- /dev/null +++ b/board/peripherals.c @@ -0,0 +1,93 @@ +/*********************************************************************************************************************** + * This file was generated by the MCUXpresso Config Tools. Any manual edits made to this file + * will be overwritten if the respective MCUXpresso Config Tools is used to update this file. + **********************************************************************************************************************/ + +/* clang-format off */ +/* TEXT BELOW IS USED AS SETTING FOR TOOLS ************************************* +!!GlobalInfo +product: Peripherals v11.0 +processor: LPC54102J512 +package_id: LPC54102J512BD64 +mcu_data: ksdk2_0 +processor_version: 11.0.1 +functionalGroups: +- name: BOARD_InitPeripherals + UUID: bf976c30-387a-4c02-956c-44a37954526e + called_from_default_init: true + selectedCore: cm4 + * BE CAREFUL MODIFYING THIS COMMENT - IT IS YAML SETTINGS FOR TOOLS **********/ + +/* TEXT BELOW IS USED AS SETTING FOR TOOLS ************************************* +component: +- type: 'system' +- type_id: 'system_54b53072540eeeb8f8e9343e71f28176' +- global_system_definitions: + - user_definitions: '' + - user_includes: '' + * BE CAREFUL MODIFYING THIS COMMENT - IT IS YAML SETTINGS FOR TOOLS **********/ + +/* TEXT BELOW IS USED AS SETTING FOR TOOLS ************************************* +component: +- type: 'gpio_adapter_common' +- type_id: 'gpio_adapter_common_57579b9ac814fe26bf95df0a384c36b6' +- global_gpio_adapter_common: + - quick_selection: 'default' + * BE CAREFUL MODIFYING THIS COMMENT - IT IS YAML SETTINGS FOR TOOLS **********/ + +/* TEXT BELOW IS USED AS SETTING FOR TOOLS ************************************* +component: +- type: 'uart_cmsis_common' +- type_id: 'uart_cmsis_common_9cb8e302497aa696fdbb5a4fd622c2a8' +- global_USART_CMSIS_common: + - quick_selection: 'default' + * BE CAREFUL MODIFYING THIS COMMENT - IT IS YAML SETTINGS FOR TOOLS **********/ +/* clang-format on */ + +/*********************************************************************************************************************** + * Included files + **********************************************************************************************************************/ +#include "peripherals.h" + +/*********************************************************************************************************************** + * BOARD_InitPeripherals functional group + **********************************************************************************************************************/ +/*********************************************************************************************************************** + * NVIC initialization code + **********************************************************************************************************************/ +/* clang-format off */ +/* TEXT BELOW IS USED AS SETTING FOR TOOLS ************************************* +instance: +- name: 'NVIC' +- type: 'nvic' +- mode: 'general' +- custom_name_enabled: 'false' +- type_id: 'nvic_57b5eef3774cc60acaede6f5b8bddc67' +- functional_group: 'BOARD_InitPeripherals' +- peripheral: 'NVIC' +- config_sets: + - nvic: + - interrupt_table: [] + - interrupts: [] + * BE CAREFUL MODIFYING THIS COMMENT - IT IS YAML SETTINGS FOR TOOLS **********/ +/* clang-format on */ + +/* Empty initialization function (commented out) +static void NVIC_init(void) { +} */ + +/*********************************************************************************************************************** + * Initialization functions + **********************************************************************************************************************/ +void BOARD_InitPeripherals(void) +{ + /* Initialize components */ +} + +/*********************************************************************************************************************** + * BOARD_InitBootPeripherals function + **********************************************************************************************************************/ +void BOARD_InitBootPeripherals(void) +{ + BOARD_InitPeripherals(); +} diff --git a/board/peripherals.h b/board/peripherals.h new file mode 100644 index 0000000..2a75809 --- /dev/null +++ b/board/peripherals.h @@ -0,0 +1,33 @@ +/*********************************************************************************************************************** + * This file was generated by the MCUXpresso Config Tools. Any manual edits made to this file + * will be overwritten if the respective MCUXpresso Config Tools is used to update this file. + **********************************************************************************************************************/ + +#ifndef _PERIPHERALS_H_ +#define _PERIPHERALS_H_ + +/*********************************************************************************************************************** + * Included files + **********************************************************************************************************************/ +#include "fsl_common.h" + +#if defined(__cplusplus) +extern "C" { +#endif /* __cplusplus */ + +/*********************************************************************************************************************** + * Initialization functions + **********************************************************************************************************************/ + +void BOARD_InitPeripherals(void); + +/*********************************************************************************************************************** + * BOARD_InitBootPeripherals function + **********************************************************************************************************************/ +void BOARD_InitBootPeripherals(void); + +#if defined(__cplusplus) +} +#endif + +#endif /* _PERIPHERALS_H_ */ diff --git a/board/pin_mux.c b/board/pin_mux.c new file mode 100644 index 0000000..92768d4 --- /dev/null +++ b/board/pin_mux.c @@ -0,0 +1,83 @@ +/*********************************************************************************************************************** + * This file was generated by the MCUXpresso Config Tools. Any manual edits made to this file + * will be overwritten if the respective MCUXpresso Config Tools is used to update this file. + **********************************************************************************************************************/ + +/* clang-format off */ +/* + * TEXT BELOW IS USED AS SETTING FOR TOOLS ************************************* +!!GlobalInfo +product: Pins v11.0 +processor: LPC54102J512 +package_id: LPC54102J512BD64 +mcu_data: ksdk2_0 +processor_version: 11.0.1 + * BE CAREFUL MODIFYING THIS COMMENT - IT IS YAML SETTINGS FOR TOOLS *********** + */ +/* clang-format on */ + +#include "fsl_common.h" +#include "pin_mux.h" + +/* FUNCTION ************************************************************************************************************ + * + * Function Name : BOARD_InitBootPins + * Description : Calls initialization functions. + * + * END ****************************************************************************************************************/ +void BOARD_InitBootPins(void) +{ + BOARD_InitPins(); +} + +/* clang-format off */ +/* + * TEXT BELOW IS USED AS SETTING FOR TOOLS ************************************* +BOARD_InitPins: +- options: {callFromInitBoot: 'true', coreID: cm4, enableClock: 'true'} +- pin_list: + - {pin_num: '31', peripheral: USART0, signal: RXD, pin_signal: PIO0_0/U0_RXD/SPI0_SSEL0/CT32B0_CAP0/SCT0_OUT3} + - {pin_num: '32', peripheral: USART0, signal: TXD, pin_signal: PIO0_1/U0_TXD/SPI0_SSEL1/CT32B0_CAP1/SCT0_OUT1} + * BE CAREFUL MODIFYING THIS COMMENT - IT IS YAML SETTINGS FOR TOOLS *********** + */ +/* clang-format on */ + +/* FUNCTION ************************************************************************************************************ + * + * Function Name : BOARD_InitPins + * Description : Configures pin routing and optionally pin electrical features. + * + * END ****************************************************************************************************************/ +/* Function assigned for the Cortex-M4F */ +void BOARD_InitPins(void) +{ + /* Enables the clock for the IOCON block. 0 = Disable; 1 = Enable.: 0x01u */ + CLOCK_EnableClock(kCLOCK_Iocon); + + IOCON->PIO[0][0] = ((IOCON->PIO[0][0] & + /* Mask bits to zero which are setting */ + (~(IOCON_PIO_FUNC_MASK | IOCON_PIO_DIGIMODE_MASK))) + + /* Selects pin function. + * : PORT00 (pin 31) is configured as U0_RXD. */ + | IOCON_PIO_FUNC(PIO00_FUNC_ALT1) + + /* Select Analog/Digital mode. + * : Digital mode. */ + | IOCON_PIO_DIGIMODE(PIO00_DIGIMODE_DIGITAL)); + + IOCON->PIO[0][1] = ((IOCON->PIO[0][1] & + /* Mask bits to zero which are setting */ + (~(IOCON_PIO_FUNC_MASK | IOCON_PIO_DIGIMODE_MASK))) + + /* Selects pin function. + * : PORT01 (pin 32) is configured as U0_TXD. */ + | IOCON_PIO_FUNC(PIO01_FUNC_ALT1) + + /* Select Analog/Digital mode. + * : Digital mode. */ + | IOCON_PIO_DIGIMODE(PIO01_DIGIMODE_DIGITAL)); +} +/*********************************************************************************************************************** + * EOF + **********************************************************************************************************************/ diff --git a/board/pin_mux.h b/board/pin_mux.h new file mode 100644 index 0000000..d1a077e --- /dev/null +++ b/board/pin_mux.h @@ -0,0 +1,50 @@ +/*********************************************************************************************************************** + * This file was generated by the MCUXpresso Config Tools. Any manual edits made to this file + * will be overwritten if the respective MCUXpresso Config Tools is used to update this file. + **********************************************************************************************************************/ + +#ifndef _PIN_MUX_H_ +#define _PIN_MUX_H_ + +/*! + * @addtogroup pin_mux + * @{ + */ + +/*********************************************************************************************************************** + * API + **********************************************************************************************************************/ + +#if defined(__cplusplus) +extern "C" { +#endif + +/*! + * @brief Calls initialization functions. + * + */ +void BOARD_InitBootPins(void); + +#define PIO00_DIGIMODE_DIGITAL 0x01u /*!<@brief Select Analog/Digital mode.: Digital mode. */ +#define PIO00_FUNC_ALT1 0x01u /*!<@brief Selects pin function.: Alternative connection 1. */ +#define PIO01_DIGIMODE_DIGITAL 0x01u /*!<@brief Select Analog/Digital mode.: Digital mode. */ +#define PIO01_FUNC_ALT1 0x01u /*!<@brief Selects pin function.: Alternative connection 1. */ + +/*! + * @brief Configures pin routing and optionally pin electrical features. + * + */ +void BOARD_InitPins(void); /* Function assigned for the Cortex-M4F */ + +#if defined(__cplusplus) +} +#endif + +/*! + * @} + */ +#endif /* _PIN_MUX_H_ */ + +/*********************************************************************************************************************** + * EOF + **********************************************************************************************************************/ diff --git a/lib/.gitkeep b/lib/.gitkeep new file mode 100644 index 0000000..e69de29 diff --git a/src/main.c b/src/main.c new file mode 100644 index 0000000..029076f --- /dev/null +++ b/src/main.c @@ -0,0 +1,20 @@ +#include "board.h" +#include "clock_config.h" +#include "peripherals.h" +#include "pin_mux.h" + +#include "fsl_debug_console.h" + +int main(void) { + BOARD_InitBootPins(); + BOARD_BootClockRUN(); + BOARD_InitBootPeripherals(); + + BOARD_InitDebugConsole(); + + PRINTF("Hello world!!\r\n"); + + for(;;) { + __WFI(); + } +} \ No newline at end of file