From 3e85432741e4d86a176de45bc545fa6363b06f46 Mon Sep 17 00:00:00 2001 From: imi415 Date: Sat, 9 Apr 2022 01:19:15 +0800 Subject: [PATCH] Hello world template project. --- .gitmodules | 3 + CMakeLists.txt | 145 +++++ LPCXpresso55S69.mex | 1221 ++++++++++++++++++++++++++++++++++++++++++ SDK | 1 + arm-none-eabi.cmake | 10 + board/board.c | 135 +++++ board/board.h | 223 ++++++++ board/clock_config.c | 286 ++++++++++ board/clock_config.h | 140 +++++ board/peripherals.c | 97 ++++ board/peripherals.h | 33 ++ board/pin_mux.c | 850 +++++++++++++++++++++++++++++ board/pin_mux.h | 449 ++++++++++++++++ src/main.c | 20 + 14 files changed, 3613 insertions(+) create mode 100644 .gitmodules create mode 100644 CMakeLists.txt create mode 100644 LPCXpresso55S69.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 src/main.c diff --git a/.gitmodules b/.gitmodules new file mode 100644 index 0000000..01dbdb2 --- /dev/null +++ b/.gitmodules @@ -0,0 +1,3 @@ +[submodule "SDK"] + path = SDK + url = https://git.minori.work/Embedded_SDK/MCUXpresso_LPC55S69.git diff --git a/CMakeLists.txt b/CMakeLists.txt new file mode 100644 index 0000000..f79b2d0 --- /dev/null +++ b/CMakeLists.txt @@ -0,0 +1,145 @@ +cmake_minimum_required(VERSION 3.10) + +project(lpcxpresso_55s69_template) + +enable_language(CXX) +enable_language(ASM) + +# Different linker scripts +set(TARGET_LDSCRIPT_FLASH "${CMAKE_SOURCE_DIR}/SDK/devices/LPC55S69/gcc/LPC55S69_cm33_core0_flash.ld") +set(TARGET_LDSCRIPT_RAM "${CMAKE_SOURCE_DIR}/SDK/devices/LPC55S69/gcc/LPC55S69_cm33_core0_ram.ld") + +set(TARGET_SOURCES + "SDK/components/serial_manager/fsl_component_serial_manager.c" + "SDK/components/serial_manager/fsl_component_serial_port_uart.c" + "SDK/components/uart/fsl_adapter_usart.c" + "SDK/devices/LPC55S69/drivers/fsl_anactrl.c" + "SDK/devices/LPC55S69/drivers/fsl_casper.c" + "SDK/devices/LPC55S69/drivers/fsl_clock.c" + "SDK/devices/LPC55S69/drivers/fsl_cmp.c" + "SDK/devices/LPC55S69/drivers/fsl_common.c" + "SDK/devices/LPC55S69/drivers/fsl_common_arm.c" + "SDK/devices/LPC55S69/drivers/fsl_crc.c" + "SDK/devices/LPC55S69/drivers/fsl_ctimer.c" + "SDK/devices/LPC55S69/drivers/fsl_dma.c" + "SDK/devices/LPC55S69/drivers/fsl_flexcomm.c" + "SDK/devices/LPC55S69/drivers/fsl_gint.c" + "SDK/devices/LPC55S69/drivers/fsl_gpio.c" + "SDK/devices/LPC55S69/drivers/fsl_hashcrypt.c" + "SDK/devices/LPC55S69/drivers/fsl_i2c.c" + "SDK/devices/LPC55S69/drivers/fsl_i2c_dma.c" + "SDK/devices/LPC55S69/drivers/fsl_i2s.c" + "SDK/devices/LPC55S69/drivers/fsl_i2s_dma.c" + "SDK/devices/LPC55S69/drivers/fsl_iap.c" + "SDK/devices/LPC55S69/drivers/fsl_inputmux.c" + "SDK/devices/LPC55S69/drivers/fsl_lpadc.c" + "SDK/devices/LPC55S69/drivers/fsl_mrt.c" + "SDK/devices/LPC55S69/drivers/fsl_ostimer.c" + "SDK/devices/LPC55S69/drivers/fsl_pint.c" + "SDK/devices/LPC55S69/drivers/fsl_plu.c" + "SDK/devices/LPC55S69/drivers/fsl_power.c" + "SDK/devices/LPC55S69/drivers/fsl_prince.c" + "SDK/devices/LPC55S69/drivers/fsl_puf.c" + "SDK/devices/LPC55S69/drivers/fsl_reset.c" + "SDK/devices/LPC55S69/drivers/fsl_rng.c" + "SDK/devices/LPC55S69/drivers/fsl_rtc.c" + "SDK/devices/LPC55S69/drivers/fsl_sctimer.c" + "SDK/devices/LPC55S69/drivers/fsl_sdif.c" + "SDK/devices/LPC55S69/drivers/fsl_spi.c" + "SDK/devices/LPC55S69/drivers/fsl_spi_dma.c" + "SDK/devices/LPC55S69/drivers/fsl_sysctl.c" + "SDK/devices/LPC55S69/drivers/fsl_usart.c" + "SDK/devices/LPC55S69/drivers/fsl_usart_dma.c" + "SDK/devices/LPC55S69/drivers/fsl_utick.c" + "SDK/devices/LPC55S69/drivers/fsl_wwdt.c" + "SDK/devices/LPC55S69/gcc/startup_LPC55S69_cm33_core0.S" + "SDK/devices/LPC55S69/system_LPC55S69_cm33_core0.c" + "SDK/devices/LPC55S69/utilities/debug_console/fsl_debug_console.c" + "SDK/devices/LPC55S69/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_LPC55S69JBD100_cm33_core0" + "MCUXPRESSO_SDK" + "SERIAL_PORT_TYPE_UART=1" + "__STARTUP_CLEAR_BSS" +) + +set(TARGET_C_INCLUDES + "SDK/CMSIS/Core/Include" + "SDK/components/serial_manager" + "SDK/components/uart" + "SDK/devices/LPC55S69" + "SDK/devices/LPC55S69/drivers" + "SDK/devices/LPC55S69/utilities/debug_console" + "SDK/devices/LPC55S69/utilities/str" + "board" + "include" +) + +# Shared libraries linked with application +set(TARGET_LIBS + +) + +# Shared library and linker script search paths +set(TARGET_LIB_DIRECTORIES + +) + +# 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/LPCXpresso55S69.mex b/LPCXpresso55S69.mex new file mode 100644 index 0000000..652fb81 --- /dev/null +++ b/LPCXpresso55S69.mex @@ -0,0 +1,1221 @@ + + + + LPC55S69 + LPC55S69JBD100 + LPCXpresso55S69 + A2 + ksdk2_0 + + + + + + + + true + false + false + true + false + + + + + + + + + 11.0.1 + + + + Configures pin routing and optionally pin electrical features. + + true + cm33_core0 + true + + + + + true + + + + + true + + + + + true + + + + + + + + + + + + + + + + + + + + + + + + Configures pin routing and optionally pin electrical features. + + false + cm33_core0 + true + + + + + true + + + + + true + + + + + true + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Configures pin routing and optionally pin electrical features. + + false + cm33_core0 + true + + + + + true + + + + + true + + + + + true + + + + + true + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Configures pin routing and optionally pin electrical features. + + false + cm33_core0 + true + + + + + true + + + + + true + + + + + true + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Configures pin routing and optionally pin electrical features. + + false + cm33_core0 + true + + + + + true + + + + + true + + + + + true + + + + + true + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Configures pin routing and optionally pin electrical features. + + true + cm33_core0 + true + + + + + true + + + + + + + Configures pin routing and optionally pin electrical features. + + true + cm33_core1 + true + + + + + true + + + + + + + Configures pin routing and optionally pin electrical features. + + false + cm33_core0 + true + + + + + true + + + + + true + + + + + true + + + + + true + + + + + true + + + + + true + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Configures pin routing and optionally pin electrical features. + + false + cm33_core0 + true + + + + + true + + + + + true + + + + + true + + + + + true + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 11.0.1 + + + + + + + + + true + + + + + true + + + + + true + + + + + true + + + + + + + + + false + + + + + + + + true + + + + + true + + + + + true + + + + + true + + + + + + + + + + + + + + false + + + + + + + + true + + + + + INPUT + + + + + true + + + + + OUTPUT + + + + + true + + + + + true + + + + + true + + + + + true + + + + + + + + + + + + + + + + + + + + false + + + + + + + + true + + + + + INPUT + + + + + true + + + + + OUTPUT + + + + + true + + + + + true + + + + + true + + + + + true + + + + + + + + + + + + + + + + + + + + true + + + + + + + 0.0.0 + + + + + + + + + + 11.0.1 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 0.0.0 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/SDK b/SDK new file mode 160000 index 0000000..864dc66 --- /dev/null +++ b/SDK @@ -0,0 +1 @@ +Subproject commit 864dc66c9e6ccee330f2b78fdcd5af930b37b06c 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..2d8c30a --- /dev/null +++ b/board/board.c @@ -0,0 +1,135 @@ +/* + * Copyright 2017-2018 NXP + * All rights reserved. + * + * SPDX-License-Identifier: BSD-3-Clause + */ + +#include +#include "fsl_common.h" +#include "fsl_debug_console.h" +#include "board.h" +#if defined(SDK_I2C_BASED_COMPONENT_USED) && SDK_I2C_BASED_COMPONENT_USED +#include "fsl_i2c.h" +#endif /* SDK_I2C_BASED_COMPONENT_USED */ + +/******************************************************************************* + * Variables + ******************************************************************************/ + +/******************************************************************************* + * Code + ******************************************************************************/ +/* Initialize debug console. */ +void BOARD_InitDebugConsole(void) +{ + /* attach 12 MHz clock to FLEXCOMM0 (debug console) */ + CLOCK_AttachClk(BOARD_DEBUG_UART_CLK_ATTACH); + + RESET_ClearPeripheralReset(BOARD_DEBUG_UART_RST); + + uint32_t uartClkSrcFreq = BOARD_DEBUG_UART_CLK_FREQ; + + DbgConsole_Init(BOARD_DEBUG_UART_INSTANCE, BOARD_DEBUG_UART_BAUDRATE, BOARD_DEBUG_UART_TYPE, uartClkSrcFreq); +} + +void BOARD_InitDebugConsole_Core1(void) +{ + /* attach 12 MHz clock to FLEXCOMM1 (debug console) */ + CLOCK_AttachClk(BOARD_DEBUG_UART_CLK_ATTACH_CORE1); + + RESET_ClearPeripheralReset(BOARD_DEBUG_UART_RST_CORE1); + + uint32_t uartClkSrcFreq = BOARD_DEBUG_UART_CLK_FREQ_CORE1; + + DbgConsole_Init(BOARD_DEBUG_UART_INSTANCE_CORE1, BOARD_DEBUG_UART_BAUDRATE_CORE1, BOARD_DEBUG_UART_TYPE_CORE1, + uartClkSrcFreq); +} + +#if defined(SDK_I2C_BASED_COMPONENT_USED) && SDK_I2C_BASED_COMPONENT_USED +void BOARD_I2C_Init(I2C_Type *base, uint32_t clkSrc_Hz) +{ + i2c_master_config_t i2cConfig = {0}; + + I2C_MasterGetDefaultConfig(&i2cConfig); + I2C_MasterInit(base, &i2cConfig, clkSrc_Hz); +} + +status_t BOARD_I2C_Send(I2C_Type *base, + uint8_t deviceAddress, + uint32_t subAddress, + uint8_t subaddressSize, + uint8_t *txBuff, + uint8_t txBuffSize) +{ + i2c_master_transfer_t masterXfer; + + /* Prepare transfer structure. */ + masterXfer.slaveAddress = deviceAddress; + masterXfer.direction = kI2C_Write; + masterXfer.subaddress = subAddress; + masterXfer.subaddressSize = subaddressSize; + masterXfer.data = txBuff; + masterXfer.dataSize = txBuffSize; + masterXfer.flags = kI2C_TransferDefaultFlag; + + return I2C_MasterTransferBlocking(base, &masterXfer); +} + +status_t BOARD_I2C_Receive(I2C_Type *base, + uint8_t deviceAddress, + uint32_t subAddress, + uint8_t subaddressSize, + uint8_t *rxBuff, + uint8_t rxBuffSize) +{ + i2c_master_transfer_t masterXfer; + + /* Prepare transfer structure. */ + masterXfer.slaveAddress = deviceAddress; + masterXfer.subaddress = subAddress; + masterXfer.subaddressSize = subaddressSize; + masterXfer.data = rxBuff; + masterXfer.dataSize = rxBuffSize; + masterXfer.direction = kI2C_Read; + masterXfer.flags = kI2C_TransferDefaultFlag; + + return I2C_MasterTransferBlocking(base, &masterXfer); +} + +void BOARD_Accel_I2C_Init(void) +{ + BOARD_I2C_Init(BOARD_ACCEL_I2C_BASEADDR, BOARD_ACCEL_I2C_CLOCK_FREQ); +} + +status_t BOARD_Accel_I2C_Send(uint8_t deviceAddress, uint32_t subAddress, uint8_t subaddressSize, uint32_t txBuff) +{ + uint8_t data = (uint8_t)txBuff; + + return BOARD_I2C_Send(BOARD_ACCEL_I2C_BASEADDR, deviceAddress, subAddress, subaddressSize, &data, 1); +} + +status_t BOARD_Accel_I2C_Receive( + uint8_t deviceAddress, uint32_t subAddress, uint8_t subaddressSize, uint8_t *rxBuff, uint8_t rxBuffSize) +{ + return BOARD_I2C_Receive(BOARD_ACCEL_I2C_BASEADDR, deviceAddress, subAddress, subaddressSize, rxBuff, rxBuffSize); +} + +void BOARD_Codec_I2C_Init(void) +{ + BOARD_I2C_Init(BOARD_CODEC_I2C_BASEADDR, BOARD_CODEC_I2C_CLOCK_FREQ); +} + +status_t BOARD_Codec_I2C_Send( + uint8_t deviceAddress, uint32_t subAddress, uint8_t subAddressSize, const uint8_t *txBuff, uint8_t txBuffSize) +{ + return BOARD_I2C_Send(BOARD_CODEC_I2C_BASEADDR, deviceAddress, subAddress, subAddressSize, (uint8_t *)txBuff, + txBuffSize); +} + +status_t BOARD_Codec_I2C_Receive( + uint8_t deviceAddress, uint32_t subAddress, uint8_t subAddressSize, uint8_t *rxBuff, uint8_t rxBuffSize) +{ + return BOARD_I2C_Receive(BOARD_CODEC_I2C_BASEADDR, deviceAddress, subAddress, subAddressSize, rxBuff, rxBuffSize); +} +#endif /* SDK_I2C_BASED_COMPONENT_USED */ diff --git a/board/board.h b/board/board.h new file mode 100644 index 0000000..adf1e7d --- /dev/null +++ b/board/board.h @@ -0,0 +1,223 @@ +/* + * 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_reset.h" +#include "fsl_gpio.h" +#include "fsl_iocon.h" + +/******************************************************************************* + * Definitions + ******************************************************************************/ +/*! @brief The board name */ +#define BOARD_NAME "LPCXpresso55S69" + +/*! @brief The UART to use for debug messages. */ +/* TODO: rename UART to USART */ +#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 12000000U +#define BOARD_DEBUG_UART_CLK_ATTACH kFRO12M_to_FLEXCOMM0 +#define BOARD_DEBUG_UART_RST kFC0_RST_SHIFT_RSTn +#define BOARD_DEBUG_UART_CLKSRC kCLOCK_Flexcomm0 +#define BOARD_UART_IRQ_HANDLER FLEXCOMM0_IRQHandler +#define BOARD_UART_IRQ FLEXCOMM0_IRQn + +#define BOARD_ACCEL_I2C_BASEADDR I2C4 +#define BOARD_ACCEL_I2C_CLOCK_FREQ 12000000 + +#define BOARD_DEBUG_UART_TYPE_CORE1 kSerialPort_Uart +#define BOARD_DEBUG_UART_BASEADDR_CORE1 (uint32_t) USART1 +#define BOARD_DEBUG_UART_INSTANCE_CORE1 1U +#define BOARD_DEBUG_UART_CLK_FREQ_CORE1 12000000U +#define BOARD_DEBUG_UART_CLK_ATTACH_CORE1 kFRO12M_to_FLEXCOMM1 +#define BOARD_DEBUG_UART_RST_CORE1 kFC1_RST_SHIFT_RSTn +#define BOARD_DEBUG_UART_CLKSRC_CORE1 kCLOCK_Flexcomm1 +#define BOARD_UART_IRQ_HANDLER_CORE1 FLEXCOMM1_IRQHandler +#define BOARD_UART_IRQ_CORE1 FLEXCOMM1_IRQn + +#ifndef BOARD_DEBUG_UART_BAUDRATE +#define BOARD_DEBUG_UART_BAUDRATE 115200U +#endif /* BOARD_DEBUG_UART_BAUDRATE */ + +#ifndef BOARD_DEBUG_UART_BAUDRATE_CORE1 +#define BOARD_DEBUG_UART_BAUDRATE_CORE1 115200U +#endif /* BOARD_DEBUG_UART_BAUDRATE_CORE1 */ + +#define BOARD_CODEC_I2C_BASEADDR I2C4 +#define BOARD_CODEC_I2C_CLOCK_FREQ 12000000 +#define BOARD_CODEC_I2C_INSTANCE 4 +#ifndef BOARD_LED_RED_GPIO +#define BOARD_LED_RED_GPIO GPIO +#endif +#define BOARD_LED_RED_GPIO_PORT 1U +#ifndef BOARD_LED_RED_GPIO_PIN +#define BOARD_LED_RED_GPIO_PIN 6U +#endif + +#ifndef BOARD_LED_BLUE_GPIO +#define BOARD_LED_BLUE_GPIO GPIO +#endif +#define BOARD_LED_BLUE_GPIO_PORT 1U +#ifndef BOARD_LED_BLUE_GPIO_PIN +#define BOARD_LED_BLUE_GPIO_PIN 4U +#endif + +#ifndef BOARD_LED_GREEN_GPIO +#define BOARD_LED_GREEN_GPIO GPIO +#endif +#define BOARD_LED_GREEN_GPIO_PORT 1U +#ifndef BOARD_LED_GREEN_GPIO_PIN +#define BOARD_LED_GREEN_GPIO_PIN 7U +#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 5U +#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 1U +#ifndef BOARD_SW2_GPIO_PIN +#define BOARD_SW2_GPIO_PIN 18U +#endif +#define BOARD_SW2_NAME "SW2" +#define BOARD_SW2_IRQ PIN_INT1_IRQn +#define BOARD_SW2_IRQ_HANDLER PIN_INT1_IRQHandler +#define BOARD_SW2_GPIO_PININT_INDEX 1 + +#ifndef BOARD_SW3_GPIO +#define BOARD_SW3_GPIO GPIO +#endif +#define BOARD_SW3_GPIO_PORT 1U +#ifndef BOARD_SW3_GPIO_PIN +#define BOARD_SW3_GPIO_PIN 9U +#endif +#define BOARD_SW3_NAME "SW3" +#define BOARD_SW3_IRQ PIN_INT1_IRQn +#define BOARD_SW3_IRQ_HANDLER PIN_INT1_IRQHandler +#define BOARD_SW3_GPIO_PININT_INDEX 1 + +/* USB PHY condfiguration */ +#define BOARD_USB_PHY_D_CAL (0x05U) +#define BOARD_USB_PHY_TXCAL45DP (0x0AU) +#define BOARD_USB_PHY_TXCAL45DM (0x0AU) + +/* Board led color mapping */ +#define LOGIC_LED_ON 0U +#define LOGIC_LED_OFF 1U + +#define LED_RED_INIT(output) \ + { \ + IOCON_PinMuxSet(IOCON, BOARD_LED_RED_GPIO_PORT, BOARD_LED_RED_GPIO_PIN, IOCON_DIGITAL_EN); \ + 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 LED1 */ \ + } +#define LED_RED_ON() \ + GPIO_PortClear(BOARD_LED_RED_GPIO, BOARD_LED_RED_GPIO_PORT, \ + 1U << BOARD_LED_RED_GPIO_PIN) /*!< Turn on target LED1 */ +#define LED_RED_OFF() \ + GPIO_PortSet(BOARD_LED_RED_GPIO, BOARD_LED_RED_GPIO_PORT, \ + 1U << BOARD_LED_RED_GPIO_PIN) /*!< Turn off target LED1 \ \ \ \ \ \ \ \ \ \ \ + */ +#define LED_RED_TOGGLE() \ + GPIO_PortToggle(BOARD_LED_RED_GPIO, BOARD_LED_RED_GPIO_PORT, \ + 1U << BOARD_LED_RED_GPIO_PIN) /*!< Toggle on target LED1 */ + +#define LED_BLUE_INIT(output) \ + { \ + IOCON_PinMuxSet(IOCON, BOARD_LED_BLUE_GPIO_PORT, BOARD_LED_BLUE_GPIO_PIN, IOCON_DIGITAL_EN); \ + 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 LED1 */ \ + } +#define LED_BLUE_ON() \ + GPIO_PortClear(BOARD_LED_BLUE_GPIO, BOARD_LED_BLUE_GPIO_PORT, \ + 1U << BOARD_LED_BLUE_GPIO_PIN) /*!< Turn on target LED1 */ +#define LED_BLUE_OFF() \ + GPIO_PortSet(BOARD_LED_BLUE_GPIO, BOARD_LED_BLUE_GPIO_PORT, \ + 1U << BOARD_LED_BLUE_GPIO_PIN) /*!< Turn off target LED1 */ +#define LED_BLUE_TOGGLE() \ + GPIO_PortToggle(BOARD_LED_BLUE_GPIO, BOARD_LED_BLUE_GPIO_PORT, \ + 1U << BOARD_LED_BLUE_GPIO_PIN) /*!< Toggle on target LED1 */ + +#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 LED1 */ +#define LED_GREEN_ON() \ + GPIO_PortClear(BOARD_LED_GREEN_GPIO, BOARD_LED_GREEN_GPIO_PORT, \ + 1U << BOARD_LED_GREEN_GPIO_PIN) /*!< Turn on target LED1 */ +#define LED_GREEN_OFF() \ + GPIO_PortSet(BOARD_LED_GREEN_GPIO, BOARD_LED_GREEN_GPIO_PORT, \ + 1U << BOARD_LED_GREEN_GPIO_PIN) /*!< Turn off target LED1 */ +#define LED_GREEN_TOGGLE() \ + GPIO_PortToggle(BOARD_LED_GREEN_GPIO, BOARD_LED_GREEN_GPIO_PORT, \ + 1U << BOARD_LED_GREEN_GPIO_PIN) /*!< Toggle on target LED1 */ + +/* Display. */ +#define BOARD_LCD_DC_GPIO GPIO +#define BOARD_LCD_DC_GPIO_PORT 1U +#define BOARD_LCD_DC_GPIO_PIN 5U + +/* Serial MWM WIFI */ +#define BOARD_SERIAL_MWM_PORT_CLK_FREQ CLOCK_GetFlexCommClkFreq(2) +#define BOARD_SERIAL_MWM_PORT USART2 +#define BOARD_SERIAL_MWM_PORT_IRQn FLEXCOMM2_IRQn +#define BOARD_SERIAL_MWM_RST_WRITE(output) + +#if defined(__cplusplus) +extern "C" { +#endif /* __cplusplus */ + +/******************************************************************************* + * API + ******************************************************************************/ + +void BOARD_InitDebugConsole(void); +void BOARD_InitDebugConsole_Core1(void); +#if defined(SDK_I2C_BASED_COMPONENT_USED) && SDK_I2C_BASED_COMPONENT_USED +void BOARD_I2C_Init(I2C_Type *base, uint32_t clkSrc_Hz); +status_t BOARD_I2C_Send(I2C_Type *base, + uint8_t deviceAddress, + uint32_t subAddress, + uint8_t subaddressSize, + uint8_t *txBuff, + uint8_t txBuffSize); +status_t BOARD_I2C_Receive(I2C_Type *base, + uint8_t deviceAddress, + uint32_t subAddress, + uint8_t subaddressSize, + uint8_t *rxBuff, + uint8_t rxBuffSize); +void BOARD_Accel_I2C_Init(void); +status_t BOARD_Accel_I2C_Send(uint8_t deviceAddress, uint32_t subAddress, uint8_t subaddressSize, uint32_t txBuff); +status_t BOARD_Accel_I2C_Receive( + uint8_t deviceAddress, uint32_t subAddress, uint8_t subaddressSize, uint8_t *rxBuff, uint8_t rxBuffSize); +void BOARD_Codec_I2C_Init(void); +status_t BOARD_Codec_I2C_Send( + uint8_t deviceAddress, uint32_t subAddress, uint8_t subAddressSize, const uint8_t *txBuff, uint8_t txBuffSize); +status_t BOARD_Codec_I2C_Receive( + uint8_t deviceAddress, uint32_t subAddress, uint8_t subAddressSize, uint8_t *rxBuff, uint8_t rxBuffSize); +#endif /* SDK_I2C_BASED_COMPONENT_USED */ + +#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..1595dbb --- /dev/null +++ b/board/clock_config.c @@ -0,0 +1,286 @@ +/*********************************************************************************************************************** + * 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. Set up wait states of the flash. + * + * 3. Set up all dividers. + * + * 4. 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: LPC55S69 +package_id: LPC55S69JBD100 +mcu_data: ksdk2_0 +processor_version: 11.0.1 +board: LPCXpresso55S69 + * 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_BootClockPLL150M(); +} + +/******************************************************************************* + ******************** Configuration BOARD_BootClockFRO12M ********************** + ******************************************************************************/ +/* clang-format off */ +/* TEXT BELOW IS USED AS SETTING FOR TOOLS ************************************* +!!Configuration +name: BOARD_BootClockFRO12M +outputs: +- {id: System_clock.outFreq, value: 12 MHz} + * BE CAREFUL MODIFYING THIS COMMENT - IT IS YAML SETTINGS FOR TOOLS **********/ +/* clang-format on */ + +/******************************************************************************* + * Variables for BOARD_BootClockFRO12M configuration + ******************************************************************************/ +/******************************************************************************* + * Code for BOARD_BootClockFRO12M configuration + ******************************************************************************/ +void BOARD_BootClockFRO12M(void) +{ +#ifndef SDK_SECONDARY_CORE + /*!< Set up the clock sources */ + /*!< Configure FRO192M */ + POWER_DisablePD(kPDRUNCFG_PD_FRO192M); /*!< Ensure FRO is on */ + CLOCK_SetupFROClocking(12000000U); /*!< Set up FRO to the 12 MHz, just for sure */ + CLOCK_AttachClk(kFRO12M_to_MAIN_CLK); /*!< Switch to FRO 12MHz first to ensure we can change the clock setting */ + + 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 */ + + /*!< Set up clock selectors - Attach clocks to the peripheries */ + CLOCK_AttachClk(kFRO12M_to_MAIN_CLK); /*!< Switch MAIN_CLK to FRO12M */ + + /*!< Set SystemCoreClock variable. */ + SystemCoreClock = BOARD_BOOTCLOCKFRO12M_CORE_CLOCK; +#endif +} + +/******************************************************************************* + ******************* Configuration BOARD_BootClockFROHF96M ********************* + ******************************************************************************/ +/* clang-format off */ +/* TEXT BELOW IS USED AS SETTING FOR TOOLS ************************************* +!!Configuration +name: BOARD_BootClockFROHF96M +outputs: +- {id: System_clock.outFreq, value: 96 MHz} +settings: +- {id: ANALOG_CONTROL_FRO192M_CTRL_ENDI_FRO_96M_CFG, value: Enable} +- {id: SYSCON.MAINCLKSELA.sel, value: ANACTRL.fro_hf_clk} +sources: +- {id: ANACTRL.fro_hf.outFreq, value: 96 MHz} + * BE CAREFUL MODIFYING THIS COMMENT - IT IS YAML SETTINGS FOR TOOLS **********/ +/* clang-format on */ + +/******************************************************************************* + * Variables for BOARD_BootClockFROHF96M configuration + ******************************************************************************/ +/******************************************************************************* + * Code for BOARD_BootClockFROHF96M configuration + ******************************************************************************/ +void BOARD_BootClockFROHF96M(void) +{ +#ifndef SDK_SECONDARY_CORE + /*!< Set up the clock sources */ + /*!< Configure FRO192M */ + POWER_DisablePD(kPDRUNCFG_PD_FRO192M); /*!< Ensure FRO is on */ + CLOCK_SetupFROClocking(12000000U); /*!< Set up FRO to the 12 MHz, just for sure */ + CLOCK_AttachClk(kFRO12M_to_MAIN_CLK); /*!< Switch to FRO 12MHz first to ensure we can change the clock setting */ + + CLOCK_SetupFROClocking(96000000U); /* Enable FRO HF(96MHz) output */ + + POWER_SetVoltageForFreq(96000000U); /*!< Set voltage for the one of the fastest clock outputs: System clock output */ + CLOCK_SetFLASHAccessCyclesForFreq(96000000U); /*!< Set FLASH wait states for core */ + + /*!< Set up dividers */ + CLOCK_SetClkDiv(kCLOCK_DivAhbClk, 1U, false); /*!< Set AHBCLKDIV divider to value 1 */ + + /*!< Set up clock selectors - Attach clocks to the peripheries */ + CLOCK_AttachClk(kFRO_HF_to_MAIN_CLK); /*!< Switch MAIN_CLK to FRO_HF */ + + /*!< Set SystemCoreClock variable. */ + SystemCoreClock = BOARD_BOOTCLOCKFROHF96M_CORE_CLOCK; +#endif +} + +/******************************************************************************* + ******************** Configuration BOARD_BootClockPLL100M ********************* + ******************************************************************************/ +/* clang-format off */ +/* TEXT BELOW IS USED AS SETTING FOR TOOLS ************************************* +!!Configuration +name: BOARD_BootClockPLL100M +outputs: +- {id: System_clock.outFreq, value: 100 MHz} +settings: +- {id: PLL0_Mode, value: Normal} +- {id: ENABLE_CLKIN_ENA, value: Enabled} +- {id: ENABLE_SYSTEM_CLK_OUT, value: Enabled} +- {id: SYSCON.MAINCLKSELB.sel, value: SYSCON.PLL0_BYPASS} +- {id: SYSCON.PLL0CLKSEL.sel, value: SYSCON.CLK_IN_EN} +- {id: SYSCON.PLL0M_MULT.scale, value: '100', locked: true} +- {id: SYSCON.PLL0N_DIV.scale, value: '4', locked: true} +- {id: SYSCON.PLL0_PDEC.scale, value: '4', locked: true} +sources: +- {id: SYSCON.XTAL32M.outFreq, value: 16 MHz, enabled: true} + * BE CAREFUL MODIFYING THIS COMMENT - IT IS YAML SETTINGS FOR TOOLS **********/ +/* clang-format on */ + +/******************************************************************************* + * Variables for BOARD_BootClockPLL100M configuration + ******************************************************************************/ +/******************************************************************************* + * Code for BOARD_BootClockPLL100M configuration + ******************************************************************************/ +void BOARD_BootClockPLL100M(void) +{ +#ifndef SDK_SECONDARY_CORE + /*!< Set up the clock sources */ + /*!< Configure FRO192M */ + POWER_DisablePD(kPDRUNCFG_PD_FRO192M); /*!< Ensure FRO is on */ + CLOCK_SetupFROClocking(12000000U); /*!< Set up FRO to the 12 MHz, just for sure */ + CLOCK_AttachClk(kFRO12M_to_MAIN_CLK); /*!< Switch to FRO 12MHz first to ensure we can change the clock setting */ + + /*!< Configure XTAL32M */ + POWER_DisablePD(kPDRUNCFG_PD_XTAL32M); /* Ensure XTAL32M is powered */ + POWER_DisablePD(kPDRUNCFG_PD_LDOXO32M); /* Ensure XTAL32M is powered */ + CLOCK_SetupExtClocking(16000000U); /* Enable clk_in clock */ + SYSCON->CLOCK_CTRL |= SYSCON_CLOCK_CTRL_CLKIN_ENA_MASK; /* Enable clk_in from XTAL32M clock */ + ANACTRL->XO32M_CTRL |= ANACTRL_XO32M_CTRL_ENABLE_SYSTEM_CLK_OUT_MASK; /* Enable clk_in to system */ + + POWER_SetVoltageForFreq(100000000U); /*!< Set voltage for the one of the fastest clock outputs: System clock output */ + CLOCK_SetFLASHAccessCyclesForFreq(100000000U); /*!< Set FLASH wait states for core */ + + /*!< Set up PLL */ + CLOCK_AttachClk(kEXT_CLK_to_PLL0); /*!< Switch PLL0CLKSEL to EXT_CLK */ + POWER_DisablePD(kPDRUNCFG_PD_PLL0); /* Ensure PLL is on */ + POWER_DisablePD(kPDRUNCFG_PD_PLL0_SSCG); + const pll_setup_t pll0Setup = { + .pllctrl = SYSCON_PLL0CTRL_CLKEN_MASK | SYSCON_PLL0CTRL_SELI(53U) | SYSCON_PLL0CTRL_SELP(26U), + .pllndec = SYSCON_PLL0NDEC_NDIV(4U), + .pllpdec = SYSCON_PLL0PDEC_PDIV(2U), + .pllsscg = {0x0U,(SYSCON_PLL0SSCG1_MDIV_EXT(100U) | SYSCON_PLL0SSCG1_SEL_EXT_MASK)}, + .pllRate = 100000000U, + .flags = PLL_SETUPFLAG_WAITLOCK + }; + CLOCK_SetPLL0Freq(&pll0Setup); /*!< Configure PLL0 to the desired values */ + + /*!< Set up dividers */ + CLOCK_SetClkDiv(kCLOCK_DivAhbClk, 1U, false); /*!< Set AHBCLKDIV divider to value 1 */ + + /*!< Set up clock selectors - Attach clocks to the peripheries */ + CLOCK_AttachClk(kPLL0_to_MAIN_CLK); /*!< Switch MAIN_CLK to PLL0 */ + + /*!< Set SystemCoreClock variable. */ + SystemCoreClock = BOARD_BOOTCLOCKPLL100M_CORE_CLOCK; +#endif +} + +/******************************************************************************* + ******************** Configuration BOARD_BootClockPLL150M ********************* + ******************************************************************************/ +/* clang-format off */ +/* TEXT BELOW IS USED AS SETTING FOR TOOLS ************************************* +!!Configuration +name: BOARD_BootClockPLL150M +called_from_default_init: true +outputs: +- {id: System_clock.outFreq, value: 150 MHz} +settings: +- {id: PLL0_Mode, value: Normal} +- {id: ENABLE_CLKIN_ENA, value: Enabled} +- {id: ENABLE_SYSTEM_CLK_OUT, value: Enabled} +- {id: SYSCON.MAINCLKSELB.sel, value: SYSCON.PLL0_BYPASS} +- {id: SYSCON.PLL0CLKSEL.sel, value: SYSCON.CLK_IN_EN} +- {id: SYSCON.PLL0M_MULT.scale, value: '150', locked: true} +- {id: SYSCON.PLL0N_DIV.scale, value: '8', locked: true} +- {id: SYSCON.PLL0_PDEC.scale, value: '2', locked: true} +sources: +- {id: SYSCON.XTAL32M.outFreq, value: 16 MHz, enabled: true} + * BE CAREFUL MODIFYING THIS COMMENT - IT IS YAML SETTINGS FOR TOOLS **********/ +/* clang-format on */ + +/******************************************************************************* + * Variables for BOARD_BootClockPLL150M configuration + ******************************************************************************/ +/******************************************************************************* + * Code for BOARD_BootClockPLL150M configuration + ******************************************************************************/ +void BOARD_BootClockPLL150M(void) +{ +#ifndef SDK_SECONDARY_CORE + /*!< Set up the clock sources */ + /*!< Configure FRO192M */ + POWER_DisablePD(kPDRUNCFG_PD_FRO192M); /*!< Ensure FRO is on */ + CLOCK_SetupFROClocking(12000000U); /*!< Set up FRO to the 12 MHz, just for sure */ + CLOCK_AttachClk(kFRO12M_to_MAIN_CLK); /*!< Switch to FRO 12MHz first to ensure we can change the clock setting */ + + /*!< Configure XTAL32M */ + POWER_DisablePD(kPDRUNCFG_PD_XTAL32M); /* Ensure XTAL32M is powered */ + POWER_DisablePD(kPDRUNCFG_PD_LDOXO32M); /* Ensure XTAL32M is powered */ + CLOCK_SetupExtClocking(16000000U); /* Enable clk_in clock */ + SYSCON->CLOCK_CTRL |= SYSCON_CLOCK_CTRL_CLKIN_ENA_MASK; /* Enable clk_in from XTAL32M clock */ + ANACTRL->XO32M_CTRL |= ANACTRL_XO32M_CTRL_ENABLE_SYSTEM_CLK_OUT_MASK; /* Enable clk_in to system */ + + POWER_SetVoltageForFreq(150000000U); /*!< Set voltage for the one of the fastest clock outputs: System clock output */ + CLOCK_SetFLASHAccessCyclesForFreq(150000000U); /*!< Set FLASH wait states for core */ + + /*!< Set up PLL */ + CLOCK_AttachClk(kEXT_CLK_to_PLL0); /*!< Switch PLL0CLKSEL to EXT_CLK */ + POWER_DisablePD(kPDRUNCFG_PD_PLL0); /* Ensure PLL is on */ + POWER_DisablePD(kPDRUNCFG_PD_PLL0_SSCG); + const pll_setup_t pll0Setup = { + .pllctrl = SYSCON_PLL0CTRL_CLKEN_MASK | SYSCON_PLL0CTRL_SELI(53U) | SYSCON_PLL0CTRL_SELP(31U), + .pllndec = SYSCON_PLL0NDEC_NDIV(8U), + .pllpdec = SYSCON_PLL0PDEC_PDIV(1U), + .pllsscg = {0x0U,(SYSCON_PLL0SSCG1_MDIV_EXT(150U) | SYSCON_PLL0SSCG1_SEL_EXT_MASK)}, + .pllRate = 150000000U, + .flags = PLL_SETUPFLAG_WAITLOCK + }; + CLOCK_SetPLL0Freq(&pll0Setup); /*!< Configure PLL0 to the desired values */ + + /*!< Set up dividers */ + CLOCK_SetClkDiv(kCLOCK_DivAhbClk, 1U, false); /*!< Set AHBCLKDIV divider to value 1 */ + + /*!< Set up clock selectors - Attach clocks to the peripheries */ + CLOCK_AttachClk(kPLL0_to_MAIN_CLK); /*!< Switch MAIN_CLK to PLL0 */ + + /*!< Set SystemCoreClock variable. */ + SystemCoreClock = BOARD_BOOTCLOCKPLL150M_CORE_CLOCK; +#endif +} + diff --git a/board/clock_config.h b/board/clock_config.h new file mode 100644 index 0000000..69a7bc6 --- /dev/null +++ b/board/clock_config.h @@ -0,0 +1,140 @@ +/*********************************************************************************************************************** + * 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 16000000U /*!< Board xtal 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_BootClockFRO12M ********************** + ******************************************************************************/ +/******************************************************************************* + * Definitions for BOARD_BootClockFRO12M configuration + ******************************************************************************/ +#define BOARD_BOOTCLOCKFRO12M_CORE_CLOCK 12000000U /*!< Core clock frequency: 12000000Hz */ + + +/******************************************************************************* + * API for BOARD_BootClockFRO12M configuration + ******************************************************************************/ +#if defined(__cplusplus) +extern "C" { +#endif /* __cplusplus*/ + +/*! + * @brief This function executes configuration of clocks. + * + */ +void BOARD_BootClockFRO12M(void); + +#if defined(__cplusplus) +} +#endif /* __cplusplus*/ + +/******************************************************************************* + ******************* Configuration BOARD_BootClockFROHF96M ********************* + ******************************************************************************/ +/******************************************************************************* + * Definitions for BOARD_BootClockFROHF96M configuration + ******************************************************************************/ +#define BOARD_BOOTCLOCKFROHF96M_CORE_CLOCK 96000000U /*!< Core clock frequency: 96000000Hz */ + + +/******************************************************************************* + * API for BOARD_BootClockFROHF96M configuration + ******************************************************************************/ +#if defined(__cplusplus) +extern "C" { +#endif /* __cplusplus*/ + +/*! + * @brief This function executes configuration of clocks. + * + */ +void BOARD_BootClockFROHF96M(void); + +#if defined(__cplusplus) +} +#endif /* __cplusplus*/ + +/******************************************************************************* + ******************** Configuration BOARD_BootClockPLL100M ********************* + ******************************************************************************/ +/******************************************************************************* + * Definitions for BOARD_BootClockPLL100M configuration + ******************************************************************************/ +#define BOARD_BOOTCLOCKPLL100M_CORE_CLOCK 100000000U /*!< Core clock frequency: 100000000Hz */ + + +/******************************************************************************* + * API for BOARD_BootClockPLL100M configuration + ******************************************************************************/ +#if defined(__cplusplus) +extern "C" { +#endif /* __cplusplus*/ + +/*! + * @brief This function executes configuration of clocks. + * + */ +void BOARD_BootClockPLL100M(void); + +#if defined(__cplusplus) +} +#endif /* __cplusplus*/ + +/******************************************************************************* + ******************** Configuration BOARD_BootClockPLL150M ********************* + ******************************************************************************/ +/******************************************************************************* + * Definitions for BOARD_BootClockPLL150M configuration + ******************************************************************************/ +#define BOARD_BOOTCLOCKPLL150M_CORE_CLOCK 150000000U /*!< Core clock frequency: 150000000Hz */ + + +/******************************************************************************* + * API for BOARD_BootClockPLL150M configuration + ******************************************************************************/ +#if defined(__cplusplus) +extern "C" { +#endif /* __cplusplus*/ + +/*! + * @brief This function executes configuration of clocks. + * + */ +void BOARD_BootClockPLL150M(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..439049f --- /dev/null +++ b/board/peripherals.c @@ -0,0 +1,97 @@ +/*********************************************************************************************************************** + * 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: LPC55S69 +package_id: LPC55S69JBD100 +mcu_data: ksdk2_0 +processor_version: 11.0.1 +board: LPCXpresso55S69 +functionalGroups: +- name: BOARD_InitPeripherals_cm33_core0 + UUID: 61d0725d-b300-49cb-9c66-b5edfbf8ffc1 + called_from_default_init: true + selectedCore: cm33_core0 +- name: BOARD_InitPeripherals_cm33_core1 + UUID: e2041cd4-ebb6-45a5-807f-e0c2dc047d48 + selectedCore: cm33_core1 + * 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' +- 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_cm33_core0 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_cm33_core0' +- 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_cm33_core0(void) +{ + /* Initialize components */ +} + +/*********************************************************************************************************************** + * BOARD_InitBootPeripherals function + **********************************************************************************************************************/ +void BOARD_InitBootPeripherals(void) +{ + BOARD_InitPeripherals_cm33_core0(); +} diff --git a/board/peripherals.h b/board/peripherals.h new file mode 100644 index 0000000..358d8de --- /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_cm33_core0(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..bdfead3 --- /dev/null +++ b/board/pin_mux.c @@ -0,0 +1,850 @@ +/*********************************************************************************************************************** + * 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: LPC55S69 +package_id: LPC55S69JBD100 +mcu_data: ksdk2_0 +processor_version: 11.0.1 +board: LPCXpresso55S69 + * BE CAREFUL MODIFYING THIS COMMENT - IT IS YAML SETTINGS FOR TOOLS *********** + */ +/* clang-format on */ + +#include "fsl_common.h" +#include "fsl_gpio.h" +#include "fsl_iocon.h" +#include "pin_mux.h" + +/* FUNCTION ************************************************************************************************************ + * + * Function Name : BOARD_InitBootPins + * Description : Calls initialization functions. + * + * END ****************************************************************************************************************/ +void BOARD_InitBootPins(void) +{ + BOARD_InitDEBUG_UARTPins(); + BOARD_InitPins_Core0(); +} + +/* clang-format off */ +/* + * TEXT BELOW IS USED AS SETTING FOR TOOLS ************************************* +BOARD_InitDEBUG_UARTPins: +- options: {callFromInitBoot: 'true', coreID: cm33_core0, enableClock: 'true'} +- pin_list: + - {pin_num: '92', peripheral: FLEXCOMM0, signal: RXD_SDA_MOSI_DATA, pin_signal: PIO0_29/FC0_RXD_SDA_MOSI_DATA/SD1_D2/CTIMER2_MAT3/SCT0_OUT8/CMP0_OUT/PLU_OUT2/SECURE_GPIO0_29, + mode: inactive, slew_rate: standard, invert: disabled, open_drain: disabled} + - {pin_num: '94', peripheral: FLEXCOMM0, signal: TXD_SCL_MISO_WS, pin_signal: PIO0_30/FC0_TXD_SCL_MISO_WS/SD1_D3/CTIMER0_MAT0/SCT0_OUT9/SECURE_GPIO0_30, mode: inactive, + slew_rate: standard, invert: disabled, open_drain: disabled} + * BE CAREFUL MODIFYING THIS COMMENT - IT IS YAML SETTINGS FOR TOOLS *********** + */ +/* clang-format on */ + +/* FUNCTION ************************************************************************************************************ + * + * Function Name : BOARD_InitDEBUG_UARTPins + * Description : Configures pin routing and optionally pin electrical features. + * + * END ****************************************************************************************************************/ +/* Function assigned for the Cortex-M33 (Core #0) */ +void BOARD_InitDEBUG_UARTPins(void) +{ + /* Enables the clock for the I/O controller.: Enable Clock. */ + CLOCK_EnableClock(kCLOCK_Iocon); + + const uint32_t DEBUG_UART_RX = (/* Pin is configured as FC0_RXD_SDA_MOSI_DATA */ + IOCON_PIO_FUNC1 | + /* No addition pin function */ + IOCON_PIO_MODE_INACT | + /* Standard mode, output slew rate control is enabled */ + IOCON_PIO_SLEW_STANDARD | + /* Input function is not inverted */ + IOCON_PIO_INV_DI | + /* Enables digital function */ + IOCON_PIO_DIGITAL_EN | + /* Open drain is disabled */ + IOCON_PIO_OPENDRAIN_DI); + /* PORT0 PIN29 (coords: 92) is configured as FC0_RXD_SDA_MOSI_DATA */ + IOCON_PinMuxSet(IOCON, BOARD_INITDEBUG_UARTPINS_DEBUG_UART_RX_PORT, BOARD_INITDEBUG_UARTPINS_DEBUG_UART_RX_PIN, DEBUG_UART_RX); + + const uint32_t DEBUG_UART_TX = (/* Pin is configured as FC0_TXD_SCL_MISO_WS */ + IOCON_PIO_FUNC1 | + /* No addition pin function */ + IOCON_PIO_MODE_INACT | + /* Standard mode, output slew rate control is enabled */ + IOCON_PIO_SLEW_STANDARD | + /* Input function is not inverted */ + IOCON_PIO_INV_DI | + /* Enables digital function */ + IOCON_PIO_DIGITAL_EN | + /* Open drain is disabled */ + IOCON_PIO_OPENDRAIN_DI); + /* PORT0 PIN30 (coords: 94) is configured as FC0_TXD_SCL_MISO_WS */ + IOCON_PinMuxSet(IOCON, BOARD_INITDEBUG_UARTPINS_DEBUG_UART_TX_PORT, BOARD_INITDEBUG_UARTPINS_DEBUG_UART_TX_PIN, DEBUG_UART_TX); +} + +/* clang-format off */ +/* + * TEXT BELOW IS USED AS SETTING FOR TOOLS ************************************* +BOARD_InitSWD_DEBUGPins: +- options: {callFromInitBoot: 'false', coreID: cm33_core0, enableClock: 'true'} +- pin_list: + - {pin_num: '13', peripheral: SWD, signal: SWCLK, pin_signal: PIO0_11/FC6_RXD_SDA_MOSI_DATA/CTIMER2_MAT2/FREQME_GPIO_CLK_A/SWCLK/SECURE_GPIO0_11/ADC0_9, mode: pullDown, + slew_rate: standard, invert: disabled, open_drain: disabled, asw: enabled} + - {pin_num: '12', peripheral: SWD, signal: SWDIO, pin_signal: PIO0_12/FC3_TXD_SCL_MISO_WS/SD1_BACKEND_PWR/FREQME_GPIO_CLK_B/SCT_GPI7/SD0_POW_EN/SWDIO/FC6_TXD_SCL_MISO_WS/SECURE_GPIO0_12/ADC0_10, + mode: pullUp, slew_rate: standard, invert: disabled, open_drain: disabled, asw: enabled} + - {pin_num: '21', peripheral: SWD, signal: SWO, pin_signal: PIO0_10/FC6_SCK/CT_INP10/CTIMER2_MAT0/FC1_TXD_SCL_MISO_WS/SCT0_OUT2/SWO/SECURE_GPIO0_10/ADC0_1, identifier: DEBUG_SWD_SWO, + mode: inactive, slew_rate: standard, invert: disabled, open_drain: disabled, asw: disabled} + * BE CAREFUL MODIFYING THIS COMMENT - IT IS YAML SETTINGS FOR TOOLS *********** + */ +/* clang-format on */ + +/* FUNCTION ************************************************************************************************************ + * + * Function Name : BOARD_InitSWD_DEBUGPins + * Description : Configures pin routing and optionally pin electrical features. + * + * END ****************************************************************************************************************/ +/* Function assigned for the Cortex-M33 (Core #0) */ +void BOARD_InitSWD_DEBUGPins(void) +{ + /* Enables the clock for the I/O controller.: Enable Clock. */ + CLOCK_EnableClock(kCLOCK_Iocon); + + const uint32_t DEBUG_SWD_SWO = (/* Pin is configured as SWO */ + IOCON_PIO_FUNC6 | + /* No addition pin function */ + IOCON_PIO_MODE_INACT | + /* Standard mode, output slew rate control is enabled */ + IOCON_PIO_SLEW_STANDARD | + /* Input function is not inverted */ + IOCON_PIO_INV_DI | + /* Enables digital function */ + IOCON_PIO_DIGITAL_EN | + /* Open drain is disabled */ + IOCON_PIO_OPENDRAIN_DI | + /* Analog switch is open (disabled) */ + IOCON_PIO_ASW_DI); + /* PORT0 PIN10 (coords: 21) is configured as SWO */ + IOCON_PinMuxSet(IOCON, BOARD_INITSWD_DEBUGPINS_DEBUG_SWD_SWO_PORT, BOARD_INITSWD_DEBUGPINS_DEBUG_SWD_SWO_PIN, DEBUG_SWD_SWO); + + if (Chip_GetVersion()==1) + { + const uint32_t DEBUG_SWD_SWDCLK = (/* Pin is configured as SWCLK */ + IOCON_PIO_FUNC6 | + /* Selects pull-down function */ + IOCON_PIO_MODE_PULLDOWN | + /* Standard mode, output slew rate control is enabled */ + IOCON_PIO_SLEW_STANDARD | + /* Input function is not inverted */ + IOCON_PIO_INV_DI | + /* Enables digital function */ + IOCON_PIO_DIGITAL_EN | + /* Open drain is disabled */ + IOCON_PIO_OPENDRAIN_DI | + /* Analog switch is closed (enabled) */ + IOCON_PIO_ASW_EN); + /* PORT0 PIN11 (coords: 13) is configured as SWCLK */ + IOCON_PinMuxSet(IOCON, BOARD_INITSWD_DEBUGPINS_DEBUG_SWD_SWDCLK_PORT, BOARD_INITSWD_DEBUGPINS_DEBUG_SWD_SWDCLK_PIN, DEBUG_SWD_SWDCLK); + } + else + { + const uint32_t DEBUG_SWD_SWDCLK = (/* Pin is configured as SWCLK */ + IOCON_PIO_FUNC6 | + /* Selects pull-down function */ + IOCON_PIO_MODE_PULLDOWN | + /* Standard mode, output slew rate control is enabled */ + IOCON_PIO_SLEW_STANDARD | + /* Input function is not inverted */ + IOCON_PIO_INV_DI | + /* Enables digital function */ + IOCON_PIO_DIGITAL_EN | + /* Open drain is disabled */ + IOCON_PIO_OPENDRAIN_DI | + /* Analog switch is closed (enabled), only for A0 version */ + IOCON_PIO_ASW_DIS_EN); + /* PORT0 PIN11 (coords: 13) is configured as SWCLK */ + IOCON_PinMuxSet(IOCON, BOARD_INITSWD_DEBUGPINS_DEBUG_SWD_SWDCLK_PORT, BOARD_INITSWD_DEBUGPINS_DEBUG_SWD_SWDCLK_PIN, DEBUG_SWD_SWDCLK); + } + + if (Chip_GetVersion()==1) + { + const uint32_t DEBUG_SWD_SWDIO = (/* Pin is configured as SWDIO */ + IOCON_PIO_FUNC6 | + /* Selects pull-up function */ + IOCON_PIO_MODE_PULLUP | + /* Standard mode, output slew rate control is enabled */ + IOCON_PIO_SLEW_STANDARD | + /* Input function is not inverted */ + IOCON_PIO_INV_DI | + /* Enables digital function */ + IOCON_PIO_DIGITAL_EN | + /* Open drain is disabled */ + IOCON_PIO_OPENDRAIN_DI | + /* Analog switch is closed (enabled) */ + IOCON_PIO_ASW_EN); + /* PORT0 PIN12 (coords: 12) is configured as SWDIO */ + IOCON_PinMuxSet(IOCON, BOARD_INITSWD_DEBUGPINS_DEBUG_SWD_SWDIO_PORT, BOARD_INITSWD_DEBUGPINS_DEBUG_SWD_SWDIO_PIN, DEBUG_SWD_SWDIO); + } + else + { + const uint32_t DEBUG_SWD_SWDIO = (/* Pin is configured as SWDIO */ + IOCON_PIO_FUNC6 | + /* Selects pull-up function */ + IOCON_PIO_MODE_PULLUP | + /* Standard mode, output slew rate control is enabled */ + IOCON_PIO_SLEW_STANDARD | + /* Input function is not inverted */ + IOCON_PIO_INV_DI | + /* Enables digital function */ + IOCON_PIO_DIGITAL_EN | + /* Open drain is disabled */ + IOCON_PIO_OPENDRAIN_DI | + /* Analog switch is closed (enabled), only for A0 version */ + IOCON_PIO_ASW_DIS_EN); + /* PORT0 PIN12 (coords: 12) is configured as SWDIO */ + IOCON_PinMuxSet(IOCON, BOARD_INITSWD_DEBUGPINS_DEBUG_SWD_SWDIO_PORT, BOARD_INITSWD_DEBUGPINS_DEBUG_SWD_SWDIO_PIN, DEBUG_SWD_SWDIO); + } +} + +/* clang-format off */ +/* + * TEXT BELOW IS USED AS SETTING FOR TOOLS ************************************* +BOARD_InitUSBPins: +- options: {callFromInitBoot: 'false', coreID: cm33_core0, enableClock: 'true'} +- pin_list: + - {pin_num: '97', peripheral: USBFSH, signal: USB_DP, pin_signal: USB0_DP} + - {pin_num: '98', peripheral: USBFSH, signal: USB_DM, pin_signal: USB0_DM} + - {pin_num: '78', peripheral: USBFSH, signal: USB_VBUS, pin_signal: PIO0_22/FC6_TXD_SCL_MISO_WS/UTICK_CAP1/CT_INP15/SCT0_OUT3/USB0_VBUS/SD1_D0/PLU_OUT7/SECURE_GPIO0_22, + mode: inactive, slew_rate: standard, invert: disabled, open_drain: disabled} + - {pin_num: '35', peripheral: USBHSH, signal: USB_DM, pin_signal: USB1_DM} + - {pin_num: '34', peripheral: USBHSH, signal: USB_DP, pin_signal: USB1_DP} + - {pin_num: '36', peripheral: USBHSH, signal: USB_VBUS, pin_signal: USB1_VBUS} + - {pin_num: '65', peripheral: USBHSH, signal: USB_OVERCURRENTN, pin_signal: PIO1_30/FC7_TXD_SCL_MISO_WS/SD0_D7/SCT_GPI7/USB1_OVERCURRENTN/USB1_LEDN/PLU_IN1, mode: pullUp} + - {pin_num: '66', peripheral: USBFSH, signal: USB_OVERCURRENTN, pin_signal: PIO0_28/FC0_SCK/SD1_CMD/CT_INP11/SCT0_OUT7/USB0_OVERCURRENTN/PLU_OUT1/SECURE_GPIO0_28, + mode: pullUp} + - {pin_num: '67', peripheral: USBFSH, signal: USB_PORTPWRN, pin_signal: PIO1_12/FC6_SCK/CTIMER1_MAT1/USB0_PORTPWRN/HS_SPI_SSEL2, mode: pullUp} + - {pin_num: '80', peripheral: USBHSH, signal: USB_PORTPWRN, pin_signal: PIO1_29/FC7_RXD_SDA_MOSI_DATA/SD0_D6/SCT_GPI6/USB1_PORTPWRN/USB1_FRAME/PLU_IN2, mode: pullUp} + * BE CAREFUL MODIFYING THIS COMMENT - IT IS YAML SETTINGS FOR TOOLS *********** + */ +/* clang-format on */ + +/* FUNCTION ************************************************************************************************************ + * + * Function Name : BOARD_InitUSBPins + * Description : Configures pin routing and optionally pin electrical features. + * + * END ****************************************************************************************************************/ +/* Function assigned for the Cortex-M33 (Core #0) */ +void BOARD_InitUSBPins(void) +{ + /* Enables the clock for the I/O controller.: Enable Clock. */ + CLOCK_EnableClock(kCLOCK_Iocon); + + const uint32_t USB0_VBUS = (/* Pin is configured as USB0_VBUS */ + IOCON_PIO_FUNC7 | + /* No addition pin function */ + IOCON_PIO_MODE_INACT | + /* Standard mode, output slew rate control is enabled */ + IOCON_PIO_SLEW_STANDARD | + /* Input function is not inverted */ + IOCON_PIO_INV_DI | + /* Enables digital function */ + IOCON_PIO_DIGITAL_EN | + /* Open drain is disabled */ + IOCON_PIO_OPENDRAIN_DI); + /* PORT0 PIN22 (coords: 78) is configured as USB0_VBUS */ + IOCON_PinMuxSet(IOCON, BOARD_INITUSBPINS_USB0_VBUS_PORT, BOARD_INITUSBPINS_USB0_VBUS_PIN, USB0_VBUS); + + IOCON->PIO[0][28] = ((IOCON->PIO[0][28] & + /* Mask bits to zero which are setting */ + (~(IOCON_PIO_FUNC_MASK | IOCON_PIO_MODE_MASK | IOCON_PIO_DIGIMODE_MASK))) + + /* Selects pin function. + * : PORT028 (pin 66) is configured as USB0_OVERCURRENTN. */ + | IOCON_PIO_FUNC(PIO0_28_FUNC_ALT7) + + /* Selects function mode (on-chip pull-up/pull-down resistor control). + * : Pull-up. + * Pull-up resistor enabled. */ + | IOCON_PIO_MODE(PIO0_28_MODE_PULL_UP) + + /* Select Digital mode. + * : Enable Digital mode. + * Digital input is enabled. */ + | IOCON_PIO_DIGIMODE(PIO0_28_DIGIMODE_DIGITAL)); + + IOCON->PIO[1][12] = ((IOCON->PIO[1][12] & + /* Mask bits to zero which are setting */ + (~(IOCON_PIO_FUNC_MASK | IOCON_PIO_MODE_MASK | IOCON_PIO_DIGIMODE_MASK))) + + /* Selects pin function. + * : PORT112 (pin 67) is configured as USB0_PORTPWRN. */ + | IOCON_PIO_FUNC(PIO1_12_FUNC_ALT4) + + /* Selects function mode (on-chip pull-up/pull-down resistor control). + * : Pull-up. + * Pull-up resistor enabled. */ + | IOCON_PIO_MODE(PIO1_12_MODE_PULL_UP) + + /* Select Digital mode. + * : Enable Digital mode. + * Digital input is enabled. */ + | IOCON_PIO_DIGIMODE(PIO1_12_DIGIMODE_DIGITAL)); + + IOCON->PIO[1][29] = ((IOCON->PIO[1][29] & + /* Mask bits to zero which are setting */ + (~(IOCON_PIO_FUNC_MASK | IOCON_PIO_MODE_MASK | IOCON_PIO_DIGIMODE_MASK))) + + /* Selects pin function. + * : PORT129 (pin 80) is configured as USB1_PORTPWRN. */ + | IOCON_PIO_FUNC(PIO1_29_FUNC_ALT4) + + /* Selects function mode (on-chip pull-up/pull-down resistor control). + * : Pull-up. + * Pull-up resistor enabled. */ + | IOCON_PIO_MODE(PIO1_29_MODE_PULL_UP) + + /* Select Digital mode. + * : Enable Digital mode. + * Digital input is enabled. */ + | IOCON_PIO_DIGIMODE(PIO1_29_DIGIMODE_DIGITAL)); + + IOCON->PIO[1][30] = ((IOCON->PIO[1][30] & + /* Mask bits to zero which are setting */ + (~(IOCON_PIO_FUNC_MASK | IOCON_PIO_MODE_MASK | IOCON_PIO_DIGIMODE_MASK))) + + /* Selects pin function. + * : PORT130 (pin 65) is configured as USB1_OVERCURRENTN. */ + | IOCON_PIO_FUNC(PIO1_30_FUNC_ALT4) + + /* Selects function mode (on-chip pull-up/pull-down resistor control). + * : Pull-up. + * Pull-up resistor enabled. */ + | IOCON_PIO_MODE(PIO1_30_MODE_PULL_UP) + + /* Select Digital mode. + * : Enable Digital mode. + * Digital input is enabled. */ + | IOCON_PIO_DIGIMODE(PIO1_30_DIGIMODE_DIGITAL)); +} + +/* clang-format off */ +/* + * TEXT BELOW IS USED AS SETTING FOR TOOLS ************************************* +BOARD_InitLEDsPins: +- options: {callFromInitBoot: 'false', coreID: cm33_core0, enableClock: 'true'} +- pin_list: + - {pin_num: '1', peripheral: GPIO, signal: 'PIO1, 4', pin_signal: PIO1_4/FC0_SCK/SD0_D0/CTIMER2_MAT1/SCT0_OUT0/FREQME_GPIO_CLK_A, direction: OUTPUT, gpio_init_state: 'true', + mode: pullUp, slew_rate: standard, invert: disabled, open_drain: disabled} + - {pin_num: '5', peripheral: GPIO, signal: 'PIO1, 6', pin_signal: PIO1_6/FC0_TXD_SCL_MISO_WS/SD0_D3/CTIMER2_MAT1/SCT_GPI3, direction: OUTPUT, gpio_init_state: 'true', + mode: pullUp, slew_rate: standard, invert: disabled, open_drain: disabled} + - {pin_num: '9', peripheral: GPIO, signal: 'PIO1, 7', pin_signal: PIO1_7/FC0_RTS_SCL_SSEL1/SD0_D1/CTIMER2_MAT2/SCT_GPI4, direction: OUTPUT, gpio_init_state: 'true', + mode: pullUp, slew_rate: standard, invert: disabled, open_drain: disabled} + * BE CAREFUL MODIFYING THIS COMMENT - IT IS YAML SETTINGS FOR TOOLS *********** + */ +/* clang-format on */ + +/* FUNCTION ************************************************************************************************************ + * + * Function Name : BOARD_InitLEDsPins + * Description : Configures pin routing and optionally pin electrical features. + * + * END ****************************************************************************************************************/ +/* Function assigned for the Cortex-M33 (Core #0) */ +void BOARD_InitLEDsPins(void) +{ + /* Enables the clock for the I/O controller.: Enable Clock. */ + CLOCK_EnableClock(kCLOCK_Iocon); + + /* Enables the clock for the GPIO1 module */ + CLOCK_EnableClock(kCLOCK_Gpio1); + + gpio_pin_config_t LED_BLUE_config = { + .pinDirection = kGPIO_DigitalOutput, + .outputLogic = 1U + }; + /* Initialize GPIO functionality on pin PIO1_4 (pin 1) */ + GPIO_PinInit(BOARD_INITLEDSPINS_LED_BLUE_GPIO, BOARD_INITLEDSPINS_LED_BLUE_PORT, BOARD_INITLEDSPINS_LED_BLUE_PIN, &LED_BLUE_config); + + gpio_pin_config_t LED_RED_config = { + .pinDirection = kGPIO_DigitalOutput, + .outputLogic = 1U + }; + /* Initialize GPIO functionality on pin PIO1_6 (pin 5) */ + GPIO_PinInit(BOARD_INITLEDSPINS_LED_RED_GPIO, BOARD_INITLEDSPINS_LED_RED_PORT, BOARD_INITLEDSPINS_LED_RED_PIN, &LED_RED_config); + + gpio_pin_config_t LED_GREEN_config = { + .pinDirection = kGPIO_DigitalOutput, + .outputLogic = 1U + }; + /* Initialize GPIO functionality on pin PIO1_7 (pin 9) */ + GPIO_PinInit(BOARD_INITLEDSPINS_LED_GREEN_GPIO, BOARD_INITLEDSPINS_LED_GREEN_PORT, BOARD_INITLEDSPINS_LED_GREEN_PIN, &LED_GREEN_config); + + const uint32_t LED_BLUE = (/* Pin is configured as PIO1_4 */ + IOCON_PIO_FUNC0 | + /* Selects pull-up function */ + IOCON_PIO_MODE_PULLUP | + /* Standard mode, output slew rate control is enabled */ + IOCON_PIO_SLEW_STANDARD | + /* Input function is not inverted */ + IOCON_PIO_INV_DI | + /* Enables digital function */ + IOCON_PIO_DIGITAL_EN | + /* Open drain is disabled */ + IOCON_PIO_OPENDRAIN_DI); + /* PORT1 PIN4 (coords: 1) is configured as PIO1_4 */ + IOCON_PinMuxSet(IOCON, BOARD_INITLEDSPINS_LED_BLUE_PORT, BOARD_INITLEDSPINS_LED_BLUE_PIN, LED_BLUE); + + const uint32_t LED_RED = (/* Pin is configured as PIO1_6 */ + IOCON_PIO_FUNC0 | + /* Selects pull-up function */ + IOCON_PIO_MODE_PULLUP | + /* Standard mode, output slew rate control is enabled */ + IOCON_PIO_SLEW_STANDARD | + /* Input function is not inverted */ + IOCON_PIO_INV_DI | + /* Enables digital function */ + IOCON_PIO_DIGITAL_EN | + /* Open drain is disabled */ + IOCON_PIO_OPENDRAIN_DI); + /* PORT1 PIN6 (coords: 5) is configured as PIO1_6 */ + IOCON_PinMuxSet(IOCON, BOARD_INITLEDSPINS_LED_RED_PORT, BOARD_INITLEDSPINS_LED_RED_PIN, LED_RED); + + const uint32_t LED_GREEN = (/* Pin is configured as PIO1_7 */ + IOCON_PIO_FUNC0 | + /* Selects pull-up function */ + IOCON_PIO_MODE_PULLUP | + /* Standard mode, output slew rate control is enabled */ + IOCON_PIO_SLEW_STANDARD | + /* Input function is not inverted */ + IOCON_PIO_INV_DI | + /* Enables digital function */ + IOCON_PIO_DIGITAL_EN | + /* Open drain is disabled */ + IOCON_PIO_OPENDRAIN_DI); + /* PORT1 PIN7 (coords: 9) is configured as PIO1_7 */ + IOCON_PinMuxSet(IOCON, BOARD_INITLEDSPINS_LED_GREEN_PORT, BOARD_INITLEDSPINS_LED_GREEN_PIN, LED_GREEN); +} + +/* clang-format off */ +/* + * TEXT BELOW IS USED AS SETTING FOR TOOLS ************************************* +BOARD_InitBUTTONsPins: +- options: {callFromInitBoot: 'false', coreID: cm33_core0, enableClock: 'true'} +- pin_list: + - {pin_num: '88', peripheral: GPIO, signal: 'PIO0, 5', pin_signal: PIO0_5/FC4_RXD_SDA_MOSI_DATA/CTIMER3_MAT0/SCT_GPI5/FC3_RTS_SCL_SSEL1/MCLK/SECURE_GPIO0_5, direction: INPUT, + mode: pullUp, slew_rate: standard, invert: disabled, open_drain: disabled} + - {pin_num: '64', peripheral: GPIO, signal: 'PIO1, 18', pin_signal: PIO1_18/SD1_POW_EN/SCT0_OUT5/PLU_OUT0, direction: INPUT, mode: pullUp, slew_rate: standard, + invert: disabled, open_drain: disabled} + - {pin_num: '10', peripheral: GPIO, signal: 'PIO1, 9', pin_signal: PIO1_9/FC1_SCK/CT_INP4/SCT0_OUT2/FC4_CTS_SDA_SSEL0/ADC0_12, direction: INPUT, mode: pullUp, slew_rate: standard, + invert: disabled, open_drain: disabled, asw: enabled} + - {pin_num: '32', peripheral: SYSCON, signal: RESET, pin_signal: RESETN} + * BE CAREFUL MODIFYING THIS COMMENT - IT IS YAML SETTINGS FOR TOOLS *********** + */ +/* clang-format on */ + +/* FUNCTION ************************************************************************************************************ + * + * Function Name : BOARD_InitBUTTONsPins + * Description : Configures pin routing and optionally pin electrical features. + * + * END ****************************************************************************************************************/ +/* Function assigned for the Cortex-M33 (Core #0) */ +void BOARD_InitBUTTONsPins(void) +{ + /* Enables the clock for the I/O controller.: Enable Clock. */ + CLOCK_EnableClock(kCLOCK_Iocon); + + /* Enables the clock for the GPIO0 module */ + CLOCK_EnableClock(kCLOCK_Gpio0); + + /* Enables the clock for the GPIO1 module */ + CLOCK_EnableClock(kCLOCK_Gpio1); + + gpio_pin_config_t S1_config = { + .pinDirection = kGPIO_DigitalInput, + .outputLogic = 0U + }; + /* Initialize GPIO functionality on pin PIO0_5 (pin 88) */ + GPIO_PinInit(BOARD_INITBUTTONSPINS_S1_GPIO, BOARD_INITBUTTONSPINS_S1_PORT, BOARD_INITBUTTONSPINS_S1_PIN, &S1_config); + + gpio_pin_config_t S3_config = { + .pinDirection = kGPIO_DigitalInput, + .outputLogic = 0U + }; + /* Initialize GPIO functionality on pin PIO1_9 (pin 10) */ + GPIO_PinInit(BOARD_INITBUTTONSPINS_S3_GPIO, BOARD_INITBUTTONSPINS_S3_PORT, BOARD_INITBUTTONSPINS_S3_PIN, &S3_config); + + gpio_pin_config_t S2_config = { + .pinDirection = kGPIO_DigitalInput, + .outputLogic = 0U + }; + /* Initialize GPIO functionality on pin PIO1_18 (pin 64) */ + GPIO_PinInit(BOARD_INITBUTTONSPINS_S2_GPIO, BOARD_INITBUTTONSPINS_S2_PORT, BOARD_INITBUTTONSPINS_S2_PIN, &S2_config); + + const uint32_t S1 = (/* Pin is configured as PIO0_5 */ + IOCON_PIO_FUNC0 | + /* Selects pull-up function */ + IOCON_PIO_MODE_PULLUP | + /* Standard mode, output slew rate control is enabled */ + IOCON_PIO_SLEW_STANDARD | + /* Input function is not inverted */ + IOCON_PIO_INV_DI | + /* Enables digital function */ + IOCON_PIO_DIGITAL_EN | + /* Open drain is disabled */ + IOCON_PIO_OPENDRAIN_DI); + /* PORT0 PIN5 (coords: 88) is configured as PIO0_5 */ + IOCON_PinMuxSet(IOCON, BOARD_INITBUTTONSPINS_S1_PORT, BOARD_INITBUTTONSPINS_S1_PIN, S1); + + const uint32_t S2 = (/* Pin is configured as PIO1_18 */ + IOCON_PIO_FUNC0 | + /* Selects pull-up function */ + IOCON_PIO_MODE_PULLUP | + /* Standard mode, output slew rate control is enabled */ + IOCON_PIO_SLEW_STANDARD | + /* Input function is not inverted */ + IOCON_PIO_INV_DI | + /* Enables digital function */ + IOCON_PIO_DIGITAL_EN | + /* Open drain is disabled */ + IOCON_PIO_OPENDRAIN_DI); + /* PORT1 PIN18 (coords: 64) is configured as PIO1_18 */ + IOCON_PinMuxSet(IOCON, BOARD_INITBUTTONSPINS_S2_PORT, BOARD_INITBUTTONSPINS_S2_PIN, S2); + + if (Chip_GetVersion()==1) + { + const uint32_t S3 = (/* Pin is configured as PIO1_9 */ + IOCON_PIO_FUNC0 | + /* Selects pull-up function */ + IOCON_PIO_MODE_PULLUP | + /* Standard mode, output slew rate control is enabled */ + IOCON_PIO_SLEW_STANDARD | + /* Input function is not inverted */ + IOCON_PIO_INV_DI | + /* Enables digital function */ + IOCON_PIO_DIGITAL_EN | + /* Open drain is disabled */ + IOCON_PIO_OPENDRAIN_DI | + /* Analog switch is closed (enabled) */ + IOCON_PIO_ASW_EN); + /* PORT1 PIN9 (coords: 10) is configured as PIO1_9 */ + IOCON_PinMuxSet(IOCON, BOARD_INITBUTTONSPINS_S3_PORT, BOARD_INITBUTTONSPINS_S3_PIN, S3); + } + else + { + const uint32_t S3 = (/* Pin is configured as PIO1_9 */ + IOCON_PIO_FUNC0 | + /* Selects pull-up function */ + IOCON_PIO_MODE_PULLUP | + /* Standard mode, output slew rate control is enabled */ + IOCON_PIO_SLEW_STANDARD | + /* Input function is not inverted */ + IOCON_PIO_INV_DI | + /* Enables digital function */ + IOCON_PIO_DIGITAL_EN | + /* Open drain is disabled */ + IOCON_PIO_OPENDRAIN_DI | + /* Analog switch is closed (enabled), only for A0 version */ + IOCON_PIO_ASW_DIS_EN); + /* PORT1 PIN9 (coords: 10) is configured as PIO1_9 */ + IOCON_PinMuxSet(IOCON, BOARD_INITBUTTONSPINS_S3_PORT, BOARD_INITBUTTONSPINS_S3_PIN, S3); + } +} + +/* clang-format off */ +/* + * TEXT BELOW IS USED AS SETTING FOR TOOLS ************************************* +BOARD_InitPins_Core0: +- options: {callFromInitBoot: 'true', coreID: cm33_core0, enableClock: 'true'} +- pin_list: [] + * BE CAREFUL MODIFYING THIS COMMENT - IT IS YAML SETTINGS FOR TOOLS *********** + */ +/* clang-format on */ + +/* FUNCTION ************************************************************************************************************ + * + * Function Name : BOARD_InitPins_Core0 + * Description : Configures pin routing and optionally pin electrical features. + * + * END ****************************************************************************************************************/ +/* Function assigned for the Cortex-M33 (Core #0) */ +void BOARD_InitPins_Core0(void) +{ +} + +/* clang-format off */ +/* + * TEXT BELOW IS USED AS SETTING FOR TOOLS ************************************* +BOARD_InitI2SPins: +- options: {callFromInitBoot: 'false', coreID: cm33_core0, enableClock: 'true'} +- pin_list: + - {pin_num: '4', peripheral: FLEXCOMM4, signal: TXD_SCL_MISO_WS, pin_signal: PIO1_20/FC7_RTS_SCL_SSEL1/CT_INP14/FC4_TXD_SCL_MISO_WS/PLU_OUT2, mode: pullUp, slew_rate: standard, + invert: disabled, open_drain: disabled} + - {pin_num: '30', peripheral: FLEXCOMM4, signal: RXD_SDA_MOSI_DATA, pin_signal: PIO1_21/FC7_CTS_SDA_SSEL0/CTIMER3_MAT2/FC4_RXD_SDA_MOSI_DATA/PLU_OUT3, mode: pullUp, + slew_rate: standard, invert: disabled, open_drain: disabled} + - {pin_num: '91', peripheral: SYSCON, signal: MCLK, pin_signal: PIO1_31/MCLK/SD1_CLK/CTIMER0_MAT2/SCT0_OUT6/PLU_IN0, mode: inactive, slew_rate: standard, invert: disabled, + open_drain: disabled} + - {pin_num: '76', peripheral: FLEXCOMM7, signal: SCK, pin_signal: PIO0_21/FC3_RTS_SCL_SSEL1/UTICK_CAP3/CTIMER3_MAT3/SCT_GPI3/FC7_SCK/PLU_CLKIN/SECURE_GPIO0_21, + mode: pullUp, slew_rate: standard, invert: disabled, open_drain: disabled} + - {pin_num: '74', peripheral: FLEXCOMM7, signal: RXD_SDA_MOSI_DATA, pin_signal: PIO0_20/FC3_CTS_SDA_SSEL0/CTIMER1_MAT1/CT_INP15/SCT_GPI2/FC7_RXD_SDA_MOSI_DATA/HS_SPI_SSEL0/PLU_IN5/SECURE_GPIO0_20/FC4_TXD_SCL_MISO_WS, + mode: pullUp, slew_rate: standard, invert: disabled, open_drain: disabled} + - {pin_num: '90', peripheral: FLEXCOMM7, signal: TXD_SCL_MISO_WS, pin_signal: PIO0_19/FC4_RTS_SCL_SSEL1/UTICK_CAP0/CTIMER0_MAT2/SCT0_OUT2/FC7_TXD_SCL_MISO_WS/PLU_IN4/SECURE_GPIO0_19, + mode: pullUp, slew_rate: standard, invert: disabled, open_drain: disabled} + - {pin_num: '21', peripheral: FLEXCOMM6, signal: SCK, pin_signal: PIO0_10/FC6_SCK/CT_INP10/CTIMER2_MAT0/FC1_TXD_SCL_MISO_WS/SCT0_OUT2/SWO/SECURE_GPIO0_10/ADC0_1, + identifier: FC6_I2S_CLK, mode: pullUp, slew_rate: standard, invert: disabled, open_drain: disabled, asw: enabled} + - {pin_num: '2', peripheral: FLEXCOMM6, signal: RXD_SDA_MOSI_DATA, pin_signal: PIO1_13/FC6_RXD_SDA_MOSI_DATA/CT_INP6/USB0_OVERCURRENTN/USB0_FRAME/SD0_CARD_DET_N, + mode: pullUp, slew_rate: standard, invert: disabled, open_drain: disabled} + - {pin_num: '87', peripheral: FLEXCOMM6, signal: TXD_SCL_MISO_WS, pin_signal: PIO1_16/FC6_TXD_SCL_MISO_WS/CTIMER1_MAT3/SD0_CMD, mode: pullUp, slew_rate: standard, + invert: disabled, open_drain: disabled} + * BE CAREFUL MODIFYING THIS COMMENT - IT IS YAML SETTINGS FOR TOOLS *********** + */ +/* clang-format on */ + +/* FUNCTION ************************************************************************************************************ + * + * Function Name : BOARD_InitI2SPins + * Description : Configures pin routing and optionally pin electrical features. + * + * END ****************************************************************************************************************/ +/* Function assigned for the Cortex-M33 (Core #0) */ +void BOARD_InitI2SPins(void) +{ + /* Enables the clock for the I/O controller.: Enable Clock. */ + CLOCK_EnableClock(kCLOCK_Iocon); + + const uint32_t FC6_I2S_CLK = (/* Pin is configured as FC6_SCK */ + IOCON_PIO_FUNC1 | + /* Selects pull-up function */ + IOCON_PIO_MODE_PULLUP | + /* Standard mode, output slew rate control is enabled */ + IOCON_PIO_SLEW_STANDARD | + /* Input function is not inverted */ + IOCON_PIO_INV_DI | + /* Enables digital function */ + IOCON_PIO_DIGITAL_EN | + /* Open drain is disabled */ + IOCON_PIO_OPENDRAIN_DI | + /* Analog switch is closed (enabled) */ + IOCON_PIO_ASW_EN); + /* PORT0 PIN10 (coords: 21) is configured as FC6_SCK */ + IOCON_PinMuxSet(IOCON, BOARD_INITI2SPINS_FC6_I2S_CLK_PORT, BOARD_INITI2SPINS_FC6_I2S_CLK_PIN, FC6_I2S_CLK); + + const uint32_t FC7_I2S_WS = (/* Pin is configured as FC7_TXD_SCL_MISO_WS */ + IOCON_PIO_FUNC7 | + /* Selects pull-up function */ + IOCON_PIO_MODE_PULLUP | + /* Standard mode, output slew rate control is enabled */ + IOCON_PIO_SLEW_STANDARD | + /* Input function is not inverted */ + IOCON_PIO_INV_DI | + /* Enables digital function */ + IOCON_PIO_DIGITAL_EN | + /* Open drain is disabled */ + IOCON_PIO_OPENDRAIN_DI); + /* PORT0 PIN19 (coords: 90) is configured as FC7_TXD_SCL_MISO_WS */ + IOCON_PinMuxSet(IOCON, BOARD_INITI2SPINS_FC7_I2S_WS_PORT, BOARD_INITI2SPINS_FC7_I2S_WS_PIN, FC7_I2S_WS); + + const uint32_t FC7_I2S_TX = (/* Pin is configured as FC7_RXD_SDA_MOSI_DATA */ + IOCON_PIO_FUNC7 | + /* Selects pull-up function */ + IOCON_PIO_MODE_PULLUP | + /* Standard mode, output slew rate control is enabled */ + IOCON_PIO_SLEW_STANDARD | + /* Input function is not inverted */ + IOCON_PIO_INV_DI | + /* Enables digital function */ + IOCON_PIO_DIGITAL_EN | + /* Open drain is disabled */ + IOCON_PIO_OPENDRAIN_DI); + /* PORT0 PIN20 (coords: 74) is configured as FC7_RXD_SDA_MOSI_DATA */ + IOCON_PinMuxSet(IOCON, BOARD_INITI2SPINS_FC7_I2S_TX_PORT, BOARD_INITI2SPINS_FC7_I2S_TX_PIN, FC7_I2S_TX); + + const uint32_t FC7_I2S_SCK = (/* Pin is configured as FC7_SCK */ + IOCON_PIO_FUNC7 | + /* Selects pull-up function */ + IOCON_PIO_MODE_PULLUP | + /* Standard mode, output slew rate control is enabled */ + IOCON_PIO_SLEW_STANDARD | + /* Input function is not inverted */ + IOCON_PIO_INV_DI | + /* Enables digital function */ + IOCON_PIO_DIGITAL_EN | + /* Open drain is disabled */ + IOCON_PIO_OPENDRAIN_DI); + /* PORT0 PIN21 (coords: 76) is configured as FC7_SCK */ + IOCON_PinMuxSet(IOCON, BOARD_INITI2SPINS_FC7_I2S_SCK_PORT, BOARD_INITI2SPINS_FC7_I2S_SCK_PIN, FC7_I2S_SCK); + + const uint32_t FC6_I2S_RX = (/* Pin is configured as FC6_RXD_SDA_MOSI_DATA */ + IOCON_PIO_FUNC2 | + /* Selects pull-up function */ + IOCON_PIO_MODE_PULLUP | + /* Standard mode, output slew rate control is enabled */ + IOCON_PIO_SLEW_STANDARD | + /* Input function is not inverted */ + IOCON_PIO_INV_DI | + /* Enables digital function */ + IOCON_PIO_DIGITAL_EN | + /* Open drain is disabled */ + IOCON_PIO_OPENDRAIN_DI); + /* PORT1 PIN13 (coords: 2) is configured as FC6_RXD_SDA_MOSI_DATA */ + IOCON_PinMuxSet(IOCON, BOARD_INITI2SPINS_FC6_I2S_RX_PORT, BOARD_INITI2SPINS_FC6_I2S_RX_PIN, FC6_I2S_RX); + + const uint32_t FC6_I2S_WS = (/* Pin is configured as FC6_TXD_SCL_MISO_WS */ + IOCON_PIO_FUNC2 | + /* Selects pull-up function */ + IOCON_PIO_MODE_PULLUP | + /* Standard mode, output slew rate control is enabled */ + IOCON_PIO_SLEW_STANDARD | + /* Input function is not inverted */ + IOCON_PIO_INV_DI | + /* Enables digital function */ + IOCON_PIO_DIGITAL_EN | + /* Open drain is disabled */ + IOCON_PIO_OPENDRAIN_DI); + /* PORT1 PIN16 (coords: 87) is configured as FC6_TXD_SCL_MISO_WS */ + IOCON_PinMuxSet(IOCON, BOARD_INITI2SPINS_FC6_I2S_WS_PORT, BOARD_INITI2SPINS_FC6_I2S_WS_PIN, FC6_I2S_WS); + + const uint32_t FC4_I2C_SCL = (/* Pin is configured as FC4_TXD_SCL_MISO_WS */ + IOCON_PIO_FUNC5 | + /* Selects pull-up function */ + IOCON_PIO_MODE_PULLUP | + /* Standard mode, output slew rate control is enabled */ + IOCON_PIO_SLEW_STANDARD | + /* Input function is not inverted */ + IOCON_PIO_INV_DI | + /* Enables digital function */ + IOCON_PIO_DIGITAL_EN | + /* Open drain is disabled */ + IOCON_PIO_OPENDRAIN_DI); + /* PORT1 PIN20 (coords: 4) is configured as FC4_TXD_SCL_MISO_WS */ + IOCON_PinMuxSet(IOCON, BOARD_INITI2SPINS_FC4_I2C_SCL_PORT, BOARD_INITI2SPINS_FC4_I2C_SCL_PIN, FC4_I2C_SCL); + + const uint32_t FC4_I2C_SDA = (/* Pin is configured as FC4_RXD_SDA_MOSI_DATA */ + IOCON_PIO_FUNC5 | + /* Selects pull-up function */ + IOCON_PIO_MODE_PULLUP | + /* Standard mode, output slew rate control is enabled */ + IOCON_PIO_SLEW_STANDARD | + /* Input function is not inverted */ + IOCON_PIO_INV_DI | + /* Enables digital function */ + IOCON_PIO_DIGITAL_EN | + /* Open drain is disabled */ + IOCON_PIO_OPENDRAIN_DI); + /* PORT1 PIN21 (coords: 30) is configured as FC4_RXD_SDA_MOSI_DATA */ + IOCON_PinMuxSet(IOCON, BOARD_INITI2SPINS_FC4_I2C_SDA_PORT, BOARD_INITI2SPINS_FC4_I2C_SDA_PIN, FC4_I2C_SDA); + + const uint32_t MCLK = (/* Pin is configured as MCLK */ + IOCON_PIO_FUNC1 | + /* No addition pin function */ + IOCON_PIO_MODE_INACT | + /* Standard mode, output slew rate control is enabled */ + IOCON_PIO_SLEW_STANDARD | + /* Input function is not inverted */ + IOCON_PIO_INV_DI | + /* Enables digital function */ + IOCON_PIO_DIGITAL_EN | + /* Open drain is disabled */ + IOCON_PIO_OPENDRAIN_DI); + /* PORT1 PIN31 (coords: 91) is configured as MCLK */ + IOCON_PinMuxSet(IOCON, BOARD_INITI2SPINS_MCLK_PORT, BOARD_INITI2SPINS_MCLK_PIN, MCLK); +} + +/* clang-format off */ +/* + * TEXT BELOW IS USED AS SETTING FOR TOOLS ************************************* +BOARD_InitACCELPins: +- options: {callFromInitBoot: 'false', coreID: cm33_core0, enableClock: 'true'} +- pin_list: + - {pin_num: '30', peripheral: FLEXCOMM4, signal: RXD_SDA_MOSI_DATA, pin_signal: PIO1_21/FC7_CTS_SDA_SSEL0/CTIMER3_MAT2/FC4_RXD_SDA_MOSI_DATA/PLU_OUT3, mode: pullUp, + slew_rate: standard, invert: disabled, open_drain: disabled} + - {pin_num: '4', peripheral: FLEXCOMM4, signal: TXD_SCL_MISO_WS, pin_signal: PIO1_20/FC7_RTS_SCL_SSEL1/CT_INP14/FC4_TXD_SCL_MISO_WS/PLU_OUT2, mode: pullUp, slew_rate: standard, + invert: disabled, open_drain: disabled} + - {pin_num: '58', peripheral: GPIO, signal: 'PIO1, 19', pin_signal: PIO1_19/SCT0_OUT7/CTIMER3_MAT1/SCT_GPI7/FC4_SCK/PLU_OUT1/ACMPVREF, direction: INPUT, mode: inactive, + slew_rate: standard, invert: disabled, open_drain: disabled, asw: disabled} + * BE CAREFUL MODIFYING THIS COMMENT - IT IS YAML SETTINGS FOR TOOLS *********** + */ +/* clang-format on */ + +/* FUNCTION ************************************************************************************************************ + * + * Function Name : BOARD_InitACCELPins + * Description : Configures pin routing and optionally pin electrical features. + * + * END ****************************************************************************************************************/ +/* Function assigned for the Cortex-M33 (Core #0) */ +void BOARD_InitACCELPins(void) +{ + /* Enables the clock for the I/O controller.: Enable Clock. */ + CLOCK_EnableClock(kCLOCK_Iocon); + + /* Enables the clock for the GPIO1 module */ + CLOCK_EnableClock(kCLOCK_Gpio1); + + gpio_pin_config_t ACCL_INTR_config = { + .pinDirection = kGPIO_DigitalInput, + .outputLogic = 0U + }; + /* Initialize GPIO functionality on pin PIO1_19 (pin 58) */ + GPIO_PinInit(BOARD_INITACCELPINS_ACCL_INTR_GPIO, BOARD_INITACCELPINS_ACCL_INTR_PORT, BOARD_INITACCELPINS_ACCL_INTR_PIN, &ACCL_INTR_config); + + const uint32_t ACCL_INTR = (/* Pin is configured as PIO1_19 */ + IOCON_PIO_FUNC0 | + /* No addition pin function */ + IOCON_PIO_MODE_INACT | + /* Standard mode, output slew rate control is enabled */ + IOCON_PIO_SLEW_STANDARD | + /* Input function is not inverted */ + IOCON_PIO_INV_DI | + /* Enables digital function */ + IOCON_PIO_DIGITAL_EN | + /* Open drain is disabled */ + IOCON_PIO_OPENDRAIN_DI | + /* Analog switch is open (disabled) */ + IOCON_PIO_ASW_DI); + /* PORT1 PIN19 (coords: 58) is configured as PIO1_19 */ + IOCON_PinMuxSet(IOCON, BOARD_INITACCELPINS_ACCL_INTR_PORT, BOARD_INITACCELPINS_ACCL_INTR_PIN, ACCL_INTR); + + const uint32_t FC4_I2C_SCL = (/* Pin is configured as FC4_TXD_SCL_MISO_WS */ + IOCON_PIO_FUNC5 | + /* Selects pull-up function */ + IOCON_PIO_MODE_PULLUP | + /* Standard mode, output slew rate control is enabled */ + IOCON_PIO_SLEW_STANDARD | + /* Input function is not inverted */ + IOCON_PIO_INV_DI | + /* Enables digital function */ + IOCON_PIO_DIGITAL_EN | + /* Open drain is disabled */ + IOCON_PIO_OPENDRAIN_DI); + /* PORT1 PIN20 (coords: 4) is configured as FC4_TXD_SCL_MISO_WS */ + IOCON_PinMuxSet(IOCON, BOARD_INITACCELPINS_FC4_I2C_SCL_PORT, BOARD_INITACCELPINS_FC4_I2C_SCL_PIN, FC4_I2C_SCL); + + const uint32_t FC4_I2C_SDA = (/* Pin is configured as FC4_RXD_SDA_MOSI_DATA */ + IOCON_PIO_FUNC5 | + /* Selects pull-up function */ + IOCON_PIO_MODE_PULLUP | + /* Standard mode, output slew rate control is enabled */ + IOCON_PIO_SLEW_STANDARD | + /* Input function is not inverted */ + IOCON_PIO_INV_DI | + /* Enables digital function */ + IOCON_PIO_DIGITAL_EN | + /* Open drain is disabled */ + IOCON_PIO_OPENDRAIN_DI); + /* PORT1 PIN21 (coords: 30) is configured as FC4_RXD_SDA_MOSI_DATA */ + IOCON_PinMuxSet(IOCON, BOARD_INITACCELPINS_FC4_I2C_SDA_PORT, BOARD_INITACCELPINS_FC4_I2C_SDA_PIN, FC4_I2C_SDA); +} +/*********************************************************************************************************************** + * EOF + **********************************************************************************************************************/ diff --git a/board/pin_mux.h b/board/pin_mux.h new file mode 100644 index 0000000..1678fa9 --- /dev/null +++ b/board/pin_mux.h @@ -0,0 +1,449 @@ +/*********************************************************************************************************************** + * 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 IOCON_PIO_DIGITAL_EN 0x0100u /*!<@brief Enables digital function */ +#define IOCON_PIO_FUNC1 0x01u /*!<@brief Selects pin function 1 */ +#define IOCON_PIO_INV_DI 0x00u /*!<@brief Input function is not inverted */ +#define IOCON_PIO_MODE_INACT 0x00u /*!<@brief No addition pin function */ +#define IOCON_PIO_OPENDRAIN_DI 0x00u /*!<@brief Open drain is disabled */ +#define IOCON_PIO_SLEW_STANDARD 0x00u /*!<@brief Standard mode, output slew rate control is enabled */ + +/*! @name PIO0_29 (number 92), P8[2]/U6[13]/FC0_USART_RXD + @{ */ +/*! + * @brief PORT peripheral base pointer */ +#define BOARD_INITDEBUG_UARTPINS_DEBUG_UART_RX_PORT 0U +/*! + * @brief PORT pin number */ +#define BOARD_INITDEBUG_UARTPINS_DEBUG_UART_RX_PIN 29U +/*! + * @brief PORT pin mask */ +#define BOARD_INITDEBUG_UARTPINS_DEBUG_UART_RX_PIN_MASK (1U << 29U) +/* @} */ + +/*! @name PIO0_30 (number 94), P8[3]/U6[12]/FC0_USART_TXD + @{ */ +/*! + * @brief PORT peripheral base pointer */ +#define BOARD_INITDEBUG_UARTPINS_DEBUG_UART_TX_PORT 0U +/*! + * @brief PORT pin number */ +#define BOARD_INITDEBUG_UARTPINS_DEBUG_UART_TX_PIN 30U +/*! + * @brief PORT pin mask */ +#define BOARD_INITDEBUG_UARTPINS_DEBUG_UART_TX_PIN_MASK (1U << 30U) +/* @} */ + +/*! + * @brief Configures pin routing and optionally pin electrical features. + * + */ +void BOARD_InitDEBUG_UARTPins(void); /* Function assigned for the Cortex-M33 (Core #0) */ + +#define IOCON_PIO_ASW_DI 0x00u /*!<@brief Analog switch is open (disabled) */ +#define IOCON_PIO_ASW_DIS_EN 0x00u /*!<@brief Analog switch is closed (enabled), only for A0 version */ +#define IOCON_PIO_ASW_EN 0x0400u /*!<@brief Analog switch is closed (enabled) */ +#define IOCON_PIO_DIGITAL_EN 0x0100u /*!<@brief Enables digital function */ +#define IOCON_PIO_FUNC6 0x06u /*!<@brief Selects pin function 6 */ +#define IOCON_PIO_INV_DI 0x00u /*!<@brief Input function is not inverted */ +#define IOCON_PIO_MODE_INACT 0x00u /*!<@brief No addition pin function */ +#define IOCON_PIO_MODE_PULLDOWN 0x10u /*!<@brief Selects pull-down function */ +#define IOCON_PIO_MODE_PULLUP 0x20u /*!<@brief Selects pull-up function */ +#define IOCON_PIO_OPENDRAIN_DI 0x00u /*!<@brief Open drain is disabled */ +#define IOCON_PIO_SLEW_STANDARD 0x00u /*!<@brief Standard mode, output slew rate control is enabled */ + +/*! @name PIO0_11 (number 13), U14[4]/SWDCLK_TRGT + @{ */ +/*! + * @brief PORT peripheral base pointer */ +#define BOARD_INITSWD_DEBUGPINS_DEBUG_SWD_SWDCLK_PORT 0U +/*! + * @brief PORT pin number */ +#define BOARD_INITSWD_DEBUGPINS_DEBUG_SWD_SWDCLK_PIN 11U +/*! + * @brief PORT pin mask */ +#define BOARD_INITSWD_DEBUGPINS_DEBUG_SWD_SWDCLK_PIN_MASK (1U << 11U) +/* @} */ + +/*! @name PIO0_12 (number 12), U15[4]/D7/P7[2]/IF_SWDIO + @{ */ +/*! + * @brief PORT peripheral base pointer */ +#define BOARD_INITSWD_DEBUGPINS_DEBUG_SWD_SWDIO_PORT 0U +/*! + * @brief PORT pin number */ +#define BOARD_INITSWD_DEBUGPINS_DEBUG_SWD_SWDIO_PIN 12U +/*! + * @brief PORT pin mask */ +#define BOARD_INITSWD_DEBUGPINS_DEBUG_SWD_SWDIO_PIN_MASK (1U << 12U) +/* @} */ + +/*! @name PIO0_10 (number 21), U14[12]/SWO_TRGT + @{ */ +/*! + * @brief PORT peripheral base pointer */ +#define BOARD_INITSWD_DEBUGPINS_DEBUG_SWD_SWO_PORT 0U +/*! + * @brief PORT pin number */ +#define BOARD_INITSWD_DEBUGPINS_DEBUG_SWD_SWO_PIN 10U +/*! + * @brief PORT pin mask */ +#define BOARD_INITSWD_DEBUGPINS_DEBUG_SWD_SWO_PIN_MASK (1U << 10U) +/* @} */ + +/*! + * @brief Configures pin routing and optionally pin electrical features. + * + */ +void BOARD_InitSWD_DEBUGPins(void); /* Function assigned for the Cortex-M33 (Core #0) */ + +/*! + * @brief Enables digital function */ +#define IOCON_PIO_DIGITAL_EN 0x0100u +/*! + * @brief Selects pin function 7 */ +#define IOCON_PIO_FUNC7 0x07u +/*! + * @brief Input function is not inverted */ +#define IOCON_PIO_INV_DI 0x00u +/*! + * @brief No addition pin function */ +#define IOCON_PIO_MODE_INACT 0x00u +/*! + * @brief Open drain is disabled */ +#define IOCON_PIO_OPENDRAIN_DI 0x00u +/*! + * @brief Standard mode, output slew rate control is enabled */ +#define IOCON_PIO_SLEW_STANDARD 0x00u +/*! + * @brief Select Digital mode.: Enable Digital mode. Digital input is enabled. */ +#define PIO0_28_DIGIMODE_DIGITAL 0x01u +/*! + * @brief Selects pin function.: Alternative connection 7. */ +#define PIO0_28_FUNC_ALT7 0x07u +/*! + * @brief Selects function mode (on-chip pull-up/pull-down resistor control).: Pull-up. Pull-up resistor enabled. */ +#define PIO0_28_MODE_PULL_UP 0x02u +/*! + * @brief Select Digital mode.: Enable Digital mode. Digital input is enabled. */ +#define PIO1_12_DIGIMODE_DIGITAL 0x01u +/*! + * @brief Selects pin function.: Alternative connection 4. */ +#define PIO1_12_FUNC_ALT4 0x04u +/*! + * @brief Selects function mode (on-chip pull-up/pull-down resistor control).: Pull-up. Pull-up resistor enabled. */ +#define PIO1_12_MODE_PULL_UP 0x02u +/*! + * @brief Select Digital mode.: Enable Digital mode. Digital input is enabled. */ +#define PIO1_29_DIGIMODE_DIGITAL 0x01u +/*! + * @brief Selects pin function.: Alternative connection 4. */ +#define PIO1_29_FUNC_ALT4 0x04u +/*! + * @brief Selects function mode (on-chip pull-up/pull-down resistor control).: Pull-up. Pull-up resistor enabled. */ +#define PIO1_29_MODE_PULL_UP 0x02u +/*! + * @brief Select Digital mode.: Enable Digital mode. Digital input is enabled. */ +#define PIO1_30_DIGIMODE_DIGITAL 0x01u +/*! + * @brief Selects pin function.: Alternative connection 4. */ +#define PIO1_30_FUNC_ALT4 0x04u +/*! + * @brief Selects function mode (on-chip pull-up/pull-down resistor control).: Pull-up. Pull-up resistor enabled. */ +#define PIO1_30_MODE_PULL_UP 0x02u + +/*! @name USB0_DP (number 97), P10[3]/D10[3]/USB0_FS_P + @{ */ +/* @} */ + +/*! @name USB0_DM (number 98), P10[2]/D10[2]/USB0_FS_N + @{ */ +/* @} */ + +/*! @name PIO0_22 (number 78), P10[1]/USB0_VBUS + @{ */ +#define BOARD_INITUSBPINS_USB0_VBUS_PORT 0U /*!<@brief PORT peripheral base pointer */ +#define BOARD_INITUSBPINS_USB0_VBUS_PIN 22U /*!<@brief PORT pin number */ +#define BOARD_INITUSBPINS_USB0_VBUS_PIN_MASK (1U << 22U) /*!<@brief PORT pin mask */ + /* @} */ + +/*! @name USB1_DM (number 35), P9[2]/D9[2]/USB1_HS_N + @{ */ +/* @} */ + +/*! @name USB1_DP (number 34), P9[3]/D9[3]/USB1_HS_P + @{ */ +/* @} */ + +/*! @name USB1_VBUS (number 36), P9[1]/USB1_VBUS + @{ */ +/* @} */ + +/*! + * @brief Configures pin routing and optionally pin electrical features. + * + */ +void BOARD_InitUSBPins(void); /* Function assigned for the Cortex-M33 (Core #0) */ + +#define IOCON_PIO_DIGITAL_EN 0x0100u /*!<@brief Enables digital function */ +#define IOCON_PIO_FUNC0 0x00u /*!<@brief Selects pin function 0 */ +#define IOCON_PIO_INV_DI 0x00u /*!<@brief Input function is not inverted */ +#define IOCON_PIO_MODE_PULLUP 0x20u /*!<@brief Selects pull-up function */ +#define IOCON_PIO_OPENDRAIN_DI 0x00u /*!<@brief Open drain is disabled */ +#define IOCON_PIO_SLEW_STANDARD 0x00u /*!<@brief Standard mode, output slew rate control is enabled */ + +/*! @name PIO1_4 (number 1), R78/P18[5]/LEDR/PWM_ARD + @{ */ + +/* Symbols to be used with GPIO driver */ +#define BOARD_INITLEDSPINS_LED_BLUE_GPIO GPIO /*!<@brief GPIO peripheral base pointer */ +#define BOARD_INITLEDSPINS_LED_BLUE_GPIO_PIN_MASK (1U << 4U) /*!<@brief GPIO pin mask */ +#define BOARD_INITLEDSPINS_LED_BLUE_PORT 1U /*!<@brief PORT peripheral base pointer */ +#define BOARD_INITLEDSPINS_LED_BLUE_PIN 4U /*!<@brief PORT pin number */ +#define BOARD_INITLEDSPINS_LED_BLUE_PIN_MASK (1U << 4U) /*!<@brief PORT pin mask */ + /* @} */ + +/*! @name PIO1_6 (number 5), R80/P18[9]/LEDB/PWM_ARD + @{ */ + +/* Symbols to be used with GPIO driver */ +#define BOARD_INITLEDSPINS_LED_RED_GPIO GPIO /*!<@brief GPIO peripheral base pointer */ +#define BOARD_INITLEDSPINS_LED_RED_GPIO_PIN_MASK (1U << 6U) /*!<@brief GPIO pin mask */ +#define BOARD_INITLEDSPINS_LED_RED_PORT 1U /*!<@brief PORT peripheral base pointer */ +#define BOARD_INITLEDSPINS_LED_RED_PIN 6U /*!<@brief PORT pin number */ +#define BOARD_INITLEDSPINS_LED_RED_PIN_MASK (1U << 6U) /*!<@brief PORT pin mask */ + /* @} */ + +/*! @name PIO1_7 (number 9), R79/P18[7]/LEDG/PWM_ARD + @{ */ + +/* Symbols to be used with GPIO driver */ +#define BOARD_INITLEDSPINS_LED_GREEN_GPIO GPIO /*!<@brief GPIO peripheral base pointer */ +#define BOARD_INITLEDSPINS_LED_GREEN_GPIO_PIN_MASK (1U << 7U) /*!<@brief GPIO pin mask */ +#define BOARD_INITLEDSPINS_LED_GREEN_PORT 1U /*!<@brief PORT peripheral base pointer */ +#define BOARD_INITLEDSPINS_LED_GREEN_PIN 7U /*!<@brief PORT pin number */ +#define BOARD_INITLEDSPINS_LED_GREEN_PIN_MASK (1U << 7U) /*!<@brief PORT pin mask */ + /* @} */ + +/*! + * @brief Configures pin routing and optionally pin electrical features. + * + */ +void BOARD_InitLEDsPins(void); /* Function assigned for the Cortex-M33 (Core #0) */ + +#define IOCON_PIO_ASW_DIS_EN 0x00u /*!<@brief Analog switch is closed (enabled), only for A0 version */ +#define IOCON_PIO_ASW_EN 0x0400u /*!<@brief Analog switch is closed (enabled) */ +#define IOCON_PIO_DIGITAL_EN 0x0100u /*!<@brief Enables digital function */ +#define IOCON_PIO_FUNC0 0x00u /*!<@brief Selects pin function 0 */ +#define IOCON_PIO_INV_DI 0x00u /*!<@brief Input function is not inverted */ +#define IOCON_PIO_MODE_PULLUP 0x20u /*!<@brief Selects pull-up function */ +#define IOCON_PIO_OPENDRAIN_DI 0x00u /*!<@brief Open drain is disabled */ +#define IOCON_PIO_SLEW_STANDARD 0x00u /*!<@brief Standard mode, output slew rate control is enabled */ + +/*! @name PIO0_5 (number 88), S1/J10[1]/U3[12]/P17[8]/P7[7]/U11[4]/P0_5-ISP1 + @{ */ + +/* Symbols to be used with GPIO driver */ +#define BOARD_INITBUTTONSPINS_S1_GPIO GPIO /*!<@brief GPIO peripheral base pointer */ +#define BOARD_INITBUTTONSPINS_S1_GPIO_PIN_MASK (1U << 5U) /*!<@brief GPIO pin mask */ +#define BOARD_INITBUTTONSPINS_S1_PORT 0U /*!<@brief PORT peripheral base pointer */ +#define BOARD_INITBUTTONSPINS_S1_PIN 5U /*!<@brief PORT pin number */ +#define BOARD_INITBUTTONSPINS_S1_PIN_MASK (1U << 5U) /*!<@brief PORT pin mask */ + /* @} */ + +/*! @name PIO1_18 (number 64), S2/P18[16]/P24[2]/WAKE/GPIO + @{ */ + +/* Symbols to be used with GPIO driver */ +#define BOARD_INITBUTTONSPINS_S2_GPIO GPIO /*!<@brief GPIO peripheral base pointer */ +#define BOARD_INITBUTTONSPINS_S2_GPIO_PIN_MASK (1U << 18U) /*!<@brief GPIO pin mask */ +#define BOARD_INITBUTTONSPINS_S2_PORT 1U /*!<@brief PORT peripheral base pointer */ +#define BOARD_INITBUTTONSPINS_S2_PIN 18U /*!<@brief PORT pin number */ +#define BOARD_INITBUTTONSPINS_S2_PIN_MASK (1U << 18U) /*!<@brief PORT pin mask */ + /* @} */ + +/*! @name PIO1_9 (number 10), S3/P18[1]/PIO1_9_GPIO_ARD + @{ */ + +/* Symbols to be used with GPIO driver */ +#define BOARD_INITBUTTONSPINS_S3_GPIO GPIO /*!<@brief GPIO peripheral base pointer */ +#define BOARD_INITBUTTONSPINS_S3_GPIO_PIN_MASK (1U << 9U) /*!<@brief GPIO pin mask */ +#define BOARD_INITBUTTONSPINS_S3_PORT 1U /*!<@brief PORT peripheral base pointer */ +#define BOARD_INITBUTTONSPINS_S3_PIN 9U /*!<@brief PORT pin number */ +#define BOARD_INITBUTTONSPINS_S3_PIN_MASK (1U << 9U) /*!<@brief PORT pin mask */ + /* @} */ + +/*! @name RESETN (number 32), S4/P16[10]/P23[2]/U14[8]/RESETN + @{ */ +/* @} */ + +/*! + * @brief Configures pin routing and optionally pin electrical features. + * + */ +void BOARD_InitBUTTONsPins(void); /* Function assigned for the Cortex-M33 (Core #0) */ + +/*! + * @brief Configures pin routing and optionally pin electrical features. + * + */ +void BOARD_InitPins_Core0(void); /* Function assigned for the Cortex-M33 (Core #0) */ + +#define IOCON_PIO_ASW_EN 0x0400u /*!<@brief Analog switch is closed (enabled) */ +#define IOCON_PIO_DIGITAL_EN 0x0100u /*!<@brief Enables digital function */ +#define IOCON_PIO_FUNC1 0x01u /*!<@brief Selects pin function 1 */ +#define IOCON_PIO_FUNC2 0x02u /*!<@brief Selects pin function 2 */ +#define IOCON_PIO_FUNC5 0x05u /*!<@brief Selects pin function 5 */ +#define IOCON_PIO_FUNC7 0x07u /*!<@brief Selects pin function 7 */ +#define IOCON_PIO_INV_DI 0x00u /*!<@brief Input function is not inverted */ +#define IOCON_PIO_MODE_INACT 0x00u /*!<@brief No addition pin function */ +#define IOCON_PIO_MODE_PULLUP 0x20u /*!<@brief Selects pull-up function */ +#define IOCON_PIO_OPENDRAIN_DI 0x00u /*!<@brief Open drain is disabled */ +#define IOCON_PIO_SLEW_STANDARD 0x00u /*!<@brief Standard mode, output slew rate control is enabled */ + +/*! @name PIO1_20 (number 4), P17[1]/P24[5]/FC4_I2C_SCL_ARD + @{ */ +#define BOARD_INITI2SPINS_FC4_I2C_SCL_PORT 1U /*!<@brief PORT peripheral base pointer */ +#define BOARD_INITI2SPINS_FC4_I2C_SCL_PIN 20U /*!<@brief PORT pin number */ +#define BOARD_INITI2SPINS_FC4_I2C_SCL_PIN_MASK (1U << 20U) /*!<@brief PORT pin mask */ + /* @} */ + +/*! @name PIO1_21 (number 30), P17[3]/P24[6]/FC4_I2C_SDA_ARD + @{ */ +#define BOARD_INITI2SPINS_FC4_I2C_SDA_PORT 1U /*!<@brief PORT peripheral base pointer */ +#define BOARD_INITI2SPINS_FC4_I2C_SDA_PIN 21U /*!<@brief PORT pin number */ +#define BOARD_INITI2SPINS_FC4_I2C_SDA_PIN_MASK (1U << 21U) /*!<@brief PORT pin mask */ + /* @} */ + +/*! @name PIO1_31 (number 91), P19[7]/P19[8]/PLU_IN0/GPIO + @{ */ +#define BOARD_INITI2SPINS_MCLK_PORT 1U /*!<@brief PORT peripheral base pointer */ +#define BOARD_INITI2SPINS_MCLK_PIN 31U /*!<@brief PORT pin number */ +#define BOARD_INITI2SPINS_MCLK_PIN_MASK (1U << 31U) /*!<@brief PORT pin mask */ + /* @} */ + +/*! @name PIO0_21 (number 76), P17[14]/FC7_I2S_SCK + @{ */ +#define BOARD_INITI2SPINS_FC7_I2S_SCK_PORT 0U /*!<@brief PORT peripheral base pointer */ +#define BOARD_INITI2SPINS_FC7_I2S_SCK_PIN 21U /*!<@brief PORT pin number */ +#define BOARD_INITI2SPINS_FC7_I2S_SCK_PIN_MASK (1U << 21U) /*!<@brief PORT pin mask */ + /* @} */ + +/*! @name PIO0_20 (number 74), P17[10]/FC7_I2S_TX + @{ */ +#define BOARD_INITI2SPINS_FC7_I2S_TX_PORT 0U /*!<@brief PORT peripheral base pointer */ +#define BOARD_INITI2SPINS_FC7_I2S_TX_PIN 20U /*!<@brief PORT pin number */ +#define BOARD_INITI2SPINS_FC7_I2S_TX_PIN_MASK (1U << 20U) /*!<@brief PORT pin mask */ + /* @} */ + +/*! @name PIO0_19 (number 90), P17[12]/FC7_I2S_WS + @{ */ +#define BOARD_INITI2SPINS_FC7_I2S_WS_PORT 0U /*!<@brief PORT peripheral base pointer */ +#define BOARD_INITI2SPINS_FC7_I2S_WS_PIN 19U /*!<@brief PORT pin number */ +#define BOARD_INITI2SPINS_FC7_I2S_WS_PIN_MASK (1U << 19U) /*!<@brief PORT pin mask */ + /* @} */ + +/*! @name PIO0_10 (number 21), U14[12]/SWO_TRGT + @{ */ +#define BOARD_INITI2SPINS_FC6_I2S_CLK_PORT 0U /*!<@brief PORT peripheral base pointer */ +#define BOARD_INITI2SPINS_FC6_I2S_CLK_PIN 10U /*!<@brief PORT pin number */ +#define BOARD_INITI2SPINS_FC6_I2S_CLK_PIN_MASK (1U << 10U) /*!<@brief PORT pin mask */ + /* @} */ + +/*! @name PIO1_13 (number 2), P17[20]/FC6_I2S_RX + @{ */ +#define BOARD_INITI2SPINS_FC6_I2S_RX_PORT 1U /*!<@brief PORT peripheral base pointer */ +#define BOARD_INITI2SPINS_FC6_I2S_RX_PIN 13U /*!<@brief PORT pin number */ +#define BOARD_INITI2SPINS_FC6_I2S_RX_PIN_MASK (1U << 13U) /*!<@brief PORT pin mask */ + /* @} */ + +/*! @name PIO1_16 (number 87), P18[17]/SD1_PWR_EN + @{ */ +#define BOARD_INITI2SPINS_FC6_I2S_WS_PORT 1U /*!<@brief PORT peripheral base pointer */ +#define BOARD_INITI2SPINS_FC6_I2S_WS_PIN 16U /*!<@brief PORT pin number */ +#define BOARD_INITI2SPINS_FC6_I2S_WS_PIN_MASK (1U << 16U) /*!<@brief PORT pin mask */ + /* @} */ + +/*! + * @brief Configures pin routing and optionally pin electrical features. + * + */ +void BOARD_InitI2SPins(void); /* Function assigned for the Cortex-M33 (Core #0) */ + +#define IOCON_PIO_ASW_DI 0x00u /*!<@brief Analog switch is open (disabled) */ +#define IOCON_PIO_DIGITAL_EN 0x0100u /*!<@brief Enables digital function */ +#define IOCON_PIO_FUNC0 0x00u /*!<@brief Selects pin function 0 */ +#define IOCON_PIO_FUNC5 0x05u /*!<@brief Selects pin function 5 */ +#define IOCON_PIO_INV_DI 0x00u /*!<@brief Input function is not inverted */ +#define IOCON_PIO_MODE_INACT 0x00u /*!<@brief No addition pin function */ +#define IOCON_PIO_MODE_PULLUP 0x20u /*!<@brief Selects pull-up function */ +#define IOCON_PIO_OPENDRAIN_DI 0x00u /*!<@brief Open drain is disabled */ +#define IOCON_PIO_SLEW_STANDARD 0x00u /*!<@brief Standard mode, output slew rate control is enabled */ + +/*! @name PIO1_21 (number 30), P17[3]/P24[6]/FC4_I2C_SDA_ARD + @{ */ +#define BOARD_INITACCELPINS_FC4_I2C_SDA_PORT 1U /*!<@brief PORT peripheral base pointer */ +#define BOARD_INITACCELPINS_FC4_I2C_SDA_PIN 21U /*!<@brief PORT pin number */ +#define BOARD_INITACCELPINS_FC4_I2C_SDA_PIN_MASK (1U << 21U) /*!<@brief PORT pin mask */ + /* @} */ + +/*! @name PIO1_20 (number 4), P17[1]/P24[5]/FC4_I2C_SCL_ARD + @{ */ +#define BOARD_INITACCELPINS_FC4_I2C_SCL_PORT 1U /*!<@brief PORT peripheral base pointer */ +#define BOARD_INITACCELPINS_FC4_I2C_SCL_PIN 20U /*!<@brief PORT pin number */ +#define BOARD_INITACCELPINS_FC4_I2C_SCL_PIN_MASK (1U << 20U) /*!<@brief PORT pin mask */ + /* @} */ + +/*! @name PIO1_19 (number 58), U7[3]/P18[14]/PLU_OUT1/GPIO + @{ */ + +/* Symbols to be used with GPIO driver */ +#define BOARD_INITACCELPINS_ACCL_INTR_GPIO GPIO /*!<@brief GPIO peripheral base pointer */ +#define BOARD_INITACCELPINS_ACCL_INTR_GPIO_PIN_MASK (1U << 19U) /*!<@brief GPIO pin mask */ +#define BOARD_INITACCELPINS_ACCL_INTR_PORT 1U /*!<@brief PORT peripheral base pointer */ +#define BOARD_INITACCELPINS_ACCL_INTR_PIN 19U /*!<@brief PORT pin number */ +#define BOARD_INITACCELPINS_ACCL_INTR_PIN_MASK (1U << 19U) /*!<@brief PORT pin mask */ + /* @} */ + +/*! + * @brief Configures pin routing and optionally pin electrical features. + * + */ +void BOARD_InitACCELPins(void); /* Function assigned for the Cortex-M33 (Core #0) */ + +#if defined(__cplusplus) +} +#endif + +/*! + * @} + */ +#endif /* _PIN_MUX_H_ */ + +/*********************************************************************************************************************** + * EOF + **********************************************************************************************************************/ diff --git a/src/main.c b/src/main.c new file mode 100644 index 0000000..21245ea --- /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_BootClockFROHF96M(); + BOARD_InitBootPeripherals(); + + BOARD_InitDebugConsole(); + + PRINTF("Hello world!!\r\n"); + + for(;;) { + __WFI(); + } +} \ No newline at end of file