From 54b2ffcb7bfabecefa89fe892da366769bb04c21 Mon Sep 17 00:00:00 2001 From: Ridha Noomane Date: Fri, 29 Nov 2024 16:44:02 +0100 Subject: [PATCH] First commit by adding drivers and Os core. --- .gitignore | 7 + LPC55S69_cm33_core0_flash.scf | 104 ++ RidhaOs/Inc/timebase.h | 13 + RidhaOs/Src/timebase.c | 72 + drivers/Inc/fsl_adapter_uart.h | 829 +++++++++ drivers/Inc/fsl_assert.h | 51 + drivers/Inc/fsl_clock.h | 1506 +++++++++++++++ drivers/Inc/fsl_common.h | 345 ++++ drivers/Inc/fsl_common_arm.h | 898 +++++++++ drivers/Inc/fsl_component_generic_list.h | 219 +++ drivers/Inc/fsl_debug_console.h | 295 +++ drivers/Inc/fsl_flexcomm.h | 64 + drivers/Inc/fsl_power.h | 611 +++++++ drivers/Inc/fsl_reset.h | 317 ++++ drivers/Inc/fsl_str.h | 129 ++ drivers/Inc/fsl_usart.h | 971 ++++++++++ drivers/Inc/led.h | 10 + drivers/Inc/uart.h | 7 + drivers/Src/fsl_adapter_usart.c | 1101 +++++++++++ drivers/Src/fsl_assert.c | 88 + drivers/Src/fsl_clock.c | 2137 ++++++++++++++++++++++ drivers/Src/fsl_common.c | 85 + drivers/Src/fsl_common_arm.c | 257 +++ drivers/Src/fsl_component_generic_list.c | 499 +++++ drivers/Src/fsl_debug_console.c | 1450 +++++++++++++++ drivers/Src/fsl_flexcomm.c | 401 ++++ drivers/Src/fsl_power.c | 1831 ++++++++++++++++++ drivers/Src/fsl_reset.c | 99 + drivers/Src/fsl_str.c | 1707 +++++++++++++++++ drivers/Src/fsl_usart.c | 1314 +++++++++++++ drivers/Src/led.c | 23 + drivers/Src/uart.c | 60 + main.c | 24 + 33 files changed, 17524 insertions(+) create mode 100644 .gitignore create mode 100644 LPC55S69_cm33_core0_flash.scf create mode 100644 RidhaOs/Inc/timebase.h create mode 100644 RidhaOs/Src/timebase.c create mode 100644 drivers/Inc/fsl_adapter_uart.h create mode 100644 drivers/Inc/fsl_assert.h create mode 100644 drivers/Inc/fsl_clock.h create mode 100644 drivers/Inc/fsl_common.h create mode 100644 drivers/Inc/fsl_common_arm.h create mode 100644 drivers/Inc/fsl_component_generic_list.h create mode 100644 drivers/Inc/fsl_debug_console.h create mode 100644 drivers/Inc/fsl_flexcomm.h create mode 100644 drivers/Inc/fsl_power.h create mode 100644 drivers/Inc/fsl_reset.h create mode 100644 drivers/Inc/fsl_str.h create mode 100644 drivers/Inc/fsl_usart.h create mode 100644 drivers/Inc/led.h create mode 100644 drivers/Inc/uart.h create mode 100644 drivers/Src/fsl_adapter_usart.c create mode 100644 drivers/Src/fsl_assert.c create mode 100644 drivers/Src/fsl_clock.c create mode 100644 drivers/Src/fsl_common.c create mode 100644 drivers/Src/fsl_common_arm.c create mode 100644 drivers/Src/fsl_component_generic_list.c create mode 100644 drivers/Src/fsl_debug_console.c create mode 100644 drivers/Src/fsl_flexcomm.c create mode 100644 drivers/Src/fsl_power.c create mode 100644 drivers/Src/fsl_reset.c create mode 100644 drivers/Src/fsl_str.c create mode 100644 drivers/Src/fsl_usart.c create mode 100644 drivers/Src/led.c create mode 100644 drivers/Src/uart.c create mode 100644 main.c diff --git a/.gitignore b/.gitignore new file mode 100644 index 0000000..fd4aa5a --- /dev/null +++ b/.gitignore @@ -0,0 +1,7 @@ +*.uvprojx +*.uvoptx +**/RTE +**/Objects +**/Listings +**/DebugConfig +osProject.uvguix.nxf54496 \ No newline at end of file diff --git a/LPC55S69_cm33_core0_flash.scf b/LPC55S69_cm33_core0_flash.scf new file mode 100644 index 0000000..b1ec872 --- /dev/null +++ b/LPC55S69_cm33_core0_flash.scf @@ -0,0 +1,104 @@ +#!armclang --target=arm-arm-none-eabi -march=armv8-m.main -E -x c +/* +** ################################################################### +** Processors: LPC55S69JBD100_cm33_core0 +** LPC55S69JBD64_cm33_core0 +** LPC55S69JEV59_cm33_core0 +** LPC55S69JEV98_cm33_core0 +** +** Compiler: Keil ARM C/C++ Compiler +** Reference manual: LPC55S6x/LPC55S2x/LPC552x User manual(UM11126) Rev.1.3 16 May 2019 +** Version: rev. 1.1, 2019-05-16 +** Build: b231019 +** +** Abstract: +** Linker file for the Keil ARM C/C++ Compiler +** +** Copyright 2016 Freescale Semiconductor, Inc. +** Copyright 2016-2023 NXP +** SPDX-License-Identifier: BSD-3-Clause +** +** http: www.nxp.com +** mail: support@nxp.com +** +** ################################################################### +*/ + + +/* USB BDT size */ +#define usb_bdt_size 0x0 +/* Sizes */ +#if (defined(__stack_size__)) + #define Stack_Size __stack_size__ +#else + #define Stack_Size 0x0400 +#endif + +#if (defined(__heap_size__)) + #define Heap_Size __heap_size__ +#else + #define Heap_Size 0x0400 +#endif + +#define m_interrupts_start 0x00000000 +#define m_interrupts_size 0x00000200 + +#define m_text_start 0x00000200 +#define m_text_size 0x00071E00 + +#define m_core1_image_start 0x00072000 +#define m_core1_image_size 0x0002B800 + +#if (defined(__use_shmem__)) + #define m_data_start 0x20000000 + #define m_data_size 0x00031800 + #define m_rpmsg_sh_mem_start 0x20031800 + #define m_rpmsg_sh_mem_size 0x00001800 +#else + #define m_data_start 0x20000000 + #define m_data_size 0x00033000 +#endif + +#define m_usb_sram_start 0x40100000 +#define m_usb_sram_size 0x00004000 + + +LR_m_text m_interrupts_start m_interrupts_size+m_text_size { ; load region size_region + + VECTOR_ROM m_interrupts_start m_interrupts_size { ; load address = execution address + * (.isr_vector,+FIRST) + } + + ER_m_text m_text_start FIXED m_text_size { ; load address = execution address + * (InRoot$$Sections) + .ANY (+RO) + } + +#if (defined(__use_shmem__)) + RPMSG_SH_MEM m_rpmsg_sh_mem_start UNINIT m_rpmsg_sh_mem_size { ; Shared memory used by RPMSG + * (rpmsg_sh_mem_section) + } +#endif + + RW_m_data m_data_start m_data_size-Stack_Size-Heap_Size { ; RW data + .ANY (+RW +ZI) + } + ARM_LIB_HEAP +0 EMPTY Heap_Size { ; Heap region growing up + } + ARM_LIB_STACK m_data_start+m_data_size EMPTY -Stack_Size { ; Stack region growing down + } + + RW_m_usb_bdt m_usb_sram_start UNINIT usb_bdt_size { + * (*m_usb_bdt) + } + + RW_m_usb_ram (m_usb_sram_start + usb_bdt_size) UNINIT (m_usb_sram_size - usb_bdt_size) { + * (*m_usb_global) + } +} + +LR_CORE1_IMAGE m_core1_image_start { + CORE1_REGION m_core1_image_start m_core1_image_size { + * (.core1_code) + } +} diff --git a/RidhaOs/Inc/timebase.h b/RidhaOs/Inc/timebase.h new file mode 100644 index 0000000..a6a1cd3 --- /dev/null +++ b/RidhaOs/Inc/timebase.h @@ -0,0 +1,13 @@ +#ifndef __TIMEBASE_H__ +#define __TIMEBASE_H__ + +#include + + +uint32_t get_tick(void); +void delay_s(uint32_t delay); +void delay_ms(uint32_t delay); + +void timebase_init(void); + +#endif /* __TIMEBASE_H__ */ \ No newline at end of file diff --git a/RidhaOs/Src/timebase.c b/RidhaOs/Src/timebase.c new file mode 100644 index 0000000..0cd459c --- /dev/null +++ b/RidhaOs/Src/timebase.c @@ -0,0 +1,72 @@ +#include "timebase.h" +#include "fsl_device_registers.h" + +#define CTRL_ENABLE (1U<<0) +#define CTRL_TICKINT (1U<<1) +#define CTRL_CLKSRC (1U<<2) +#define CTRL_COUNTFLAG (1U<<16) +#define MAX_DELAY 0xFFFFFFFFU + +volatile uint32_t g_curr_tick; +volatile uint32_t g_curr_tick_p; +volatile uint32_t tick_freq = 1; + +uint8_t tick_freq_div = 1; + +void tick_increment(void) +{ + g_curr_tick += tick_freq; +} + +void delay_s(uint32_t delay) +{ + delay_ms(delay * 1000); +} + +void delay_ms(uint32_t delay) +{ + uint32_t tickstart = get_tick(); + uint32_t wait = delay; + if(wait < MAX_DELAY) + { + wait += (uint32_t)(tick_freq); + } + + while((get_tick() - tickstart) < wait){} + +} + +uint32_t get_tick(void) +{ + __disable_irq(); + g_curr_tick_p = g_curr_tick; + __enable_irq(); + return g_curr_tick_p; +} + +void timebase_init(void) +{ + /* Reload the timer with number of cycles per second */ + /* Getting SystemCoreClock divide by 1000 to get interrupt every 1ms */ + SysTick->LOAD = (SystemCoreClock / 1000) - 1; + + /* Clear Systick current value register */ + SysTick->VAL = 0x00; + + /* Select Internal Clock source */ + SysTick->CTRL = CTRL_CLKSRC; + + /* Enable interrupt */ + SysTick->CTRL |= CTRL_TICKINT; + + /* Enable Systick */ + SysTick->CTRL |= CTRL_ENABLE; + + /* Enable Global Interrupt */ + __enable_irq(); + +} + +void SysTick_Handler(void){ + tick_increment(); +} \ No newline at end of file diff --git a/drivers/Inc/fsl_adapter_uart.h b/drivers/Inc/fsl_adapter_uart.h new file mode 100644 index 0000000..5bb9f82 --- /dev/null +++ b/drivers/Inc/fsl_adapter_uart.h @@ -0,0 +1,829 @@ +/* + * Copyright 2018-2020 NXP + * All rights reserved. + * + * + * SPDX-License-Identifier: BSD-3-Clause + */ + +#ifndef __HAL_UART_ADAPTER_H__ +#define __HAL_UART_ADAPTER_H__ + +#include "fsl_common.h" +#if defined(SDK_OS_FREE_RTOS) +#include "FreeRTOS.h" +#endif + +/*! + * @addtogroup UART_Adapter + * @{ + */ + +/******************************************************************************* + * Definitions + ******************************************************************************/ + +/*! @brief Enable or disable UART adapter non-blocking mode (1 - enable, 0 - disable) */ +#ifdef DEBUG_CONSOLE_TRANSFER_NON_BLOCKING +#define UART_ADAPTER_NON_BLOCKING_MODE (1U) +#else +#ifndef SERIAL_MANAGER_NON_BLOCKING_MODE +#define UART_ADAPTER_NON_BLOCKING_MODE (0U) +#else +#define UART_ADAPTER_NON_BLOCKING_MODE SERIAL_MANAGER_NON_BLOCKING_MODE +#endif +#endif + +#if defined(__GIC_PRIO_BITS) +#ifndef HAL_UART_ISR_PRIORITY +#define HAL_UART_ISR_PRIORITY (25U) +#endif +#else +#if defined(configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY) +#ifndef HAL_UART_ISR_PRIORITY +#define HAL_UART_ISR_PRIORITY (configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY) +#endif +#else +/* The default value 3 is used to support different ARM Core, such as CM0P, CM4, CM7, and CM33, etc. + * The minimum number of priority bits implemented in the NVIC is 2 on these SOCs. The value of mininum + * priority is 3 (2^2 - 1). So, the default value is 3. + */ +#ifndef HAL_UART_ISR_PRIORITY +#define HAL_UART_ISR_PRIORITY (3U) +#endif +#endif +#endif + +#ifndef HAL_UART_ADAPTER_LOWPOWER +#define HAL_UART_ADAPTER_LOWPOWER (0U) +#endif /* HAL_UART_ADAPTER_LOWPOWER */ + +/*! @brief Enable or disable uart hardware FIFO mode (1 - enable, 0 - disable) */ +#ifndef HAL_UART_ADAPTER_FIFO +#define HAL_UART_ADAPTER_FIFO (1U) +#endif /* HAL_UART_ADAPTER_FIFO */ + +#if (defined(SERIAL_PORT_TYPE_UART_DMA) && (SERIAL_PORT_TYPE_UART_DMA > 0U)) +#ifndef HAL_UART_DMA_ENABLE +#define HAL_UART_DMA_ENABLE (1U) +#endif +#endif + +#ifndef HAL_UART_DMA_ENABLE +#define HAL_UART_DMA_ENABLE (0U) +#endif /* HAL_UART_DMA_ENABLE */ + +/*! @brief Enable or disable uart DMA adapter int mode (1 - enable, 0 - disable) */ +#ifndef HAL_UART_DMA_INIT_ENABLE +#define HAL_UART_DMA_INIT_ENABLE (1U) +#endif /* HAL_SPI_MASTER_DMA_INIT_ENABLE */ + +/*! @brief Definition of uart dma adapter software idleline detection timeout value in ms. */ +#ifndef HAL_UART_DMA_IDLELINE_TIMEOUT +#define HAL_UART_DMA_IDLELINE_TIMEOUT (1U) +#endif /* HAL_UART_DMA_IDLELINE_TIMEOUT */ + +/*! @brief Definition of uart adapter handle size. */ +#if (defined(UART_ADAPTER_NON_BLOCKING_MODE) && (UART_ADAPTER_NON_BLOCKING_MODE > 0U)) +#define HAL_UART_HANDLE_SIZE (92U + HAL_UART_ADAPTER_LOWPOWER * 16U + HAL_UART_DMA_ENABLE * 4U) +#define HAL_UART_BLOCK_HANDLE_SIZE (8U + HAL_UART_ADAPTER_LOWPOWER * 16U + HAL_UART_DMA_ENABLE * 4U) +#else +#define HAL_UART_HANDLE_SIZE (8U + HAL_UART_ADAPTER_LOWPOWER * 16U + HAL_UART_DMA_ENABLE * 4U) +#endif + +/*! @brief Definition of uart dma adapter handle size. */ +#if (defined(HAL_UART_DMA_ENABLE) && (HAL_UART_DMA_ENABLE > 0U)) +#if (defined(FSL_FEATURE_SOC_DMA_COUNT) && (FSL_FEATURE_SOC_DMA_COUNT > 0U)) +#define HAL_UART_DMA_HANDLE_SIZE (124U + HAL_UART_ADAPTER_LOWPOWER * 36U) +#elif (defined(FSL_FEATURE_SOC_EDMA_COUNT) && (FSL_FEATURE_SOC_EDMA_COUNT > 0U)) +#define HAL_UART_DMA_HANDLE_SIZE (140U + HAL_UART_ADAPTER_LOWPOWER * 36U) +#else +#error This SOC does not have DMA or EDMA available! +#endif +#endif /* HAL_UART_DMA_ENABLE */ + +/*! + * @brief Defines the uart handle + * + * This macro is used to define a 4 byte aligned uart handle. + * Then use "(hal_uart_handle_t)name" to get the uart handle. + * + * The macro should be global and could be optional. You could also define uart handle by yourself. + * + * This is an example, + * @code + * UART_HANDLE_DEFINE(uartHandle); + * @endcode + * + * @param name The name string of the uart handle. + */ +#define UART_HANDLE_DEFINE(name) uint32_t name[((HAL_UART_HANDLE_SIZE + sizeof(uint32_t) - 1U) / sizeof(uint32_t))] + +#if (defined(HAL_UART_DMA_ENABLE) && (HAL_UART_DMA_ENABLE > 0U)) +#define UART_DMA_HANDLE_DEFINE(name) \ + uint32_t name[((HAL_UART_DMA_HANDLE_SIZE + sizeof(uint32_t) - 1U) / sizeof(uint32_t))] +#endif + +/*! @brief Whether enable transactional function of the UART. (0 - disable, 1 - enable) */ +#ifndef HAL_UART_TRANSFER_MODE +#define HAL_UART_TRANSFER_MODE (0U) +#endif + +/*! @brief The handle of uart adapter. */ +typedef void *hal_uart_handle_t; + +/*! @brief The handle of uart dma adapter. */ +typedef void *hal_uart_dma_handle_t; + +/*! @brief UART status */ +typedef enum _hal_uart_status +{ + kStatus_HAL_UartSuccess = kStatus_Success, /*!< Successfully */ + kStatus_HAL_UartTxBusy = MAKE_STATUS(kStatusGroup_HAL_UART, 1), /*!< TX busy */ + kStatus_HAL_UartRxBusy = MAKE_STATUS(kStatusGroup_HAL_UART, 2), /*!< RX busy */ + kStatus_HAL_UartTxIdle = MAKE_STATUS(kStatusGroup_HAL_UART, 3), /*!< HAL UART transmitter is idle. */ + kStatus_HAL_UartRxIdle = MAKE_STATUS(kStatusGroup_HAL_UART, 4), /*!< HAL UART receiver is idle */ + kStatus_HAL_UartBaudrateNotSupport = + MAKE_STATUS(kStatusGroup_HAL_UART, 5), /*!< Baudrate is not support in current clock source */ + kStatus_HAL_UartProtocolError = MAKE_STATUS( + kStatusGroup_HAL_UART, + 6), /*!< Error occurs for Noise, Framing, Parity, etc. + For transactional transfer, The up layer needs to abort the transfer and then starts again */ + kStatus_HAL_UartError = MAKE_STATUS(kStatusGroup_HAL_UART, 7), /*!< Error occurs on HAL UART */ +} hal_uart_status_t; + +/*! @brief UART parity mode. */ +typedef enum _hal_uart_parity_mode +{ + kHAL_UartParityDisabled = 0x0U, /*!< Parity disabled */ + kHAL_UartParityEven = 0x2U, /*!< Parity even enabled */ + kHAL_UartParityOdd = 0x3U, /*!< Parity odd enabled */ +} hal_uart_parity_mode_t; + +/*! @brief UART stop bit count. */ +typedef enum _hal_uart_stop_bit_count +{ + kHAL_UartOneStopBit = 0U, /*!< One stop bit */ + kHAL_UartTwoStopBit = 1U, /*!< Two stop bits */ +} hal_uart_stop_bit_count_t; + +/*! @brief UART configuration structure. */ +typedef struct _hal_uart_config +{ + uint32_t srcClock_Hz; /*!< Source clock */ + uint32_t baudRate_Bps; /*!< Baud rate */ + hal_uart_parity_mode_t parityMode; /*!< Parity mode, disabled (default), even, odd */ + hal_uart_stop_bit_count_t stopBitCount; /*!< Number of stop bits, 1 stop bit (default) or 2 stop bits */ + uint8_t enableRx; /*!< Enable RX */ + uint8_t enableTx; /*!< Enable TX */ + uint8_t enableRxRTS; /*!< Enable RX RTS */ + uint8_t enableTxCTS; /*!< Enable TX CTS */ + uint8_t instance; /*!< Instance (0 - UART0, 1 - UART1, ...), detail information please refer to the + SOC corresponding RM. + Invalid instance value will cause initialization failure. */ +#if (defined(HAL_UART_ADAPTER_FIFO) && (HAL_UART_ADAPTER_FIFO > 0u)) + uint8_t txFifoWatermark; + uint8_t rxFifoWatermark; +#endif +} hal_uart_config_t; + +#if (defined(HAL_UART_DMA_ENABLE) && (HAL_UART_DMA_ENABLE > 0U)) +/*! @brief UART DMA status */ +typedef enum _hal_uart_dma_status +{ + kStatus_HAL_UartDmaSuccess = 0U, + kStatus_HAL_UartDmaRxIdle = (1U << 1U), + kStatus_HAL_UartDmaRxBusy = (1U << 2U), + kStatus_HAL_UartDmaTxIdle = (1U << 3U), + kStatus_HAL_UartDmaTxBusy = (1U << 4U), + kStatus_HAL_UartDmaIdleline = (1U << 5U), + kStatus_HAL_UartDmaError = (1U << 6U), +} hal_uart_dma_status_t; + +typedef struct _dma_mux_configure_t +{ + union + { + struct + { + uint8_t dma_mux_instance; + uint32_t rx_request; + uint32_t tx_request; + } dma_dmamux_configure; + }; +} dma_mux_configure_t; +typedef struct _dma_channel_mux_configure_t +{ + union + { + struct + { + uint32_t dma_rx_channel_mux; + uint32_t dma_tx_channel_mux; + } dma_dmamux_configure; + }; +} dma_channel_mux_configure_t; + +typedef struct _hal_uart_dma_config_t +{ + uint8_t uart_instance; + uint8_t dma_instance; + uint8_t rx_channel; + uint8_t tx_channel; + void *dma_mux_configure; + void *dma_channel_mux_configure; +} hal_uart_dma_config_t; +#endif /* HAL_UART_DMA_ENABLE */ + +/*! @brief UART transfer callback function. */ +typedef void (*hal_uart_transfer_callback_t)(hal_uart_handle_t handle, hal_uart_status_t status, void *callbackParam); + +#if (defined(HAL_UART_DMA_ENABLE) && (HAL_UART_DMA_ENABLE > 0U)) +typedef struct _dma_callback_msg +{ + hal_uart_dma_status_t status; + uint8_t *data; + uint32_t dataSize; +} hal_dma_callback_msg_t; + +/*! @brief UART transfer callback function. */ +typedef void (*hal_uart_dma_transfer_callback_t)(hal_uart_dma_handle_t handle, + hal_dma_callback_msg_t *msg, + void *callbackParam); +#endif /* HAL_UART_DMA_ENABLE */ + +/*! @brief UART transfer structure. */ +typedef struct _hal_uart_transfer +{ + uint8_t *data; /*!< The buffer of data to be transfer.*/ + size_t dataSize; /*!< The byte count to be transfer. */ +} hal_uart_transfer_t; + +/******************************************************************************* + * API + ******************************************************************************/ + +#if defined(__cplusplus) +extern "C" { +#endif /* _cplusplus */ + +/*! + * @name Initialization and deinitialization + * @{ + */ + +/*! + * @brief Initializes a UART instance with the UART handle and the user configuration structure. + * + * This function configures the UART module with user-defined settings. The user can configure the configuration + * structure. The parameter handle is a pointer to point to a memory space of size #HAL_UART_HANDLE_SIZE allocated by + * the caller. Example below shows how to use this API to configure the UART. + * @code + * UART_HANDLE_DEFINE(g_UartHandle); + * hal_uart_config_t config; + * config.srcClock_Hz = 48000000; + * config.baudRate_Bps = 115200U; + * config.parityMode = kHAL_UartParityDisabled; + * config.stopBitCount = kHAL_UartOneStopBit; + * config.enableRx = 1; + * config.enableTx = 1; + * config.enableRxRTS = 0; + * config.enableTxCTS = 0; + * config.instance = 0; + * HAL_UartInit((hal_uart_handle_t)g_UartHandle, &config); + * @endcode + * + * @param handle Pointer to point to a memory space of size #HAL_UART_HANDLE_SIZE allocated by the caller. + * The handle should be 4 byte aligned, because unaligned access doesn't be supported on some devices. + * You can define the handle in the following two ways: + * #UART_HANDLE_DEFINE(handle); + * or + * uint32_t handle[((HAL_UART_HANDLE_SIZE + sizeof(uint32_t) - 1U) / sizeof(uint32_t))]; + * @param uart_config Pointer to user-defined configuration structure. + * @retval kStatus_HAL_UartBaudrateNotSupport Baudrate is not support in current clock source. + * @retval kStatus_HAL_UartSuccess UART initialization succeed + */ +hal_uart_status_t HAL_UartInit(hal_uart_handle_t handle, const hal_uart_config_t *uart_config); + +/*! + * @brief Deinitializes a UART instance. + * + * This function waits for TX complete, disables TX and RX, and disables the UART clock. + * + * @param handle UART handle pointer. + * @retval kStatus_HAL_UartSuccess UART de-initialization succeed + */ +hal_uart_status_t HAL_UartDeinit(hal_uart_handle_t handle); + +/*! @}*/ + +/*! + * @name Blocking bus Operations + * @{ + */ + +/*! + * @brief Reads RX data register using a blocking method. + * + * This function polls the RX register, waits for the RX register to be full or for RX FIFO to + * have data, and reads data from the RX register. + * + * @note The function #HAL_UartReceiveBlocking and the function HAL_UartTransferReceiveNonBlocking + * cannot be used at the same time. + * And, the function HAL_UartTransferAbortReceive cannot be used to abort the transmission of this function. + * + * @param handle UART handle pointer. + * @param data Start address of the buffer to store the received data. + * @param length Size of the buffer. + * @retval kStatus_HAL_UartError An error occurred while receiving data. + * @retval kStatus_HAL_UartParityError A parity error occurred while receiving data. + * @retval kStatus_HAL_UartSuccess Successfully received all data. + */ +hal_uart_status_t HAL_UartReceiveBlocking(hal_uart_handle_t handle, uint8_t *data, size_t length); + +/*! + * @brief Writes to the TX register using a blocking method. + * + * This function polls the TX register, waits for the TX register to be empty or for the TX FIFO + * to have room and writes data to the TX buffer. + * + * @note The function #HAL_UartSendBlocking and the function HAL_UartTransferSendNonBlocking + * cannot be used at the same time. + * And, the function HAL_UartTransferAbortSend cannot be used to abort the transmission of this function. + * + * @param handle UART handle pointer. + * @param data Start address of the data to write. + * @param length Size of the data to write. + * @retval kStatus_HAL_UartSuccess Successfully sent all data. + */ +hal_uart_status_t HAL_UartSendBlocking(hal_uart_handle_t handle, const uint8_t *data, size_t length); + +/*! @}*/ + +#if (defined(UART_ADAPTER_NON_BLOCKING_MODE) && (UART_ADAPTER_NON_BLOCKING_MODE > 0U)) +#if (defined(HAL_UART_TRANSFER_MODE) && (HAL_UART_TRANSFER_MODE > 0U)) + +/*! + * @name Transactional + * @note The transactional API and the functional API cannot be used at the same time. The macro + * #HAL_UART_TRANSFER_MODE is used to set which one will be used. If #HAL_UART_TRANSFER_MODE is zero, the + * functional API with non-blocking mode will be used. Otherwise, transactional API will be used. + * @{ + */ + +/*! + * @brief Installs a callback and callback parameter. + * + * This function is used to install the callback and callback parameter for UART module. + * When any status of the UART changed, the driver will notify the upper layer by the installed callback + * function. And the status is also passed as status parameter when the callback is called. + * + * @param handle UART handle pointer. + * @param callback The callback function. + * @param callbackParam The parameter of the callback function. + * @retval kStatus_HAL_UartSuccess Successfully install the callback. + */ +hal_uart_status_t HAL_UartTransferInstallCallback(hal_uart_handle_t handle, + hal_uart_transfer_callback_t callback, + void *callbackParam); + +/*! + * @brief Receives a buffer of data using an interrupt method. + * + * This function receives data using an interrupt method. This is a non-blocking function, which + * returns directly without waiting for all data to be received. + * The receive request is saved by the UART driver. + * When the new data arrives, the receive request is serviced first. + * When all data is received, the UART driver notifies the upper layer + * through a callback function and passes the status parameter @ref kStatus_HAL_UartRxIdle. + * + * @note The function #HAL_UartReceiveBlocking and the function #HAL_UartTransferReceiveNonBlocking + * cannot be used at the same time. + * + * @param handle UART handle pointer. + * @param transfer UART transfer structure, see #hal_uart_transfer_t. + * @retval kStatus_HAL_UartSuccess Successfully queue the transfer into transmit queue. + * @retval kStatus_HAL_UartRxBusy Previous receive request is not finished. + * @retval kStatus_HAL_UartError An error occurred. + */ +hal_uart_status_t HAL_UartTransferReceiveNonBlocking(hal_uart_handle_t handle, hal_uart_transfer_t *transfer); + +/*! + * @brief Transmits a buffer of data using the interrupt method. + * + * This function sends data using an interrupt method. This is a non-blocking function, which + * returns directly without waiting for all data to be written to the TX register. When + * all data is written to the TX register in the ISR, the UART driver calls the callback + * function and passes the @ref kStatus_HAL_UartTxIdle as status parameter. + * + * @note The function #HAL_UartSendBlocking and the function #HAL_UartTransferSendNonBlocking + * cannot be used at the same time. + * + * @param handle UART handle pointer. + * @param transfer UART transfer structure. See #hal_uart_transfer_t. + * @retval kStatus_HAL_UartSuccess Successfully start the data transmission. + * @retval kStatus_HAL_UartTxBusy Previous transmission still not finished; data not all written to TX register yet. + * @retval kStatus_HAL_UartError An error occurred. + */ +hal_uart_status_t HAL_UartTransferSendNonBlocking(hal_uart_handle_t handle, hal_uart_transfer_t *transfer); + +/*! + * @brief Gets the number of bytes that have been received. + * + * This function gets the number of bytes that have been received. + * + * @param handle UART handle pointer. + * @param count Receive bytes count. + * @retval kStatus_HAL_UartError An error occurred. + * @retval kStatus_Success Get successfully through the parameter \p count. + */ +hal_uart_status_t HAL_UartTransferGetReceiveCount(hal_uart_handle_t handle, uint32_t *count); + +/*! + * @brief Gets the number of bytes written to the UART TX register. + * + * This function gets the number of bytes written to the UART TX + * register by using the interrupt method. + * + * @param handle UART handle pointer. + * @param count Send bytes count. + * @retval kStatus_HAL_UartError An error occurred. + * @retval kStatus_Success Get successfully through the parameter \p count. + */ +hal_uart_status_t HAL_UartTransferGetSendCount(hal_uart_handle_t handle, uint32_t *count); + +/*! + * @brief Aborts the interrupt-driven data receiving. + * + * This function aborts the interrupt-driven data receiving. The user can get the remainBytes to know + * how many bytes are not received yet. + * + * @note The function #HAL_UartTransferAbortReceive cannot be used to abort the transmission of + * the function #HAL_UartReceiveBlocking. + * + * @param handle UART handle pointer. + * @retval kStatus_Success Get successfully abort the receiving. + */ +hal_uart_status_t HAL_UartTransferAbortReceive(hal_uart_handle_t handle); + +/*! + * @brief Aborts the interrupt-driven data sending. + * + * This function aborts the interrupt-driven data sending. The user can get the remainBytes to find out + * how many bytes are not sent out. + * + * @note The function #HAL_UartTransferAbortSend cannot be used to abort the transmission of + * the function #HAL_UartSendBlocking. + * + * @param handle UART handle pointer. + * @retval kStatus_Success Get successfully abort the sending. + */ +hal_uart_status_t HAL_UartTransferAbortSend(hal_uart_handle_t handle); + +/*! @}*/ + +#else + +/*! + * @name Functional API with non-blocking mode. + * @note The functional API and the transactional API cannot be used at the same time. The macro + * #HAL_UART_TRANSFER_MODE is used to set which one will be used. If #HAL_UART_TRANSFER_MODE is zero, the + * functional API with non-blocking mode will be used. Otherwise, transactional API will be used. + * @{ + */ + +/*! + * @brief Installs a callback and callback parameter. + * + * This function is used to install the callback and callback parameter for UART module. + * When non-blocking sending or receiving finished, the adapter will notify the upper layer by the installed callback + * function. And the status is also passed as status parameter when the callback is called. + * + * @param handle UART handle pointer. + * @param callback The callback function. + * @param callbackParam The parameter of the callback function. + * @retval kStatus_HAL_UartSuccess Successfully install the callback. + */ +hal_uart_status_t HAL_UartInstallCallback(hal_uart_handle_t handle, + hal_uart_transfer_callback_t callback, + void *callbackParam); + +/*! + * @brief Receives a buffer of data using an interrupt method. + * + * This function receives data using an interrupt method. This is a non-blocking function, which + * returns directly without waiting for all data to be received. + * The receive request is saved by the UART adapter. + * When the new data arrives, the receive request is serviced first. + * When all data is received, the UART adapter notifies the upper layer + * through a callback function and passes the status parameter @ref kStatus_HAL_UartRxIdle. + * + * @note The function #HAL_UartReceiveBlocking and the function #HAL_UartReceiveNonBlocking + * cannot be used at the same time. + * + * @param handle UART handle pointer. + * @param data Start address of the data to write. + * @param length Size of the data to write. + * @retval kStatus_HAL_UartSuccess Successfully queue the transfer into transmit queue. + * @retval kStatus_HAL_UartRxBusy Previous receive request is not finished. + * @retval kStatus_HAL_UartError An error occurred. + */ +hal_uart_status_t HAL_UartReceiveNonBlocking(hal_uart_handle_t handle, uint8_t *data, size_t length); + +/*! + * @brief Transmits a buffer of data using the interrupt method. + * + * This function sends data using an interrupt method. This is a non-blocking function, which + * returns directly without waiting for all data to be written to the TX register. When + * all data is written to the TX register in the ISR, the UART driver calls the callback + * function and passes the @ref kStatus_HAL_UartTxIdle as status parameter. + * + * @note The function #HAL_UartSendBlocking and the function #HAL_UartSendNonBlocking + * cannot be used at the same time. + * + * @param handle UART handle pointer. + * @param data Start address of the data to write. + * @param length Size of the data to write. + * @retval kStatus_HAL_UartSuccess Successfully start the data transmission. + * @retval kStatus_HAL_UartTxBusy Previous transmission still not finished; data not all written to TX register yet. + * @retval kStatus_HAL_UartError An error occurred. + */ +hal_uart_status_t HAL_UartSendNonBlocking(hal_uart_handle_t handle, uint8_t *data, size_t length); + +/*! + * @brief Gets the number of bytes that have been received. + * + * This function gets the number of bytes that have been received. + * + * @param handle UART handle pointer. + * @param reCount Receive bytes count. + * @retval kStatus_HAL_UartError An error occurred. + * @retval kStatus_Success Get successfully through the parameter \p count. + */ +hal_uart_status_t HAL_UartGetReceiveCount(hal_uart_handle_t handle, uint32_t *reCount); + +/*! + * @brief Gets the number of bytes written to the UART TX register. + * + * This function gets the number of bytes written to the UART TX + * register by using the interrupt method. + * + * @param handle UART handle pointer. + * @param seCount Send bytes count. + * @retval kStatus_HAL_UartError An error occurred. + * @retval kStatus_Success Get successfully through the parameter \p count. + */ +hal_uart_status_t HAL_UartGetSendCount(hal_uart_handle_t handle, uint32_t *seCount); + +/*! + * @brief Aborts the interrupt-driven data receiving. + * + * This function aborts the interrupt-driven data receiving. The user can get the remainBytes to know + * how many bytes are not received yet. + * + * @note The function #HAL_UartAbortReceive cannot be used to abort the transmission of + * the function #HAL_UartReceiveBlocking. + * + * @param handle UART handle pointer. + * @retval kStatus_Success Get successfully abort the receiving. + */ +hal_uart_status_t HAL_UartAbortReceive(hal_uart_handle_t handle); + +/*! + * @brief Aborts the interrupt-driven data sending. + * + * This function aborts the interrupt-driven data sending. The user can get the remainBytes to find out + * how many bytes are not sent out. + * + * @note The function #HAL_UartAbortSend cannot be used to abort the transmission of + * the function #HAL_UartSendBlocking. + * + * @param handle UART handle pointer. + * @retval kStatus_Success Get successfully abort the sending. + */ +hal_uart_status_t HAL_UartAbortSend(hal_uart_handle_t handle); + +/*! @}*/ + +#endif +#endif + +#if (defined(HAL_UART_DMA_ENABLE) && (HAL_UART_DMA_ENABLE > 0U)) + +/*! + * @brief Initializes a UART dma instance with the UART dma handle and the user configuration structure. + * + * This function configures the UART dma module with user-defined settings. The user can configure the configuration + * structure. The parameter handle is a pointer to point to a memory space of size #HAL_UART_DMA_HANDLE_SIZE allocated + * by the caller. Example below shows how to use this API to configure the UART. + * @code + * + * Init TimerManager, only used in UART without Idleline interrupt + * timer_config_t timerConfig; + * timerConfig.srcClock_Hz = 16000000; + * timerConfig.instance = 0; + * TM_Init(&timerConfig); + * + * Init the DMA module + * DMA_Init(DMA0); + * + * Define a uart dma handle + * UART_HANDLE_DEFINE(g_uartHandle); + * UART_DMA_HANDLE_DEFINE(g_UartDmaHandle); + * + * Configure uart settings + * hal_uart_config_t uartConfig; + * uartConfig.srcClock_Hz = 48000000; + * uartConfig.baudRate_Bps = 115200; + * uartConfig.parityMode = kHAL_UartParityDisabled; + * uartConfig.stopBitCount = kHAL_UartOneStopBit; + * uartConfig.enableRx = 1; + * uartConfig.enableTx = 1; + * uartConfig.enableRxRTS = 0; + * uartConfig.enableTxCTS = 0; + * uartConfig.instance = 0; + * + * Init uart + * HAL_UartInit((hal_uart_handle_t *)g_uartHandle, &uartConfig); + * + * Configure uart dma settings + * hal_uart_dma_config_t dmaConfig; + * dmaConfig.uart_instance = 0; + * dmaConfig.dma_instance = 0; + * dmaConfig.rx_channel = 0; + * dmaConfig.tx_channel = 1; + * + * Init uart dma + * HAL_UartDMAInit((hal_uart_handle_t *)g_uartHandle, (hal_uart_dma_handle_t *)g_uartDmaHandle, &dmaConfig); + * @endcode + * + * @param handle UART handle pointer. + * @param dmaHandle Pointer to point to a memory space of size #HAL_UART_DMA_HANDLE_SIZE allocated by the caller. + * The handle should be 4 byte aligned, because unaligned access doesn't be supported on some devices. + * You can define the handle in the following two ways: + * #UART_DMA_HANDLE_DEFINE(handle); + * or + * uint32_t handle[((HAL_UART_DMA_HANDLE_SIZE + sizeof(uint32_t) - 1U) / sizeof(uint32_t))]; + * @param dmaConfig Pointer to user-defined configuration structure. + * @retval kStatus_HAL_UartDmaError UART dma initialization failed. + * @retval kStatus_HAL_UartDmaSuccess UART dma initialization succeed. + */ +hal_uart_dma_status_t HAL_UartDMAInit(hal_uart_handle_t handle, + hal_uart_dma_handle_t dmaHandle, + hal_uart_dma_config_t *dmaConfig); + +/*! + * @brief Deinitializes a UART DMA instance. + * + * This function will abort uart dma receive/send transfer and deinitialize UART. + * + * @param handle UART handle pointer. + * @retval kStatus_HAL_UartDmaSuccess UART DMA de-initialization succeed + */ +hal_uart_dma_status_t HAL_UartDMADeinit(hal_uart_handle_t handle); + +/*! + * @brief Installs a callback and callback parameter. + * + * This function is used to install the callback and callback parameter for UART DMA module. + * When any status of the UART DMA changed, the driver will notify the upper layer by the installed callback + * function. And the status is also passed as status parameter when the callback is called. + * + * @param handle UART handle pointer. + * @param callback The callback function. + * @param callbackParam The parameter of the callback function. + * @retval kStatus_HAL_UartDmaSuccess Successfully install the callback. + */ +hal_uart_dma_status_t HAL_UartDMATransferInstallCallback(hal_uart_handle_t handle, + hal_uart_dma_transfer_callback_t callback, + void *callbackParam); + +/*! + * @brief Receives a buffer of data using an dma method. + * + * This function receives data using an dma method. This is a non-blocking function, which + * returns directly without waiting for all data to be received. + * The receive request is saved by the UART DMA driver. + * When all data is received, the UART DMA adapter notifies the upper layer + * through a callback function and passes the status parameter @ref kStatus_HAL_UartDmaRxIdle. + * + * When an idleline is detected, the UART DMA adapter notifies the upper layer through a callback function, + * and passes the status parameter @ref kStatus_HAL_UartDmaIdleline. For the UARTs without hardware idleline + * interrupt(like usart), it will use a software idleline detection method with the help of TimerManager. + * + * When the soc support cache, uplayer should do cache maintain operations for transfer buffer before call this API. + * + * @param handle UART handle pointer. + * @param data data Start address of the buffer to store the received data. + * @param length Size of the buffer. + * @param receiveAll Idleline interrupt will not end transfer process if set true. + * @retval kStatus_HAL_UartDmaSuccess Successfully start the data receive. + * @retval kStatus_HAL_UartDmaRxBusy Previous receive request is not finished. + */ +hal_uart_dma_status_t HAL_UartDMATransferReceive(hal_uart_handle_t handle, + uint8_t *data, + size_t length, + bool receiveAll); + +/*! + * @brief Transmits a buffer of data using an dma method. + * + * This function sends data using an dma method. This is a non-blocking function, which + * returns directly without waiting for all data to be written to the TX register. When + * all data is written to the TX register by DMA, the UART DMA driver calls the callback + * function and passes the @ref kStatus_HAL_UartDmaTxIdle as status parameter. + * + * When the soc support cache, uplayer should do cache maintain operations for transfer buffer before call this API. + * + * @param handle UART handle pointer. + * @param data data Start address of the data to write. + * @param length Size of the data to write. + * @retval kStatus_HAL_UartDmaSuccess Successfully start the data transmission. + * @retval kStatus_HAL_UartDmaTxBusy Previous send request is not finished. + */ +hal_uart_dma_status_t HAL_UartDMATransferSend(hal_uart_handle_t handle, uint8_t *data, size_t length); + +/*! + * @brief Gets the number of bytes that have been received. + * + * This function gets the number of bytes that have been received. + * + * @param handle UART handle pointer. + * @param reCount Receive bytes count. + * @retval kStatus_HAL_UartDmaError An error occurred. + * @retval kStatus_HAL_UartDmaSuccess Get successfully through the parameter \p reCount. + */ +hal_uart_dma_status_t HAL_UartDMAGetReceiveCount(hal_uart_handle_t handle, uint32_t *reCount); + +/*! + * @brief Gets the number of bytes written to the UART TX register. + * + * This function gets the number of bytes written to the UART TX + * register by using the DMA method. + * + * @param handle UART handle pointer. + * @param seCount Send bytes count. + * @retval kStatus_HAL_UartDmaError An error occurred. + * @retval kStatus_HAL_UartDmaSuccess Get successfully through the parameter \p seCount. + */ +hal_uart_dma_status_t HAL_UartDMAGetSendCount(hal_uart_handle_t handle, uint32_t *seCount); + +/*! + * @brief Aborts the DMA-driven data receiving. + * + * This function aborts the DMA-driven data receiving. + * + * @param handle UART handle pointer. + * @retval kStatus_HAL_UartDmaSuccess Get successfully abort the receiving. + */ +hal_uart_dma_status_t HAL_UartDMAAbortReceive(hal_uart_handle_t handle); + +/*! + * @brief Aborts the DMA-driven data sending. + * + * This function aborts the DMA-driven data sending. + * + * @param handle UART handle pointer. + * @retval kStatus_Success Get successfully abort the sending. + */ +hal_uart_dma_status_t HAL_UartDMAAbortSend(hal_uart_handle_t handle); +#endif /* HAL_UART_DMA_ENABLE */ + +/*! + * @brief Prepares to enter low power consumption. + * + * This function is used to prepare to enter low power consumption. + * + * @param handle UART handle pointer. + * @retval kStatus_HAL_UartSuccess Successful operation. + * @retval kStatus_HAL_UartError An error occurred. + */ +hal_uart_status_t HAL_UartEnterLowpower(hal_uart_handle_t handle); + +/*! + * @brief Restores from low power consumption. + * + * This function is used to restore from low power consumption. + * + * @param handle UART handle pointer. + * @retval kStatus_HAL_UartSuccess Successful operation. + * @retval kStatus_HAL_UartError An error occurred. + */ +hal_uart_status_t HAL_UartExitLowpower(hal_uart_handle_t handle); + +#if (defined(UART_ADAPTER_NON_BLOCKING_MODE) && (UART_ADAPTER_NON_BLOCKING_MODE > 0U)) +/*! + * @brief UART IRQ handle function. + * + * This function handles the UART transmit and receive IRQ request. + * + * @param handle UART handle pointer. + */ +void HAL_UartIsrFunction(hal_uart_handle_t handle); +#endif + +#if defined(__cplusplus) +} +#endif +/*! @}*/ +#endif /* __HAL_UART_ADAPTER_H__ */ diff --git a/drivers/Inc/fsl_assert.h b/drivers/Inc/fsl_assert.h new file mode 100644 index 0000000..58b50dc --- /dev/null +++ b/drivers/Inc/fsl_assert.h @@ -0,0 +1,51 @@ +/* + * Copyright 2023 NXP + * All rights reserved. + * + * SPDX-License-Identifier: BSD-3-Clause + */ + +#ifndef _FSL_ASSERT_H_ +#define _FSL_ASSERT_H_ + +/*! + * @addtogroup assert + * @{ + */ + +/******************************************************************************* + * Definitions + ******************************************************************************/ + + +/******************************************************************************* + * Prototypes + ******************************************************************************/ + +#if defined(__cplusplus) +extern "C" { +#endif /* __cplusplus */ + +/*! @name Initialization*/ +/* @{ */ + + +/*! + * @brief Assert hook that can be redifined + * + * @param failedExpr Expression that caused the assert + * @param file File where the exception occured. + * @param line Line on the file where the exception occured. + */ +int fsl_assert_hook(const char *failedExpr, const char *file, int line); + +/*! @} */ + +#if defined(__cplusplus) +} +#endif /* __cplusplus */ + +/*! @} */ + +#endif /* _FSL_DEBUGCONSOLE_H_ */ + diff --git a/drivers/Inc/fsl_clock.h b/drivers/Inc/fsl_clock.h new file mode 100644 index 0000000..500ef62 --- /dev/null +++ b/drivers/Inc/fsl_clock.h @@ -0,0 +1,1506 @@ +/* + * Copyright 2017 - 2021 , 2023 NXP + * All rights reserved. + * + * SPDX-License-Identifier: BSD-3-Clause + */ + +#ifndef _FSL_CLOCK_H_ +#define _FSL_CLOCK_H_ + +#include "fsl_common.h" + +/*! @addtogroup clock */ +/*! @{ */ + +/*! @file */ + +/******************************************************************************* + * Definitions + *****************************************************************************/ + +/*! @name Driver version */ +/*@{*/ +/*! @brief CLOCK driver version 2.3.8. */ +#define FSL_CLOCK_DRIVER_VERSION (MAKE_VERSION(2, 3, 8)) +/*@}*/ + +/*! @brief Configure whether driver controls clock + * + * When set to 0, peripheral drivers will enable clock in initialize function + * and disable clock in de-initialize function. When set to 1, peripheral + * driver will not control the clock, application could control the clock out of + * the driver. + * + * @note All drivers share this feature switcher. If it is set to 1, application + * should handle clock enable and disable for all drivers. + */ +#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)) +#define FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL 0 +#endif + +/*! + * @brief User-defined the size of cache for CLOCK_PllGetConfig() function. + * + * Once define this MACRO to be non-zero value, CLOCK_PllGetConfig() function + * would cache the recent calulation and accelerate the execution to get the + * right settings. + */ +#ifndef CLOCK_USR_CFG_PLL_CONFIG_CACHE_COUNT +#define CLOCK_USR_CFG_PLL_CONFIG_CACHE_COUNT 2U +#endif + +/* Definition for delay API in clock driver, users can redefine it to the real application. */ +#ifndef SDK_DEVICE_MAXIMUM_CPU_CLOCK_FREQUENCY +#define SDK_DEVICE_MAXIMUM_CPU_CLOCK_FREQUENCY (150000000UL) +#endif + +/*! @brief Clock ip name array for ROM. */ +#define ROM_CLOCKS \ + { \ + kCLOCK_Rom \ + } +/*! @brief Clock ip name array for SRAM. */ +#define SRAM_CLOCKS \ + { \ + kCLOCK_Sram1, kCLOCK_Sram2, kCLOCK_Sram3, kCLOCK_Sram4 \ + } +/*! @brief Clock ip name array for FLASH. */ +#define FLASH_CLOCKS \ + { \ + kCLOCK_Flash \ + } +/*! @brief Clock ip name array for FMC. */ +#define FMC_CLOCKS \ + { \ + kCLOCK_Fmc \ + } +/*! @brief Clock ip name array for INPUTMUX. */ +#define INPUTMUX_CLOCKS \ + { \ + kCLOCK_InputMux0 \ + } +/*! @brief Clock ip name array for IOCON. */ +#define IOCON_CLOCKS \ + { \ + kCLOCK_Iocon \ + } +/*! @brief Clock ip name array for GPIO. */ +#define GPIO_CLOCKS \ + { \ + kCLOCK_Gpio0, kCLOCK_Gpio1, kCLOCK_Gpio2, kCLOCK_Gpio3 \ + } +/*! @brief Clock ip name array for PINT. */ +#define PINT_CLOCKS \ + { \ + kCLOCK_Pint \ + } +/*! @brief Clock ip name array for GINT. */ +#define GINT_CLOCKS \ + { \ + kCLOCK_Gint, kCLOCK_Gint \ + } +/*! @brief Clock ip name array for DMA. */ +#define DMA_CLOCKS \ + { \ + kCLOCK_Dma0, kCLOCK_Dma1 \ + } +/*! @brief Clock ip name array for CRC. */ +#define CRC_CLOCKS \ + { \ + kCLOCK_Crc \ + } +/*! @brief Clock ip name array for WWDT. */ +#define WWDT_CLOCKS \ + { \ + kCLOCK_Wwdt \ + } +/*! @brief Clock ip name array for RTC. */ +#define RTC_CLOCKS \ + { \ + kCLOCK_Rtc \ + } +/*! @brief Clock ip name array for Mailbox. */ +#define MAILBOX_CLOCKS \ + { \ + kCLOCK_Mailbox \ + } +/*! @brief Clock ip name array for LPADC. */ +#define LPADC_CLOCKS \ + { \ + kCLOCK_Adc0 \ + } +/*! @brief Clock ip name array for MRT. */ +#define MRT_CLOCKS \ + { \ + kCLOCK_Mrt \ + } +/*! @brief Clock ip name array for OSTIMER. */ +#define OSTIMER_CLOCKS \ + { \ + kCLOCK_OsTimer0 \ + } +/*! @brief Clock ip name array for SCT0. */ +#define SCT_CLOCKS \ + { \ + kCLOCK_Sct0 \ + } +/*! @brief Clock ip name array for UTICK. */ +#define UTICK_CLOCKS \ + { \ + kCLOCK_Utick0 \ + } +/*! @brief Clock ip name array for FLEXCOMM. */ +#define FLEXCOMM_CLOCKS \ + { \ + kCLOCK_FlexComm0, kCLOCK_FlexComm1, kCLOCK_FlexComm2, kCLOCK_FlexComm3, kCLOCK_FlexComm4, kCLOCK_FlexComm5, \ + kCLOCK_FlexComm6, kCLOCK_FlexComm7, kCLOCK_Hs_Lspi \ + } +/*! @brief Clock ip name array for LPUART. */ +#define LPUART_CLOCKS \ + { \ + kCLOCK_MinUart0, kCLOCK_MinUart1, kCLOCK_MinUart2, kCLOCK_MinUart3, kCLOCK_MinUart4, kCLOCK_MinUart5, \ + kCLOCK_MinUart6, kCLOCK_MinUart7 \ + } + +/*! @brief Clock ip name array for BI2C. */ +#define BI2C_CLOCKS \ + { \ + kCLOCK_BI2c0, kCLOCK_BI2c1, kCLOCK_BI2c2, kCLOCK_BI2c3, kCLOCK_BI2c4, kCLOCK_BI2c5, kCLOCK_BI2c6, kCLOCK_BI2c7 \ + } +/*! @brief Clock ip name array for LSPI. */ +#define LPSPI_CLOCKS \ + { \ + kCLOCK_LSpi0, kCLOCK_LSpi1, kCLOCK_LSpi2, kCLOCK_LSpi3, kCLOCK_LSpi4, kCLOCK_LSpi5, kCLOCK_LSpi6, kCLOCK_LSpi7 \ + } +/*! @brief Clock ip name array for FLEXI2S. */ +#define FLEXI2S_CLOCKS \ + { \ + kCLOCK_FlexI2s0, kCLOCK_FlexI2s1, kCLOCK_FlexI2s2, kCLOCK_FlexI2s3, kCLOCK_FlexI2s4, kCLOCK_FlexI2s5, \ + kCLOCK_FlexI2s6, kCLOCK_FlexI2s7 \ + } +/*! @brief Clock ip name array for CTIMER. */ +#define CTIMER_CLOCKS \ + { \ + kCLOCK_Timer0, kCLOCK_Timer1, kCLOCK_Timer2, kCLOCK_Timer3, kCLOCK_Timer4 \ + } +/*! @brief Clock ip name array for COMP */ +#define COMP_CLOCKS \ + { \ + kCLOCK_Comp \ + } +/*! @brief Clock ip name array for SDIO. */ +#define SDIO_CLOCKS \ + { \ + kCLOCK_Sdio \ + } +/*! @brief Clock ip name array for USB1CLK. */ +#define USB1CLK_CLOCKS \ + { \ + kCLOCK_Usb1Clk \ + } +/*! @brief Clock ip name array for FREQME. */ +#define FREQME_CLOCKS \ + { \ + kCLOCK_Freqme \ + } +/*! @brief Clock ip name array for USBRAM. */ +#define USBRAM_CLOCKS \ + { \ + kCLOCK_UsbRam1 \ + } +/*! @brief Clock ip name array for RNG. */ +#define RNG_CLOCKS \ + { \ + kCLOCK_Rng \ + } +/*! @brief Clock ip name array for USBHMR0. */ +#define USBHMR0_CLOCKS \ + { \ + kCLOCK_Usbhmr0 \ + } +/*! @brief Clock ip name array for USBHSL0. */ +#define USBHSL0_CLOCKS \ + { \ + kCLOCK_Usbhsl0 \ + } +/*! @brief Clock ip name array for HashCrypt. */ +#define HASHCRYPT_CLOCKS \ + { \ + kCLOCK_HashCrypt \ + } +/*! @brief Clock ip name array for PowerQuad. */ +#define POWERQUAD_CLOCKS \ + { \ + kCLOCK_PowerQuad \ + } +/*! @brief Clock ip name array for PLULUT. */ +#define PLULUT_CLOCKS \ + { \ + kCLOCK_PluLut \ + } +/*! @brief Clock ip name array for PUF. */ +#define PUF_CLOCKS \ + { \ + kCLOCK_Puf \ + } +/*! @brief Clock ip name array for CASPER. */ +#define CASPER_CLOCKS \ + { \ + kCLOCK_Casper \ + } +/*! @brief Clock ip name array for ANALOGCTRL. */ +#define ANALOGCTRL_CLOCKS \ + { \ + kCLOCK_AnalogCtrl \ + } +/*! @brief Clock ip name array for HS_LSPI. */ +#define HS_LSPI_CLOCKS \ + { \ + kCLOCK_Hs_Lspi \ + } +/*! @brief Clock ip name array for GPIO_SEC. */ +#define GPIO_SEC_CLOCKS \ + { \ + kCLOCK_Gpio_Sec \ + } +/*! @brief Clock ip name array for GPIO_SEC_INT. */ +#define GPIO_SEC_INT_CLOCKS \ + { \ + kCLOCK_Gpio_Sec_Int \ + } +/*! @brief Clock ip name array for USBD. */ +#define USBD_CLOCKS \ + { \ + kCLOCK_Usbd0, kCLOCK_Usbh1, kCLOCK_Usbd1 \ + } +/*! @brief Clock ip name array for USBH. */ +#define USBH_CLOCKS \ + { \ + kCLOCK_Usbh1 \ + } +#define PLU_CLOCKS \ + { \ + kCLOCK_PluLut \ + } +#define SYSCTL_CLOCKS \ + { \ + kCLOCK_Sysctl \ + } +/*! @brief Clock gate name used for CLOCK_EnableClock/CLOCK_DisableClock. */ +/*------------------------------------------------------------------------------ + clock_ip_name_t definition: +------------------------------------------------------------------------------*/ + +#define CLK_GATE_REG_OFFSET_SHIFT 8U +#define CLK_GATE_REG_OFFSET_MASK 0xFFFFFF00U +#define CLK_GATE_BIT_SHIFT_SHIFT 0U +#define CLK_GATE_BIT_SHIFT_MASK 0x000000FFU + +#define CLK_GATE_DEFINE(reg_offset, bit_shift) \ + ((((reg_offset) << CLK_GATE_REG_OFFSET_SHIFT) & CLK_GATE_REG_OFFSET_MASK) | \ + (((bit_shift) << CLK_GATE_BIT_SHIFT_SHIFT) & CLK_GATE_BIT_SHIFT_MASK)) + +#define CLK_GATE_ABSTRACT_REG_OFFSET(x) (((uint32_t)(x)&CLK_GATE_REG_OFFSET_MASK) >> CLK_GATE_REG_OFFSET_SHIFT) +#define CLK_GATE_ABSTRACT_BITS_SHIFT(x) (((uint32_t)(x)&CLK_GATE_BIT_SHIFT_MASK) >> CLK_GATE_BIT_SHIFT_SHIFT) + +#define AHB_CLK_CTRL0 0 +#define AHB_CLK_CTRL1 1 +#define AHB_CLK_CTRL2 2 + +/*! @brief Clock gate name used for CLOCK_EnableClock/CLOCK_DisableClock. */ +typedef enum _clock_ip_name +{ + kCLOCK_IpInvalid = 0U, /*!< Invalid Ip Name. */ + kCLOCK_Rom = CLK_GATE_DEFINE(AHB_CLK_CTRL0, 1), /*!< Clock gate name: Rom. */ + + kCLOCK_Sram1 = CLK_GATE_DEFINE(AHB_CLK_CTRL0, 3), /*!< Clock gate name: Sram1. */ + + kCLOCK_Sram2 = CLK_GATE_DEFINE(AHB_CLK_CTRL0, 4), /*!< Clock gate name: Sram2. */ + + kCLOCK_Sram3 = CLK_GATE_DEFINE(AHB_CLK_CTRL0, 5), /*!< Clock gate name: Sram3. */ + + kCLOCK_Sram4 = CLK_GATE_DEFINE(AHB_CLK_CTRL0, 6), /*!< Clock gate name: Sram4. */ + + kCLOCK_Flash = CLK_GATE_DEFINE(AHB_CLK_CTRL0, 7), /*!< Clock gate name: Flash. */ + + kCLOCK_Fmc = CLK_GATE_DEFINE(AHB_CLK_CTRL0, 8), /*!< Clock gate name: Fmc. */ + + kCLOCK_InputMux = CLK_GATE_DEFINE(AHB_CLK_CTRL0, 11), /*!< Clock gate name: InputMux. */ + + kCLOCK_Iocon = CLK_GATE_DEFINE(AHB_CLK_CTRL0, 13), /*!< Clock gate name: Iocon. */ + + kCLOCK_Gpio0 = CLK_GATE_DEFINE(AHB_CLK_CTRL0, 14), /*!< Clock gate name: Gpio0. */ + + kCLOCK_Gpio1 = CLK_GATE_DEFINE(AHB_CLK_CTRL0, 15), /*!< Clock gate name: Gpio1. */ + + kCLOCK_Gpio2 = CLK_GATE_DEFINE(AHB_CLK_CTRL0, 16), /*!< Clock gate name: Gpio2. */ + + kCLOCK_Gpio3 = CLK_GATE_DEFINE(AHB_CLK_CTRL0, 17), /*!< Clock gate name: Gpio3. */ + + kCLOCK_Pint = CLK_GATE_DEFINE(AHB_CLK_CTRL0, 18), /*!< Clock gate name: Pint. */ + + kCLOCK_Gint = CLK_GATE_DEFINE(AHB_CLK_CTRL0, 19), /*!< Clock gate name: Gint. */ + + kCLOCK_Dma0 = CLK_GATE_DEFINE(AHB_CLK_CTRL0, 20), /*!< Clock gate name: Dma0. */ + + kCLOCK_Crc = CLK_GATE_DEFINE(AHB_CLK_CTRL0, 21), /*!< Clock gate name: Crc. */ + + kCLOCK_Wwdt = CLK_GATE_DEFINE(AHB_CLK_CTRL0, 22), /*!< Clock gate name: Wwdt. */ + + kCLOCK_Rtc = CLK_GATE_DEFINE(AHB_CLK_CTRL0, 23), /*!< Clock gate name: Rtc. */ + + kCLOCK_Mailbox = CLK_GATE_DEFINE(AHB_CLK_CTRL0, 26), /*!< Clock gate name: Mailbox. */ + + kCLOCK_Adc0 = CLK_GATE_DEFINE(AHB_CLK_CTRL0, 27), /*!< Clock gate name: Adc0. */ + + kCLOCK_Mrt = CLK_GATE_DEFINE(AHB_CLK_CTRL1, 0), /*!< Clock gate name: Mrt. */ + + kCLOCK_OsTimer0 = CLK_GATE_DEFINE(AHB_CLK_CTRL1, 1), /*!< Clock gate name: OsTimer0. */ + + kCLOCK_Sct0 = CLK_GATE_DEFINE(AHB_CLK_CTRL1, 2), /*!< Clock gate name: Sct0. */ + + kCLOCK_Utick0 = CLK_GATE_DEFINE(AHB_CLK_CTRL1, 10), /*!< Clock gate name: Utick0. */ + + kCLOCK_FlexComm0 = CLK_GATE_DEFINE(AHB_CLK_CTRL1, 11), /*!< Clock gate name: FlexComm0. */ + + kCLOCK_FlexComm1 = CLK_GATE_DEFINE(AHB_CLK_CTRL1, 12), /*!< Clock gate name: FlexComm1. */ + + kCLOCK_FlexComm2 = CLK_GATE_DEFINE(AHB_CLK_CTRL1, 13), /*!< Clock gate name: FlexComm2. */ + + kCLOCK_FlexComm3 = CLK_GATE_DEFINE(AHB_CLK_CTRL1, 14), /*!< Clock gate name: FlexComm3. */ + + kCLOCK_FlexComm4 = CLK_GATE_DEFINE(AHB_CLK_CTRL1, 15), /*!< Clock gate name: FlexComm4. */ + + kCLOCK_FlexComm5 = CLK_GATE_DEFINE(AHB_CLK_CTRL1, 16), /*!< Clock gate name: FlexComm5. */ + + kCLOCK_FlexComm6 = CLK_GATE_DEFINE(AHB_CLK_CTRL1, 17), /*!< Clock gate name: FlexComm6. */ + + kCLOCK_FlexComm7 = CLK_GATE_DEFINE(AHB_CLK_CTRL1, 18), /*!< Clock gate name: FlexComm7. */ + + kCLOCK_MinUart0 = CLK_GATE_DEFINE(AHB_CLK_CTRL1, 11), /*!< Clock gate name: MinUart0. */ + + kCLOCK_MinUart1 = CLK_GATE_DEFINE(AHB_CLK_CTRL1, 12), /*!< Clock gate name: MinUart1. */ + + kCLOCK_MinUart2 = CLK_GATE_DEFINE(AHB_CLK_CTRL1, 13), /*!< Clock gate name: MinUart2. */ + + kCLOCK_MinUart3 = CLK_GATE_DEFINE(AHB_CLK_CTRL1, 14), /*!< Clock gate name: MinUart3. */ + + kCLOCK_MinUart4 = CLK_GATE_DEFINE(AHB_CLK_CTRL1, 15), /*!< Clock gate name: MinUart4. */ + + kCLOCK_MinUart5 = CLK_GATE_DEFINE(AHB_CLK_CTRL1, 16), /*!< Clock gate name: MinUart5. */ + + kCLOCK_MinUart6 = CLK_GATE_DEFINE(AHB_CLK_CTRL1, 17), /*!< Clock gate name: MinUart6. */ + + kCLOCK_MinUart7 = CLK_GATE_DEFINE(AHB_CLK_CTRL1, 18), /*!< Clock gate name: MinUart7. */ + + kCLOCK_LSpi0 = CLK_GATE_DEFINE(AHB_CLK_CTRL1, 11), /*!< Clock gate name: LSpi0. */ + + kCLOCK_LSpi1 = CLK_GATE_DEFINE(AHB_CLK_CTRL1, 12), /*!< Clock gate name: LSpi1. */ + + kCLOCK_LSpi2 = CLK_GATE_DEFINE(AHB_CLK_CTRL1, 13), /*!< Clock gate name: LSpi2. */ + + kCLOCK_LSpi3 = CLK_GATE_DEFINE(AHB_CLK_CTRL1, 14), /*!< Clock gate name: LSpi3. */ + + kCLOCK_LSpi4 = CLK_GATE_DEFINE(AHB_CLK_CTRL1, 15), /*!< Clock gate name: LSpi4. */ + + kCLOCK_LSpi5 = CLK_GATE_DEFINE(AHB_CLK_CTRL1, 16), /*!< Clock gate name: LSpi5. */ + + kCLOCK_LSpi6 = CLK_GATE_DEFINE(AHB_CLK_CTRL1, 17), /*!< Clock gate name: LSpi6. */ + + kCLOCK_LSpi7 = CLK_GATE_DEFINE(AHB_CLK_CTRL1, 18), /*!< Clock gate name: LSpi7. */ + + kCLOCK_BI2c0 = CLK_GATE_DEFINE(AHB_CLK_CTRL1, 11), /*!< Clock gate name: BI2c0. */ + + kCLOCK_BI2c1 = CLK_GATE_DEFINE(AHB_CLK_CTRL1, 12), /*!< Clock gate name: BI2c1. */ + + kCLOCK_BI2c2 = CLK_GATE_DEFINE(AHB_CLK_CTRL1, 13), /*!< Clock gate name: BI2c2. */ + + kCLOCK_BI2c3 = CLK_GATE_DEFINE(AHB_CLK_CTRL1, 14), /*!< Clock gate name: BI2c3. */ + + kCLOCK_BI2c4 = CLK_GATE_DEFINE(AHB_CLK_CTRL1, 15), /*!< Clock gate name: BI2c4. */ + + kCLOCK_BI2c5 = CLK_GATE_DEFINE(AHB_CLK_CTRL1, 16), /*!< Clock gate name: BI2c5. */ + + kCLOCK_BI2c6 = CLK_GATE_DEFINE(AHB_CLK_CTRL1, 17), /*!< Clock gate name: BI2c6. */ + + kCLOCK_BI2c7 = CLK_GATE_DEFINE(AHB_CLK_CTRL1, 18), /*!< Clock gate name: BI2c7. */ + + kCLOCK_FlexI2s0 = CLK_GATE_DEFINE(AHB_CLK_CTRL1, 11), /*!< Clock gate name: FlexI2s0. */ + + kCLOCK_FlexI2s1 = CLK_GATE_DEFINE(AHB_CLK_CTRL1, 12), /*!< Clock gate name: FlexI2s1. */ + + kCLOCK_FlexI2s2 = CLK_GATE_DEFINE(AHB_CLK_CTRL1, 13), /*!< Clock gate name: FlexI2s2. */ + + kCLOCK_FlexI2s3 = CLK_GATE_DEFINE(AHB_CLK_CTRL1, 14), /*!< Clock gate name: FlexI2s3. */ + + kCLOCK_FlexI2s4 = CLK_GATE_DEFINE(AHB_CLK_CTRL1, 15), /*!< Clock gate name: FlexI2s4. */ + + kCLOCK_FlexI2s5 = CLK_GATE_DEFINE(AHB_CLK_CTRL1, 16), /*!< Clock gate name: FlexI2s5. */ + + kCLOCK_FlexI2s6 = CLK_GATE_DEFINE(AHB_CLK_CTRL1, 17), /*!< Clock gate name: FlexI2s6. */ + + kCLOCK_FlexI2s7 = CLK_GATE_DEFINE(AHB_CLK_CTRL1, 18), /*!< Clock gate name: FlexI2s7. */ + + kCLOCK_Timer2 = CLK_GATE_DEFINE(AHB_CLK_CTRL1, 22), /*!< Clock gate name: Timer2. */ + + kCLOCK_Usbd0 = CLK_GATE_DEFINE(AHB_CLK_CTRL1, 25), /*!< Clock gate name: Usbd0. */ + + kCLOCK_Timer0 = CLK_GATE_DEFINE(AHB_CLK_CTRL1, 26), /*!< Clock gate name: Timer0. */ + + kCLOCK_Timer1 = CLK_GATE_DEFINE(AHB_CLK_CTRL1, 27), /*!< Clock gate name: Timer1. */ + + kCLOCK_Pvt = CLK_GATE_DEFINE(AHB_CLK_CTRL1, 28), /*!< Clock gate name: Pvt. */ + + kCLOCK_Ezha = CLK_GATE_DEFINE(AHB_CLK_CTRL1, 30), /*!< Clock gate name: Ezha. */ + + kCLOCK_Ezhb = CLK_GATE_DEFINE(AHB_CLK_CTRL1, 31), /*!< Clock gate name: Ezhb. */ + + kCLOCK_Dma1 = CLK_GATE_DEFINE(AHB_CLK_CTRL2, 1), /*!< Clock gate name: Dma1. */ + + kCLOCK_Comp = CLK_GATE_DEFINE(AHB_CLK_CTRL2, 2), /*!< Clock gate name: Comp. */ + + kCLOCK_Sdio = CLK_GATE_DEFINE(AHB_CLK_CTRL2, 3), /*!< Clock gate name: Sdio. */ + + kCLOCK_Usbh1 = CLK_GATE_DEFINE(AHB_CLK_CTRL2, 4), /*!< Clock gate name: Usbh1. */ + + kCLOCK_Usbd1 = CLK_GATE_DEFINE(AHB_CLK_CTRL2, 5), /*!< Clock gate name: Usbd1. */ + + kCLOCK_UsbRam1 = CLK_GATE_DEFINE(AHB_CLK_CTRL2, 6), /*!< Clock gate name: UsbRam1. */ + + kCLOCK_Usb1Clk = CLK_GATE_DEFINE(AHB_CLK_CTRL2, 7), /*!< Clock gate name: Usb1Clk. */ + + kCLOCK_Freqme = CLK_GATE_DEFINE(AHB_CLK_CTRL2, 8), /*!< Clock gate name: Freqme. */ + + kCLOCK_Rng = CLK_GATE_DEFINE(AHB_CLK_CTRL2, 13), /*!< Clock gate name: Rng. */ + + kCLOCK_InputMux1 = CLK_GATE_DEFINE(AHB_CLK_CTRL2, 14), /*!< Clock gate name: InputMux1. */ + + kCLOCK_Sysctl = CLK_GATE_DEFINE(AHB_CLK_CTRL2, 15), /*!< Clock gate name: Sysctl. */ + + kCLOCK_Usbhmr0 = CLK_GATE_DEFINE(AHB_CLK_CTRL2, 16), /*!< Clock gate name: Usbhmr0. */ + + kCLOCK_Usbhsl0 = CLK_GATE_DEFINE(AHB_CLK_CTRL2, 17), /*!< Clock gate name: Usbhsl0. */ + + kCLOCK_HashCrypt = CLK_GATE_DEFINE(AHB_CLK_CTRL2, 18), /*!< Clock gate name: HashCrypt. */ + + kCLOCK_PowerQuad = CLK_GATE_DEFINE(AHB_CLK_CTRL2, 19), /*!< Clock gate name: PowerQuad. */ + + kCLOCK_PluLut = CLK_GATE_DEFINE(AHB_CLK_CTRL2, 20), /*!< Clock gate name: PluLut. */ + + kCLOCK_Timer3 = CLK_GATE_DEFINE(AHB_CLK_CTRL2, 21), /*!< Clock gate name: Timer3. */ + + kCLOCK_Timer4 = CLK_GATE_DEFINE(AHB_CLK_CTRL2, 22), /*!< Clock gate name: Timer4. */ + + kCLOCK_Puf = CLK_GATE_DEFINE(AHB_CLK_CTRL2, 23), /*!< Clock gate name: Puf. */ + + kCLOCK_Casper = CLK_GATE_DEFINE(AHB_CLK_CTRL2, 24), /*!< Clock gate name: Casper. */ + + kCLOCK_AnalogCtrl = CLK_GATE_DEFINE(AHB_CLK_CTRL2, 27), /*!< Clock gate name: AnalogCtrl. */ + + kCLOCK_Hs_Lspi = CLK_GATE_DEFINE(AHB_CLK_CTRL2, 28), /*!< Clock gate name: Lspi. */ + + kCLOCK_Gpio_Sec = CLK_GATE_DEFINE(AHB_CLK_CTRL2, 29), /*!< Clock gate name: GPIO Sec. */ + + kCLOCK_Gpio_Sec_Int = CLK_GATE_DEFINE(AHB_CLK_CTRL2, 30) /*!< Clock gate name: GPIO SEC Int. */ +} clock_ip_name_t; + +/*! @brief Peripherals clock source definition. */ +#define BUS_CLK kCLOCK_BusClk + +#define I2C0_CLK_SRC BUS_CLK + +/*! @brief Clock name used to get clock frequency. */ +typedef enum _clock_name +{ + kCLOCK_CoreSysClk, /*!< Core/system clock (aka MAIN_CLK) */ + kCLOCK_BusClk, /*!< Bus clock (AHB clock) */ + kCLOCK_ClockOut, /*!< CLOCKOUT */ + kCLOCK_FroHf, /*!< FRO48/96 */ + kCLOCK_Pll1Out, /*!< PLL1 Output */ + kCLOCK_Mclk, /*!< MCLK */ + kCLOCK_Fro12M, /*!< FRO12M */ + kCLOCK_ExtClk, /*!< External Clock */ + kCLOCK_Pll0Out, /*!< PLL0 Output */ + kCLOCK_FlexI2S, /*!< FlexI2S clock */ + +} clock_name_t; + +/*! @brief Clock Mux Switches + * The encoding is as follows each connection identified is 32bits wide while 24bits are valuable + * starting from LSB upwards + * + * [4 bits for choice, 0 means invalid choice] [8 bits mux ID]* + * + */ + +#define CLK_ATTACH_ID(mux, sel, pos) \ + ((((uint32_t)(mux) << 0U) | (((uint32_t)(sel) + 1U) & 0xFU) << 8U) << ((uint32_t)(pos)*12U)) +#define MUX_A(mux, sel) CLK_ATTACH_ID((mux), (sel), 0U) +#define MUX_B(mux, sel, selector) (CLK_ATTACH_ID((mux), (sel), 1U) | ((selector) << 24U)) + +#define GET_ID_ITEM(connection) ((connection)&0xFFFU) +#define GET_ID_NEXT_ITEM(connection) ((connection) >> 12U) +#define GET_ID_ITEM_MUX(connection) (((uint8_t)connection) & 0xFFU) +#define GET_ID_ITEM_SEL(connection) ((uint8_t)((((uint32_t)(connection)&0xF00U) >> 8U) - 1U)) +#define GET_ID_SELECTOR(connection) ((connection)&0xF000000U) + +#define CM_SYSTICKCLKSEL0 0U +#define CM_SYSTICKCLKSEL1 1U +#define CM_TRACECLKSEL 2U +#define CM_CTIMERCLKSEL0 3U +#define CM_CTIMERCLKSEL1 4U +#define CM_CTIMERCLKSEL2 5U +#define CM_CTIMERCLKSEL3 6U +#define CM_CTIMERCLKSEL4 7U +#define CM_MAINCLKSELA 8U +#define CM_MAINCLKSELB 9U +#define CM_CLKOUTCLKSEL 10U +#define CM_PLL0CLKSEL 12U +#define CM_PLL1CLKSEL 13U +#define CM_ADCASYNCCLKSEL 17U +#define CM_USB0CLKSEL 18U +#define CM_FXCOMCLKSEL0 20U +#define CM_FXCOMCLKSEL1 21U +#define CM_FXCOMCLKSEL2 22U +#define CM_FXCOMCLKSEL3 23U +#define CM_FXCOMCLKSEL4 24U +#define CM_FXCOMCLKSEL5 25U +#define CM_FXCOMCLKSEL6 26U +#define CM_FXCOMCLKSEL7 27U +#define CM_HSLSPICLKSEL 28U +#define CM_MCLKCLKSEL 32U +#define CM_SCTCLKSEL 36U +#define CM_SDIOCLKSEL 38U + +#define CM_RTCOSC32KCLKSEL 63U + +/*! + * @brief The enumerator of clock attach Id. + */ +typedef enum _clock_attach_id +{ + + kFRO12M_to_MAIN_CLK = MUX_A(CM_MAINCLKSELA, 0) | MUX_B(CM_MAINCLKSELB, 0, 0), /*!< Attach FRO12M to MAIN_CLK. */ + + kEXT_CLK_to_MAIN_CLK = MUX_A(CM_MAINCLKSELA, 1) | MUX_B(CM_MAINCLKSELB, 0, 0), /*!< Attach EXT_CLK to MAIN_CLK. */ + + kFRO1M_to_MAIN_CLK = MUX_A(CM_MAINCLKSELA, 2) | MUX_B(CM_MAINCLKSELB, 0, 0), /*!< Attach FRO1M to MAIN_CLK. */ + + kFRO_HF_to_MAIN_CLK = MUX_A(CM_MAINCLKSELA, 3) | MUX_B(CM_MAINCLKSELB, 0, 0), /*!< Attach FRO_HF to MAIN_CLK. */ + + kPLL0_to_MAIN_CLK = MUX_A(CM_MAINCLKSELA, 0) | MUX_B(CM_MAINCLKSELB, 1, 0), /*!< Attach PLL0 to MAIN_CLK. */ + + kPLL1_to_MAIN_CLK = MUX_A(CM_MAINCLKSELA, 0) | MUX_B(CM_MAINCLKSELB, 2, 0), /*!< Attach PLL1 to MAIN_CLK. */ + + kOSC32K_to_MAIN_CLK = MUX_A(CM_MAINCLKSELA, 0) | MUX_B(CM_MAINCLKSELB, 3, 0), /*!< Attach OSC32K to MAIN_CLK. */ + + kMAIN_CLK_to_CLKOUT = MUX_A(CM_CLKOUTCLKSEL, 0), /*!< Attach MAIN_CLK to CLKOUT. */ + + kPLL0_to_CLKOUT = MUX_A(CM_CLKOUTCLKSEL, 1), /*!< Attach PLL0 to CLKOUT. */ + + kEXT_CLK_to_CLKOUT = MUX_A(CM_CLKOUTCLKSEL, 2), /*!< Attach EXT_CLK to CLKOUT. */ + + kFRO_HF_to_CLKOUT = MUX_A(CM_CLKOUTCLKSEL, 3), /*!< Attach FRO_HF to CLKOUT. */ + + kFRO1M_to_CLKOUT = MUX_A(CM_CLKOUTCLKSEL, 4), /*!< Attach FRO1M to CLKOUT. */ + + kPLL1_to_CLKOUT = MUX_A(CM_CLKOUTCLKSEL, 5), /*!< Attach PLL1 to CLKOUT. */ + + kOSC32K_to_CLKOUT = MUX_A(CM_CLKOUTCLKSEL, 6), /*!< Attach OSC32K to CLKOUT. */ + + kNONE_to_SYS_CLKOUT = MUX_A(CM_CLKOUTCLKSEL, 7), /*!< Attach NONE to SYS_CLKOUT. */ + + kFRO12M_to_PLL0 = MUX_A(CM_PLL0CLKSEL, 0), /*!< Attach FRO12M to PLL0. */ + + kEXT_CLK_to_PLL0 = MUX_A(CM_PLL0CLKSEL, 1), /*!< Attach EXT_CLK to PLL0. */ + + kFRO1M_to_PLL0 = MUX_A(CM_PLL0CLKSEL, 2), /*!< Attach FRO1M to PLL0. */ + + kOSC32K_to_PLL0 = MUX_A(CM_PLL0CLKSEL, 3), /*!< Attach OSC32K to PLL0. */ + + kNONE_to_PLL0 = MUX_A(CM_PLL0CLKSEL, 7), /*!< Attach NONE to PLL0. */ + + kMAIN_CLK_to_ADC_CLK = MUX_A(CM_ADCASYNCCLKSEL, 0), /*!< Attach MAIN_CLK to ADC_CLK. */ + + kPLL0_to_ADC_CLK = MUX_A(CM_ADCASYNCCLKSEL, 1), /*!< Attach PLL0 to ADC_CLK. */ + + kFRO_HF_to_ADC_CLK = MUX_A(CM_ADCASYNCCLKSEL, 2), /*!< Attach FRO_HF to ADC_CLK. */ + + kNONE_to_ADC_CLK = MUX_A(CM_ADCASYNCCLKSEL, 7), /*!< Attach NONE to ADC_CLK. */ + + kMAIN_CLK_to_USB0_CLK = MUX_A(CM_USB0CLKSEL, 0), /*!< Attach MAIN_CLK to USB0_CLK. */ + + kPLL0_to_USB0_CLK = MUX_A(CM_USB0CLKSEL, 1), /*!< Attach PLL0 to USB0_CLK. */ + + kFRO_HF_to_USB0_CLK = MUX_A(CM_USB0CLKSEL, 3), /*!< Attach FRO_HF to USB0_CLK. */ + + kPLL1_to_USB0_CLK = MUX_A(CM_USB0CLKSEL, 5), /*!< Attach PLL1 to USB0_CLK. */ + + kNONE_to_USB0_CLK = MUX_A(CM_USB0CLKSEL, 7), /*!< Attach NONE to USB0_CLK. */ + + kMAIN_CLK_to_FLEXCOMM0 = MUX_A(CM_FXCOMCLKSEL0, 0), /*!< Attach MAIN_CLK to FLEXCOMM0. */ + + kPLL0_DIV_to_FLEXCOMM0 = MUX_A(CM_FXCOMCLKSEL0, 1), /*!< Attach PLL0_DIV to FLEXCOMM0. */ + + kFRO12M_to_FLEXCOMM0 = MUX_A(CM_FXCOMCLKSEL0, 2), /*!< Attach FRO12M to FLEXCOMM0. */ + + kFRO_HF_DIV_to_FLEXCOMM0 = MUX_A(CM_FXCOMCLKSEL0, 3), /*!< Attach FRO_HF_DIV to FLEXCOMM0. */ + + kFRO1M_to_FLEXCOMM0 = MUX_A(CM_FXCOMCLKSEL0, 4), /*!< Attach FRO1M to FLEXCOMM0. */ + + kMCLK_to_FLEXCOMM0 = MUX_A(CM_FXCOMCLKSEL0, 5), /*!< Attach MCLK to FLEXCOMM0. */ + + kOSC32K_to_FLEXCOMM0 = MUX_A(CM_FXCOMCLKSEL0, 6), /*!< Attach OSC32K to FLEXCOMM0. */ + + kNONE_to_FLEXCOMM0 = MUX_A(CM_FXCOMCLKSEL0, 7), /*!< Attach NONE to FLEXCOMM0. */ + + kMAIN_CLK_to_FLEXCOMM1 = MUX_A(CM_FXCOMCLKSEL1, 0), /*!< Attach MAIN_CLK to FLEXCOMM1. */ + + kPLL0_DIV_to_FLEXCOMM1 = MUX_A(CM_FXCOMCLKSEL1, 1), /*!< Attach PLL0_DIV to FLEXCOMM1. */ + + kFRO12M_to_FLEXCOMM1 = MUX_A(CM_FXCOMCLKSEL1, 2), /*!< Attach FRO12M to FLEXCOMM1. */ + + kFRO_HF_DIV_to_FLEXCOMM1 = MUX_A(CM_FXCOMCLKSEL1, 3), /*!< Attach FRO_HF_DIV to FLEXCOMM1. */ + + kFRO1M_to_FLEXCOMM1 = MUX_A(CM_FXCOMCLKSEL1, 4), /*!< Attach FRO1M to FLEXCOMM1. */ + + kMCLK_to_FLEXCOMM1 = MUX_A(CM_FXCOMCLKSEL1, 5), /*!< Attach MCLK to FLEXCOMM1. */ + + kOSC32K_to_FLEXCOMM1 = MUX_A(CM_FXCOMCLKSEL1, 6), /*!< Attach OSC32K to FLEXCOMM1. */ + + kNONE_to_FLEXCOMM1 = MUX_A(CM_FXCOMCLKSEL1, 7), /*!< Attach NONE to FLEXCOMM1. */ + + kMAIN_CLK_to_FLEXCOMM2 = MUX_A(CM_FXCOMCLKSEL2, 0), /*!< Attach MAIN_CLK to FLEXCOMM2. */ + + kPLL0_DIV_to_FLEXCOMM2 = MUX_A(CM_FXCOMCLKSEL2, 1), /*!< Attach PLL0_DIV to FLEXCOMM2. */ + + kFRO12M_to_FLEXCOMM2 = MUX_A(CM_FXCOMCLKSEL2, 2), /*!< Attach FRO12M to FLEXCOMM2. */ + + kFRO_HF_DIV_to_FLEXCOMM2 = MUX_A(CM_FXCOMCLKSEL2, 3), /*!< Attach FRO_HF_DIV to FLEXCOMM2. */ + + kFRO1M_to_FLEXCOMM2 = MUX_A(CM_FXCOMCLKSEL2, 4), /*!< Attach FRO1M to FLEXCOMM2. */ + + kMCLK_to_FLEXCOMM2 = MUX_A(CM_FXCOMCLKSEL2, 5), /*!< Attach MCLK to FLEXCOMM2. */ + + kOSC32K_to_FLEXCOMM2 = MUX_A(CM_FXCOMCLKSEL2, 6), /*!< Attach OSC32K to FLEXCOMM2. */ + + kNONE_to_FLEXCOMM2 = MUX_A(CM_FXCOMCLKSEL2, 7), /*!< Attach NONE to FLEXCOMM2. */ + + kMAIN_CLK_to_FLEXCOMM3 = MUX_A(CM_FXCOMCLKSEL3, 0), /*!< Attach MAIN_CLK to FLEXCOMM3. */ + + kPLL0_DIV_to_FLEXCOMM3 = MUX_A(CM_FXCOMCLKSEL3, 1), /*!< Attach PLL0_DIV to FLEXCOMM3. */ + + kFRO12M_to_FLEXCOMM3 = MUX_A(CM_FXCOMCLKSEL3, 2), /*!< Attach FRO12M to FLEXCOMM3. */ + + kFRO_HF_DIV_to_FLEXCOMM3 = MUX_A(CM_FXCOMCLKSEL3, 3), /*!< Attach FRO_HF_DIV to FLEXCOMM3. */ + + kFRO1M_to_FLEXCOMM3 = MUX_A(CM_FXCOMCLKSEL3, 4), /*!< Attach FRO1M to FLEXCOMM3. */ + + kMCLK_to_FLEXCOMM3 = MUX_A(CM_FXCOMCLKSEL3, 5), /*!< Attach MCLK to FLEXCOMM3. */ + + kOSC32K_to_FLEXCOMM3 = MUX_A(CM_FXCOMCLKSEL3, 6), /*!< Attach OSC32K to FLEXCOMM3. */ + + kNONE_to_FLEXCOMM3 = MUX_A(CM_FXCOMCLKSEL3, 7), /*!< Attach NONE to FLEXCOMM3. */ + + kMAIN_CLK_to_FLEXCOMM4 = MUX_A(CM_FXCOMCLKSEL4, 0), /*!< Attach MAIN_CLK to FLEXCOMM4. */ + + kPLL0_DIV_to_FLEXCOMM4 = MUX_A(CM_FXCOMCLKSEL4, 1), /*!< Attach PLL0_DIV to FLEXCOMM4. */ + + kFRO12M_to_FLEXCOMM4 = MUX_A(CM_FXCOMCLKSEL4, 2), /*!< Attach FRO12M to FLEXCOMM4. */ + + kFRO_HF_DIV_to_FLEXCOMM4 = MUX_A(CM_FXCOMCLKSEL4, 3), /*!< Attach FRO_HF_DIV to FLEXCOMM4. */ + + kFRO1M_to_FLEXCOMM4 = MUX_A(CM_FXCOMCLKSEL4, 4), /*!< Attach FRO1M to FLEXCOMM4. */ + + kMCLK_to_FLEXCOMM4 = MUX_A(CM_FXCOMCLKSEL4, 5), /*!< Attach MCLK to FLEXCOMM4. */ + + kOSC32K_to_FLEXCOMM4 = MUX_A(CM_FXCOMCLKSEL4, 6), /*!< Attach OSC32K to FLEXCOMM4. */ + + kNONE_to_FLEXCOMM4 = MUX_A(CM_FXCOMCLKSEL4, 7), /*!< Attach NONE to FLEXCOMM4. */ + + kMAIN_CLK_to_FLEXCOMM5 = MUX_A(CM_FXCOMCLKSEL5, 0), /*!< Attach MAIN_CLK to FLEXCOMM5. */ + + kPLL0_DIV_to_FLEXCOMM5 = MUX_A(CM_FXCOMCLKSEL5, 1), /*!< Attach PLL0_DIV to FLEXCOMM5. */ + + kFRO12M_to_FLEXCOMM5 = MUX_A(CM_FXCOMCLKSEL5, 2), /*!< Attach FRO12M to FLEXCOMM5. */ + + kFRO_HF_DIV_to_FLEXCOMM5 = MUX_A(CM_FXCOMCLKSEL5, 3), /*!< Attach FRO_HF_DIV to FLEXCOMM5. */ + + kFRO1M_to_FLEXCOMM5 = MUX_A(CM_FXCOMCLKSEL5, 4), /*!< Attach FRO1M to FLEXCOMM5. */ + + kMCLK_to_FLEXCOMM5 = MUX_A(CM_FXCOMCLKSEL5, 5), /*!< Attach MCLK to FLEXCOMM5. */ + + kOSC32K_to_FLEXCOMM5 = MUX_A(CM_FXCOMCLKSEL5, 6), /*!< Attach OSC32K to FLEXCOMM5. */ + + kNONE_to_FLEXCOMM5 = MUX_A(CM_FXCOMCLKSEL5, 7), /*!< Attach NONE to FLEXCOMM5. */ + + kMAIN_CLK_to_FLEXCOMM6 = MUX_A(CM_FXCOMCLKSEL6, 0), /*!< Attach MAIN_CLK to FLEXCOMM6. */ + + kPLL0_DIV_to_FLEXCOMM6 = MUX_A(CM_FXCOMCLKSEL6, 1), /*!< Attach PLL0_DIV to FLEXCOMM6. */ + + kFRO12M_to_FLEXCOMM6 = MUX_A(CM_FXCOMCLKSEL6, 2), /*!< Attach FRO12M to FLEXCOMM6. */ + + kFRO_HF_DIV_to_FLEXCOMM6 = MUX_A(CM_FXCOMCLKSEL6, 3), /*!< Attach FRO_HF_DIV to FLEXCOMM6. */ + + kFRO1M_to_FLEXCOMM6 = MUX_A(CM_FXCOMCLKSEL6, 4), /*!< Attach FRO1M to FLEXCOMM6. */ + + kMCLK_to_FLEXCOMM6 = MUX_A(CM_FXCOMCLKSEL6, 5), /*!< Attach MCLK to FLEXCOMM6. */ + + kOSC32K_to_FLEXCOMM6 = MUX_A(CM_FXCOMCLKSEL6, 6), /*!< Attach OSC32K to FLEXCOMM6. */ + + kNONE_to_FLEXCOMM6 = MUX_A(CM_FXCOMCLKSEL6, 7), /*!< Attach NONE to FLEXCOMM6. */ + + kMAIN_CLK_to_FLEXCOMM7 = MUX_A(CM_FXCOMCLKSEL7, 0), /*!< Attach MAIN_CLK to FLEXCOMM7. */ + + kPLL0_DIV_to_FLEXCOMM7 = MUX_A(CM_FXCOMCLKSEL7, 1), /*!< Attach PLL0_DIV to FLEXCOMM7. */ + + kFRO12M_to_FLEXCOMM7 = MUX_A(CM_FXCOMCLKSEL7, 2), /*!< Attach FRO12M to FLEXCOMM7. */ + + kFRO_HF_DIV_to_FLEXCOMM7 = MUX_A(CM_FXCOMCLKSEL7, 3), /*!< Attach FRO_HF_DIV to FLEXCOMM7. */ + + kFRO1M_to_FLEXCOMM7 = MUX_A(CM_FXCOMCLKSEL7, 4), /*!< Attach FRO1M to FLEXCOMM7. */ + + kMCLK_to_FLEXCOMM7 = MUX_A(CM_FXCOMCLKSEL7, 5), /*!< Attach MCLK to FLEXCOMM7. */ + + kOSC32K_to_FLEXCOMM7 = MUX_A(CM_FXCOMCLKSEL7, 6), /*!< Attach OSC32K to FLEXCOMM7. */ + + kNONE_to_FLEXCOMM7 = MUX_A(CM_FXCOMCLKSEL7, 7), /*!< Attach NONE to FLEXCOMM7. */ + + kMAIN_CLK_to_HSLSPI = MUX_A(CM_HSLSPICLKSEL, 0), /*!< Attach MAIN_CLK to HSLSPI. */ + + kPLL0_DIV_to_HSLSPI = MUX_A(CM_HSLSPICLKSEL, 1), /*!< Attach PLL0_DIV to HSLSPI. */ + + kFRO12M_to_HSLSPI = MUX_A(CM_HSLSPICLKSEL, 2), /*!< Attach FRO12M to HSLSPI. */ + + kFRO_HF_DIV_to_HSLSPI = MUX_A(CM_HSLSPICLKSEL, 3), /*!< Attach FRO_HF_DIV to HSLSPI. */ + + kFRO1M_to_HSLSPI = MUX_A(CM_HSLSPICLKSEL, 4), /*!< Attach FRO1M to HSLSPI. */ + + kOSC32K_to_HSLSPI = MUX_A(CM_HSLSPICLKSEL, 6), /*!< Attach OSC32K to HSLSPI. */ + + kNONE_to_HSLSPI = MUX_A(CM_HSLSPICLKSEL, 7), /*!< Attach NONE to HSLSPI. */ + + kFRO_HF_to_MCLK = MUX_A(CM_MCLKCLKSEL, 0), /*!< Attach FRO_HF to MCLK. */ + + kPLL0_to_MCLK = MUX_A(CM_MCLKCLKSEL, 1), /*!< Attach PLL0 to MCLK. */ + + kNONE_to_MCLK = MUX_A(CM_MCLKCLKSEL, 7), /*!< Attach NONE to MCLK. */ + + kMAIN_CLK_to_SCT_CLK = MUX_A(CM_SCTCLKSEL, 0), /*!< Attach MAIN_CLK to SCT_CLK. */ + + kPLL0_to_SCT_CLK = MUX_A(CM_SCTCLKSEL, 1), /*!< Attach PLL0 to SCT_CLK. */ + + kEXT_CLK_to_SCT_CLK = MUX_A(CM_SCTCLKSEL, 2), /*!< Attach EXT_CLK to SCT_CLK. */ + + kFRO_HF_to_SCT_CLK = MUX_A(CM_SCTCLKSEL, 3), /*!< Attach FRO_HF to SCT_CLK. */ + + kMCLK_to_SCT_CLK = MUX_A(CM_SCTCLKSEL, 5), /*!< Attach MCLK to SCT_CLK. */ + + kNONE_to_SCT_CLK = MUX_A(CM_SCTCLKSEL, 7), /*!< Attach NONE to SCT_CLK. */ + + kMAIN_CLK_to_SDIO_CLK = MUX_A(CM_SDIOCLKSEL, 0), /*!< Attach MAIN_CLK to SDIO_CLK. */ + + kPLL0_to_SDIO_CLK = MUX_A(CM_SDIOCLKSEL, 1), /*!< Attach PLL0 to SDIO_CLK. */ + + kFRO_HF_to_SDIO_CLK = MUX_A(CM_SDIOCLKSEL, 3), /*!< Attach FRO_HF to SDIO_CLK. */ + + kPLL1_to_SDIO_CLK = MUX_A(CM_SDIOCLKSEL, 5), /*!< Attach PLL1 to SDIO_CLK. */ + + kNONE_to_SDIO_CLK = MUX_A(CM_SDIOCLKSEL, 7), /*!< Attach NONE to SDIO_CLK. */ + + kFRO32K_to_OSC32K = MUX_A(CM_RTCOSC32KCLKSEL, 0), /*!< Attach FRO32K to OSC32K. */ + + kXTAL32K_to_OSC32K = MUX_A(CM_RTCOSC32KCLKSEL, 1), /*!< Attach XTAL32K to OSC32K. */ + + kTRACE_DIV_to_TRACE = MUX_A(CM_TRACECLKSEL, 0), /*!< Attach TRACE_DIV to TRACE. */ + + kFRO1M_to_TRACE = MUX_A(CM_TRACECLKSEL, 1), /*!< Attach FRO1M to TRACE. */ + + kOSC32K_to_TRACE = MUX_A(CM_TRACECLKSEL, 2), /*!< Attach OSC32K to TRACE. */ + + kNONE_to_TRACE = MUX_A(CM_TRACECLKSEL, 7), /*!< Attach NONE to TRACE. */ + + kSYSTICK_DIV0_to_SYSTICK0 = MUX_A(CM_SYSTICKCLKSEL0, 0), /*!< Attach SYSTICK_DIV0 to SYSTICK0. */ + + kFRO1M_to_SYSTICK0 = MUX_A(CM_SYSTICKCLKSEL0, 1), /*!< Attach FRO1M to SYSTICK0. */ + + kOSC32K_to_SYSTICK0 = MUX_A(CM_SYSTICKCLKSEL0, 2), /*!< Attach OSC32K to SYSTICK0. */ + + kNONE_to_SYSTICK0 = MUX_A(CM_SYSTICKCLKSEL0, 7), /*!< Attach NONE to SYSTICK0. */ + + kSYSTICK_DIV1_to_SYSTICK1 = MUX_A(CM_SYSTICKCLKSEL1, 0), /*!< Attach SYSTICK_DIV1 to SYSTICK1. */ + + kFRO1M_to_SYSTICK1 = MUX_A(CM_SYSTICKCLKSEL1, 1), /*!< Attach FRO1M to SYSTICK1. */ + + kOSC32K_to_SYSTICK1 = MUX_A(CM_SYSTICKCLKSEL1, 2), /*!< Attach OSC32K to SYSTICK1. */ + + kNONE_to_SYSTICK1 = MUX_A(CM_SYSTICKCLKSEL1, 7), /*!< Attach NONE to SYSTICK1. */ + + kFRO12M_to_PLL1 = MUX_A(CM_PLL1CLKSEL, 0), /*!< Attach FRO12M to PLL1. */ + + kEXT_CLK_to_PLL1 = MUX_A(CM_PLL1CLKSEL, 1), /*!< Attach EXT_CLK to PLL1. */ + + kFRO1M_to_PLL1 = MUX_A(CM_PLL1CLKSEL, 2), /*!< Attach FRO1M to PLL1. */ + + kOSC32K_to_PLL1 = MUX_A(CM_PLL1CLKSEL, 3), /*!< Attach OSC32K to PLL1. */ + + kNONE_to_PLL1 = MUX_A(CM_PLL1CLKSEL, 7), /*!< Attach NONE to PLL1. */ + + kMAIN_CLK_to_CTIMER0 = MUX_A(CM_CTIMERCLKSEL0, 0), /*!< Attach MAIN_CLK to CTIMER0. */ + + kPLL0_to_CTIMER0 = MUX_A(CM_CTIMERCLKSEL0, 1), /*!< Attach PLL0 to CTIMER0. */ + + kFRO_HF_to_CTIMER0 = MUX_A(CM_CTIMERCLKSEL0, 3), /*!< Attach FRO_HF to CTIMER0. */ + + kFRO1M_to_CTIMER0 = MUX_A(CM_CTIMERCLKSEL0, 4), /*!< Attach FRO1M to CTIMER0. */ + + kMCLK_to_CTIMER0 = MUX_A(CM_CTIMERCLKSEL0, 5), /*!< Attach MCLK to CTIMER0. */ + + kOSC32K_to_CTIMER0 = MUX_A(CM_CTIMERCLKSEL0, 6), /*!< Attach OSC32K to CTIMER0. */ + + kNONE_to_CTIMER0 = MUX_A(CM_CTIMERCLKSEL0, 7), /*!< Attach NONE to CTIMER0. */ + + kMAIN_CLK_to_CTIMER1 = MUX_A(CM_CTIMERCLKSEL1, 0), /*!< Attach MAIN_CLK to CTIMER1. */ + + kPLL0_to_CTIMER1 = MUX_A(CM_CTIMERCLKSEL1, 1), /*!< Attach PLL0 to CTIMER1. */ + + kFRO_HF_to_CTIMER1 = MUX_A(CM_CTIMERCLKSEL1, 3), /*!< Attach FRO_HF to CTIMER1. */ + + kFRO1M_to_CTIMER1 = MUX_A(CM_CTIMERCLKSEL1, 4), /*!< Attach FRO1M to CTIMER1. */ + + kMCLK_to_CTIMER1 = MUX_A(CM_CTIMERCLKSEL1, 5), /*!< Attach MCLK to CTIMER1. */ + + kOSC32K_to_CTIMER1 = MUX_A(CM_CTIMERCLKSEL1, 6), /*!< Attach OSC32K to CTIMER1. */ + + kNONE_to_CTIMER1 = MUX_A(CM_CTIMERCLKSEL1, 7), /*!< Attach NONE to CTIMER1. */ + + kMAIN_CLK_to_CTIMER2 = MUX_A(CM_CTIMERCLKSEL2, 0), /*!< Attach MAIN_CLK to CTIMER2. */ + + kPLL0_to_CTIMER2 = MUX_A(CM_CTIMERCLKSEL2, 1), /*!< Attach PLL0 to CTIMER2. */ + + kFRO_HF_to_CTIMER2 = MUX_A(CM_CTIMERCLKSEL2, 3), /*!< Attach FRO_HF to CTIMER2. */ + + kFRO1M_to_CTIMER2 = MUX_A(CM_CTIMERCLKSEL2, 4), /*!< Attach FRO1M to CTIMER2. */ + + kMCLK_to_CTIMER2 = MUX_A(CM_CTIMERCLKSEL2, 5), /*!< Attach MCLK to CTIMER2. */ + + kOSC32K_to_CTIMER2 = MUX_A(CM_CTIMERCLKSEL2, 6), /*!< Attach OSC32K to CTIMER2. */ + + kNONE_to_CTIMER2 = MUX_A(CM_CTIMERCLKSEL2, 7), /*!< Attach NONE to CTIMER2. */ + + kMAIN_CLK_to_CTIMER3 = MUX_A(CM_CTIMERCLKSEL3, 0), /*!< Attach MAIN_CLK to CTIMER3. */ + + kPLL0_to_CTIMER3 = MUX_A(CM_CTIMERCLKSEL3, 1), /*!< Attach PLL0 to CTIMER3. */ + + kFRO_HF_to_CTIMER3 = MUX_A(CM_CTIMERCLKSEL3, 3), /*!< Attach FRO_HF to CTIMER3. */ + + kFRO1M_to_CTIMER3 = MUX_A(CM_CTIMERCLKSEL3, 4), /*!< Attach FRO1M to CTIMER3. */ + + kMCLK_to_CTIMER3 = MUX_A(CM_CTIMERCLKSEL3, 5), /*!< Attach MCLK to CTIMER3. */ + + kOSC32K_to_CTIMER3 = MUX_A(CM_CTIMERCLKSEL3, 6), /*!< Attach OSC32K to CTIMER3. */ + + kNONE_to_CTIMER3 = MUX_A(CM_CTIMERCLKSEL3, 7), /*!< Attach NONE to CTIMER3. */ + + kMAIN_CLK_to_CTIMER4 = MUX_A(CM_CTIMERCLKSEL4, 0), /*!< Attach MAIN_CLK to CTIMER4. */ + + kPLL0_to_CTIMER4 = MUX_A(CM_CTIMERCLKSEL4, 1), /*!< Attach PLL0 to CTIMER4. */ + + kFRO_HF_to_CTIMER4 = MUX_A(CM_CTIMERCLKSEL4, 3), /*!< Attach FRO_HF to CTIMER4. */ + + kFRO1M_to_CTIMER4 = MUX_A(CM_CTIMERCLKSEL4, 4), /*!< Attach FRO1M to CTIMER4. */ + + kMCLK_to_CTIMER4 = MUX_A(CM_CTIMERCLKSEL4, 5), /*!< Attach MCLK to CTIMER4. */ + + kOSC32K_to_CTIMER4 = MUX_A(CM_CTIMERCLKSEL4, 6), /*!< Attach OSC32K to CTIMER4. */ + + kNONE_to_CTIMER4 = MUX_A(CM_CTIMERCLKSEL4, 7), /*!< Attach NONE to CTIMER4. */ + + kNONE_to_NONE = (int)0x80000000U, /*!< Attach NONE to NONE. */ + +} clock_attach_id_t; + +/*! @brief Clock dividers */ +typedef enum _clock_div_name +{ + kCLOCK_DivSystickClk0 = 0, /*!< Systick Clk0 Divider. */ + + kCLOCK_DivSystickClk1 = 1, /*!< Systick Clk1 Divider. */ + + kCLOCK_DivArmTrClkDiv = 2, /*!< Arm Tr Clk Div Divider. */ + + kCLOCK_DivFlexFrg0 = 8, /*!< Flex Frg0 Divider. */ + + kCLOCK_DivFlexFrg1 = 9, /*!< Flex Frg1 Divider. */ + + kCLOCK_DivFlexFrg2 = 10, /*!< Flex Frg2 Divider. */ + + kCLOCK_DivFlexFrg3 = 11, /*!< Flex Frg3 Divider. */ + + kCLOCK_DivFlexFrg4 = 12, /*!< Flex Frg4 Divider. */ + + kCLOCK_DivFlexFrg5 = 13, /*!< Flex Frg5 Divider. */ + + kCLOCK_DivFlexFrg6 = 14, /*!< Flex Frg6 Divider. */ + + kCLOCK_DivFlexFrg7 = 15, /*!< Flex Frg7 Divider. */ + + kCLOCK_DivAhbClk = 32, /*!< Ahb Clock Divider. */ + + kCLOCK_DivClkOut = 33, /*!< Clk Out Divider. */ + + kCLOCK_DivFrohfClk = 34, /*!< Frohf Clock Divider. */ + + kCLOCK_DivWdtClk = 35, /*!< Wdt Clock Divider. */ + + kCLOCK_DivAdcAsyncClk = 37, /*!< Adc Async Clock Divider. */ + + kCLOCK_DivUsb0Clk = 38, /*!< Usb0 Clock Divider. */ + + kCLOCK_DivMClk = 43, /*!< I2S MCLK Clock Divider. */ + + kCLOCK_DivSctClk = 45, /*!< Sct Clock Divider. */ + + kCLOCK_DivSdioClk = 47, /*!< Sdio Clock Divider. */ + + kCLOCK_DivPll0Clk = 49 /*!< PLL clock divider. */ +} clock_div_name_t; + +/******************************************************************************* + * API + ******************************************************************************/ + +#if defined(__cplusplus) +extern "C" { +#endif /* __cplusplus */ + +/** + * @brief Enable the clock for specific IP. + * @param clk : Clock to be enabled. + * @return Nothing + */ +static inline void CLOCK_EnableClock(clock_ip_name_t clk) +{ + uint32_t index = CLK_GATE_ABSTRACT_REG_OFFSET(clk); + SYSCON->AHBCLKCTRLSET[index] = (1UL << CLK_GATE_ABSTRACT_BITS_SHIFT(clk)); +} +/** + * @brief Disable the clock for specific IP. + * @param clk : Clock to be Disabled. + * @return Nothing + */ +static inline void CLOCK_DisableClock(clock_ip_name_t clk) +{ + uint32_t index = CLK_GATE_ABSTRACT_REG_OFFSET(clk); + SYSCON->AHBCLKCTRLCLR[index] = (1UL << CLK_GATE_ABSTRACT_BITS_SHIFT(clk)); +} +/** + * @brief Initialize the Core clock to given frequency (12, 48 or 96 MHz). + * Turns on FRO and uses default CCO, if freq is 12000000, then high speed output is off, else high speed output is + * enabled. + * @param iFreq : Desired frequency (must be one of CLK_FRO_12MHZ or CLK_FRO_48MHZ or CLK_FRO_96MHZ) + * @return returns success or fail status. + */ +status_t CLOCK_SetupFROClocking(uint32_t iFreq); +/** + * @brief Set the flash wait states for the input freuqency. + * @param iFreq : Input frequency + * @return Nothing + */ +void CLOCK_SetFLASHAccessCyclesForFreq(uint32_t iFreq); +/** + * @brief Initialize the external osc clock to given frequency. + * @param iFreq : Desired frequency (must be equal to exact rate in Hz) + * @return returns success or fail status. + */ +status_t CLOCK_SetupExtClocking(uint32_t iFreq); +/** + * @brief Initialize the I2S MCLK clock to given frequency. + * @param iFreq : Desired frequency (must be equal to exact rate in Hz) + * @return returns success or fail status. + */ +status_t CLOCK_SetupI2SMClkClocking(uint32_t iFreq); +/** + * @brief Initialize the PLU CLKIN clock to given frequency. + * @param iFreq : Desired frequency (must be equal to exact rate in Hz) + * @return returns success or fail status. + */ +status_t CLOCK_SetupPLUClkInClocking(uint32_t iFreq); +/** + * @brief Configure the clock selection muxes. + * @param connection : Clock to be configured. + * @return Nothing + */ +void CLOCK_AttachClk(clock_attach_id_t connection); +/** + * @brief Get the actual clock attach id. + * This fuction uses the offset in input attach id, then it reads the actual source value in + * the register and combine the offset to obtain an actual attach id. + * @param attachId : Clock attach id to get. + * @return Clock source value. + */ +clock_attach_id_t CLOCK_GetClockAttachId(clock_attach_id_t attachId); +/** + * @brief Setup peripheral clock dividers. + * @param div_name : Clock divider name + * @param divided_by_value: Value to be divided + * @param reset : Whether to reset the divider counter. + * @return Nothing + */ +void CLOCK_SetClkDiv(clock_div_name_t div_name, uint32_t divided_by_value, bool reset); +/** + * @brief Setup rtc 1khz clock divider. + * @param divided_by_value: Value to be divided + * @return Nothing + */ +void CLOCK_SetRtc1khzClkDiv(uint32_t divided_by_value); +/** + * @brief Setup rtc 1hz clock divider. + * @param divided_by_value: Value to be divided + * @return Nothing + */ +void CLOCK_SetRtc1hzClkDiv(uint32_t divided_by_value); + +/** + * @brief Set the flexcomm output frequency. + * @param id : flexcomm instance id + * @param freq : output frequency + * @return 0 : the frequency range is out of range. + * 1 : switch successfully. + */ +uint32_t CLOCK_SetFlexCommClock(uint32_t id, uint32_t freq); + +/*! @brief Return Frequency of flexcomm input clock + * @param id : flexcomm instance id + * @return Frequency value + */ +uint32_t CLOCK_GetFlexCommInputClock(uint32_t id); + +/*! @brief Return Frequency of selected clock + * @return Frequency of selected clock + */ +uint32_t CLOCK_GetFreq(clock_name_t clockName); +/*! @brief Return Frequency of FRO 12MHz + * @return Frequency of FRO 12MHz + */ +uint32_t CLOCK_GetFro12MFreq(void); +/*! @brief Return Frequency of FRO 1MHz + * @return Frequency of FRO 1MHz + */ +uint32_t CLOCK_GetFro1MFreq(void); +/*! @brief Return Frequency of ClockOut + * @return Frequency of ClockOut + */ +uint32_t CLOCK_GetClockOutClkFreq(void); +/*! @brief Return Frequency of Adc Clock + * @return Frequency of Adc. + */ +uint32_t CLOCK_GetAdcClkFreq(void); +/*! @brief Return Frequency of Usb0 Clock + * @return Frequency of Usb0 Clock. + */ +uint32_t CLOCK_GetUsb0ClkFreq(void); +/*! @brief Return Frequency of Usb1 Clock + * @return Frequency of Usb1 Clock. + */ +uint32_t CLOCK_GetUsb1ClkFreq(void); +/*! @brief Return Frequency of MClk Clock + * @return Frequency of MClk Clock. + */ +uint32_t CLOCK_GetMclkClkFreq(void); +/*! @brief Return Frequency of SCTimer Clock + * @return Frequency of SCTimer Clock. + */ +uint32_t CLOCK_GetSctClkFreq(void); +/*! @brief Return Frequency of SDIO Clock + * @return Frequency of SDIO Clock. + */ +uint32_t CLOCK_GetSdioClkFreq(void); +/*! @brief Return Frequency of External Clock + * @return Frequency of External Clock. If no external clock is used returns 0. + */ +uint32_t CLOCK_GetExtClkFreq(void); +/*! @brief Return Frequency of Watchdog + * @return Frequency of Watchdog + */ +uint32_t CLOCK_GetWdtClkFreq(void); +/*! @brief Return Frequency of High-Freq output of FRO + * @return Frequency of High-Freq output of FRO + */ +uint32_t CLOCK_GetFroHfFreq(void); +/*! @brief Return Frequency of PLL + * @return Frequency of PLL + */ +uint32_t CLOCK_GetPll0OutFreq(void); +/*! @brief Return Frequency of USB PLL + * @return Frequency of PLL + */ +uint32_t CLOCK_GetPll1OutFreq(void); +/*! @brief Return Frequency of 32kHz osc + * @return Frequency of 32kHz osc + */ +uint32_t CLOCK_GetOsc32KFreq(void); +/*! @brief Return Frequency of Core System + * @return Frequency of Core System + */ +uint32_t CLOCK_GetCoreSysClkFreq(void); +/*! @brief Return Frequency of I2S MCLK Clock + * @return Frequency of I2S MCLK Clock + */ +uint32_t CLOCK_GetI2SMClkFreq(void); +/*! @brief Return Frequency of PLU CLKIN Clock + * @return Frequency of PLU CLKIN Clock + */ +uint32_t CLOCK_GetPLUClkInFreq(void); +/*! @brief Return Frequency of FlexComm Clock + * @return Frequency of FlexComm Clock + */ +uint32_t CLOCK_GetFlexCommClkFreq(uint32_t id); +/*! @brief Return Frequency of High speed SPI Clock + * @return Frequency of High speed SPI Clock + */ +uint32_t CLOCK_GetHsLspiClkFreq(void); +/*! @brief Return Frequency of CTimer functional Clock + * @return Frequency of CTimer functional Clock + */ +uint32_t CLOCK_GetCTimerClkFreq(uint32_t id); +/*! @brief Return Frequency of SystickClock + * @return Frequency of Systick Clock + */ +uint32_t CLOCK_GetSystickClkFreq(uint32_t id); + +/*! @brief Return PLL0 input clock rate + * @return PLL0 input clock rate + */ +uint32_t CLOCK_GetPLL0InClockRate(void); + +/*! @brief Return PLL1 input clock rate + * @return PLL1 input clock rate + */ +uint32_t CLOCK_GetPLL1InClockRate(void); + +/*! @brief Return PLL0 output clock rate + * @param recompute : Forces a PLL rate recomputation if true + * @return PLL0 output clock rate + * @note The PLL rate is cached in the driver in a variable as + * the rate computation function can take some time to perform. It + * is recommended to use 'false' with the 'recompute' parameter. + */ +uint32_t CLOCK_GetPLL0OutClockRate(bool recompute); + +/*! @brief Enables and disables PLL0 bypass mode + * @brief bypass : true to bypass PLL0 (PLL0 output = PLL0 input, false to disable bypass + * @return PLL0 output clock rate + */ +__STATIC_INLINE void CLOCK_SetBypassPLL0(bool bypass) +{ + if (bypass) + { + SYSCON->PLL0CTRL |= (1UL << SYSCON_PLL0CTRL_BYPASSPLL_SHIFT); + } + else + { + SYSCON->PLL0CTRL &= ~(1UL << SYSCON_PLL0CTRL_BYPASSPLL_SHIFT); + } +} + +/*! @brief Enables and disables PLL1 bypass mode + * @brief bypass : true to bypass PLL1 (PLL1 output = PLL1 input, false to disable bypass + * @return PLL1 output clock rate + */ +__STATIC_INLINE void CLOCK_SetBypassPLL1(bool bypass) +{ + if (bypass) + { + SYSCON->PLL1CTRL |= (1UL << SYSCON_PLL1CTRL_BYPASSPLL_SHIFT); + } + else + { + SYSCON->PLL1CTRL &= ~(1UL << SYSCON_PLL1CTRL_BYPASSPLL_SHIFT); + } +} + +/*! @brief Check if PLL is locked or not + * @return true if the PLL is locked, false if not locked + */ +__STATIC_INLINE bool CLOCK_IsPLL0Locked(void) +{ + return (bool)((SYSCON->PLL0STAT & SYSCON_PLL0STAT_LOCK_MASK) != 0UL); +} + +/*! @brief Check if PLL1 is locked or not + * @return true if the PLL1 is locked, false if not locked + */ +__STATIC_INLINE bool CLOCK_IsPLL1Locked(void) +{ + return (bool)((SYSCON->PLL1STAT & SYSCON_PLL1STAT_LOCK_MASK) != 0UL); +} + +/*! @brief Store the current PLL0 rate + * @param rate: Current rate of the PLL0 + * @return Nothing + **/ +void CLOCK_SetStoredPLL0ClockRate(uint32_t rate); + +/*! @brief PLL configuration structure flags for 'flags' field + * These flags control how the PLL configuration function sets up the PLL setup structure.
+ * + * When the PLL_CONFIGFLAG_USEINRATE flag is selected, the 'InputRate' field in the + * configuration structure must be assigned with the expected PLL frequency. If the + * PLL_CONFIGFLAG_USEINRATE is not used, 'InputRate' is ignored in the configuration + * function and the driver will determine the PLL rate from the currently selected + * PLL source. This flag might be used to configure the PLL input clock more accurately + * when using the WDT oscillator or a more dyanmic CLKIN source.
+ * + * When the PLL_CONFIGFLAG_FORCENOFRACT flag is selected, the PLL hardware for the + * automatic bandwidth selection, Spread Spectrum (SS) support, and fractional M-divider + * are not used.
+ */ +#define PLL_CONFIGFLAG_USEINRATE (1U << 0U) /*!< Flag to use InputRate in PLL configuration structure for setup */ +#define PLL_CONFIGFLAG_FORCENOFRACT (1U << 2U) +/*!< Force non-fractional output mode, PLL output will not use the fractional, automatic bandwidth, or SS hardware */ + +/*! @brief PLL Spread Spectrum (SS) Programmable modulation frequency + * See (MF) field in the PLL0SSCG1 register in the UM. + */ +typedef enum _ss_progmodfm +{ + kSS_MF_512 = (0U << SYSCON_PLL0SSCG1_MF_SHIFT), /*!< Nss = 512 (fm ? 3.9 - 7.8 kHz) */ + kSS_MF_384 = (1U << SYSCON_PLL0SSCG1_MF_SHIFT), /*!< Nss ?= 384 (fm ? 5.2 - 10.4 kHz) */ + kSS_MF_256 = (2U << SYSCON_PLL0SSCG1_MF_SHIFT), /*!< Nss = 256 (fm ? 7.8 - 15.6 kHz) */ + kSS_MF_128 = (3U << SYSCON_PLL0SSCG1_MF_SHIFT), /*!< Nss = 128 (fm ? 15.6 - 31.3 kHz) */ + kSS_MF_64 = (4U << SYSCON_PLL0SSCG1_MF_SHIFT), /*!< Nss = 64 (fm ? 32.3 - 64.5 kHz) */ + kSS_MF_32 = (5U << SYSCON_PLL0SSCG1_MF_SHIFT), /*!< Nss = 32 (fm ? 62.5- 125 kHz) */ + kSS_MF_24 = (6U << SYSCON_PLL0SSCG1_MF_SHIFT), /*!< Nss ?= 24 (fm ? 83.3- 166.6 kHz) */ + kSS_MF_16 = (7U << SYSCON_PLL0SSCG1_MF_SHIFT) /*!< Nss = 16 (fm ? 125- 250 kHz) */ +} ss_progmodfm_t; + +/*! @brief PLL Spread Spectrum (SS) Programmable frequency modulation depth + * See (MR) field in the PLL0SSCG1 register in the UM. + */ +typedef enum _ss_progmoddp +{ + kSS_MR_K0 = (0U << SYSCON_PLL0SSCG1_MR_SHIFT), /*!< k = 0 (no spread spectrum) */ + kSS_MR_K1 = (1U << SYSCON_PLL0SSCG1_MR_SHIFT), /*!< k = 1 */ + kSS_MR_K1_5 = (2U << SYSCON_PLL0SSCG1_MR_SHIFT), /*!< k = 1.5 */ + kSS_MR_K2 = (3U << SYSCON_PLL0SSCG1_MR_SHIFT), /*!< k = 2 */ + kSS_MR_K3 = (4U << SYSCON_PLL0SSCG1_MR_SHIFT), /*!< k = 3 */ + kSS_MR_K4 = (5U << SYSCON_PLL0SSCG1_MR_SHIFT), /*!< k = 4 */ + kSS_MR_K6 = (6U << SYSCON_PLL0SSCG1_MR_SHIFT), /*!< k = 6 */ + kSS_MR_K8 = (7U << SYSCON_PLL0SSCG1_MR_SHIFT) /*!< k = 8 */ +} ss_progmoddp_t; + +/*! @brief PLL Spread Spectrum (SS) Modulation waveform control + * See (MC) field in the PLL0SSCG1 register in the UM.
+ * Compensation for low pass filtering of the PLL to get a triangular + * modulation at the output of the PLL, giving a flat frequency spectrum. + */ +typedef enum _ss_modwvctrl +{ + kSS_MC_NOC = (0U << SYSCON_PLL0SSCG1_MC_SHIFT), /*!< no compensation */ + kSS_MC_RECC = (2U << SYSCON_PLL0SSCG1_MC_SHIFT), /*!< recommended setting */ + kSS_MC_MAXC = (3U << SYSCON_PLL0SSCG1_MC_SHIFT), /*!< max. compensation */ +} ss_modwvctrl_t; + +/*! @brief PLL configuration structure + * + * This structure can be used to configure the settings for a PLL + * setup structure. Fill in the desired configuration for the PLL + * and call the PLL setup function to fill in a PLL setup structure. + */ +typedef struct _pll_config +{ + uint32_t desiredRate; /*!< Desired PLL rate in Hz */ + uint32_t inputRate; /*!< PLL input clock in Hz, only used if PLL_CONFIGFLAG_USEINRATE flag is set */ + uint32_t flags; /*!< PLL configuration flags, Or'ed value of PLL_CONFIGFLAG_* definitions */ + ss_progmodfm_t ss_mf; /*!< SS Programmable modulation frequency, only applicable when not using + PLL_CONFIGFLAG_FORCENOFRACT flag */ + ss_progmoddp_t ss_mr; /*!< SS Programmable frequency modulation depth, only applicable when not using + PLL_CONFIGFLAG_FORCENOFRACT flag */ + ss_modwvctrl_t + ss_mc; /*!< SS Modulation waveform control, only applicable when not using PLL_CONFIGFLAG_FORCENOFRACT flag */ + bool mfDither; /*!< false for fixed modulation frequency or true for dithering, only applicable when not using + PLL_CONFIGFLAG_FORCENOFRACT flag */ + +} pll_config_t; + +/*! @brief PLL setup structure flags for 'flags' field + * These flags control how the PLL setup function sets up the PLL + */ +#define PLL_SETUPFLAG_POWERUP (1U << 0U) /*!< Setup will power on the PLL after setup */ +#define PLL_SETUPFLAG_WAITLOCK (1U << 1U) /*!< Setup will wait for PLL lock, implies the PLL will be pwoered on */ +#define PLL_SETUPFLAG_ADGVOLT (1U << 2U) /*!< Optimize system voltage for the new PLL rate */ +#define PLL_SETUPFLAG_USEFEEDBACKDIV2 (1U << 3U) /*!< Use feedback divider by 2 in divider path */ + +/*! @brief PLL0 setup structure + * This structure can be used to pre-build a PLL setup configuration + * at run-time and quickly set the PLL to the configuration. It can be + * populated with the PLL setup function. If powering up or waiting + * for PLL lock, the PLL input clock source should be configured prior + * to PLL setup. + */ +typedef struct _pll_setup +{ + uint32_t pllctrl; /*!< PLL control register PLL0CTRL */ + uint32_t pllndec; /*!< PLL NDEC register PLL0NDEC */ + uint32_t pllpdec; /*!< PLL PDEC register PLL0PDEC */ + uint32_t pllmdec; /*!< PLL MDEC registers PLL0PDEC */ + uint32_t pllsscg[2]; /*!< PLL SSCTL registers PLL0SSCG*/ + uint32_t pllRate; /*!< Acutal PLL rate */ + uint32_t flags; /*!< PLL setup flags, Or'ed value of PLL_SETUPFLAG_* definitions */ +} pll_setup_t; + +/*! @brief PLL status definitions + */ +typedef enum _pll_error +{ + kStatus_PLL_Success = MAKE_STATUS(kStatusGroup_Generic, 0), /*!< PLL operation was successful */ + kStatus_PLL_OutputTooLow = MAKE_STATUS(kStatusGroup_Generic, 1), /*!< PLL output rate request was too low */ + kStatus_PLL_OutputTooHigh = MAKE_STATUS(kStatusGroup_Generic, 2), /*!< PLL output rate request was too high */ + kStatus_PLL_InputTooLow = MAKE_STATUS(kStatusGroup_Generic, 3), /*!< PLL input rate is too low */ + kStatus_PLL_InputTooHigh = MAKE_STATUS(kStatusGroup_Generic, 4), /*!< PLL input rate is too high */ + kStatus_PLL_OutsideIntLimit = MAKE_STATUS(kStatusGroup_Generic, 5), /*!< Requested output rate isn't possible */ + kStatus_PLL_CCOTooLow = MAKE_STATUS(kStatusGroup_Generic, 6), /*!< Requested CCO rate isn't possible */ + kStatus_PLL_CCOTooHigh = MAKE_STATUS(kStatusGroup_Generic, 7) /*!< Requested CCO rate isn't possible */ +} pll_error_t; + +/*! @brief USB FS clock source definition. */ +typedef enum _clock_usbfs_src +{ + kCLOCK_UsbfsSrcFro = (uint32_t)kCLOCK_FroHf, /*!< Use FRO 96 MHz. */ + kCLOCK_UsbfsSrcPll0 = (uint32_t)kCLOCK_Pll0Out, /*!< Use PLL0 output. */ + kCLOCK_UsbfsSrcMainClock = (uint32_t)kCLOCK_CoreSysClk, /*!< Use Main clock. */ + kCLOCK_UsbfsSrcPll1 = (uint32_t)kCLOCK_Pll1Out, /*!< Use PLL1 clock. */ + + kCLOCK_UsbfsSrcNone = + SYSCON_USB0CLKSEL_SEL(7) /*! +#include +#include +#include +#include + +#if defined(__ICCARM__) || (defined(__CC_ARM) || defined(__ARMCC_VERSION)) || defined(__GNUC__) +#include +#endif + +#include "fsl_device_registers.h" + +/*! + * @addtogroup ksdk_common + * @{ + */ + +/******************************************************************************* + * Configurations + ******************************************************************************/ + +/*! @brief Macro to use the default weak IRQ handler in drivers. */ +#ifndef FSL_DRIVER_TRANSFER_DOUBLE_WEAK_IRQ +#define FSL_DRIVER_TRANSFER_DOUBLE_WEAK_IRQ 1 +#endif + +/******************************************************************************* + * Definitions + ******************************************************************************/ + +/*! @brief Construct a status code value from a group and code number. */ +#define MAKE_STATUS(group, code) ((((group)*100L) + (code))) + +/*! @brief Construct the version number for drivers. + * + * The driver version is a 32-bit number, for both 32-bit platforms(such as Cortex M) + * and 16-bit platforms(such as DSC). + * + * @verbatim + + | Unused || Major Version || Minor Version || Bug Fix | + 31 25 24 17 16 9 8 0 + + @endverbatim + */ +#define MAKE_VERSION(major, minor, bugfix) (((major)*65536L) + ((minor)*256L) + (bugfix)) + +/*! @name Driver version */ +/*! @{ */ +/*! @brief common driver version. */ +#define FSL_COMMON_DRIVER_VERSION (MAKE_VERSION(2, 4, 1)) +/*! @} */ + +/*! @name Debug console type definition. */ +/*! @{ */ +#define DEBUG_CONSOLE_DEVICE_TYPE_NONE 0U /*!< No debug console. */ +#define DEBUG_CONSOLE_DEVICE_TYPE_UART 1U /*!< Debug console based on UART. */ +#define DEBUG_CONSOLE_DEVICE_TYPE_LPUART 2U /*!< Debug console based on LPUART. */ +#define DEBUG_CONSOLE_DEVICE_TYPE_LPSCI 3U /*!< Debug console based on LPSCI. */ +#define DEBUG_CONSOLE_DEVICE_TYPE_USBCDC 4U /*!< Debug console based on USBCDC. */ +#define DEBUG_CONSOLE_DEVICE_TYPE_FLEXCOMM 5U /*!< Debug console based on FLEXCOMM. */ +#define DEBUG_CONSOLE_DEVICE_TYPE_IUART 6U /*!< Debug console based on i.MX UART. */ +#define DEBUG_CONSOLE_DEVICE_TYPE_VUSART 7U /*!< Debug console based on LPC_VUSART. */ +#define DEBUG_CONSOLE_DEVICE_TYPE_MINI_USART 8U /*!< Debug console based on LPC_USART. */ +#define DEBUG_CONSOLE_DEVICE_TYPE_SWO 9U /*!< Debug console based on SWO. */ +#define DEBUG_CONSOLE_DEVICE_TYPE_QSCI 10U /*!< Debug console based on QSCI. */ +/*! @} */ + +/*! @brief Status group numbers. */ +enum _status_groups +{ + kStatusGroup_Generic = 0, /*!< Group number for generic status codes. */ + kStatusGroup_FLASH = 1, /*!< Group number for FLASH status codes. */ + kStatusGroup_LPSPI = 4, /*!< Group number for LPSPI status codes. */ + kStatusGroup_FLEXIO_SPI = 5, /*!< Group number for FLEXIO SPI status codes. */ + kStatusGroup_DSPI = 6, /*!< Group number for DSPI status codes. */ + kStatusGroup_FLEXIO_UART = 7, /*!< Group number for FLEXIO UART status codes. */ + kStatusGroup_FLEXIO_I2C = 8, /*!< Group number for FLEXIO I2C status codes. */ + kStatusGroup_LPI2C = 9, /*!< Group number for LPI2C status codes. */ + kStatusGroup_UART = 10, /*!< Group number for UART status codes. */ + kStatusGroup_I2C = 11, /*!< Group number for UART status codes. */ + kStatusGroup_LPSCI = 12, /*!< Group number for LPSCI status codes. */ + kStatusGroup_LPUART = 13, /*!< Group number for LPUART status codes. */ + kStatusGroup_SPI = 14, /*!< Group number for SPI status code.*/ + kStatusGroup_XRDC = 15, /*!< Group number for XRDC status code.*/ + kStatusGroup_SEMA42 = 16, /*!< Group number for SEMA42 status code.*/ + kStatusGroup_SDHC = 17, /*!< Group number for SDHC status code */ + kStatusGroup_SDMMC = 18, /*!< Group number for SDMMC status code */ + kStatusGroup_SAI = 19, /*!< Group number for SAI status code */ + kStatusGroup_MCG = 20, /*!< Group number for MCG status codes. */ + kStatusGroup_SCG = 21, /*!< Group number for SCG status codes. */ + kStatusGroup_SDSPI = 22, /*!< Group number for SDSPI status codes. */ + kStatusGroup_FLEXIO_I2S = 23, /*!< Group number for FLEXIO I2S status codes */ + kStatusGroup_FLEXIO_MCULCD = 24, /*!< Group number for FLEXIO LCD status codes */ + kStatusGroup_FLASHIAP = 25, /*!< Group number for FLASHIAP status codes */ + kStatusGroup_FLEXCOMM_I2C = 26, /*!< Group number for FLEXCOMM I2C status codes */ + kStatusGroup_I2S = 27, /*!< Group number for I2S status codes */ + kStatusGroup_IUART = 28, /*!< Group number for IUART status codes */ + kStatusGroup_CSI = 29, /*!< Group number for CSI status codes */ + kStatusGroup_MIPI_DSI = 30, /*!< Group number for MIPI DSI status codes */ + kStatusGroup_SDRAMC = 35, /*!< Group number for SDRAMC status codes. */ + kStatusGroup_POWER = 39, /*!< Group number for POWER status codes. */ + kStatusGroup_ENET = 40, /*!< Group number for ENET status codes. */ + kStatusGroup_PHY = 41, /*!< Group number for PHY status codes. */ + kStatusGroup_TRGMUX = 42, /*!< Group number for TRGMUX status codes. */ + kStatusGroup_SMARTCARD = 43, /*!< Group number for SMARTCARD status codes. */ + kStatusGroup_LMEM = 44, /*!< Group number for LMEM status codes. */ + kStatusGroup_QSPI = 45, /*!< Group number for QSPI status codes. */ + kStatusGroup_DMA = 50, /*!< Group number for DMA status codes. */ + kStatusGroup_EDMA = 51, /*!< Group number for EDMA status codes. */ + kStatusGroup_DMAMGR = 52, /*!< Group number for DMAMGR status codes. */ + kStatusGroup_FLEXCAN = 53, /*!< Group number for FlexCAN status codes. */ + kStatusGroup_LTC = 54, /*!< Group number for LTC status codes. */ + kStatusGroup_FLEXIO_CAMERA = 55, /*!< Group number for FLEXIO CAMERA status codes. */ + kStatusGroup_LPC_SPI = 56, /*!< Group number for LPC_SPI status codes. */ + kStatusGroup_LPC_USART = 57, /*!< Group number for LPC_USART status codes. */ + kStatusGroup_DMIC = 58, /*!< Group number for DMIC status codes. */ + kStatusGroup_SDIF = 59, /*!< Group number for SDIF status codes.*/ + kStatusGroup_SPIFI = 60, /*!< Group number for SPIFI status codes. */ + kStatusGroup_OTP = 61, /*!< Group number for OTP status codes. */ + kStatusGroup_MCAN = 62, /*!< Group number for MCAN status codes. */ + kStatusGroup_CAAM = 63, /*!< Group number for CAAM status codes. */ + kStatusGroup_ECSPI = 64, /*!< Group number for ECSPI status codes. */ + kStatusGroup_USDHC = 65, /*!< Group number for USDHC status codes.*/ + kStatusGroup_LPC_I2C = 66, /*!< Group number for LPC_I2C status codes.*/ + kStatusGroup_DCP = 67, /*!< Group number for DCP status codes.*/ + kStatusGroup_MSCAN = 68, /*!< Group number for MSCAN status codes.*/ + kStatusGroup_ESAI = 69, /*!< Group number for ESAI status codes. */ + kStatusGroup_FLEXSPI = 70, /*!< Group number for FLEXSPI status codes. */ + kStatusGroup_MMDC = 71, /*!< Group number for MMDC status codes. */ + kStatusGroup_PDM = 72, /*!< Group number for MIC status codes. */ + kStatusGroup_SDMA = 73, /*!< Group number for SDMA status codes. */ + kStatusGroup_ICS = 74, /*!< Group number for ICS status codes. */ + kStatusGroup_SPDIF = 75, /*!< Group number for SPDIF status codes. */ + kStatusGroup_LPC_MINISPI = 76, /*!< Group number for LPC_MINISPI status codes. */ + kStatusGroup_HASHCRYPT = 77, /*!< Group number for Hashcrypt status codes */ + kStatusGroup_LPC_SPI_SSP = 78, /*!< Group number for LPC_SPI_SSP status codes. */ + kStatusGroup_I3C = 79, /*!< Group number for I3C status codes */ + kStatusGroup_LPC_I2C_1 = 97, /*!< Group number for LPC_I2C_1 status codes. */ + kStatusGroup_NOTIFIER = 98, /*!< Group number for NOTIFIER status codes. */ + kStatusGroup_DebugConsole = 99, /*!< Group number for debug console status codes. */ + kStatusGroup_SEMC = 100, /*!< Group number for SEMC status codes. */ + kStatusGroup_ApplicationRangeStart = 101, /*!< Starting number for application groups. */ + kStatusGroup_IAP = 102, /*!< Group number for IAP status codes */ + kStatusGroup_SFA = 103, /*!< Group number for SFA status codes*/ + kStatusGroup_SPC = 104, /*!< Group number for SPC status codes. */ + kStatusGroup_PUF = 105, /*!< Group number for PUF status codes. */ + kStatusGroup_TOUCH_PANEL = 106, /*!< Group number for touch panel status codes */ + kStatusGroup_VBAT = 107, /*!< Group number for VBAT status codes */ + kStatusGroup_XSPI = 108, /*!< Group number for XSPI status codes */ + kStatusGroup_PNGDEC = 109, /*!< Group number for PNGDEC status codes */ + kStatusGroup_JPEGDEC = 110, /*!< Group number for JPEGDEC status codes */ + + kStatusGroup_HAL_GPIO = 121, /*!< Group number for HAL GPIO status codes. */ + kStatusGroup_HAL_UART = 122, /*!< Group number for HAL UART status codes. */ + kStatusGroup_HAL_TIMER = 123, /*!< Group number for HAL TIMER status codes. */ + kStatusGroup_HAL_SPI = 124, /*!< Group number for HAL SPI status codes. */ + kStatusGroup_HAL_I2C = 125, /*!< Group number for HAL I2C status codes. */ + kStatusGroup_HAL_FLASH = 126, /*!< Group number for HAL FLASH status codes. */ + kStatusGroup_HAL_PWM = 127, /*!< Group number for HAL PWM status codes. */ + kStatusGroup_HAL_RNG = 128, /*!< Group number for HAL RNG status codes. */ + kStatusGroup_HAL_I2S = 129, /*!< Group number for HAL I2S status codes. */ + kStatusGroup_HAL_ADC_SENSOR = 130, /*!< Group number for HAL ADC SENSOR status codes. */ + kStatusGroup_TIMERMANAGER = 135, /*!< Group number for TiMER MANAGER status codes. */ + kStatusGroup_SERIALMANAGER = 136, /*!< Group number for SERIAL MANAGER status codes. */ + kStatusGroup_LED = 137, /*!< Group number for LED status codes. */ + kStatusGroup_BUTTON = 138, /*!< Group number for BUTTON status codes. */ + kStatusGroup_EXTERN_EEPROM = 139, /*!< Group number for EXTERN EEPROM status codes. */ + kStatusGroup_SHELL = 140, /*!< Group number for SHELL status codes. */ + kStatusGroup_MEM_MANAGER = 141, /*!< Group number for MEM MANAGER status codes. */ + kStatusGroup_LIST = 142, /*!< Group number for List status codes. */ + kStatusGroup_OSA = 143, /*!< Group number for OSA status codes. */ + kStatusGroup_COMMON_TASK = 144, /*!< Group number for Common task status codes. */ + kStatusGroup_MSG = 145, /*!< Group number for messaging status codes. */ + kStatusGroup_SDK_OCOTP = 146, /*!< Group number for OCOTP status codes. */ + kStatusGroup_SDK_FLEXSPINOR = 147, /*!< Group number for FLEXSPINOR status codes.*/ + kStatusGroup_CODEC = 148, /*!< Group number for codec status codes. */ + kStatusGroup_ASRC = 149, /*!< Group number for codec status ASRC. */ + kStatusGroup_OTFAD = 150, /*!< Group number for codec status codes. */ + kStatusGroup_SDIOSLV = 151, /*!< Group number for SDIOSLV status codes. */ + kStatusGroup_MECC = 152, /*!< Group number for MECC status codes. */ + kStatusGroup_ENET_QOS = 153, /*!< Group number for ENET_QOS status codes. */ + kStatusGroup_LOG = 154, /*!< Group number for LOG status codes. */ + kStatusGroup_I3CBUS = 155, /*!< Group number for I3CBUS status codes. */ + kStatusGroup_QSCI = 156, /*!< Group number for QSCI status codes. */ + kStatusGroup_ELEMU = 157, /*!< Group number for ELEMU status codes. */ + kStatusGroup_QUEUEDSPI = 158, /*!< Group number for QSPI status codes. */ + kStatusGroup_POWER_MANAGER = 159, /*!< Group number for POWER_MANAGER status codes. */ + kStatusGroup_IPED = 160, /*!< Group number for IPED status codes. */ + kStatusGroup_ELS_PKC = 161, /*!< Group number for ELS PKC status codes. */ + kStatusGroup_CSS_PKC = 162, /*!< Group number for CSS PKC status codes. */ + kStatusGroup_HOSTIF = 163, /*!< Group number for HOSTIF status codes. */ + kStatusGroup_CLIF = 164, /*!< Group number for CLIF status codes. */ + kStatusGroup_BMA = 165, /*!< Group number for BMA status codes. */ + kStatusGroup_NETC = 166, /*!< Group number for NETC status codes. */ + kStatusGroup_ELE = 167, /*!< Group number for ELE status codes. */ + kStatusGroup_GLIKEY = 168, /*!< Group number for GLIKEY status codes. */ +}; + +/*! \public + * @brief Generic status return codes. + */ +enum +{ + kStatus_Success = MAKE_STATUS(kStatusGroup_Generic, 0), /*!< Generic status for Success. */ + kStatus_Fail = MAKE_STATUS(kStatusGroup_Generic, 1), /*!< Generic status for Fail. */ + kStatus_ReadOnly = MAKE_STATUS(kStatusGroup_Generic, 2), /*!< Generic status for read only failure. */ + kStatus_OutOfRange = MAKE_STATUS(kStatusGroup_Generic, 3), /*!< Generic status for out of range access. */ + kStatus_InvalidArgument = MAKE_STATUS(kStatusGroup_Generic, 4), /*!< Generic status for invalid argument check. */ + kStatus_Timeout = MAKE_STATUS(kStatusGroup_Generic, 5), /*!< Generic status for timeout. */ + kStatus_NoTransferInProgress = + MAKE_STATUS(kStatusGroup_Generic, 6), /*!< Generic status for no transfer in progress. */ + kStatus_Busy = MAKE_STATUS(kStatusGroup_Generic, 7), /*!< Generic status for module is busy. */ + kStatus_NoData = + MAKE_STATUS(kStatusGroup_Generic, 8), /*!< Generic status for no data is found for the operation. */ +}; + +/*! @brief Type used for all status and error return values. */ +typedef int32_t status_t; + +#ifdef __ZEPHYR__ +#include +#else +/*! + * @name Min/max macros + * @{ + */ +#if !defined(MIN) +/*! Computes the minimum of \a a and \a b. */ +#define MIN(a, b) (((a) < (b)) ? (a) : (b)) +#endif + +#if !defined(MAX) +/*! Computes the maximum of \a a and \a b. */ +#define MAX(a, b) (((a) > (b)) ? (a) : (b)) +#endif +/*! @} */ + +/*! @brief Computes the number of elements in an array. */ +#if !defined(ARRAY_SIZE) +#define ARRAY_SIZE(x) (sizeof(x) / sizeof((x)[0])) +#endif +#endif /* __ZEPHYR__ */ + +/*! @name UINT16_MAX/UINT32_MAX value */ +/*! @{ */ +#if !defined(UINT16_MAX) +/*! Max value of uint16_t type. */ +#define UINT16_MAX ((uint16_t)-1) +#endif + +#if !defined(UINT32_MAX) +/*! Max value of uint32_t type. */ +#define UINT32_MAX ((uint32_t)-1) +#endif +/*! @} */ + +/*! Macro to get upper 32 bits of a 64-bit value */ +#if !defined(UINT64_H) +#define UINT64_H(X) ((uint32_t)((((uint64_t) (X)) >> 32U) & 0x0FFFFFFFFULL)) +#endif + +/*! Macro to get lower 32 bits of a 64-bit value */ +#if !defined(UINT64_L) +#define UINT64_L(X) ((uint32_t)(((uint64_t) (X)) & 0x0FFFFFFFFULL)) +#endif + +/*! + * @def SUPPRESS_FALL_THROUGH_WARNING() + * + * For switch case code block, if case section ends without "break;" statement, there wil be + * fallthrough warning with compiler flag -Wextra or -Wimplicit-fallthrough=n when using armgcc. + * To suppress this warning, "SUPPRESS_FALL_THROUGH_WARNING();" need to be added at the end of each + * case section which misses "break;"statement. + */ +#if defined(__GNUC__) && !defined(__ARMCC_VERSION) +#define SUPPRESS_FALL_THROUGH_WARNING() __attribute__((fallthrough)) +#else +#define SUPPRESS_FALL_THROUGH_WARNING() +#endif + +/******************************************************************************* + * API + ******************************************************************************/ + +#if defined(__cplusplus) +extern "C" { +#endif + +#if !((defined(__DSC__) && defined(__CW__))) +/*! + * @brief Allocate memory with given alignment and aligned size. + * + * This is provided to support the dynamically allocated memory + * used in cache-able region. + * @param size The length required to malloc. + * @param alignbytes The alignment size. + * @retval The allocated memory. + */ +void *SDK_Malloc(size_t size, size_t alignbytes); + +/*! + * @brief Free memory. + * + * @param ptr The memory to be release. + */ +void SDK_Free(void *ptr); +#endif + +/*! + * @brief Delay at least for some time. + * Please note that, this API uses while loop for delay, different run-time environments make the time not precise, + * if precise delay count was needed, please implement a new delay function with hardware timer. + * + * @param delayTime_us Delay time in unit of microsecond. + * @param coreClock_Hz Core clock frequency with Hz. + */ +void SDK_DelayAtLeastUs(uint32_t delayTime_us, uint32_t coreClock_Hz); + +#if defined(__cplusplus) +} +#endif + +/*! @} */ + +#if (defined(__DSC__) && defined(__CW__)) +#include "fsl_common_dsc.h" +#elif defined(__XTENSA__) +#include "fsl_common_dsp.h" +#else +#include "fsl_common_arm.h" +#endif + +#endif /* FSL_COMMON_H_ */ diff --git a/drivers/Inc/fsl_common_arm.h b/drivers/Inc/fsl_common_arm.h new file mode 100644 index 0000000..3d35d76 --- /dev/null +++ b/drivers/Inc/fsl_common_arm.h @@ -0,0 +1,898 @@ +/* + * Copyright (c) 2015-2016, Freescale Semiconductor, Inc. + * Copyright 2016-2022 NXP + * All rights reserved. + * + * SPDX-License-Identifier: BSD-3-Clause + */ + +#ifndef FSL_COMMON_ARM_H_ +#define FSL_COMMON_ARM_H_ + +/* + * For CMSIS pack RTE. + * CMSIS pack RTE generates "RTC_Components.h" which contains the statements + * of the related element for all selected software components. + */ +#ifdef _RTE_ +#include "RTE_Components.h" +#endif + +/*! + * @addtogroup ksdk_common + * @{ + */ + +/*! @name Atomic modification + * + * These macros are used for atomic access, such as read-modify-write + * to the peripheral registers. + * + * Take @ref SDK_ATOMIC_LOCAL_CLEAR_AND_SET as an example: the parameter @c addr + * means the address of the peripheral register or variable you want to modify + * atomically, the parameter @c clearBits is the bits to clear, the parameter + * @c setBits it the bits to set. + * For example, to set a 32-bit register bit1:bit0 to 0b10, use like this: + * + * @code + volatile uint32_t * reg = (volatile uint32_t *)REG_ADDR; + + SDK_ATOMIC_LOCAL_CLEAR_AND_SET(reg, 0x03, 0x02); + @endcode + * + * In this example, the register bit1:bit0 are cleared and bit1 is set, as a result, + * register bit1:bit0 = 0b10. + * + * @note For the platforms don't support exclusive load and store, these macros + * disable the global interrupt to pretect the modification. + * + * @note These macros only guarantee the local processor atomic operations. For + * the multi-processor devices, use hardware semaphore such as SEMA42 to + * guarantee exclusive access if necessary. + * + * @{ + */ + +/*! + * @def SDK_ATOMIC_LOCAL_ADD(addr, val) + * Add value \a val from the variable at address \a address. + * + * @def SDK_ATOMIC_LOCAL_SUB(addr, val) + * Subtract value \a val to the variable at address \a address. + * + * @def SDK_ATOMIC_LOCAL_SET(addr, bits) + * Set the bits specifiled by \a bits to the variable at address \a address. + * + * @def SDK_ATOMIC_LOCAL_CLEAR(addr, bits) + * Clear the bits specifiled by \a bits to the variable at address \a address. + * + * @def SDK_ATOMIC_LOCAL_TOGGLE(addr, bits) + * Toggle the bits specifiled by \a bits to the variable at address \a address. + * + * @def SDK_ATOMIC_LOCAL_CLEAR_AND_SET(addr, clearBits, setBits) + * For the variable at address \a address, clear the bits specifiled by \a clearBits + * and set the bits specifiled by \a setBits. + */ + +/* clang-format off */ +#if ((defined(__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ + (defined(__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ + (defined(__ARM_ARCH_8M_MAIN__) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ + (defined(__ARM_ARCH_8M_BASE__) && (__ARM_ARCH_8M_BASE__ == 1))) +/* clang-format on */ + +/* If the LDREX and STREX are supported, use them. */ +#define _SDK_ATOMIC_LOCAL_OPS_1BYTE(addr, val, ops) \ + do \ + { \ + (val) = __LDREXB(addr); \ + (ops); \ + } while (0UL != __STREXB((val), (addr))) + +#define _SDK_ATOMIC_LOCAL_OPS_2BYTE(addr, val, ops) \ + do \ + { \ + (val) = __LDREXH(addr); \ + (ops); \ + } while (0UL != __STREXH((val), (addr))) + +#define _SDK_ATOMIC_LOCAL_OPS_4BYTE(addr, val, ops) \ + do \ + { \ + (val) = __LDREXW(addr); \ + (ops); \ + } while (0UL != __STREXW((val), (addr))) + +static inline void _SDK_AtomicLocalAdd1Byte(volatile uint8_t *addr, uint8_t val) +{ + uint8_t s_val; + + _SDK_ATOMIC_LOCAL_OPS_1BYTE(addr, s_val, s_val += val); +} + +static inline void _SDK_AtomicLocalAdd2Byte(volatile uint16_t *addr, uint16_t val) +{ + uint16_t s_val; + + _SDK_ATOMIC_LOCAL_OPS_2BYTE(addr, s_val, s_val += val); +} + +static inline void _SDK_AtomicLocalAdd4Byte(volatile uint32_t *addr, uint32_t val) +{ + uint32_t s_val; + + _SDK_ATOMIC_LOCAL_OPS_4BYTE(addr, s_val, s_val += val); +} + +static inline void _SDK_AtomicLocalSub1Byte(volatile uint8_t *addr, uint8_t val) +{ + uint8_t s_val; + + _SDK_ATOMIC_LOCAL_OPS_1BYTE(addr, s_val, s_val -= val); +} + +static inline void _SDK_AtomicLocalSub2Byte(volatile uint16_t *addr, uint16_t val) +{ + uint16_t s_val; + + _SDK_ATOMIC_LOCAL_OPS_2BYTE(addr, s_val, s_val -= val); +} + +static inline void _SDK_AtomicLocalSub4Byte(volatile uint32_t *addr, uint32_t val) +{ + uint32_t s_val; + + _SDK_ATOMIC_LOCAL_OPS_4BYTE(addr, s_val, s_val -= val); +} + +static inline void _SDK_AtomicLocalSet1Byte(volatile uint8_t *addr, uint8_t bits) +{ + uint8_t s_val; + + _SDK_ATOMIC_LOCAL_OPS_1BYTE(addr, s_val, s_val |= bits); +} + +static inline void _SDK_AtomicLocalSet2Byte(volatile uint16_t *addr, uint16_t bits) +{ + uint16_t s_val; + + _SDK_ATOMIC_LOCAL_OPS_2BYTE(addr, s_val, s_val |= bits); +} + +static inline void _SDK_AtomicLocalSet4Byte(volatile uint32_t *addr, uint32_t bits) +{ + uint32_t s_val; + + _SDK_ATOMIC_LOCAL_OPS_4BYTE(addr, s_val, s_val |= bits); +} + +static inline void _SDK_AtomicLocalClear1Byte(volatile uint8_t *addr, uint8_t bits) +{ + uint8_t s_val; + + _SDK_ATOMIC_LOCAL_OPS_1BYTE(addr, s_val, s_val &= ~bits); +} + +static inline void _SDK_AtomicLocalClear2Byte(volatile uint16_t *addr, uint16_t bits) +{ + uint16_t s_val; + + _SDK_ATOMIC_LOCAL_OPS_2BYTE(addr, s_val, s_val &= ~bits); +} + +static inline void _SDK_AtomicLocalClear4Byte(volatile uint32_t *addr, uint32_t bits) +{ + uint32_t s_val; + + _SDK_ATOMIC_LOCAL_OPS_4BYTE(addr, s_val, s_val &= ~bits); +} + +static inline void _SDK_AtomicLocalToggle1Byte(volatile uint8_t *addr, uint8_t bits) +{ + uint8_t s_val; + + _SDK_ATOMIC_LOCAL_OPS_1BYTE(addr, s_val, s_val ^= bits); +} + +static inline void _SDK_AtomicLocalToggle2Byte(volatile uint16_t *addr, uint16_t bits) +{ + uint16_t s_val; + + _SDK_ATOMIC_LOCAL_OPS_2BYTE(addr, s_val, s_val ^= bits); +} + +static inline void _SDK_AtomicLocalToggle4Byte(volatile uint32_t *addr, uint32_t bits) +{ + uint32_t s_val; + + _SDK_ATOMIC_LOCAL_OPS_4BYTE(addr, s_val, s_val ^= bits); +} + +static inline void _SDK_AtomicLocalClearAndSet1Byte(volatile uint8_t *addr, uint8_t clearBits, uint8_t setBits) +{ + uint8_t s_val; + + _SDK_ATOMIC_LOCAL_OPS_1BYTE(addr, s_val, s_val = (s_val & ~clearBits) | setBits); +} + +static inline void _SDK_AtomicLocalClearAndSet2Byte(volatile uint16_t *addr, uint16_t clearBits, uint16_t setBits) +{ + uint16_t s_val; + + _SDK_ATOMIC_LOCAL_OPS_2BYTE(addr, s_val, s_val = (s_val & ~clearBits) | setBits); +} + +static inline void _SDK_AtomicLocalClearAndSet4Byte(volatile uint32_t *addr, uint32_t clearBits, uint32_t setBits) +{ + uint32_t s_val; + + _SDK_ATOMIC_LOCAL_OPS_4BYTE(addr, s_val, s_val = (s_val & ~clearBits) | setBits); +} + +#define SDK_ATOMIC_LOCAL_ADD(addr, val) \ + ((1UL == sizeof(*(addr))) ? \ + _SDK_AtomicLocalAdd1Byte((volatile uint8_t *)(volatile void *)(addr), (uint8_t)(val)) : \ + ((2UL == sizeof(*(addr))) ? _SDK_AtomicLocalAdd2Byte((volatile uint16_t *)(volatile void *)(addr), (uint16_t)(val)) : \ + _SDK_AtomicLocalAdd4Byte((volatile uint32_t *)(volatile void *)(addr), (uint32_t)(val)))) + +#define SDK_ATOMIC_LOCAL_SUB(addr, val) \ + ((1UL == sizeof(*(addr))) ? \ + _SDK_AtomicLocalSub1Byte((volatile uint8_t *)(volatile void *)(addr), (uint8_t)(val)) : \ + ((2UL == sizeof(*(addr))) ? _SDK_AtomicLocalSub2Byte((volatile uint16_t *)(volatile void *)(addr), (uint16_t)(val)) : \ + _SDK_AtomicLocalSub4Byte((volatile uint32_t *)(volatile void *)(addr), (uint32_t)(val)))) + +#define SDK_ATOMIC_LOCAL_SET(addr, bits) \ + ((1UL == sizeof(*(addr))) ? \ + _SDK_AtomicLocalSet1Byte((volatile uint8_t *)(volatile void *)(addr), (uint8_t)(bits)) : \ + ((2UL == sizeof(*(addr))) ? _SDK_AtomicLocalSet2Byte((volatile uint16_t *)(volatile void *)(addr), (uint16_t)(bits)) : \ + _SDK_AtomicLocalSet4Byte((volatile uint32_t *)(volatile void *)(addr), (uint32_t)(bits)))) + +#define SDK_ATOMIC_LOCAL_CLEAR(addr, bits) \ + ((1UL == sizeof(*(addr))) ? \ + _SDK_AtomicLocalClear1Byte((volatile uint8_t *)(volatile void *)(addr), (uint8_t)(bits)) : \ + ((2UL == sizeof(*(addr))) ? \ + _SDK_AtomicLocalClear2Byte((volatile uint16_t *)(volatile void *)(addr), (uint16_t)(bits)) : \ + _SDK_AtomicLocalClear4Byte((volatile uint32_t *)(volatile void *)(addr), (uint32_t)(bits)))) + +#define SDK_ATOMIC_LOCAL_TOGGLE(addr, bits) \ + ((1UL == sizeof(*(addr))) ? \ + _SDK_AtomicLocalToggle1Byte((volatile uint8_t *)(volatile void *)(addr), (uint8_t)(bits)) : \ + ((2UL == sizeof(*(addr))) ? \ + _SDK_AtomicLocalToggle2Byte((volatile uint16_t *)(volatile void *)(addr), (uint16_t)(bits)) : \ + _SDK_AtomicLocalToggle4Byte((volatile uint32_t *)(volatile void *)(addr), (uint32_t)(bits)))) + +#define SDK_ATOMIC_LOCAL_CLEAR_AND_SET(addr, clearBits, setBits) \ + ((1UL == sizeof(*(addr))) ? \ + _SDK_AtomicLocalClearAndSet1Byte((volatile uint8_t *)(volatile void *)(addr), (uint8_t)(clearBits), (uint8_t)(setBits)) : \ + ((2UL == sizeof(*(addr))) ? \ + _SDK_AtomicLocalClearAndSet2Byte((volatile uint16_t *)(volatile void *)(addr), (uint16_t)(clearBits), (uint16_t)(setBits)) : \ + _SDK_AtomicLocalClearAndSet4Byte((volatile uint32_t *)(volatile void *)(addr), (uint32_t)(clearBits), (uint32_t)(setBits)))) +#else + +#define SDK_ATOMIC_LOCAL_ADD(addr, val) \ + do \ + { \ + uint32_t s_atomicOldInt; \ + s_atomicOldInt = DisableGlobalIRQ(); \ + *(addr) += (val); \ + EnableGlobalIRQ(s_atomicOldInt); \ + } while (false) + +#define SDK_ATOMIC_LOCAL_SUB(addr, val) \ + do \ + { \ + uint32_t s_atomicOldInt; \ + s_atomicOldInt = DisableGlobalIRQ(); \ + *(addr) -= (val); \ + EnableGlobalIRQ(s_atomicOldInt); \ + } while (false) + +#define SDK_ATOMIC_LOCAL_SET(addr, bits) \ + do \ + { \ + uint32_t s_atomicOldInt; \ + s_atomicOldInt = DisableGlobalIRQ(); \ + *(addr) |= (bits); \ + EnableGlobalIRQ(s_atomicOldInt); \ + } while (false) + +#define SDK_ATOMIC_LOCAL_CLEAR(addr, bits) \ + do \ + { \ + uint32_t s_atomicOldInt; \ + s_atomicOldInt = DisableGlobalIRQ(); \ + *(addr) &= ~(bits); \ + EnableGlobalIRQ(s_atomicOldInt); \ + } while (false) + +#define SDK_ATOMIC_LOCAL_TOGGLE(addr, bits) \ + do \ + { \ + uint32_t s_atomicOldInt; \ + s_atomicOldInt = DisableGlobalIRQ(); \ + *(addr) ^= (bits); \ + EnableGlobalIRQ(s_atomicOldInt); \ + } while (false) + +#define SDK_ATOMIC_LOCAL_CLEAR_AND_SET(addr, clearBits, setBits) \ + do \ + { \ + uint32_t s_atomicOldInt; \ + s_atomicOldInt = DisableGlobalIRQ(); \ + *(addr) = (*(addr) & ~(clearBits)) | (setBits); \ + EnableGlobalIRQ(s_atomicOldInt); \ + } while (false) + +#endif +/*! @} */ + +/*! @name Timer utilities */ +/*! @{ */ +/*! Macro to convert a microsecond period to raw count value */ +#define USEC_TO_COUNT(us, clockFreqInHz) (uint64_t)(((uint64_t)(us) * (clockFreqInHz)) / 1000000U) +/*! Macro to convert a raw count value to microsecond */ +#define COUNT_TO_USEC(count, clockFreqInHz) (uint64_t)((uint64_t)(count)*1000000U / (clockFreqInHz)) + +/*! Macro to convert a millisecond period to raw count value */ +#define MSEC_TO_COUNT(ms, clockFreqInHz) (uint64_t)((uint64_t)(ms) * (clockFreqInHz) / 1000U) +/*! Macro to convert a raw count value to millisecond */ +#define COUNT_TO_MSEC(count, clockFreqInHz) (uint64_t)((uint64_t)(count)*1000U / (clockFreqInHz)) +/*! @} */ + +/*! @name ISR exit barrier + * @{ + * + * ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping + * exception return operation might vector to incorrect interrupt. + * For Cortex-M7, if core speed much faster than peripheral register write speed, + * the peripheral interrupt flags may be still set after exiting ISR, this results to + * the same error similar with errata 83869. + */ +#if (defined __CORTEX_M) && ((__CORTEX_M == 4U) || (__CORTEX_M == 7U)) +#define SDK_ISR_EXIT_BARRIER __DSB() +#else +#define SDK_ISR_EXIT_BARRIER +#endif + +/*! @} */ + +/*! @name Alignment variable definition macros */ +/*! @{ */ +#if (defined(__ICCARM__)) +/* + * Workaround to disable MISRA C message suppress warnings for IAR compiler. + * http:/ /supp.iar.com/Support/?note=24725 + */ +_Pragma("diag_suppress=Pm120") +#define SDK_PRAGMA(x) _Pragma(#x) + _Pragma("diag_error=Pm120") +/*! Macro to define a variable with alignbytes alignment */ +#define SDK_ALIGN(var, alignbytes) SDK_PRAGMA(data_alignment = alignbytes) var +#elif defined(__CC_ARM) || defined(__ARMCC_VERSION) +/*! Macro to define a variable with alignbytes alignment */ +#define SDK_ALIGN(var, alignbytes) __attribute__((aligned(alignbytes))) var +#elif defined(__GNUC__) || defined(DOXYGEN_OUTPUT) +/*! Macro to define a variable with alignbytes alignment */ +#define SDK_ALIGN(var, alignbytes) var __attribute__((aligned(alignbytes))) +#else +#error Toolchain not supported +#endif + +/*! Macro to define a variable with L1 d-cache line size alignment */ +#if defined(FSL_FEATURE_L1DCACHE_LINESIZE_BYTE) +#define SDK_L1DCACHE_ALIGN(var) SDK_ALIGN(var, FSL_FEATURE_L1DCACHE_LINESIZE_BYTE) +#endif +/*! Macro to define a variable with L2 cache line size alignment */ +#if defined(FSL_FEATURE_L2CACHE_LINESIZE_BYTE) +#define SDK_L2CACHE_ALIGN(var) SDK_ALIGN(var, FSL_FEATURE_L2CACHE_LINESIZE_BYTE) +#endif + +/*! Macro to change a value to a given size aligned value */ +#define SDK_SIZEALIGN(var, alignbytes) \ + ((unsigned int)((var) + ((alignbytes)-1U)) & (unsigned int)(~(unsigned int)((alignbytes)-1U))) +/*! @} */ + +/*! + * @name Non-cacheable region definition macros + * + * For initialized non-zero non-cacheable variables, please use "AT_NONCACHEABLE_SECTION_INIT(var) ={xx};" or + * "AT_NONCACHEABLE_SECTION_ALIGN_INIT(var) ={xx};" in your projects to define them. For zero-inited non-cacheable + * variables, please use "AT_NONCACHEABLE_SECTION(var);" or "AT_NONCACHEABLE_SECTION_ALIGN(var);" to define them, + * these zero-inited variables will be initialized to zero in system startup. + * + * @note For GCC, when the non-cacheable section is required, please define "__STARTUP_INITIALIZE_NONCACHEDATA" + * in your projects to make sure the non-cacheable section variables will be initialized in system startup. + * + * @{ + */ + +/*! + * @def AT_NONCACHEABLE_SECTION(var) + * Define a variable \a var, and place it in non-cacheable section. + * + * @def AT_NONCACHEABLE_SECTION_ALIGN(var, alignbytes) + * Define a variable \a var, and place it in non-cacheable section, the start address + * of the variable is aligned to \a alignbytes. + * + * @def AT_NONCACHEABLE_SECTION_INIT(var) + * Define a variable \a var with initial value, and place it in non-cacheable section. + * + * @def AT_NONCACHEABLE_SECTION_ALIGN_INIT(var, alignbytes) + * Define a variable \a var with initial value, and place it in non-cacheable section, + * the start address of the variable is aligned to \a alignbytes. + */ + +#if ((!(defined(FSL_FEATURE_HAS_NO_NONCACHEABLE_SECTION) && FSL_FEATURE_HAS_NO_NONCACHEABLE_SECTION)) && \ + defined(FSL_FEATURE_L1ICACHE_LINESIZE_BYTE)) + +#if (defined(__ICCARM__)) +#define AT_NONCACHEABLE_SECTION(var) var @"NonCacheable" +#define AT_NONCACHEABLE_SECTION_ALIGN(var, alignbytes) SDK_PRAGMA(data_alignment = alignbytes) var @"NonCacheable" +#define AT_NONCACHEABLE_SECTION_INIT(var) var @"NonCacheable.init" +#define AT_NONCACHEABLE_SECTION_ALIGN_INIT(var, alignbytes) \ + SDK_PRAGMA(data_alignment = alignbytes) var @"NonCacheable.init" + +#elif (defined(__CC_ARM) || defined(__ARMCC_VERSION)) +#define AT_NONCACHEABLE_SECTION_INIT(var) __attribute__((section("NonCacheable.init"))) var +#define AT_NONCACHEABLE_SECTION_ALIGN_INIT(var, alignbytes) \ + __attribute__((section("NonCacheable.init"))) __attribute__((aligned(alignbytes))) var +#if (defined(__CC_ARM)) +#define AT_NONCACHEABLE_SECTION(var) __attribute__((section("NonCacheable"), zero_init)) var +#define AT_NONCACHEABLE_SECTION_ALIGN(var, alignbytes) \ + __attribute__((section("NonCacheable"), zero_init)) __attribute__((aligned(alignbytes))) var +#else +#define AT_NONCACHEABLE_SECTION(var) __attribute__((section(".bss.NonCacheable"))) var +#define AT_NONCACHEABLE_SECTION_ALIGN(var, alignbytes) \ + __attribute__((section(".bss.NonCacheable"))) __attribute__((aligned(alignbytes))) var +#endif + +#elif (defined(__GNUC__)) || defined(DOXYGEN_OUTPUT) +/* For GCC, when the non-cacheable section is required, please define "__STARTUP_INITIALIZE_NONCACHEDATA" + * in your projects to make sure the non-cacheable section variables will be initialized in system startup. + */ +#define AT_NONCACHEABLE_SECTION_INIT(var) __attribute__((section("NonCacheable.init"))) var +#define AT_NONCACHEABLE_SECTION_ALIGN_INIT(var, alignbytes) \ + __attribute__((section("NonCacheable.init"))) var __attribute__((aligned(alignbytes))) +#define AT_NONCACHEABLE_SECTION(var) __attribute__((section("NonCacheable,\"aw\",%nobits @"))) var +#define AT_NONCACHEABLE_SECTION_ALIGN(var, alignbytes) \ + __attribute__((section("NonCacheable,\"aw\",%nobits @"))) var __attribute__((aligned(alignbytes))) +#else +#error Toolchain not supported. +#endif + +#else + +#define AT_NONCACHEABLE_SECTION(var) var +#define AT_NONCACHEABLE_SECTION_ALIGN(var, alignbytes) SDK_ALIGN(var, alignbytes) +#define AT_NONCACHEABLE_SECTION_INIT(var) var +#define AT_NONCACHEABLE_SECTION_ALIGN_INIT(var, alignbytes) SDK_ALIGN(var, alignbytes) + +#endif + +/*! @} */ + +/*! + * @name Time sensitive region + * @{ + */ + +/*! + * @def AT_QUICKACCESS_SECTION_CODE(func) + * Place function in a section which can be accessed quickly by core. + * + * @def AT_QUICKACCESS_SECTION_DATA(var) + * Place data in a section which can be accessed quickly by core. + * + * @def AT_QUICKACCESS_SECTION_DATA_ALIGN(var, alignbytes) + * Place data in a section which can be accessed quickly by core, and the variable + * address is set to align with \a alignbytes. + */ +#if (defined(__ICCARM__)) +#define AT_QUICKACCESS_SECTION_CODE(func) func @"CodeQuickAccess" +#define AT_QUICKACCESS_SECTION_DATA(var) var @"DataQuickAccess" +#define AT_QUICKACCESS_SECTION_DATA_ALIGN(var, alignbytes) \ + SDK_PRAGMA(data_alignment = alignbytes) var @"DataQuickAccess" +#elif (defined(__CC_ARM) || defined(__ARMCC_VERSION)) +#define AT_QUICKACCESS_SECTION_CODE(func) __attribute__((section("CodeQuickAccess"), __noinline__)) func +#define AT_QUICKACCESS_SECTION_DATA(var) __attribute__((section("DataQuickAccess"))) var +#define AT_QUICKACCESS_SECTION_DATA_ALIGN(var, alignbytes) \ + __attribute__((section("DataQuickAccess"))) __attribute__((aligned(alignbytes))) var +#elif (defined(__GNUC__)) || defined(DOXYGEN_OUTPUT) +#define AT_QUICKACCESS_SECTION_CODE(func) __attribute__((section("CodeQuickAccess"), __noinline__)) func +#define AT_QUICKACCESS_SECTION_DATA(var) __attribute__((section("DataQuickAccess"))) var +#define AT_QUICKACCESS_SECTION_DATA_ALIGN(var, alignbytes) \ + __attribute__((section("DataQuickAccess"))) var __attribute__((aligned(alignbytes))) +#else +#error Toolchain not supported. +#endif /* defined(__ICCARM__) */ +/*! @} */ + +/*! + * @name Ram Function + * @{ + * + * @def RAMFUNCTION_SECTION_CODE(func) + * Place function in ram. + */ +#if (defined(__ICCARM__)) +#define RAMFUNCTION_SECTION_CODE(func) func @"RamFunction" +#elif (defined(__CC_ARM) || defined(__ARMCC_VERSION)) +#define RAMFUNCTION_SECTION_CODE(func) __attribute__((section("RamFunction"))) func +#elif (defined(__GNUC__)) || defined(DOXYGEN_OUTPUT) +#define RAMFUNCTION_SECTION_CODE(func) __attribute__((section("RamFunction"))) func +#else +#error Toolchain not supported. +#endif /* defined(__ICCARM__) */ +/*! @} */ + +#if defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) + void DefaultISR(void); +#endif + +/* + * The fsl_clock.h is included here because it needs MAKE_VERSION/MAKE_STATUS/status_t + * defined in previous of this file. + */ +#include "fsl_clock.h" + +/* + * Chip level peripheral reset API, for MCUs that implement peripheral reset control external to a peripheral + */ +#if ((defined(FSL_FEATURE_SOC_SYSCON_COUNT) && (FSL_FEATURE_SOC_SYSCON_COUNT > 0)) || \ + (defined(FSL_FEATURE_SOC_ASYNC_SYSCON_COUNT) && (FSL_FEATURE_SOC_ASYNC_SYSCON_COUNT > 0))) +#include "fsl_reset.h" +#endif + +/******************************************************************************* + * API + ******************************************************************************/ + +#if defined(__cplusplus) +extern "C" { +#endif /* __cplusplus*/ + +/*! + * @brief Enable specific interrupt. + * + * Enable LEVEL1 interrupt. For some devices, there might be multiple interrupt + * levels. For example, there are NVIC and intmux. Here the interrupts connected + * to NVIC are the LEVEL1 interrupts, because they are routed to the core directly. + * The interrupts connected to intmux are the LEVEL2 interrupts, they are routed + * to NVIC first then routed to core. + * + * This function only enables the LEVEL1 interrupts. The number of LEVEL1 interrupts + * is indicated by the feature macro FSL_FEATURE_NUMBER_OF_LEVEL1_INT_VECTORS. + * + * @param interrupt The IRQ number. + * @retval kStatus_Success Interrupt enabled successfully + * @retval kStatus_Fail Failed to enable the interrupt + */ +static inline status_t EnableIRQ(IRQn_Type interrupt) +{ + status_t status = kStatus_Success; + + if (NotAvail_IRQn == interrupt) + { + status = kStatus_Fail; + } + +#if defined(FSL_FEATURE_NUMBER_OF_LEVEL1_INT_VECTORS) && (FSL_FEATURE_NUMBER_OF_LEVEL1_INT_VECTORS > 0) + else if ((int32_t)interrupt >= (int32_t)FSL_FEATURE_NUMBER_OF_LEVEL1_INT_VECTORS) + { + status = kStatus_Fail; + } +#endif + + else + { +#if defined(__GIC_PRIO_BITS) + GIC_EnableIRQ(interrupt); +#else + NVIC_EnableIRQ(interrupt); +#endif + } + + return status; +} + +/*! + * @brief Disable specific interrupt. + * + * Disable LEVEL1 interrupt. For some devices, there might be multiple interrupt + * levels. For example, there are NVIC and intmux. Here the interrupts connected + * to NVIC are the LEVEL1 interrupts, because they are routed to the core directly. + * The interrupts connected to intmux are the LEVEL2 interrupts, they are routed + * to NVIC first then routed to core. + * + * This function only disables the LEVEL1 interrupts. The number of LEVEL1 interrupts + * is indicated by the feature macro FSL_FEATURE_NUMBER_OF_LEVEL1_INT_VECTORS. + * + * @param interrupt The IRQ number. + * @retval kStatus_Success Interrupt disabled successfully + * @retval kStatus_Fail Failed to disable the interrupt + */ +static inline status_t DisableIRQ(IRQn_Type interrupt) +{ + status_t status = kStatus_Success; + + if (NotAvail_IRQn == interrupt) + { + status = kStatus_Fail; + } + +#if defined(FSL_FEATURE_NUMBER_OF_LEVEL1_INT_VECTORS) && (FSL_FEATURE_NUMBER_OF_LEVEL1_INT_VECTORS > 0) + else if ((int32_t)interrupt >= (int32_t)FSL_FEATURE_NUMBER_OF_LEVEL1_INT_VECTORS) + { + status = kStatus_Fail; + } +#endif + + else + { +#if defined(__GIC_PRIO_BITS) + GIC_DisableIRQ(interrupt); +#else + NVIC_DisableIRQ(interrupt); +#endif + } + + return status; +} + +/*! + * @brief Enable the IRQ, and also set the interrupt priority. + * + * Only handle LEVEL1 interrupt. For some devices, there might be multiple interrupt + * levels. For example, there are NVIC and intmux. Here the interrupts connected + * to NVIC are the LEVEL1 interrupts, because they are routed to the core directly. + * The interrupts connected to intmux are the LEVEL2 interrupts, they are routed + * to NVIC first then routed to core. + * + * This function only handles the LEVEL1 interrupts. The number of LEVEL1 interrupts + * is indicated by the feature macro FSL_FEATURE_NUMBER_OF_LEVEL1_INT_VECTORS. + * + * @param interrupt The IRQ to Enable. + * @param priNum Priority number set to interrupt controller register. + * @retval kStatus_Success Interrupt priority set successfully + * @retval kStatus_Fail Failed to set the interrupt priority. + */ +static inline status_t EnableIRQWithPriority(IRQn_Type interrupt, uint8_t priNum) +{ + status_t status = kStatus_Success; + + if (NotAvail_IRQn == interrupt) + { + status = kStatus_Fail; + } + +#if defined(FSL_FEATURE_NUMBER_OF_LEVEL1_INT_VECTORS) && (FSL_FEATURE_NUMBER_OF_LEVEL1_INT_VECTORS > 0) + else if ((int32_t)interrupt >= (int32_t)FSL_FEATURE_NUMBER_OF_LEVEL1_INT_VECTORS) + { + status = kStatus_Fail; + } +#endif + + else + { +#if defined(__GIC_PRIO_BITS) + GIC_SetPriority(interrupt, priNum); + GIC_EnableIRQ(interrupt); +#else + NVIC_SetPriority(interrupt, priNum); + NVIC_EnableIRQ(interrupt); +#endif + } + + return status; +} + +/*! + * @brief Set the IRQ priority. + * + * Only handle LEVEL1 interrupt. For some devices, there might be multiple interrupt + * levels. For example, there are NVIC and intmux. Here the interrupts connected + * to NVIC are the LEVEL1 interrupts, because they are routed to the core directly. + * The interrupts connected to intmux are the LEVEL2 interrupts, they are routed + * to NVIC first then routed to core. + * + * This function only handles the LEVEL1 interrupts. The number of LEVEL1 interrupts + * is indicated by the feature macro FSL_FEATURE_NUMBER_OF_LEVEL1_INT_VECTORS. + * + * @param interrupt The IRQ to set. + * @param priNum Priority number set to interrupt controller register. + * + * @retval kStatus_Success Interrupt priority set successfully + * @retval kStatus_Fail Failed to set the interrupt priority. + */ +static inline status_t IRQ_SetPriority(IRQn_Type interrupt, uint8_t priNum) +{ + status_t status = kStatus_Success; + + if (NotAvail_IRQn == interrupt) + { + status = kStatus_Fail; + } + +#if defined(FSL_FEATURE_NUMBER_OF_LEVEL1_INT_VECTORS) && (FSL_FEATURE_NUMBER_OF_LEVEL1_INT_VECTORS > 0) + else if ((int32_t)interrupt >= (int32_t)FSL_FEATURE_NUMBER_OF_LEVEL1_INT_VECTORS) + { + status = kStatus_Fail; + } +#endif + + else + { +#if defined(__GIC_PRIO_BITS) + GIC_SetPriority(interrupt, priNum); +#else + NVIC_SetPriority(interrupt, priNum); +#endif + } + + return status; +} + +/*! + * @brief Clear the pending IRQ flag. + * + * Only handle LEVEL1 interrupt. For some devices, there might be multiple interrupt + * levels. For example, there are NVIC and intmux. Here the interrupts connected + * to NVIC are the LEVEL1 interrupts, because they are routed to the core directly. + * The interrupts connected to intmux are the LEVEL2 interrupts, they are routed + * to NVIC first then routed to core. + * + * This function only handles the LEVEL1 interrupts. The number of LEVEL1 interrupts + * is indicated by the feature macro FSL_FEATURE_NUMBER_OF_LEVEL1_INT_VECTORS. + * + * @param interrupt The flag which IRQ to clear. + * + * @retval kStatus_Success Interrupt priority set successfully + * @retval kStatus_Fail Failed to set the interrupt priority. + */ +static inline status_t IRQ_ClearPendingIRQ(IRQn_Type interrupt) +{ + status_t status = kStatus_Success; + + if (NotAvail_IRQn == interrupt) + { + status = kStatus_Fail; + } + +#if defined(FSL_FEATURE_NUMBER_OF_LEVEL1_INT_VECTORS) && (FSL_FEATURE_NUMBER_OF_LEVEL1_INT_VECTORS > 0) + else if ((int32_t)interrupt >= (int32_t)FSL_FEATURE_NUMBER_OF_LEVEL1_INT_VECTORS) + { + status = kStatus_Fail; + } +#endif + + else + { +#if defined(__GIC_PRIO_BITS) + GIC_ClearPendingIRQ(interrupt); +#else + NVIC_ClearPendingIRQ(interrupt); +#endif + } + + return status; +} + +/*! + * @brief Disable the global IRQ + * + * Disable the global interrupt and return the current primask register. User is required to provided the primask + * register for the EnableGlobalIRQ(). + * + * @return Current primask value. + */ +static inline uint32_t DisableGlobalIRQ(void) +{ + uint32_t mask; + +#if defined(CPSR_I_Msk) + mask = __get_CPSR() & CPSR_I_Msk; +#elif defined(DAIF_I_BIT) + mask = __get_DAIF() & DAIF_I_BIT; +#else + mask = __get_PRIMASK(); +#endif + __disable_irq(); + + return mask; +} + +/*! + * @brief Enable the global IRQ + * + * Set the primask register with the provided primask value but not just enable the primask. The idea is for the + * convenience of integration of RTOS. some RTOS get its own management mechanism of primask. User is required to + * use the EnableGlobalIRQ() and DisableGlobalIRQ() in pair. + * + * @param primask value of primask register to be restored. The primask value is supposed to be provided by the + * DisableGlobalIRQ(). + */ +static inline void EnableGlobalIRQ(uint32_t primask) +{ +#if defined(CPSR_I_Msk) + __set_CPSR((__get_CPSR() & ~CPSR_I_Msk) | primask); +#elif defined(DAIF_I_BIT) + if (0UL == primask) + { + __enable_irq(); + } +#else + __set_PRIMASK(primask); +#endif +} + +#if defined(ENABLE_RAM_VECTOR_TABLE) +/*! + * @brief install IRQ handler + * + * @param irq IRQ number + * @param irqHandler IRQ handler address + * @return The old IRQ handler address + */ +uint32_t InstallIRQHandler(IRQn_Type irq, uint32_t irqHandler); +#endif /* ENABLE_RAM_VECTOR_TABLE. */ + +#if (defined(FSL_FEATURE_SOC_SYSCON_COUNT) && (FSL_FEATURE_SOC_SYSCON_COUNT > 0)) + +/* + * When FSL_FEATURE_POWERLIB_EXTEND is defined to non-zero value, + * powerlib should be used instead of these functions. + */ +#if !(defined(FSL_FEATURE_POWERLIB_EXTEND) && (FSL_FEATURE_POWERLIB_EXTEND != 0)) +/*! + * @brief Enable specific interrupt for wake-up from deep-sleep mode. + * + * Enable the interrupt for wake-up from deep sleep mode. + * Some interrupts are typically used in sleep mode only and will not occur during + * deep-sleep mode because relevant clocks are stopped. However, it is possible to enable + * those clocks (significantly increasing power consumption in the reduced power mode), + * making these wake-ups possible. + * + * @note This function also enables the interrupt in the NVIC (EnableIRQ() is called internaly). + * + * @param interrupt The IRQ number. + */ +void EnableDeepSleepIRQ(IRQn_Type interrupt); + +/*! + * @brief Disable specific interrupt for wake-up from deep-sleep mode. + * + * Disable the interrupt for wake-up from deep sleep mode. + * Some interrupts are typically used in sleep mode only and will not occur during + * deep-sleep mode because relevant clocks are stopped. However, it is possible to enable + * those clocks (significantly increasing power consumption in the reduced power mode), + * making these wake-ups possible. + * + * @note This function also disables the interrupt in the NVIC (DisableIRQ() is called internaly). + * + * @param interrupt The IRQ number. + */ +void DisableDeepSleepIRQ(IRQn_Type interrupt); +#endif /* FSL_FEATURE_POWERLIB_EXTEND */ +#endif /* FSL_FEATURE_SOC_SYSCON_COUNT */ + +#if defined(DWT) +/*! + * @brief Enable the counter to get CPU cycles. + */ +void MSDK_EnableCpuCycleCounter(void); + +/*! + * @brief Get the current CPU cycle count. + * + * @return Current CPU cycle count. + */ +uint32_t MSDK_GetCpuCycleCount(void); +#endif + +#if defined(__cplusplus) +} +#endif /* __cplusplus*/ + +/*! @} */ + +#endif /* FSL_COMMON_ARM_H_ */ diff --git a/drivers/Inc/fsl_component_generic_list.h b/drivers/Inc/fsl_component_generic_list.h new file mode 100644 index 0000000..ab7ea1a --- /dev/null +++ b/drivers/Inc/fsl_component_generic_list.h @@ -0,0 +1,219 @@ +/* + * Copyright 2018-2020, 2022 NXP + * All rights reserved. + * + * + * SPDX-License-Identifier: BSD-3-Clause + */ + +#ifndef _GENERIC_LIST_H_ +#define _GENERIC_LIST_H_ + +#ifndef SDK_COMPONENT_DEPENDENCY_FSL_COMMON +#define SDK_COMPONENT_DEPENDENCY_FSL_COMMON (1U) +#endif +#if (defined(SDK_COMPONENT_DEPENDENCY_FSL_COMMON) && (SDK_COMPONENT_DEPENDENCY_FSL_COMMON > 0U)) +#include "fsl_common.h" +#else +#endif +/*! + * @addtogroup GenericList + * @{ + */ + +/********************************************************************************** + * Include + ***********************************************************************************/ + +/********************************************************************************** + * Public macro definitions + ***********************************************************************************/ +/*! @brief Definition to determine whether use list light. */ +#ifndef GENERIC_LIST_LIGHT +#define GENERIC_LIST_LIGHT (1) +#endif + +/*! @brief Definition to determine whether enable list duplicated checking. */ +#ifndef GENERIC_LIST_DUPLICATED_CHECKING +#define GENERIC_LIST_DUPLICATED_CHECKING (0) +#endif + +/********************************************************************************** + * Public type definitions + ***********************************************************************************/ +/*! @brief The list status */ +#if (defined(SDK_COMPONENT_DEPENDENCY_FSL_COMMON) && (SDK_COMPONENT_DEPENDENCY_FSL_COMMON > 0U)) +typedef enum _list_status +{ + kLIST_Ok = kStatus_Success, /*!< Success */ + kLIST_DuplicateError = MAKE_STATUS(kStatusGroup_LIST, 1), /*!< Duplicate Error */ + kLIST_Full = MAKE_STATUS(kStatusGroup_LIST, 2), /*!< FULL */ + kLIST_Empty = MAKE_STATUS(kStatusGroup_LIST, 3), /*!< Empty */ + kLIST_OrphanElement = MAKE_STATUS(kStatusGroup_LIST, 4), /*!< Orphan Element */ + kLIST_NotSupport = MAKE_STATUS(kStatusGroup_LIST, 5), /*!< Not Support */ +} list_status_t; +#else +typedef enum _list_status +{ + kLIST_Ok = 0, /*!< Success */ + kLIST_DuplicateError = 1, /*!< Duplicate Error */ + kLIST_Full = 2, /*!< FULL */ + kLIST_Empty = 3, /*!< Empty */ + kLIST_OrphanElement = 4, /*!< Orphan Element */ + kLIST_NotSupport = 5, /*!< Not Support */ +} list_status_t; +#endif + +/*! @brief The list structure*/ +typedef struct list_label +{ + struct list_element_tag *head; /*!< list head */ + struct list_element_tag *tail; /*!< list tail */ + uint32_t size; /*!< list size */ + uint32_t max; /*!< list max number of elements */ +} list_label_t, *list_handle_t; +#if (defined(GENERIC_LIST_LIGHT) && (GENERIC_LIST_LIGHT > 0U)) +/*! @brief The list element*/ +typedef struct list_element_tag +{ + struct list_element_tag *next; /*!< next list element */ + struct list_label *list; /*!< pointer to the list */ +} list_element_t, *list_element_handle_t; +#else +/*! @brief The list element*/ +typedef struct list_element_tag +{ + struct list_element_tag *next; /*!< next list element */ + struct list_element_tag *prev; /*!< previous list element */ + struct list_label *list; /*!< pointer to the list */ +} list_element_t, *list_element_handle_t; +#endif +/********************************************************************************** + * Public prototypes + ***********************************************************************************/ +/********************************************************************************** + * API + **********************************************************************************/ + +#if defined(__cplusplus) +extern "C" { +#endif /* _cplusplus */ +/*! + * @brief Initialize the list. + * + * This function initialize the list. + * + * @param list - List handle to initialize. + * @param max - Maximum number of elements in list. 0 for unlimited. + */ +void LIST_Init(list_handle_t list, uint32_t max); + +/*! + * @brief Gets the list that contains the given element. + * + * + * @param listElement - Handle of the element. + * @retval NULL if element is orphan, Handle of the list the element is inserted into. + */ +list_handle_t LIST_GetList(list_element_handle_t listElement); + +/*! + * @brief Links element to the head of the list. + * + * @param list - Handle of the list. + * @param listElement - Handle of the element. + * @retval kLIST_Full if list is full, kLIST_Ok if insertion was successful. + */ +list_status_t LIST_AddHead(list_handle_t list, list_element_handle_t listElement); + +/*! + * @brief Links element to the tail of the list. + * + * @param list - Handle of the list. + * @param listElement - Handle of the element. + * @retval kLIST_Full if list is full, kLIST_Ok if insertion was successful. + */ +list_status_t LIST_AddTail(list_handle_t list, list_element_handle_t listElement); + +/*! + * @brief Unlinks element from the head of the list. + * + * @param list - Handle of the list. + * + * @retval NULL if list is empty, handle of removed element(pointer) if removal was successful. + */ +list_element_handle_t LIST_RemoveHead(list_handle_t list); + +/*! + * @brief Gets head element handle. + * + * @param list - Handle of the list. + * + * @retval NULL if list is empty, handle of removed element(pointer) if removal was successful. + */ +list_element_handle_t LIST_GetHead(list_handle_t list); + +/*! + * @brief Gets next element handle for given element handle. + * + * @param listElement - Handle of the element. + * + * @retval NULL if list is empty, handle of removed element(pointer) if removal was successful. + */ +list_element_handle_t LIST_GetNext(list_element_handle_t listElement); + +/*! + * @brief Gets previous element handle for given element handle. + * + * @param listElement - Handle of the element. + * + * @retval NULL if list is empty, handle of removed element(pointer) if removal was successful. + */ +list_element_handle_t LIST_GetPrev(list_element_handle_t listElement); + +/*! + * @brief Unlinks an element from its list. + * + * @param listElement - Handle of the element. + * + * @retval kLIST_OrphanElement if element is not part of any list. + * @retval kLIST_Ok if removal was successful. + */ +list_status_t LIST_RemoveElement(list_element_handle_t listElement); + +/*! + * @brief Links an element in the previous position relative to a given member of a list. + * + * @param listElement - Handle of the element. + * @param newElement - New element to insert before the given member. + * + * @retval kLIST_OrphanElement if element is not part of any list. + * @retval kLIST_Ok if removal was successful. + */ +list_status_t LIST_AddPrevElement(list_element_handle_t listElement, list_element_handle_t newElement); + +/*! + * @brief Gets the current size of a list. + * + * @param list - Handle of the list. + * + * @retval Current size of the list. + */ +uint32_t LIST_GetSize(list_handle_t list); + +/*! + * @brief Gets the number of free places in the list. + * + * @param list - Handle of the list. + * + * @retval Available size of the list. + */ +uint32_t LIST_GetAvailableSize(list_handle_t list); + +/*! @} */ + +#if defined(__cplusplus) +} +#endif +/*! @}*/ +#endif /*_GENERIC_LIST_H_*/ diff --git a/drivers/Inc/fsl_debug_console.h b/drivers/Inc/fsl_debug_console.h new file mode 100644 index 0000000..3efe7d3 --- /dev/null +++ b/drivers/Inc/fsl_debug_console.h @@ -0,0 +1,295 @@ +/* + * Copyright 2017-2018, 2020, 2022 NXP + * All rights reserved. + * + * + * SPDX-License-Identifier: BSD-3-Clause + * + * Debug console shall provide input and output functions to scan and print formatted data. + * o Support a format specifier for PRINTF follows this prototype "%[flags][width][.precision][length]specifier" + * - [flags] :'-', '+', '#', ' ', '0' + * - [width]: number (0,1...) + * - [.precision]: number (0,1...) + * - [length]: do not support + * - [specifier]: 'd', 'i', 'f', 'F', 'x', 'X', 'o', 'p', 'u', 'c', 's', 'n' + * o Support a format specifier for SCANF follows this prototype " %[*][width][length]specifier" + * - [*]: is supported. + * - [width]: number (0,1...) + * - [length]: 'h', 'hh', 'l','ll','L'. ignore ('j','z','t') + * - [specifier]: 'd', 'i', 'u', 'f', 'F', 'e', 'E', 'g', 'G', 'a', 'A', 'o', 'c', 's' + */ + +#ifndef _FSL_DEBUGCONSOLE_H_ +#define _FSL_DEBUGCONSOLE_H_ + +#include "fsl_common.h" + +/*! + * @addtogroup debugconsolelite + * @{ + */ + +/******************************************************************************* + * Definitions + ******************************************************************************/ + +/*! @brief Definition select redirect toolchain printf, scanf to uart or not. */ +#define DEBUGCONSOLE_REDIRECT_TO_TOOLCHAIN 0U /*!< Select toolchain printf and scanf. */ +#define DEBUGCONSOLE_REDIRECT_TO_SDK 1U /*!< Select SDK version printf, scanf. */ +#define DEBUGCONSOLE_DISABLE 2U /*!< Disable debugconsole function. */ + +/*! @brief Definition to select sdk or toolchain printf, scanf. */ +#ifndef SDK_DEBUGCONSOLE +#define SDK_DEBUGCONSOLE DEBUGCONSOLE_REDIRECT_TO_SDK +#endif + +#if defined(SDK_DEBUGCONSOLE) && !(SDK_DEBUGCONSOLE) +#include +#else +#include +#endif + +/*! @brief Definition to printf the float number. */ +#ifndef PRINTF_FLOAT_ENABLE +#define PRINTF_FLOAT_ENABLE 0U +#endif /* PRINTF_FLOAT_ENABLE */ + +/*! @brief Definition to scanf the float number. */ +#ifndef SCANF_FLOAT_ENABLE +#define SCANF_FLOAT_ENABLE 0U +#endif /* SCANF_FLOAT_ENABLE */ + +/*! @brief Definition to support advanced format specifier for printf. */ +#ifndef PRINTF_ADVANCED_ENABLE +#define PRINTF_ADVANCED_ENABLE 0U +#endif /* PRINTF_ADVANCED_ENABLE */ + +/*! @brief Definition to support advanced format specifier for scanf. */ +#ifndef SCANF_ADVANCED_ENABLE +#define SCANF_ADVANCED_ENABLE 0U +#endif /* SCANF_ADVANCED_ENABLE */ + +/*! @brief Definition to select redirect toolchain printf, scanf to uart or not. + * + * if SDK_DEBUGCONSOLE defined to 0,it represents select toolchain printf, scanf. + * if SDK_DEBUGCONSOLE defined to 1,it represents select SDK version printf, scanf. + * if SDK_DEBUGCONSOLE defined to 2,it represents disable debugconsole function. + */ +#if SDK_DEBUGCONSOLE == DEBUGCONSOLE_DISABLE /* Disable debug console */ +static inline int DbgConsole_Disabled(void) +{ + return -1; +} +#define PRINTF(...) DbgConsole_Disabled() +#define SCANF(...) DbgConsole_Disabled() +#define PUTCHAR(...) DbgConsole_Disabled() +#define GETCHAR() DbgConsole_Disabled() +#elif SDK_DEBUGCONSOLE == DEBUGCONSOLE_REDIRECT_TO_SDK /* Select printf, scanf, putchar, getchar of SDK version. */ +#define PRINTF DbgConsole_Printf +#define SCANF DbgConsole_Scanf +#define PUTCHAR DbgConsole_Putchar +#define GETCHAR DbgConsole_Getchar +#elif SDK_DEBUGCONSOLE == \ + DEBUGCONSOLE_REDIRECT_TO_TOOLCHAIN /* Select printf, scanf, putchar, getchar of toolchain. \ */ +#define PRINTF printf +#define SCANF scanf +#define PUTCHAR putchar +#define GETCHAR getchar +#endif /* SDK_DEBUGCONSOLE */ +/*! @} */ + +/*! @brief serial port type + * + * The serial port type aligned with the definition in serial manager, but please note + * only kSerialPort_Uart can be supported in debug console lite. + */ +#ifndef _SERIAL_PORT_T_ +#define _SERIAL_PORT_T_ +typedef enum _serial_port_type +{ + kSerialPort_None = 0U, /*!< Serial port is none */ + kSerialPort_Uart = 1U, /*!< Serial port UART */ + kSerialPort_UsbCdc, /*!< Serial port USB CDC */ + kSerialPort_Swo, /*!< Serial port SWO */ + kSerialPort_Virtual, /*!< Serial port Virtual */ + kSerialPort_Rpmsg, /*!< Serial port RPMSG */ + kSerialPort_UartDma, /*!< Serial port UART DMA*/ + kSerialPort_SpiMaster, /*!< Serial port SPIMASTER*/ + kSerialPort_SpiSlave, /*!< Serial port SPISLAVE*/ +} serial_port_type_t; +#endif + +/*! + * @addtogroup debugconsolelite + * @{ + */ +/******************************************************************************* + * Prototypes + ******************************************************************************/ + +#if defined(__cplusplus) +extern "C" { +#endif /* __cplusplus */ + +/*! @name Initialization*/ +/* @{ */ + +#if ((SDK_DEBUGCONSOLE == DEBUGCONSOLE_REDIRECT_TO_SDK) || defined(SDK_DEBUGCONSOLE_UART)) +/*! + * @brief Initializes the peripheral used for debug messages. + * + * Call this function to enable debug log messages to be output via the specified peripheral, + * frequency of peripheral source clock, and base address at the specified baud rate. + * After this function has returned, stdout and stdin are connected to the selected peripheral. + * + * @param instance The instance of the module.If the device is kSerialPort_Uart, + * the instance is UART peripheral instance. The UART hardware peripheral + * type is determined by UART adapter. For example, if the instance is 1, + * if the lpuart_adapter.c is added to the current project, the UART periheral + * is LPUART1. + * If the uart_adapter.c is added to the current project, the UART periheral + * is UART1. + * @param baudRate The desired baud rate in bits per second. + * @param device Low level device type for the debug console, can be one of the following. + * @arg kSerialPort_Uart. + * @param clkSrcFreq Frequency of peripheral source clock. + * + * @return Indicates whether initialization was successful or not. + * @retval kStatus_Success Execution successfully + * @retval kStatus_Fail Execution failure + */ +status_t DbgConsole_Init(uint8_t instance, uint32_t baudRate, serial_port_type_t device, uint32_t clkSrcFreq); + +/*! + * @brief De-initializes the peripheral used for debug messages. + * + * Call this function to disable debug log messages to be output via the specified peripheral + * base address and at the specified baud rate. + * + * @return Indicates whether de-initialization was successful or not. + */ +status_t DbgConsole_Deinit(void); +/*! + * @brief Prepares to enter low power consumption. + * + * This function is used to prepare to enter low power consumption. + * + * @return Indicates whether de-initialization was successful or not. + */ +status_t DbgConsole_EnterLowpower(void); + +/*! + * @brief Restores from low power consumption. + * + * This function is used to restore from low power consumption. + * + * @return Indicates whether de-initialization was successful or not. + */ +status_t DbgConsole_ExitLowpower(void); + +#else +/*! + * Use an error to replace the DbgConsole_Init when SDK_DEBUGCONSOLE is not DEBUGCONSOLE_REDIRECT_TO_SDK and + * SDK_DEBUGCONSOLE_UART is not defined. + */ +static inline status_t DbgConsole_Init(uint8_t instance, + uint32_t baudRate, + serial_port_type_t device, + uint32_t clkSrcFreq) +{ + (void)instance; + (void)baudRate; + (void)device; + (void)clkSrcFreq; + return (status_t)kStatus_Fail; +} +/*! + * Use an error to replace the DbgConsole_Deinit when SDK_DEBUGCONSOLE is not DEBUGCONSOLE_REDIRECT_TO_SDK and + * SDK_DEBUGCONSOLE_UART is not defined. + */ +static inline status_t DbgConsole_Deinit(void) +{ + return (status_t)kStatus_Fail; +} + +/*! + * Use an error to replace the DbgConsole_EnterLowpower when SDK_DEBUGCONSOLE is not DEBUGCONSOLE_REDIRECT_TO_SDK and + * SDK_DEBUGCONSOLE_UART is not defined. + */ +static inline status_t DbgConsole_EnterLowpower(void) +{ + return (status_t)kStatus_Fail; +} + +/*! + * Use an error to replace the DbgConsole_ExitLowpower when SDK_DEBUGCONSOLE is not DEBUGCONSOLE_REDIRECT_TO_SDK and + * SDK_DEBUGCONSOLE_UART is not defined. + */ +static inline status_t DbgConsole_ExitLowpower(void) +{ + return (status_t)kStatus_Fail; +} + +#endif /* ((SDK_DEBUGCONSOLE == DEBUGCONSOLE_REDIRECT_TO_SDK) || defined(SDK_DEBUGCONSOLE_UART)) */ + +#if (defined(SDK_DEBUGCONSOLE) && (SDK_DEBUGCONSOLE == DEBUGCONSOLE_REDIRECT_TO_SDK)) +/*! + * @brief Writes formatted output to the standard output stream. + * + * Call this function to write a formatted output to the standard output stream. + * + * @param fmt_s Format control string. + * @return Returns the number of characters printed or a negative value if an error occurs. + */ +int DbgConsole_Printf(const char *fmt_s, ...); + +/*! + * @brief Writes formatted output to the standard output stream. + * + * Call this function to write a formatted output to the standard output stream. + * + * @param fmt_s Format control string. + * @param formatStringArg Format arguments. + * @return Returns the number of characters printed or a negative value if an error occurs. + */ +int DbgConsole_Vprintf(const char *fmt_s, va_list formatStringArg); + +/*! + * @brief Writes a character to stdout. + * + * Call this function to write a character to stdout. + * + * @param dbgConsoleCh Character to be written. + * @return Returns the character written. + */ +int DbgConsole_Putchar(int dbgConsoleCh); + +/*! + * @brief Reads formatted data from the standard input stream. + * + * Call this function to read formatted data from the standard input stream. + * + * @param fmt_s Format control string. + * @return Returns the number of fields successfully converted and assigned. + */ +int DbgConsole_Scanf(char *fmt_s, ...); + +/*! + * @brief Reads a character from standard input. + * + * Call this function to read a character from standard input. + * + * @return Returns the character read. + */ +int DbgConsole_Getchar(void); + +#endif /* SDK_DEBUGCONSOLE */ + +/*! @} */ + +#if defined(__cplusplus) +} +#endif /* __cplusplus */ + +/*! @} */ +#endif /* _FSL_DEBUGCONSOLE_H_ */ diff --git a/drivers/Inc/fsl_flexcomm.h b/drivers/Inc/fsl_flexcomm.h new file mode 100644 index 0000000..3b4669a --- /dev/null +++ b/drivers/Inc/fsl_flexcomm.h @@ -0,0 +1,64 @@ +/* + * Copyright (c) 2016, Freescale Semiconductor, Inc. + * Copyright 2016-2019 NXP + * All rights reserved. + * + * SPDX-License-Identifier: BSD-3-Clause + */ +#ifndef FSL_FLEXCOMM_H_ +#define FSL_FLEXCOMM_H_ + +#include "fsl_common.h" + +/*! + * @addtogroup flexcomm_driver + * @{ + */ + +/*! @name Driver version */ +/*! @{ */ +/*! @brief FlexCOMM driver version 2.0.2. */ +#define FSL_FLEXCOMM_DRIVER_VERSION (MAKE_VERSION(2, 0, 2)) +/*! @} */ + +/*! @brief FLEXCOMM peripheral modes. */ +typedef enum +{ + FLEXCOMM_PERIPH_NONE, /*!< No peripheral */ + FLEXCOMM_PERIPH_USART, /*!< USART peripheral */ + FLEXCOMM_PERIPH_SPI, /*!< SPI Peripheral */ + FLEXCOMM_PERIPH_I2C, /*!< I2C Peripheral */ + FLEXCOMM_PERIPH_I2S_TX, /*!< I2S TX Peripheral */ + FLEXCOMM_PERIPH_I2S_RX, /*!< I2S RX Peripheral */ +} FLEXCOMM_PERIPH_T; + +/*! @brief Typedef for interrupt handler. */ +typedef void (*flexcomm_irq_handler_t)(void *base, void *handle); + +/*! @brief Array with IRQ number for each FLEXCOMM module. */ +extern IRQn_Type const kFlexcommIrqs[]; + +/******************************************************************************* + * API + ******************************************************************************/ +#if defined(__cplusplus) +extern "C" { +#endif + +/*! @brief Returns instance number for FLEXCOMM module with given base address. */ +uint32_t FLEXCOMM_GetInstance(void *base); + +/*! @brief Initializes FLEXCOMM and selects peripheral mode according to the second parameter. */ +status_t FLEXCOMM_Init(void *base, FLEXCOMM_PERIPH_T periph); + +/*! @brief Sets IRQ handler for given FLEXCOMM module. It is used by drivers register IRQ handler according to FLEXCOMM + * mode */ +void FLEXCOMM_SetIRQHandler(void *base, flexcomm_irq_handler_t handler, void *flexcommHandle); + +#if defined(__cplusplus) +} +#endif + +/*! @} */ + +#endif /* FSL_FLEXCOMM_H_*/ diff --git a/drivers/Inc/fsl_power.h b/drivers/Inc/fsl_power.h new file mode 100644 index 0000000..37d77ce --- /dev/null +++ b/drivers/Inc/fsl_power.h @@ -0,0 +1,611 @@ +/* + * Copyright 2017, NXP + * All rights reserved. + * + * SPDX-License-Identifier: BSD-3-Clause + */ +#ifndef _FSL_POWER_H_ +#define _FSL_POWER_H_ + +#include "fsl_common.h" +#include "fsl_device_registers.h" +#include + +/*! + * @addtogroup power + * @{ + */ +/******************************************************************************* + * Definitions + ******************************************************************************/ + +/*! @name Driver version */ +/*@{*/ +/*! @brief power driver version 2.0.1. */ +#define FSL_POWER_DRIVER_VERSION (MAKE_VERSION(2, 0, 1)) +/*@}*/ + +/* Power mode configuration API parameter */ +typedef enum _power_mode_config +{ + kPmu_Sleep = 0U, + kPmu_Deep_Sleep = 1U, + kPmu_PowerDown = 2U, + kPmu_Deep_PowerDown = 3U, +} power_mode_cfg_t; + +/** + * @brief Analog components power modes control during low power modes + */ +typedef enum pd_bits +{ + kPDRUNCFG_PD_DCDC = (1UL << 0), + kPDRUNCFG_PD_BIAS = (1UL << 1), + kPDRUNCFG_PD_BODCORE = (1UL << 2), + kPDRUNCFG_PD_BODVBAT = (1UL << 3), + kPDRUNCFG_PD_FRO1M = (1UL << 4), + kPDRUNCFG_PD_FRO192M = (1UL << 5), + kPDRUNCFG_PD_FRO32K = (1UL << 6), + kPDRUNCFG_PD_XTAL32K = (1UL << 7), + kPDRUNCFG_PD_XTAL32M = (1UL << 8), + kPDRUNCFG_PD_PLL0 = (1UL << 9), + kPDRUNCFG_PD_PLL1 = (1UL << 10), + kPDRUNCFG_PD_USB0_PHY = (1UL << 11), + kPDRUNCFG_PD_USB1_PHY = (1UL << 12), + kPDRUNCFG_PD_COMP = (1UL << 13), + kPDRUNCFG_PD_TEMPSENS = (1UL << 14), + kPDRUNCFG_PD_GPADC = (1UL << 15), + kPDRUNCFG_PD_LDOMEM = (1UL << 16), + kPDRUNCFG_PD_LDODEEPSLEEP = (1UL << 17), + kPDRUNCFG_PD_LDOUSBHS = (1UL << 18), + kPDRUNCFG_PD_LDOGPADC = (1UL << 19), + kPDRUNCFG_PD_LDOXO32M = (1UL << 20), + kPDRUNCFG_PD_LDOFLASHNV = (1UL << 21), + kPDRUNCFG_PD_RNG = (1UL << 22), + kPDRUNCFG_PD_PLL0_SSCG = (1UL << 23), + kPDRUNCFG_PD_ROM = (1UL << 24), + /* + This enum member has no practical meaning,it is used to avoid MISRA issue, + user should not trying to use it. + */ + kPDRUNCFG_ForceUnsigned = 0x80000000U, +} pd_bit_t; + +/*! @brief BOD VBAT level */ +typedef enum _power_bod_vbat_level +{ + kPOWER_BodVbatLevel1000mv = 0, /*!< Brown out detector VBAT level 1V */ + kPOWER_BodVbatLevel1100mv = 1, /*!< Brown out detector VBAT level 1.1V */ + kPOWER_BodVbatLevel1200mv = 2, /*!< Brown out detector VBAT level 1.2V */ + kPOWER_BodVbatLevel1300mv = 3, /*!< Brown out detector VBAT level 1.3V */ + kPOWER_BodVbatLevel1400mv = 4, /*!< Brown out detector VBAT level 1.4V */ + kPOWER_BodVbatLevel1500mv = 5, /*!< Brown out detector VBAT level 1.5V */ + kPOWER_BodVbatLevel1600mv = 6, /*!< Brown out detector VBAT level 1.6V */ + kPOWER_BodVbatLevel1650mv = 7, /*!< Brown out detector VBAT level 1.65V */ + kPOWER_BodVbatLevel1700mv = 8, /*!< Brown out detector VBAT level 1.7V */ + kPOWER_BodVbatLevel1750mv = 9, /*!< Brown out detector VBAT level 1.75V */ + kPOWER_BodVbatLevel1800mv = 10, /*!< Brown out detector VBAT level 1.8V */ + kPOWER_BodVbatLevel1900mv = 11, /*!< Brown out detector VBAT level 1.9V */ + kPOWER_BodVbatLevel2000mv = 12, /*!< Brown out detector VBAT level 2V */ + kPOWER_BodVbatLevel2100mv = 13, /*!< Brown out detector VBAT level 2.1V */ + kPOWER_BodVbatLevel2200mv = 14, /*!< Brown out detector VBAT level 2.2V */ + kPOWER_BodVbatLevel2300mv = 15, /*!< Brown out detector VBAT level 2.3V */ + kPOWER_BodVbatLevel2400mv = 16, /*!< Brown out detector VBAT level 2.4V */ + kPOWER_BodVbatLevel2500mv = 17, /*!< Brown out detector VBAT level 2.5V */ + kPOWER_BodVbatLevel2600mv = 18, /*!< Brown out detector VBAT level 2.6V */ + kPOWER_BodVbatLevel2700mv = 19, /*!< Brown out detector VBAT level 2.7V */ + kPOWER_BodVbatLevel2806mv = 20, /*!< Brown out detector VBAT level 2.806V */ + kPOWER_BodVbatLevel2900mv = 21, /*!< Brown out detector VBAT level 2.9V */ + kPOWER_BodVbatLevel3000mv = 22, /*!< Brown out detector VBAT level 3.0V */ + kPOWER_BodVbatLevel3100mv = 23, /*!< Brown out detector VBAT level 3.1V */ + kPOWER_BodVbatLevel3200mv = 24, /*!< Brown out detector VBAT level 3.2V */ + kPOWER_BodVbatLevel3300mv = 25, /*!< Brown out detector VBAT level 3.3V */ +} power_bod_vbat_level_t; + +/*! @brief BOD Hysteresis control */ +typedef enum _power_bod_hyst +{ + kPOWER_BodHystLevel25mv = 0U, /*!< BOD Hysteresis control level 25mv */ + kPOWER_BodHystLevel50mv = 1U, /*!< BOD Hysteresis control level 50mv */ + kPOWER_BodHystLevel75mv = 2U, /*!< BOD Hysteresis control level 75mv */ + kPOWER_BodHystLevel100mv = 3U, /*!< BOD Hysteresis control level 100mv */ +} power_bod_hyst_t; + +/*! @brief BOD core level */ +typedef enum _power_bod_core_level +{ + kPOWER_BodCoreLevel600mv = 0, /*!< Brown out detector core level 600mV */ + kPOWER_BodCoreLevel650mv = 1, /*!< Brown out detector core level 650mV */ + kPOWER_BodCoreLevel700mv = 2, /*!< Brown out detector core level 700mV */ + kPOWER_BodCoreLevel750mv = 3, /*!< Brown out detector core level 750mV */ + kPOWER_BodCoreLevel800mv = 4, /*!< Brown out detector core level 800mV */ + kPOWER_BodCoreLevel850mv = 5, /*!< Brown out detector core level 850mV */ + kPOWER_BodCoreLevel900mv = 6, /*!< Brown out detector core level 900mV */ + kPOWER_BodCoreLevel950mv = 7, /*!< Brown out detector core level 950mV */ +} power_bod_core_level_t; + +/** + * @brief Device Reset Causes + */ +typedef enum _power_device_reset_cause +{ + kRESET_CAUSE_POR = 0UL, /*!< Power On Reset */ + kRESET_CAUSE_PADRESET = 1UL, /*!< Hardware Pin Reset */ + kRESET_CAUSE_BODRESET = 2UL, /*!< Brown-out Detector reset (either BODVBAT or BODCORE) */ + kRESET_CAUSE_ARMSYSTEMRESET = 3UL, /*!< ARM System Reset */ + kRESET_CAUSE_WDTRESET = 4UL, /*!< Watchdog Timer Reset */ + kRESET_CAUSE_SWRRESET = 5UL, /*!< Software Reset */ + kRESET_CAUSE_CDOGRESET = 6UL, /*!< Code Watchdog Reset */ + /* Reset causes in DEEP-POWER-DOWN low power mode */ + kRESET_CAUSE_DPDRESET_WAKEUPIO = 7UL, /*!< Any of the 4 wake-up pins */ + kRESET_CAUSE_DPDRESET_RTC = 8UL, /*!< Real Time Counter (RTC) */ + kRESET_CAUSE_DPDRESET_OSTIMER = 9UL, /*!< OS Event Timer (OSTIMER) */ + kRESET_CAUSE_DPDRESET_WAKEUPIO_RTC = 10UL, /*!< Any of the 4 wake-up pins and RTC (it is not possible to distinguish + which of these 2 events occured first) */ + kRESET_CAUSE_DPDRESET_WAKEUPIO_OSTIMER = 11UL, /*!< Any of the 4 wake-up pins and OSTIMER (it is not possible to + distinguish which of these 2 events occured first) */ + kRESET_CAUSE_DPDRESET_RTC_OSTIMER = 12UL, /*!< Real Time Counter or OS Event Timer (it is not possible to + distinguish which of these 2 events occured first) */ + kRESET_CAUSE_DPDRESET_WAKEUPIO_RTC_OSTIMER = 13UL, /*!< Any of the 4 wake-up pins (it is not possible to distinguish + which of these 3 events occured first) */ + /* Miscallenous */ + kRESET_CAUSE_NOT_RELEVANT = + 14UL, /*!< No reset cause (for example, this code is used when waking up from DEEP-SLEEP low power mode) */ + kRESET_CAUSE_NOT_DETERMINISTIC = 15UL, /*!< Unknown Reset Cause. Should be treated like "Hardware Pin Reset" from an + application point of view. */ +} power_device_reset_cause_t; + +/** + * @brief Device Boot Modes + */ +typedef enum _power_device_boot_mode +{ + kBOOT_MODE_POWER_UP = + 0UL, /*!< All non Low Power Mode wake up (Power On Reset, Pin Reset, BoD Reset, ARM System Reset ... ) */ + kBOOT_MODE_LP_DEEP_SLEEP = 1UL, /*!< Wake up from DEEP-SLEEP Low Power mode */ + kBOOT_MODE_LP_POWER_DOWN = 2UL, /*!< Wake up from POWER-DOWN Low Power mode */ + kBOOT_MODE_LP_DEEP_POWER_DOWN = 4UL, /*!< Wake up from DEEP-POWER-DOWN Low Power mode */ +} power_device_boot_mode_t; + +/** + * @brief SRAM instances retention control during low power modes + */ +#define LOWPOWER_SRAMRETCTRL_RETEN_RAMX0 \ + (1UL << 0) /*!< Enable SRAMX_0 retention when entering in Low power modes */ +#define LOWPOWER_SRAMRETCTRL_RETEN_RAMX1 \ + (1UL << 1) /*!< Enable SRAMX_1 retention when entering in Low power modes */ +#define LOWPOWER_SRAMRETCTRL_RETEN_RAMX2 \ + (1UL << 2) /*!< Enable SRAMX_2 retention when entering in Low power modes */ +#define LOWPOWER_SRAMRETCTRL_RETEN_RAMX3 \ + (1UL << 3) /*!< Enable SRAMX_3 retention when entering in Low power modes */ +#define LOWPOWER_SRAMRETCTRL_RETEN_RAM00 \ + (1UL << 4) /*!< Enable SRAM0_0 retention when entering in Low power modes */ +#define LOWPOWER_SRAMRETCTRL_RETEN_RAM01 \ + (1UL << 5) /*!< Enable SRAM0_1 retention when entering in Low power modes */ +#define LOWPOWER_SRAMRETCTRL_RETEN_RAM10 \ + (1UL << 6) /*!< Enable SRAM1_0 retention when entering in Low power modes */ +#define LOWPOWER_SRAMRETCTRL_RETEN_RAM20 \ + (1UL << 7) /*!< Enable SRAM2_0 retention when entering in Low power modes */ +#define LOWPOWER_SRAMRETCTRL_RETEN_RAM30 \ + (1UL << 8) /*!< Enable SRAM3_0 retention when entering in Low power modes */ +#define LOWPOWER_SRAMRETCTRL_RETEN_RAM31 \ + (1UL << 9) /*!< Enable SRAM3_1 retention when entering in Low power modes */ +#define LOWPOWER_SRAMRETCTRL_RETEN_RAM40 \ + (1UL << 10) /*!< Enable SRAM4_0 retention when entering in Low power modes */ +#define LOWPOWER_SRAMRETCTRL_RETEN_RAM41 \ + (1UL << 11) /*!< Enable SRAM4_1 retention when entering in Low power modes */ +#define LOWPOWER_SRAMRETCTRL_RETEN_RAM42 \ + (1UL << 12) /*!< Enable SRAM4_2 retention when entering in Low power modes */ +#define LOWPOWER_SRAMRETCTRL_RETEN_RAM43 \ + (1UL << 13) /*!< Enable SRAM4_3 retention when entering in Low power modes */ +#define LOWPOWER_SRAMRETCTRL_RETEN_RAM_USB_HS \ + (1UL << 14) /*!< Enable SRAM USB HS retention when entering in Low power modes */ +#define LOWPOWER_SRAMRETCTRL_RETEN_RAM_PUF \ + (1UL << 15) /*!< Enable SRAM PUFF retention when entering in Low power modes */ + +/** + * @brief Low Power Modes Wake up sources + */ +#define WAKEUP_SYS (1ULL << 0) /*!< [SLEEP, DEEP SLEEP ] */ /* WWDT0_IRQ and BOD_IRQ*/ +#define WAKEUP_SDMA0 (1ULL << 1) /*!< [SLEEP, DEEP SLEEP ] */ +#define WAKEUP_GPIO_GLOBALINT0 (1ULL << 2) /*!< [SLEEP, DEEP SLEEP, POWER DOWN ] */ +#define WAKEUP_GPIO_GLOBALINT1 (1ULL << 3) /*!< [SLEEP, DEEP SLEEP, POWER DOWN ] */ +#define WAKEUP_GPIO_INT0_0 (1ULL << 4) /*!< [SLEEP, DEEP SLEEP ] */ +#define WAKEUP_GPIO_INT0_1 (1ULL << 5) /*!< [SLEEP, DEEP SLEEP ] */ +#define WAKEUP_GPIO_INT0_2 (1ULL << 6) /*!< [SLEEP, DEEP SLEEP ] */ +#define WAKEUP_GPIO_INT0_3 (1ULL << 7) /*!< [SLEEP, DEEP SLEEP ] */ +#define WAKEUP_UTICK (1ULL << 8) /*!< [SLEEP, ] */ +#define WAKEUP_MRT (1ULL << 9) /*!< [SLEEP, ] */ +#define WAKEUP_CTIMER0 (1ULL << 10) /*!< [SLEEP, DEEP SLEEP ] */ +#define WAKEUP_CTIMER1 (1ULL << 11) /*!< [SLEEP, DEEP SLEEP ] */ +#define WAKEUP_SCT (1ULL << 12) /*!< [SLEEP, ] */ +#define WAKEUP_CTIMER3 (1ULL << 13) /*!< [SLEEP, DEEP SLEEP ] */ +#define WAKEUP_FLEXCOMM0 (1ULL << 14) /*!< [SLEEP, DEEP SLEEP ] */ +#define WAKEUP_FLEXCOMM1 (1ULL << 15) /*!< [SLEEP, DEEP SLEEP ] */ +#define WAKEUP_FLEXCOMM2 (1ULL << 16) /*!< [SLEEP, DEEP SLEEP ] */ +#define WAKEUP_FLEXCOMM3 (1ULL << 17) /*!< [SLEEP, DEEP SLEEP, POWER DOWN ] */ +#define WAKEUP_FLEXCOMM4 (1ULL << 18) /*!< [SLEEP, DEEP SLEEP ] */ +#define WAKEUP_FLEXCOMM5 (1ULL << 19) /*!< [SLEEP, DEEP SLEEP ] */ +#define WAKEUP_FLEXCOMM6 (1ULL << 20) /*!< [SLEEP, DEEP SLEEP ] */ +#define WAKEUP_FLEXCOMM7 (1ULL << 21) /*!< [SLEEP, DEEP SLEEP ] */ +#define WAKEUP_ADC (1ULL << 22) /*!< [SLEEP, ] */ +#define WAKEUP_ACMP_CAPT (1ULL << 24) /*!< [SLEEP, DEEP SLEEP, POWER DOWN ] */ +// reserved (1ULL << 25) +// reserved (1ULL << 26) +#define WAKEUP_USB0_NEEDCLK (1ULL << 27) /*!< [SLEEP, DEEP SLEEP ] */ +#define WAKEUP_USB0 (1ULL << 28) /*!< [SLEEP, DEEP SLEEP ] */ +#define WAKEUP_RTC_LITE_ALARM_WAKEUP (1ULL << 29) /*!< [SLEEP, DEEP SLEEP, POWER DOWN, DEEP POWER DOWN] */ +#define WAKEUP_EZH_ARCH_B (1ULL << 30) /*!< [SLEEP, ] */ +#define WAKEUP_WAKEUP_MAILBOX (1ULL << 31) /*!< [SLEEP, DEEP SLEEP, POWER DOWN ] */ +#define WAKEUP_GPIO_INT0_4 (1ULL << 32) /*!< [SLEEP, DEEP SLEEP ] */ +#define WAKEUP_GPIO_INT0_5 (1ULL << 33) /*!< [SLEEP, DEEP SLEEP ] */ +#define WAKEUP_GPIO_INT0_6 (1ULL << 34) /*!< [SLEEP, DEEP SLEEP ] */ +#define WAKEUP_GPIO_INT0_7 (1ULL << 35) /*!< [SLEEP, DEEP SLEEP ] */ +#define WAKEUP_CTIMER2 (1ULL << 36) /*!< [SLEEP, DEEP SLEEP ] */ +#define WAKEUP_CTIMER4 (1ULL << 37) /*!< [SLEEP, DEEP SLEEP ] */ +#define WAKEUP_OS_EVENT_TIMER (1ULL << 38) /*!< [SLEEP, DEEP SLEEP, POWER DOWN, DEEP POWER DOWN] */ +// reserved (1ULL << 39) +// reserved (1ULL << 40) +// reserved (1ULL << 41) +#define WAKEUP_SDIO (1ULL << 42) /*!< [SLEEP, ] */ +// reserved (1ULL << 43) +// reserved (1ULL << 44) +// reserved (1ULL << 45) +// reserved (1ULL << 46) +#define WAKEUP_USB1 (1ULL << 47) /*!< [SLEEP, DEEP SLEEP ] */ +#define WAKEUP_USB1_NEEDCLK (1ULL << 48) /*!< [SLEEP, DEEP SLEEP ] */ +#define WAKEUP_SEC_HYPERVISOR_CALL (1ULL << 49) /*!< [SLEEP, ] */ +#define WAKEUP_SEC_GPIO_INT0_0 (1ULL << 50) /*!< [SLEEP, DEEP SLEEP ] */ +#define WAKEUP_SEC_GPIO_INT0_1 (1ULL << 51) /*!< [SLEEP, DEEP SLEEP ] */ +#define WAKEUP_PLU (1ULL << 52) /*!< [SLEEP, DEEP SLEEP ] */ +#define WAKEUP_SEC_VIO (1ULL << 53) +#define WAKEUP_SHA (1ULL << 54) /*!< [SLEEP, ] */ +#define WAKEUP_CASPER (1ULL << 55) /*!< [SLEEP, ] */ +#define WAKEUP_PUFF (1ULL << 56) /*!< [SLEEP, ] */ +#define WAKEUP_PQ (1ULL << 57) /*!< [SLEEP, ] */ +#define WAKEUP_SDMA1 (1ULL << 58) /*!< [SLEEP, DEEP SLEEP ] */ +#define WAKEUP_LSPI_HS (1ULL << 59) /*!< [SLEEP, DEEP SLEEP ] */ +// reserved WAKEUP_PVTVF0_AMBER (1ULL << 60) +// reserved WAKEUP_PVTVF0_RED (1ULL << 61) +// reserved WAKEUP_PVTVF1_AMBER (1ULL << 62) +#define WAKEUP_ALLWAKEUPIOS (1ULL << 63) /*!< [ , DEEP POWER DOWN] */ + +/** + * @brief Sleep Postpone + */ +#define LOWPOWER_HWWAKE_FORCED (1UL << 0) /*!< Force peripheral clocking to stay on during deep-sleep mode. */ +#define LOWPOWER_HWWAKE_PERIPHERALS \ + (1UL << 1) /*!< Wake for Flexcomms. Any Flexcomm FIFO reaching the level specified by its own TXLVL will cause \ + peripheral clocking to wake up temporarily while the related status is asserted */ +#define LOWPOWER_HWWAKE_SDMA0 \ + (1UL << 3) /*!< Wake for DMA0. DMA0 being busy will cause peripheral clocking to remain running until DMA \ + completes. Used in conjonction with LOWPOWER_HWWAKE_PERIPHERALS */ +#define LOWPOWER_HWWAKE_SDMA1 \ + (1UL << 5) /*!< Wake for DMA1. DMA0 being busy will cause peripheral clocking to remain running until DMA \ + completes. Used in conjonction with LOWPOWER_HWWAKE_PERIPHERALS */ +#define LOWPOWER_HWWAKE_ENABLE_FRO192M \ + (1UL << 31) /*!< Need to be set if FRO192M is disable - via PDCTRL0 - in Deep Sleep mode and any of \ + LOWPOWER_HWWAKE_PERIPHERALS, LOWPOWER_HWWAKE_SDMA0 or LOWPOWER_HWWAKE_SDMA1 is set */ + +#define LOWPOWER_CPURETCTRL_ENA_DISABLE 0 /*!< In POWER DOWN mode, CPU Retention is disabled */ +#define LOWPOWER_CPURETCTRL_ENA_ENABLE 1 /*!< In POWER DOWN mode, CPU Retention is enabled */ +/** + * @brief Wake up I/O sources + */ +#define LOWPOWER_WAKEUPIOSRC_PIO0_INDEX 0 /*!< Pin P1( 1) */ +#define LOWPOWER_WAKEUPIOSRC_PIO1_INDEX 2 /*!< Pin P0(28) */ +#define LOWPOWER_WAKEUPIOSRC_PIO2_INDEX 4 /*!< Pin P1(18) */ +#define LOWPOWER_WAKEUPIOSRC_PIO3_INDEX 6 /*!< Pin P1(30) */ + +#define LOWPOWER_WAKEUPIOSRC_DISABLE 0 /*!< Wake up is disable */ +#define LOWPOWER_WAKEUPIOSRC_RISING 1 /*!< Wake up on rising edge */ +#define LOWPOWER_WAKEUPIOSRC_FALLING 2 /*!< Wake up on falling edge */ +#define LOWPOWER_WAKEUPIOSRC_RISING_FALLING 3 /*!< Wake up on both rising or falling edges */ + +#define LOWPOWER_WAKEUPIO_PIO0_PULLUPDOWN_INDEX 8 /*!< Wake-up I/O 0 pull-up/down configuration index */ +#define LOWPOWER_WAKEUPIO_PIO1_PULLUPDOWN_INDEX 9 /*!< Wake-up I/O 1 pull-up/down configuration index */ +#define LOWPOWER_WAKEUPIO_PIO2_PULLUPDOWN_INDEX 10 /*!< Wake-up I/O 2 pull-up/down configuration index */ +#define LOWPOWER_WAKEUPIO_PIO3_PULLUPDOWN_INDEX 11 /*!< Wake-up I/O 3 pull-up/down configuration index */ + +#define LOWPOWER_WAKEUPIO_PIO0_PULLUPDOWN_MASK \ + (1UL << LOWPOWER_WAKEUPIO_PIO0_PULLUPDOWN_INDEX) /*!< Wake-up I/O 0 pull-up/down mask */ +#define LOWPOWER_WAKEUPIO_PIO1_PULLUPDOWN_MASK \ + (1UL << LOWPOWER_WAKEUPIO_PIO1_PULLUPDOWN_INDEX) /*!< Wake-up I/O 1 pull-up/down mask */ +#define LOWPOWER_WAKEUPIO_PIO2_PULLUPDOWN_MASK \ + (1UL << LOWPOWER_WAKEUPIO_PIO2_PULLUPDOWN_INDEX) /*!< Wake-up I/O 2 pull-up/down mask */ +#define LOWPOWER_WAKEUPIO_PIO3_PULLUPDOWN_MASK \ + (1UL << LOWPOWER_WAKEUPIO_PIO3_PULLUPDOWN_INDEX) /*!< Wake-up I/O 3 pull-up/down mask */ + +#define LOWPOWER_WAKEUPIO_PULLDOWN 0 /*!< Select pull-down */ +#define LOWPOWER_WAKEUPIO_PULLUP 1 /*!< Select pull-up */ + +#define LOWPOWER_WAKEUPIO_PIO0_DISABLEPULLUPDOWN_INDEX \ + 12 /*!< Wake-up I/O 0 pull-up/down disable/enable control index */ +#define LOWPOWER_WAKEUPIO_PIO1_DISABLEPULLUPDOWN_INDEX \ + 13 /*!< Wake-up I/O 1 pull-up/down disable/enable control index */ +#define LOWPOWER_WAKEUPIO_PIO2_DISABLEPULLUPDOWN_INDEX \ + 14 /*!< Wake-up I/O 2 pull-up/down disable/enable control index */ +#define LOWPOWER_WAKEUPIO_PIO3_DISABLEPULLUPDOWN_INDEX \ + 15 /*!< Wake-up I/O 3 pull-up/down disable/enable control index */ +#define LOWPOWER_WAKEUPIO_PIO0_DISABLEPULLUPDOWN_MASK \ + (1UL << LOWPOWER_WAKEUPIO_PIO0_DISABLEPULLUPDOWN_INDEX) /*!< Wake-up I/O 0 pull-up/down disable/enable mask */ +#define LOWPOWER_WAKEUPIO_PIO1_DISABLEPULLUPDOWN_MASK \ + (1UL << LOWPOWER_WAKEUPIO_PIO1_DISABLEPULLUPDOWN_INDEX) /*!< Wake-up I/O 1 pull-up/down disable/enable mask */ +#define LOWPOWER_WAKEUPIO_PIO2_DISABLEPULLUPDOWN_MASK \ + (1UL << LOWPOWER_WAKEUPIO_PIO2_DISABLEPULLUPDOWN_INDEX) /*!< Wake-up I/O 2 pull-up/down disable/enable mask */ +#define LOWPOWER_WAKEUPIO_PIO3_DISABLEPULLUPDOWN_MASK \ + (1UL << LOWPOWER_WAKEUPIO_PIO3_DISABLEPULLUPDOWN_INDEX) /*!< Wake-up I/O 3 pull-up/down disable/enable mask */ + +#define LOWPOWER_WAKEUPIO_PIO0_USEEXTERNALPULLUPDOWN_INDEX \ + (16) /*!< Wake-up I/O 0 use external pull-up/down disable/enable control index*/ +#define LOWPOWER_WAKEUPIO_PIO1_USEEXTERNALPULLUPDOWN_INDEX \ + (17) /*!< Wake-up I/O 1 use external pull-up/down disable/enable control index */ +#define LOWPOWER_WAKEUPIO_PIO2_USEEXTERNALPULLUPDOWN_INDEX \ + (18) /*!< Wake-up I/O 2 use external pull-up/down disable/enable control index */ +#define LOWPOWER_WAKEUPIO_PIO3_USEEXTERNALPULLUPDOWN_INDEX \ + (19) /*!< Wake-up I/O 3 use external pull-up/down disable/enable control index */ +#define LOWPOWER_WAKEUPIO_PIO0_USEEXTERNALPULLUPDOWN_MASK \ + (1UL << LOWPOWER_WAKEUPIO_PIO0_USEEXTERNALPULLUPDOWN_INDEX) /*!< Wake-up I/O 0 use external pull-up/down \ + disable/enable mask, 0: disable, 1: enable */ +#define LOWPOWER_WAKEUPIO_PIO1_USEEXTERNALPULLUPDOWN_MASK \ + (1UL << LOWPOWER_WAKEUPIO_PIO1_USEEXTERNALPULLUPDOWN_INDEX) /*!< Wake-up I/O 1 use external pull-up/down \ + disable/enable mask, 0: disable, 1: enable */ +#define LOWPOWER_WAKEUPIO_PIO2_USEEXTERNALPULLUPDOWN_MASK \ + (1UL << LOWPOWER_WAKEUPIO_PIO2_USEEXTERNALPULLUPDOWN_INDEX) /*!< Wake-up I/O 2 use external pull-up/down \ + disable/enable mask, 0: disable, 1: enable */ +#define LOWPOWER_WAKEUPIO_PIO3_USEEXTERNALPULLUPDOWN_MASK \ + (1UL << LOWPOWER_WAKEUPIO_PIO3_USEEXTERNALPULLUPDOWN_INDEX) /*!< Wake-up I/O 3 use external pull-up/down \ + disable/enable mask, 0: disable, 1: enable */ + +#ifdef __cplusplus +extern "C" { +#endif +/******************************************************************************* + * API + ******************************************************************************/ + +/*! + * @brief API to enable PDRUNCFG bit in the Syscon. Note that enabling the bit powers down the peripheral + * + * @param en peripheral for which to enable the PDRUNCFG bit + * @return none + */ +static inline void POWER_EnablePD(pd_bit_t en) +{ + /* PDRUNCFGSET */ + PMC->PDRUNCFGSET0 = (uint32_t)en; +} + +/*! + * @brief API to disable PDRUNCFG bit in the Syscon. Note that disabling the bit powers up the peripheral + * + * @param en peripheral for which to disable the PDRUNCFG bit + * @return none + */ +static inline void POWER_DisablePD(pd_bit_t en) +{ + /* PDRUNCFGCLR */ + PMC->PDRUNCFGCLR0 = (uint32_t)en; +} + +/*! + * @brief set BOD VBAT level. + * + * @param level BOD detect level + * @param hyst BoD Hysteresis control + * @param enBodVbatReset VBAT brown out detect reset + */ +static inline void POWER_SetBodVbatLevel(power_bod_vbat_level_t level, power_bod_hyst_t hyst, bool enBodVbatReset) +{ + PMC->BODVBAT = (PMC->BODVBAT & (~(PMC_BODVBAT_TRIGLVL_MASK | PMC_BODVBAT_HYST_MASK))) | PMC_BODVBAT_TRIGLVL(level) | + PMC_BODVBAT_HYST(hyst); + PMC->RESETCTRL = + (PMC->RESETCTRL & (~PMC_RESETCTRL_BODVBATRESETENABLE_MASK)) | PMC_RESETCTRL_BODVBATRESETENABLE(enBodVbatReset); +} + +#if defined(PMC_BODCORE_TRIGLVL_MASK) +/*! + * @brief set BOD core level. + * + * @param level BOD detect level + * @param hyst BoD Hysteresis control + * @param enBodCoreReset core brown out detect reset + */ +static inline void POWER_SetBodCoreLevel(power_bod_core_level_t level, power_bod_hyst_t hyst, bool enBodCoreReset) +{ + PMC->BODCORE = (PMC->BODCORE & (~(PMC_BODCORE_TRIGLVL_MASK | PMC_BODCORE_HYST_MASK))) | PMC_BODCORE_TRIGLVL(level) | + PMC_BODCORE_HYST(hyst); + PMC->RESETCTRL = + (PMC->RESETCTRL & (~PMC_RESETCTRL_BODCORERESETENABLE_MASK)) | PMC_RESETCTRL_BODCORERESETENABLE(enBodCoreReset); +} +#endif + +/*! + * @brief API to enable deep sleep bit in the ARM Core. + * + * @return none + */ +static inline void POWER_EnableDeepSleep(void) +{ + SCB->SCR |= SCB_SCR_SLEEPDEEP_Msk; +} + +/*! + * @brief API to disable deep sleep bit in the ARM Core. + * + * @return none + */ +static inline void POWER_DisableDeepSleep(void) +{ + SCB->SCR &= ~SCB_SCR_SLEEPDEEP_Msk; +} + +/** + * @brief Shut off the Flash and execute the _WFI(), then power up the Flash after wake-up event + * This MUST BE EXECUTED outside the Flash: + * either from ROM or from SRAM. The rest could stay in Flash. But, for consistency, it is + * preferable to have all functions defined in this file implemented in ROM. + * + * @return Nothing + */ +void POWER_CycleCpuAndFlash(void); + +/** + * @brief Configures and enters in DEEP-SLEEP low power mode + * @param exclude_from_pd: + * @param sram_retention_ctrl: + * @param wakeup_interrupts: + * @param hardware_wake_ctrl: + + * @return Nothing + * + * !!! IMPORTANT NOTES : + 0 - CPU0 & System CLock frequency is switched to FRO12MHz and is NOT restored back by the API. + * 1 - CPU0 Interrupt Enable registers (NVIC->ISER) are modified by this function. They are restored back in + case of CPU retention or if POWERDOWN is not taken (for instance because an interrupt is pending). + * 2 - The Non Maskable Interrupt (NMI) is disabled and its configuration before calling this function will be + restored back if POWERDOWN is not taken (for instance because an RTC or OSTIMER interrupt is pending). + * 3 - The HARD FAULT handler should execute from SRAM. (The Hard fault handler should initiate a full chip + reset) reset) + */ +void POWER_EnterDeepSleep(uint32_t exclude_from_pd, + uint32_t sram_retention_ctrl, + uint64_t wakeup_interrupts, + uint32_t hardware_wake_ctrl); + +/** + * @brief Configures and enters in POWERDOWN low power mode + * @param exclude_from_pd: + * @param sram_retention_ctrl: + * @param wakeup_interrupts: + * @param cpu_retention_ctrl: 0 = CPU retention is disable / 1 = CPU retention is enabled, all other values are + RESERVED. + + * @return Nothing + * + * !!! IMPORTANT NOTES : + 0 - CPU0 & System CLock frequency is switched to FRO12MHz and is NOT restored back by the API. + * 1 - CPU0 Interrupt Enable registers (NVIC->ISER) are modified by this function. They are restored back in + case of CPU retention or if POWERDOWN is not taken (for instance because an interrupt is pending). + * 2 - The Non Maskable Interrupt (NMI) is disabled and its configuration before calling this function will be + restored back if POWERDOWN is not taken (for instance because an RTC or OSTIMER interrupt is pending). + * 3 - In case of CPU retention, it is the responsability of the user to make sure that SRAM instance + containing the stack used to call this function WILL BE preserved during low power (via parameter + "sram_retention_ctrl") + * 4 - The HARD FAULT handler should execute from SRAM. (The Hard fault handler should initiate a full chip + reset) reset) + */ + +void POWER_EnterPowerDown(uint32_t exclude_from_pd, + uint32_t sram_retention_ctrl, + uint64_t wakeup_interrupts, + uint32_t cpu_retention_ctrl); + +/** + * @brief Configures and enters in DEEPPOWERDOWN low power mode + * @param exclude_from_pd: + * @param sram_retention_ctrl: + * @param wakeup_interrupts: + * @param wakeup_io_ctrl: + + * @return Nothing + * + * !!! IMPORTANT NOTES : + 0 - CPU0 & System CLock frequency is switched to FRO12MHz and is NOT restored back by the API. + * 1 - CPU0 Interrupt Enable registers (NVIC->ISER) are modified by this function. They are restored back if + DEEPPOWERDOWN is not taken (for instance because an RTC or OSTIMER interrupt is pending). + * 2 - The Non Maskable Interrupt (NMI) is disabled and its configuration before calling this function will be + restored back if DEEPPOWERDOWN is not taken (for instance because an RTC or OSTIMER interrupt is pending). + * 3 - The HARD FAULT handler should execute from SRAM. (The Hard fault handler should initiate a full chip + reset) + */ +void POWER_EnterDeepPowerDown(uint32_t exclude_from_pd, + uint32_t sram_retention_ctrl, + uint64_t wakeup_interrupts, + uint32_t wakeup_io_ctrl); + +/** + * @brief Configures and enters in SLEEP low power mode + * @param : + * @return Nothing + */ +void POWER_EnterSleep(void); + +/*! + * @brief Power Library API to choose normal regulation and set the voltage for the desired operating frequency. + * + * @param system_freq_hz - The desired frequency (in Hertz) at which the part would like to operate, + * note that the voltage and flash wait states should be set before changing frequency + * @return none + */ +void POWER_SetVoltageForFreq(uint32_t system_freq_hz); + +/** + * @brief Sets board-specific trim values for 16MHz XTAL + * @param pi32_16MfXtalIecLoadpF_x100 Load capacitance, pF x 100. For example, 6pF becomes 600, 1.2pF becomes 120 + * @param pi32_16MfXtalPPcbParCappF_x100 PCB +ve parasitic capacitance, pF x 100. For example, 6pF becomes 600, 1.2pF + * becomes 120 + * @param pi32_16MfXtalNPcbParCappF_x100 PCB -ve parasitic capacitance, pF x 100. For example, 6pF becomes 600, 1.2pF + * becomes 120 + * @return none + * @note Following default Values can be used: + * pi32_32MfXtalIecLoadpF_x100 Load capacitance, pF x 100 : 600 + * pi32_32MfXtalPPcbParCappF_x100 PCB +ve parasitic capacitance, pF x 100 : 20 + * pi32_32MfXtalNPcbParCappF_x100 PCB -ve parasitic capacitance, pF x 100 : 40 + */ +extern void POWER_Xtal16mhzCapabankTrim(int32_t pi32_16MfXtalIecLoadpF_x100, + int32_t pi32_16MfXtalPPcbParCappF_x100, + int32_t pi32_16MfXtalNPcbParCappF_x100); +/** + * @brief Sets board-specific trim values for 32kHz XTAL + * @param pi32_32kfXtalIecLoadpF_x100 Load capacitance, pF x 100. For example, 6pF becomes 600, 1.2pF becomes 120 + * @param pi32_32kfXtalPPcbParCappF_x100 PCB +ve parasitic capacitance, pF x 100. For example, 6pF becomes 600, 1.2pF + becomes 120 + * @param pi32_32kfXtalNPcbParCappF_x100 PCB -ve parasitic capacitance, pF x 100. For example, 6pF becomes 600, 1.2pF + becomes 120 + + * @return none + * @note Following default Values can be used: + * pi32_32kfXtalIecLoadpF_x100 Load capacitance, pF x 100 : 600 + * pi32_32kfXtalPPcbParCappF_x100 PCB +ve parasitic capacitance, pF x 100 : 40 + * pi32_32kfXtalNPcbParCappF_x100 PCB -ve parasitic capacitance, pF x 100 : 40 + */ +extern void POWER_Xtal32khzCapabankTrim(int32_t pi32_32kfXtalIecLoadpF_x100, + int32_t pi32_32kfXtalPPcbParCappF_x100, + int32_t pi32_32kfXtalNPcbParCappF_x100); +/** + * @brief Enables and sets LDO for 16MHz XTAL + * + * @return none + */ +extern void POWER_SetXtal16mhzLdo(void); + +/** + * @brief Return some key information related to the device reset causes / wake-up sources, for all power modes. + * @param p_reset_cause : the device reset cause, according to the definition of power_device_reset_cause_t type. + * @param p_boot_mode : the device boot mode, according to the definition of power_device_boot_mode_t type. + * @param p_wakeupio_cause: the wake-up pin sources, according to the definition of register PMC->WAKEIOCAUSE[3:0]. + + * @return Nothing + * + * !!! IMPORTANT ERRATA - IMPORTANT ERRATA - IMPORTANT ERRATA !!! + * !!! valid ONLY for LPC55S69 (not for LPC55S16 and LPC55S06) !!! + * !!! when FALLING EDGE DETECTION is enabled on wake-up pins: !!! + * - 1. p_wakeupio_cause is NOT ACCURATE + * - 2. Spurious kRESET_CAUSE_DPDRESET_WAKEUPIO* event is reported when + * several wake-up sources are enabled during DEEP-POWER-DOWN + * (like enabling wake-up on RTC and Falling edge wake-up pins) + * + */ +void POWER_GetWakeUpCause(power_device_reset_cause_t *p_reset_cause, + power_device_boot_mode_t *p_boot_mode, + uint32_t *p_wakeupio_cause); +#ifdef __cplusplus +} +#endif + +/** + * @} + */ + +#endif /* _FSL_POWER_H_ */ diff --git a/drivers/Inc/fsl_reset.h b/drivers/Inc/fsl_reset.h new file mode 100644 index 0000000..70bb1bc --- /dev/null +++ b/drivers/Inc/fsl_reset.h @@ -0,0 +1,317 @@ +/* + * Copyright (c) 2016, Freescale Semiconductor, Inc. + * Copyright 2016, NXP + * All rights reserved. + * + * SPDX-License-Identifier: BSD-3-Clause + */ + +#ifndef _FSL_RESET_H_ +#define _FSL_RESET_H_ + +#include +#include +#include +#include +#include "fsl_device_registers.h" + +/*! + * @addtogroup reset + * @{ + */ + +/******************************************************************************* + * Definitions + ******************************************************************************/ + +/*! @name Driver version */ +/*@{*/ +/*! @brief reset driver version 2.4.0 */ +#define FSL_RESET_DRIVER_VERSION (MAKE_VERSION(2, 4, 0)) +/*@}*/ + +/*! + * @brief Enumeration for peripheral reset control bits + * + * Defines the enumeration for peripheral reset control bits in PRESETCTRL/ASYNCPRESETCTRL registers + */ +typedef enum _SYSCON_RSTn +{ + kROM_RST_SHIFT_RSTn = 0 | 1U, /**< ROM reset control */ + kSRAM1_RST_SHIFT_RSTn = 0 | 3U, /**< SRAM1 reset control */ + kSRAM2_RST_SHIFT_RSTn = 0 | 4U, /**< SRAM2 reset control */ + kSRAM3_RST_SHIFT_RSTn = 0 | 5U, /**< SRAM3 reset control */ + kSRAM4_RST_SHIFT_RSTn = 0 | 6U, /**< SRAM4 reset control */ + kFLASH_RST_SHIFT_RSTn = 0 | 7U, /**< Flash controller reset control */ + kFMC_RST_SHIFT_RSTn = 0 | 8U, /**< Flash accelerator reset control */ + kSPIFI_RST_SHIFT_RSTn = 0 | 10U, /**< SPIFI reset control */ + kMUX0_RST_SHIFT_RSTn = 0 | 11U, /**< Input mux0 reset control */ + kIOCON_RST_SHIFT_RSTn = 0 | 13U, /**< IOCON reset control */ + kGPIO0_RST_SHIFT_RSTn = 0 | 14U, /**< GPIO0 reset control */ + kGPIO1_RST_SHIFT_RSTn = 0 | 15U, /**< GPIO1 reset control */ + kGPIO2_RST_SHIFT_RSTn = 0 | 16U, /**< GPIO2 reset control */ + kGPIO3_RST_SHIFT_RSTn = 0 | 17U, /**< GPIO3 reset control */ + kPINT_RST_SHIFT_RSTn = 0 | 18U, /**< Pin interrupt (PINT) reset control */ + kGINT_RST_SHIFT_RSTn = 0 | 19U, /**< Grouped interrupt (PINT) reset control. */ + kDMA0_RST_SHIFT_RSTn = 0 | 20U, /**< DMA reset control */ + kCRC_RST_SHIFT_RSTn = 0 | 21U, /**< CRC reset control */ + kWWDT_RST_SHIFT_RSTn = 0 | 22U, /**< Watchdog timer reset control */ + kRTC_RST_SHIFT_RSTn = 0 | 23U, /**< RTC reset control */ + kMAILBOX_RST_SHIFT_RSTn = 0 | 26U, /**< Mailbox reset control */ + kADC0_RST_SHIFT_RSTn = 0 | 27U, /**< ADC0 reset control */ + + kMRT_RST_SHIFT_RSTn = 65536 | 0U, /**< Multi-rate timer (MRT) reset control */ + kOSTIMER0_RST_SHIFT_RSTn = 65536 | 1U, /**< OSTimer0 reset control */ + kSCT0_RST_SHIFT_RSTn = 65536 | 2U, /**< SCTimer/PWM 0 (SCT0) reset control */ + kSCTIPU_RST_SHIFT_RSTn = 65536 | 6U, /**< SCTIPU reset control */ + kUTICK_RST_SHIFT_RSTn = 65536 | 10U, /**< Micro-tick timer reset control */ + kFC0_RST_SHIFT_RSTn = 65536 | 11U, /**< Flexcomm Interface 0 reset control */ + kFC1_RST_SHIFT_RSTn = 65536 | 12U, /**< Flexcomm Interface 1 reset control */ + kFC2_RST_SHIFT_RSTn = 65536 | 13U, /**< Flexcomm Interface 2 reset control */ + kFC3_RST_SHIFT_RSTn = 65536 | 14U, /**< Flexcomm Interface 3 reset control */ + kFC4_RST_SHIFT_RSTn = 65536 | 15U, /**< Flexcomm Interface 4 reset control */ + kFC5_RST_SHIFT_RSTn = 65536 | 16U, /**< Flexcomm Interface 5 reset control */ + kFC6_RST_SHIFT_RSTn = 65536 | 17U, /**< Flexcomm Interface 6 reset control */ + kFC7_RST_SHIFT_RSTn = 65536 | 18U, /**< Flexcomm Interface 7 reset control */ + kCTIMER2_RST_SHIFT_RSTn = 65536 | 22U, /**< CTimer 2 reset control */ + kUSB0D_RST_SHIFT_RSTn = 65536 | 25U, /**< USB0 Device reset control */ + kCTIMER0_RST_SHIFT_RSTn = 65536 | 26U, /**< CTimer 0 reset control */ + kCTIMER1_RST_SHIFT_RSTn = 65536 | 27U, /**< CTimer 1 reset control */ + kPVT_RST_SHIFT_RSTn = 65536 | 28U, /**< PVT reset control */ + kEZHA_RST_SHIFT_RSTn = 65536 | 30U, /**< EZHA reset control */ + kEZHB_RST_SHIFT_RSTn = 65536 | 31U, /**< EZHB reset control */ + + kDMA1_RST_SHIFT_RSTn = 131072 | 1U, /**< DMA1 reset control */ + kCMP_RST_SHIFT_RSTn = 131072 | 2U, /**< CMP reset control */ + kSDIO_RST_SHIFT_RSTn = 131072 | 3U, /**< SDIO reset control */ + kUSB1H_RST_SHIFT_RSTn = 131072 | 4U, /**< USBHS Host reset control */ + kUSB1D_RST_SHIFT_RSTn = 131072 | 5U, /**< USBHS Device reset control */ + kUSB1RAM_RST_SHIFT_RSTn = 131072 | 6U, /**< USB RAM reset control */ + kUSB1_RST_SHIFT_RSTn = 131072 | 7U, /**< USBHS reset control */ + kFREQME_RST_SHIFT_RSTn = 131072 | 8U, /**< FREQME reset control */ + kGPIO4_RST_SHIFT_RSTn = 131072 | 9U, /**< GPIO4 reset control */ + kGPIO5_RST_SHIFT_RSTn = 131072 | 10U, /**< GPIO5 reset control */ + kAES_RST_SHIFT_RSTn = 131072 | 11U, /**< AES reset control */ + kOTP_RST_SHIFT_RSTn = 131072 | 12U, /**< OTP reset control */ + kRNG_RST_SHIFT_RSTn = 131072 | 13U, /**< RNG reset control */ + kMUX1_RST_SHIFT_RSTn = 131072 | 14U, /**< Input mux1 reset control */ + kUSB0HMR_RST_SHIFT_RSTn = 131072 | 16U, /**< USB0HMR reset control */ + kUSB0HSL_RST_SHIFT_RSTn = 131072 | 17U, /**< USB0HSL reset control */ + kHASHCRYPT_RST_SHIFT_RSTn = 131072 | 18U, /**< HASHCRYPT reset control */ + kPOWERQUAD_RST_SHIFT_RSTn = 131072 | 19U, /**< PowerQuad reset control */ + kPLULUT_RST_SHIFT_RSTn = 131072 | 20U, /**< PLU LUT reset control */ + kCTIMER3_RST_SHIFT_RSTn = 131072 | 21U, /**< CTimer 3 reset control */ + kCTIMER4_RST_SHIFT_RSTn = 131072 | 22U, /**< CTimer 4 reset control */ + kPUF_RST_SHIFT_RSTn = 131072 | 23U, /**< PUF reset control */ + kCASPER_RST_SHIFT_RSTn = 131072 | 24U, /**< CASPER reset control */ + kCAP0_RST_SHIFT_RSTn = 131072 | 25U, /**< CASPER reset control */ + kOSTIMER1_RST_SHIFT_RSTn = 131072 | 26U, /**< OSTIMER1 reset control */ + kANALOGCTL_RST_SHIFT_RSTn = 131072 | 27U, /**< ANALOG_CTL reset control */ + kHSLSPI_RST_SHIFT_RSTn = 131072 | 28U, /**< HS LSPI reset control */ + kGPIOSEC_RST_SHIFT_RSTn = 131072 | 29U, /**< GPIO Secure reset control */ + kGPIOSECINT_RST_SHIFT_RSTn = 131072 | 30U, /**< GPIO Secure int reset control */ +} SYSCON_RSTn_t; + +/** Array initializers with peripheral reset bits **/ +#define ADC_RSTS \ + { \ + kADC0_RST_SHIFT_RSTn \ + } /* Reset bits for ADC peripheral */ +#define AES_RSTS \ + { \ + kAES_RST_SHIFT_RSTn \ + } /* Reset bits for AES peripheral */ +#define CRC_RSTS \ + { \ + kCRC_RST_SHIFT_RSTn \ + } /* Reset bits for CRC peripheral */ +#define CTIMER_RSTS \ + { \ + kCTIMER0_RST_SHIFT_RSTn, kCTIMER1_RST_SHIFT_RSTn, kCTIMER2_RST_SHIFT_RSTn, kCTIMER3_RST_SHIFT_RSTn, \ + kCTIMER4_RST_SHIFT_RSTn \ + } /* Reset bits for CTIMER peripheral */ +#define DMA_RSTS_N \ + { \ + kDMA0_RST_SHIFT_RSTn, kDMA1_RST_SHIFT_RSTn \ + } /* Reset bits for DMA peripheral */ + +#define FLEXCOMM_RSTS \ + { \ + kFC0_RST_SHIFT_RSTn, kFC1_RST_SHIFT_RSTn, kFC2_RST_SHIFT_RSTn, kFC3_RST_SHIFT_RSTn, kFC4_RST_SHIFT_RSTn, \ + kFC5_RST_SHIFT_RSTn, kFC6_RST_SHIFT_RSTn, kFC7_RST_SHIFT_RSTn, kHSLSPI_RST_SHIFT_RSTn \ + } /* Reset bits for FLEXCOMM peripheral */ +#define GINT_RSTS \ + { \ + kGINT_RST_SHIFT_RSTn, kGINT_RST_SHIFT_RSTn \ + } /* Reset bits for GINT peripheral. GINT0 & GINT1 share same slot */ +#define GPIO_RSTS_N \ + { \ + kGPIO0_RST_SHIFT_RSTn, kGPIO1_RST_SHIFT_RSTn, kGPIO2_RST_SHIFT_RSTn, kGPIO3_RST_SHIFT_RSTn, \ + kGPIO4_RST_SHIFT_RSTn, kGPIO5_RST_SHIFT_RSTn \ + } /* Reset bits for GPIO peripheral */ +#define INPUTMUX_RSTS \ + { \ + kMUX0_RST_SHIFT_RSTn, kMUX1_RST_SHIFT_RSTn \ + } /* Reset bits for INPUTMUX peripheral */ +#define IOCON_RSTS \ + { \ + kIOCON_RST_SHIFT_RSTn \ + } /* Reset bits for IOCON peripheral */ +#define FLASH_RSTS \ + { \ + kFLASH_RST_SHIFT_RSTn, kFMC_RST_SHIFT_RSTn \ + } /* Reset bits for Flash peripheral */ +#define MRT_RSTS \ + { \ + kMRT_RST_SHIFT_RSTn \ + } /* Reset bits for MRT peripheral */ +#define OTP_RSTS \ + { \ + kOTP_RST_SHIFT_RSTn \ + } /* Reset bits for OTP peripheral */ +#define PINT_RSTS \ + { \ + kPINT_RST_SHIFT_RSTn, kGPIOSECINT_RST_SHIFT_RSTn \ + } /* Reset bits for PINT peripheral */ +#define RNG_RSTS \ + { \ + kRNG_RST_SHIFT_RSTn \ + } /* Reset bits for RNG peripheral */ +#define SDIO_RST \ + { \ + kSDIO_RST_SHIFT_RSTn \ + } /* Reset bits for SDIO peripheral */ +#define SCT_RSTS \ + { \ + kSCT0_RST_SHIFT_RSTn \ + } /* Reset bits for SCT peripheral */ +#define SPIFI_RSTS \ + { \ + kSPIFI_RST_SHIFT_RSTn \ + } /* Reset bits for SPIFI peripheral */ +#define USB0D_RST \ + { \ + kUSB0D_RST_SHIFT_RSTn \ + } /* Reset bits for USB0D peripheral */ +#define USB0HMR_RST \ + { \ + kUSB0HMR_RST_SHIFT_RSTn \ + } /* Reset bits for USB0HMR peripheral */ +#define USB0HSL_RST \ + { \ + kUSB0HSL_RST_SHIFT_RSTn \ + } /* Reset bits for USB0HSL peripheral */ +#define USB1H_RST \ + { \ + kUSB1H_RST_SHIFT_RSTn \ + } /* Reset bits for USB1H peripheral */ +#define USB1D_RST \ + { \ + kUSB1D_RST_SHIFT_RSTn \ + } /* Reset bits for USB1D peripheral */ +#define USB1RAM_RST \ + { \ + kUSB1RAM_RST_SHIFT_RSTn \ + } /* Reset bits for USB1RAM peripheral */ +#define UTICK_RSTS \ + { \ + kUTICK_RST_SHIFT_RSTn \ + } /* Reset bits for UTICK peripheral */ +#define WWDT_RSTS \ + { \ + kWWDT_RST_SHIFT_RSTn \ + } /* Reset bits for WWDT peripheral */ +#define CAPT_RSTS_N \ + { \ + kCAP0_RST_SHIFT_RSTn \ + } /* Reset bits for CAPT peripheral */ +#define PLU_RSTS_N \ + { \ + kPLULUT_RST_SHIFT_RSTn \ + } /* Reset bits for PLU peripheral */ +#define OSTIMER_RSTS \ + { \ + kOSTIMER0_RST_SHIFT_RSTn \ + } /* Reset bits for OSTIMER peripheral */ +#define POWERQUAD_RSTS \ + { \ + kPOWERQUAD_RST_SHIFT_RSTn \ + } /* Reset bits for Powerquad peripheral */ +#define CASPER_RSTS \ + { \ + kCASPER_RST_SHIFT_RSTn \ + } /* Reset bits for Casper peripheral */ +#define HASHCRYPT_RSTS \ + { \ + kHASHCRYPT_RST_SHIFT_RSTn \ + } /* Reset bits for Hashcrypt peripheral */ +#define PUF_RSTS \ + { \ + kPUF_RST_SHIFT_RSTn \ + } /* Reset bits for PUF peripheral */ +typedef SYSCON_RSTn_t reset_ip_name_t; +#define USB1RAM_RSTS USB1RAM_RST +#define USB1H_RSTS USB1H_RST +#define USB1D_RSTS USB1D_RST +#define USB0HSL_RSTS USB0HSL_RST +#define USB0HMR_RSTS USB0HMR_RST +#define USB0D_RSTS USB0D_RST +#define SDIO_RSTS SDIO_RST + +/******************************************************************************* + * API + ******************************************************************************/ +#if defined(__cplusplus) +extern "C" { +#endif + +/*! + * @brief Assert reset to peripheral. + * + * Asserts reset signal to specified peripheral module. + * + * @param peripheral Assert reset to this peripheral. The enum argument contains encoding of reset register + * and reset bit position in the reset register. + */ +void RESET_SetPeripheralReset(reset_ip_name_t peripheral); + +/*! + * @brief Clear reset to peripheral. + * + * Clears reset signal to specified peripheral module, allows it to operate. + * + * @param peripheral Clear reset to this peripheral. The enum argument contains encoding of reset register + * and reset bit position in the reset register. + */ +void RESET_ClearPeripheralReset(reset_ip_name_t peripheral); + +/*! + * @brief Reset peripheral module. + * + * Reset peripheral module. + * + * @param peripheral Peripheral to reset. The enum argument contains encoding of reset register + * and reset bit position in the reset register. + */ +void RESET_PeripheralReset(reset_ip_name_t peripheral); + +/*! + * @brief Release peripheral module. + * + * Release peripheral module. + * + * @param peripheral Peripheral to release. The enum argument contains encoding of reset register + * and reset bit position in the reset register. + */ +static inline void RESET_ReleasePeripheralReset(reset_ip_name_t peripheral) +{ + RESET_ClearPeripheralReset(peripheral); +} + +#if defined(__cplusplus) +} +#endif + +/*! @} */ + +#endif /* _FSL_RESET_H_ */ diff --git a/drivers/Inc/fsl_str.h b/drivers/Inc/fsl_str.h new file mode 100644 index 0000000..9e8c232 --- /dev/null +++ b/drivers/Inc/fsl_str.h @@ -0,0 +1,129 @@ +/* + * Copyright 2017 NXP + * All rights reserved. + * + * + * SPDX-License-Identifier: BSD-3-Clause + * + */ + +#ifndef _FSL_STR_H +#define _FSL_STR_H + +#include "fsl_common.h" + +/*! + * @addtogroup debugconsole + * @{ + */ + +/******************************************************************************* + * Definitions + ******************************************************************************/ + +/*! @brief Definition to printf the float number. */ +#ifndef PRINTF_FLOAT_ENABLE +#define PRINTF_FLOAT_ENABLE 0U +#endif /* PRINTF_FLOAT_ENABLE */ + +/*! @brief Definition to scanf the float number. */ +#ifndef SCANF_FLOAT_ENABLE +#define SCANF_FLOAT_ENABLE 0U +#endif /* SCANF_FLOAT_ENABLE */ + +/*! @brief Definition to support advanced format specifier for printf. */ +#ifndef PRINTF_ADVANCED_ENABLE +#define PRINTF_ADVANCED_ENABLE 0U +#endif /* PRINTF_ADVANCED_ENABLE */ + +/*! @brief Definition to support advanced format specifier for scanf. */ +#ifndef SCANF_ADVANCED_ENABLE +#define SCANF_ADVANCED_ENABLE 0U +#endif /* SCANF_ADVANCED_ENABLE */ + +/******************************************************************************* + * Prototypes + ******************************************************************************/ +#if (defined(PRINTF_ADVANCED_ENABLE) && (PRINTF_ADVANCED_ENABLE > 0U)) +/*! @brief Specification modifier flags for printf. */ +enum _debugconsole_printf_flag +{ + kPRINTF_Minus = 0x01U, /*!< Minus FLag. */ + kPRINTF_Plus = 0x02U, /*!< Plus Flag. */ + kPRINTF_Space = 0x04U, /*!< Space Flag. */ + kPRINTF_Zero = 0x08U, /*!< Zero Flag. */ + kPRINTF_Pound = 0x10U, /*!< Pound Flag. */ + kPRINTF_LengthChar = 0x20U, /*!< Length: Char Flag. */ + kPRINTF_LengthShortInt = 0x40U, /*!< Length: Short Int Flag. */ + kPRINTF_LengthLongInt = 0x80U, /*!< Length: Long Int Flag. */ + kPRINTF_LengthLongLongInt = 0x100U, /*!< Length: Long Long Int Flag. */ +}; +#endif /* PRINTF_ADVANCED_ENABLE */ + +/*! @brief Specification modifier flags for scanf. */ +enum _debugconsole_scanf_flag +{ + kSCANF_Suppress = 0x2U, /*!< Suppress Flag. */ + kSCANF_DestMask = 0x7cU, /*!< Destination Mask. */ + kSCANF_DestChar = 0x4U, /*!< Destination Char Flag. */ + kSCANF_DestString = 0x8U, /*!< Destination String FLag. */ + kSCANF_DestSet = 0x10U, /*!< Destination Set Flag. */ + kSCANF_DestInt = 0x20U, /*!< Destination Int Flag. */ + kSCANF_DestFloat = 0x30U, /*!< Destination Float Flag. */ + kSCANF_LengthMask = 0x1f00U, /*!< Length Mask Flag. */ +#if (defined(SCANF_ADVANCED_ENABLE) && (SCANF_ADVANCED_ENABLE > 0U)) + kSCANF_LengthChar = 0x100U, /*!< Length Char Flag. */ + kSCANF_LengthShortInt = 0x200U, /*!< Length ShortInt Flag. */ + kSCANF_LengthLongInt = 0x400U, /*!< Length LongInt Flag. */ + kSCANF_LengthLongLongInt = 0x800U, /*!< Length LongLongInt Flag. */ +#endif /* SCANF_ADVANCED_ENABLE */ +#if (defined(SCANF_FLOAT_ENABLE) && (SCANF_FLOAT_ENABLE > 0)) + kSCANF_LengthLongLongDouble = 0x1000U, /*!< Length LongLongDuoble Flag. */ +#endif /*PRINTF_FLOAT_ENABLE */ + kSCANF_TypeSinged = 0x2000U, /*!< TypeSinged Flag. */ +}; + +#if defined(__cplusplus) +extern "C" { +#endif /* __cplusplus */ + +/*! + * @brief A function pointer which is used when format printf log. + */ +typedef void (*printfCb)(char *buf, int32_t *indicator, char val, int len); + +/*! + * @brief This function outputs its parameters according to a formatted string. + * + * @note I/O is performed by calling given function pointer using following + * (*func_ptr)(c); + * + * @param[in] fmt Format string for printf. + * @param[in] ap Arguments to printf. + * @param[in] buf pointer to the buffer + * @param cb print callbck function pointer + * + * @return Number of characters to be print + */ +int StrFormatPrintf(const char *fmt, va_list ap, char *buf, printfCb cb); + +/*! + * @brief Converts an input line of ASCII characters based upon a provided + * string format. + * + * @param[in] line_ptr The input line of ASCII data. + * @param[in] format Format first points to the format string. + * @param[in] args_ptr The list of parameters. + * + * @return Number of input items converted and assigned. + * @retval IO_EOF When line_ptr is empty string "". + */ +int StrFormatScanf(const char *line_ptr, char *format, va_list args_ptr); + +#if defined(__cplusplus) +} +#endif /* __cplusplus */ + +/*! @} */ + +#endif /* _FSL_STR_H */ diff --git a/drivers/Inc/fsl_usart.h b/drivers/Inc/fsl_usart.h new file mode 100644 index 0000000..007c595 --- /dev/null +++ b/drivers/Inc/fsl_usart.h @@ -0,0 +1,971 @@ +/* + * Copyright (c) 2016, Freescale Semiconductor, Inc. + * Copyright 2016-2023 NXP + * All rights reserved. + * + * SPDX-License-Identifier: BSD-3-Clause + */ +#ifndef FSL_USART_H_ +#define FSL_USART_H_ + +#include "fsl_common.h" + +/*! + * @addtogroup usart_driver + * @{ + */ + +/******************************************************************************* + * Definitions + ******************************************************************************/ + +/*! @name Driver version */ +/*! @{ */ +/*! @brief USART driver version. */ +#define FSL_USART_DRIVER_VERSION (MAKE_VERSION(2, 8, 4)) +/*! @} */ + +#define USART_FIFOTRIG_TXLVL_GET(base) (((base)->FIFOTRIG & USART_FIFOTRIG_TXLVL_MASK) >> USART_FIFOTRIG_TXLVL_SHIFT) +#define USART_FIFOTRIG_RXLVL_GET(base) (((base)->FIFOTRIG & USART_FIFOTRIG_RXLVL_MASK) >> USART_FIFOTRIG_RXLVL_SHIFT) + +/*! @brief Retry times for waiting flag. + * + * Defining to zero means to keep waiting for the flag until it is assert/deassert in blocking transfer, + * otherwise the program will wait until the UART_RETRY_TIMES counts down to 0, + * if the flag still remains unchanged then program will return kStatus_USART_Timeout. + * It is not advised to use this macro in formal application to prevent any hardware error + * because the actual wait period is affected by the compiler and optimization. + */ +#ifndef UART_RETRY_TIMES +#define UART_RETRY_TIMES 0U +#endif + +/*! @brief Error codes for the USART driver. */ +enum +{ + kStatus_USART_TxBusy = MAKE_STATUS(kStatusGroup_LPC_USART, 0), /*!< Transmitter is busy. */ + kStatus_USART_RxBusy = MAKE_STATUS(kStatusGroup_LPC_USART, 1), /*!< Receiver is busy. */ + kStatus_USART_TxIdle = MAKE_STATUS(kStatusGroup_LPC_USART, 2), /*!< USART transmitter is idle. */ + kStatus_USART_RxIdle = MAKE_STATUS(kStatusGroup_LPC_USART, 3), /*!< USART receiver is idle. */ + kStatus_USART_TxError = MAKE_STATUS(kStatusGroup_LPC_USART, 7), /*!< Error happens on txFIFO. */ + kStatus_USART_RxError = MAKE_STATUS(kStatusGroup_LPC_USART, 9), /*!< Error happens on rxFIFO. */ + kStatus_USART_RxRingBufferOverrun = MAKE_STATUS(kStatusGroup_LPC_USART, 8), /*!< Error happens on rx ring buffer */ + kStatus_USART_NoiseError = MAKE_STATUS(kStatusGroup_LPC_USART, 10), /*!< USART noise error. */ + kStatus_USART_FramingError = MAKE_STATUS(kStatusGroup_LPC_USART, 11), /*!< USART framing error. */ + kStatus_USART_ParityError = MAKE_STATUS(kStatusGroup_LPC_USART, 12), /*!< USART parity error. */ + kStatus_USART_BaudrateNotSupport = + MAKE_STATUS(kStatusGroup_LPC_USART, 13), /*!< Baudrate is not support in current clock source */ +#if UART_RETRY_TIMES + kStatus_USART_Timeout = MAKE_STATUS(kStatusGroup_LPC_USART, 14), /*!< USART time out. */ +#endif +}; + +/*! @brief USART synchronous mode. */ +typedef enum _usart_sync_mode +{ + kUSART_SyncModeDisabled = 0x0U, /*!< Asynchronous mode. */ + kUSART_SyncModeSlave = 0x2U, /*!< Synchronous slave mode. */ + kUSART_SyncModeMaster = 0x3U, /*!< Synchronous master mode. */ +} usart_sync_mode_t; + +/*! @brief USART parity mode. */ +typedef enum _usart_parity_mode +{ + kUSART_ParityDisabled = 0x0U, /*!< Parity disabled */ + kUSART_ParityEven = 0x2U, /*!< Parity enabled, type even, bit setting: PE|PT = 10 */ + kUSART_ParityOdd = 0x3U, /*!< Parity enabled, type odd, bit setting: PE|PT = 11 */ +} usart_parity_mode_t; + +/*! @brief USART stop bit count. */ +typedef enum _usart_stop_bit_count +{ + kUSART_OneStopBit = 0U, /*!< One stop bit */ + kUSART_TwoStopBit = 1U, /*!< Two stop bits */ +} usart_stop_bit_count_t; + +/*! @brief USART data size. */ +typedef enum _usart_data_len +{ + kUSART_7BitsPerChar = 0U, /*!< Seven bit mode */ + kUSART_8BitsPerChar = 1U, /*!< Eight bit mode */ +} usart_data_len_t; + +/*! @brief USART clock polarity configuration, used in sync mode.*/ +typedef enum _usart_clock_polarity +{ + kUSART_RxSampleOnFallingEdge = 0x0U, /*!< Un_RXD is sampled on the falling edge of SCLK. */ + kUSART_RxSampleOnRisingEdge = 0x1U, /*!< Un_RXD is sampled on the rising edge of SCLK. */ +} usart_clock_polarity_t; + +/*! @brief txFIFO watermark values */ +typedef enum _usart_txfifo_watermark +{ + kUSART_TxFifo0 = 0, /*!< USART tx watermark is empty */ + kUSART_TxFifo1 = 1, /*!< USART tx watermark at 1 item */ + kUSART_TxFifo2 = 2, /*!< USART tx watermark at 2 items */ + kUSART_TxFifo3 = 3, /*!< USART tx watermark at 3 items */ + kUSART_TxFifo4 = 4, /*!< USART tx watermark at 4 items */ + kUSART_TxFifo5 = 5, /*!< USART tx watermark at 5 items */ + kUSART_TxFifo6 = 6, /*!< USART tx watermark at 6 items */ + kUSART_TxFifo7 = 7, /*!< USART tx watermark at 7 items */ +} usart_txfifo_watermark_t; + +/*! @brief rxFIFO watermark values */ +typedef enum _usart_rxfifo_watermark +{ + kUSART_RxFifo1 = 0, /*!< USART rx watermark at 1 item */ + kUSART_RxFifo2 = 1, /*!< USART rx watermark at 2 items */ + kUSART_RxFifo3 = 2, /*!< USART rx watermark at 3 items */ + kUSART_RxFifo4 = 3, /*!< USART rx watermark at 4 items */ + kUSART_RxFifo5 = 4, /*!< USART rx watermark at 5 items */ + kUSART_RxFifo6 = 5, /*!< USART rx watermark at 6 items */ + kUSART_RxFifo7 = 6, /*!< USART rx watermark at 7 items */ + kUSART_RxFifo8 = 7, /*!< USART rx watermark at 8 items */ +} usart_rxfifo_watermark_t; + +/*! + * @brief USART interrupt configuration structure, default settings all disabled. + */ +enum _usart_interrupt_enable +{ + kUSART_TxErrorInterruptEnable = (USART_FIFOINTENSET_TXERR_MASK), + kUSART_RxErrorInterruptEnable = (USART_FIFOINTENSET_RXERR_MASK), + kUSART_TxLevelInterruptEnable = (USART_FIFOINTENSET_TXLVL_MASK), + kUSART_RxLevelInterruptEnable = (USART_FIFOINTENSET_RXLVL_MASK), + kUSART_TxIdleInterruptEnable = (USART_INTENSET_TXIDLEEN_MASK << 16U), /*!< Transmitter idle. */ + kUSART_CtsChangeInterruptEnable = + (USART_INTENSET_DELTACTSEN_MASK << 16U), /*!< Change in the state of the CTS input. */ + kUSART_RxBreakChangeInterruptEnable = + (USART_INTENSET_DELTARXBRKEN_MASK), /*!< Break condition asserted or deasserted. */ + kUSART_RxStartInterruptEnable = (USART_INTENSET_STARTEN_MASK), /*!< Rx start bit detected. */ + kUSART_FramingErrorInterruptEnable = (USART_INTENSET_FRAMERREN_MASK), /*!< Framing error detected. */ + kUSART_ParityErrorInterruptEnable = (USART_INTENSET_PARITYERREN_MASK), /*!< Parity error detected. */ + kUSART_NoiseErrorInterruptEnable = (USART_INTENSET_RXNOISEEN_MASK), /*!< Noise error detected. */ + kUSART_AutoBaudErrorInterruptEnable = (USART_INTENSET_ABERREN_MASK), /*!< Auto baudrate error detected. */ +#if defined(FSL_FEATURE_USART_HAS_FIFORXTIMEOUTCFG) && FSL_FEATURE_USART_HAS_FIFORXTIMEOUTCFG + kUSART_RxTimeoutInterruptEnable = (USART_FIFOINTENSET_RXTIMEOUT_MASK), /*!< Receive timeout detected. */ +#endif + kUSART_AllInterruptEnables = + kUSART_TxErrorInterruptEnable | kUSART_RxErrorInterruptEnable | kUSART_TxLevelInterruptEnable | + kUSART_RxLevelInterruptEnable | kUSART_TxIdleInterruptEnable | kUSART_CtsChangeInterruptEnable | + kUSART_RxBreakChangeInterruptEnable | kUSART_RxStartInterruptEnable | kUSART_FramingErrorInterruptEnable | + kUSART_ParityErrorInterruptEnable | kUSART_NoiseErrorInterruptEnable | +#if defined(FSL_FEATURE_USART_HAS_FIFORXTIMEOUTCFG) && FSL_FEATURE_USART_HAS_FIFORXTIMEOUTCFG + kUSART_RxTimeoutInterruptEnable | +#endif + kUSART_AutoBaudErrorInterruptEnable, +}; + +/*! + * @brief USART status flags. + * + * This provides constants for the USART status flags for use in the USART functions. + */ +enum _usart_flags +{ + kUSART_TxError = (USART_FIFOSTAT_TXERR_MASK), /*!< TEERR bit, sets if TX buffer is error */ + kUSART_RxError = (USART_FIFOSTAT_RXERR_MASK), /*!< RXERR bit, sets if RX buffer is error */ + kUSART_TxFifoEmptyFlag = (USART_FIFOSTAT_TXEMPTY_MASK), /*!< TXEMPTY bit, sets if TX buffer is empty */ + kUSART_TxFifoNotFullFlag = (USART_FIFOSTAT_TXNOTFULL_MASK), /*!< TXNOTFULL bit, sets if TX buffer is not full */ + kUSART_RxFifoNotEmptyFlag = (USART_FIFOSTAT_RXNOTEMPTY_MASK), /*!< RXNOEMPTY bit, sets if RX buffer is not empty */ + kUSART_RxFifoFullFlag = (USART_FIFOSTAT_RXFULL_MASK), /*!< RXFULL bit, sets if RX buffer is full */ + kUSART_RxIdleFlag = (USART_STAT_RXIDLE_MASK << 16U), /*!< Receiver idle. */ + kUSART_TxIdleFlag = (USART_STAT_TXIDLE_MASK << 16U), /*!< Transmitter idle. */ + kUSART_CtsAssertFlag = (USART_STAT_CTS_MASK << 16U), /*!< CTS signal high. */ + kUSART_CtsChangeFlag = (USART_STAT_DELTACTS_MASK << 16U), /*!< CTS signal changed interrupt status. */ + kUSART_BreakDetectFlag = (USART_STAT_RXBRK_MASK), /*!< Break detected. Self cleared when rx pin goes high again. */ + kUSART_BreakDetectChangeFlag = (USART_STAT_DELTARXBRK_MASK), /*!< Break detect change interrupt flag. A change in + the state of receiver break detection. */ + kUSART_RxStartFlag = (USART_STAT_START_MASK), /*!< Rx start bit detected interrupt flag. */ + kUSART_FramingErrorFlag = (USART_STAT_FRAMERRINT_MASK), /*!< Framing error interrupt flag. */ + kUSART_ParityErrorFlag = (USART_STAT_PARITYERRINT_MASK), /*!< parity error interrupt flag. */ + kUSART_NoiseErrorFlag = (USART_STAT_RXNOISEINT_MASK), /*!< Noise error interrupt flag. */ + kUSART_AutobaudErrorFlag = (USART_STAT_ABERR_MASK), /*!< Auto baudrate error interrupt flag, caused by the baudrate + counter timeout before the end of start bit. */ +#if defined(FSL_FEATURE_USART_HAS_FIFORXTIMEOUTCFG) && FSL_FEATURE_USART_HAS_FIFORXTIMEOUTCFG + kUSART_RxTimeoutFlag = (USART_FIFOSTAT_RXTIMEOUT_MASK), /*!< RXTIMEOUT bit, sets if RX FIFO Timeout. */ +#endif + kUSART_AllClearFlags = kUSART_TxError | kUSART_RxError | kUSART_CtsChangeFlag | kUSART_BreakDetectChangeFlag | + kUSART_RxStartFlag | kUSART_FramingErrorFlag | kUSART_ParityErrorFlag | +#if defined(FSL_FEATURE_USART_HAS_FIFORXTIMEOUTCFG) && FSL_FEATURE_USART_HAS_FIFORXTIMEOUTCFG + kUSART_RxTimeoutFlag | +#endif + kUSART_NoiseErrorFlag | kUSART_AutobaudErrorFlag, +}; + +#if defined(FSL_FEATURE_USART_HAS_FIFORXTIMEOUTCFG) && FSL_FEATURE_USART_HAS_FIFORXTIMEOUTCFG +/*! @brief USART receive timeout configuration structure. */ +typedef struct _usart_rx_timeout_config +{ + bool enable; /*!< Enable RX timeout */ + bool resetCounterOnEmpty; /*!< Enable RX timeout counter reset when RX FIFO becames empty. */ + bool resetCounterOnReceive; /*!< Enable RX timeout counter reset when RX FIFO receives data from the transmitter + side. */ + uint32_t counter; /*!< RX timeout counter*/ + uint8_t prescaler; /*!< RX timeout prescaler*/ +} usart_rx_timeout_config; +#endif + +/*! @brief USART configuration structure. */ +typedef struct _usart_config +{ + uint32_t baudRate_Bps; /*!< USART baud rate */ + usart_parity_mode_t parityMode; /*!< Parity mode, disabled (default), even, odd */ + usart_stop_bit_count_t stopBitCount; /*!< Number of stop bits, 1 stop bit (default) or 2 stop bits */ + usart_data_len_t bitCountPerChar; /*!< Data length - 7 bit, 8 bit */ + bool loopback; /*!< Enable peripheral loopback */ + bool enableRx; /*!< Enable RX */ + bool enableTx; /*!< Enable TX */ + bool enableContinuousSCLK; /*!< USART continuous Clock generation enable in synchronous master mode. */ + bool enableMode32k; /*!< USART uses 32 kHz clock from the RTC oscillator as the clock source. */ + bool enableHardwareFlowControl; /*!< Enable hardware control RTS/CTS */ + usart_txfifo_watermark_t txWatermark; /*!< txFIFO watermark */ + usart_rxfifo_watermark_t rxWatermark; /*!< rxFIFO watermark */ + usart_sync_mode_t syncMode; /*!< Transfer mode select - asynchronous, synchronous master, synchronous slave. */ + usart_clock_polarity_t clockPolarity; /*!< Selects the clock polarity and sampling edge in synchronous mode. */ +#if defined(FSL_FEATURE_USART_HAS_FIFORXTIMEOUTCFG) && FSL_FEATURE_USART_HAS_FIFORXTIMEOUTCFG + usart_rx_timeout_config rxTimeout; /*!< rx timeout configuration */ +#endif +} usart_config_t; + +/*! @brief USART transfer structure. */ +typedef struct _usart_transfer +{ + /* + * Use separate TX and RX data pointer, because TX data is const data. + * The member data is kept for backward compatibility. + */ + union + { + uint8_t *data; /*!< The buffer of data to be transfer.*/ + uint8_t *rxData; /*!< The buffer to receive data. */ + const uint8_t *txData; /*!< The buffer of data to be sent. */ + }; + size_t dataSize; /*!< The byte count to be transfer. */ +} usart_transfer_t; + +/* Forward declaration of the handle typedef. */ +typedef struct _usart_handle usart_handle_t; + +/*! @brief USART transfer callback function. */ +typedef void (*usart_transfer_callback_t)(USART_Type *base, usart_handle_t *handle, status_t status, void *userData); + +/*! @brief USART handle structure. */ +struct _usart_handle +{ + const uint8_t *volatile txData; /*!< Address of remaining data to send. */ + volatile size_t txDataSize; /*!< Size of the remaining data to send. */ + size_t txDataSizeAll; /*!< Size of the data to send out. */ + uint8_t *volatile rxData; /*!< Address of remaining data to receive. */ + volatile size_t rxDataSize; /*!< Size of the remaining data to receive. */ + size_t rxDataSizeAll; /*!< Size of the data to receive. */ + + uint8_t *rxRingBuffer; /*!< Start address of the receiver ring buffer. */ + size_t rxRingBufferSize; /*!< Size of the ring buffer. */ + volatile uint16_t rxRingBufferHead; /*!< Index for the driver to store received data into ring buffer. */ + volatile uint16_t rxRingBufferTail; /*!< Index for the user to get data from the ring buffer. */ + + usart_transfer_callback_t callback; /*!< Callback function. */ + void *userData; /*!< USART callback function parameter.*/ + + volatile uint8_t txState; /*!< TX transfer state. */ + volatile uint8_t rxState; /*!< RX transfer state */ + + uint8_t txWatermark; /*!< txFIFO watermark */ + uint8_t rxWatermark; /*!< rxFIFO watermark */ +}; + +/*! @brief Typedef for usart interrupt handler. */ +typedef void (*flexcomm_usart_irq_handler_t)(USART_Type *base, usart_handle_t *handle); + +/******************************************************************************* + * API + ******************************************************************************/ + +#if defined(__cplusplus) +extern "C" { +#endif /* _cplusplus */ + +/*! @brief Returns instance number for USART peripheral base address. */ +uint32_t USART_GetInstance(USART_Type *base); + +/*! + * @name Initialization and deinitialization + * @{ + */ + +/*! + * @brief Initializes a USART instance with user configuration structure and peripheral clock. + * + * This function configures the USART module with the user-defined settings. The user can configure the configuration + * structure and also get the default configuration by using the USART_GetDefaultConfig() function. + * Example below shows how to use this API to configure USART. + * @code + * usart_config_t usartConfig; + * usartConfig.baudRate_Bps = 115200U; + * usartConfig.parityMode = kUSART_ParityDisabled; + * usartConfig.stopBitCount = kUSART_OneStopBit; + * USART_Init(USART1, &usartConfig, 20000000U); + * @endcode + * + * @param base USART peripheral base address. + * @param config Pointer to user-defined configuration structure. + * @param srcClock_Hz USART clock source frequency in HZ. + * @retval kStatus_USART_BaudrateNotSupport Baudrate is not support in current clock source. + * @retval kStatus_InvalidArgument USART base address is not valid + * @retval kStatus_Success Status USART initialize succeed + */ +status_t USART_Init(USART_Type *base, const usart_config_t *config, uint32_t srcClock_Hz); +#if defined(FSL_FEATURE_USART_HAS_FIFORXTIMEOUTCFG) && FSL_FEATURE_USART_HAS_FIFORXTIMEOUTCFG +/*! + * @brief Calculate the USART instance RX timeout prescaler and counter. + * + * This function for calculate the USART RXFIFO timeout config. This function is used to calculate + * suitable prescaler and counter for target_us. + * @code + * usart_config_t config; + * config.rxWatermark = kUSART_RxFifo2; + * config.rxTimeout.enable = true; + * config.rxTimeout.resetCounterOnEmpty = true; + * config.rxTimeout.resetCounterOnReceive = true; + * USART_CalcTimeoutConfig(200U, &config.rxTimeout.prescaler, &config.rxTimeout.counter, + * CLOCK_GetFreq(kCLOCK_BusClk)); + * @endcode + * @param target_us Time for rx timeout unit us. + * @param rxTimeoutPrescaler The prescaler to be setted after function. + * @param rxTimeoutcounter The counter to be setted after function. + * @param srcClock_Hz The clockSrc for rx timeout. + */ +void USART_CalcTimeoutConfig(uint32_t target_us, + uint8_t *rxTimeoutPrescaler, + uint32_t *rxTimeoutcounter, + uint32_t srcClock_Hz); +/*! + * @brief Sets the USART instance RX timeout config. + * + * This function configures the USART RXFIFO timeout config. This function is used to config + * the USART RXFIFO timeout config after the USART module is initialized by the USART_Init. + * + * @param base USART peripheral base address. + * @param config pointer to receive timeout configuration structure. + */ +void USART_SetRxTimeoutConfig(USART_Type *base, const usart_rx_timeout_config *config); +#endif +/*! + * @brief Deinitializes a USART instance. + * + * This function waits for TX complete, disables TX and RX, and disables the USART clock. + * + * @param base USART peripheral base address. + */ +void USART_Deinit(USART_Type *base); + +/*! + * @brief Gets the default configuration structure. + * + * This function initializes the USART configuration structure to a default value. The default + * values are: + * usartConfig->baudRate_Bps = 115200U; + * usartConfig->parityMode = kUSART_ParityDisabled; + * usartConfig->stopBitCount = kUSART_OneStopBit; + * usartConfig->bitCountPerChar = kUSART_8BitsPerChar; + * usartConfig->loopback = false; + * usartConfig->enableTx = false; + * usartConfig->enableRx = false; + * + * @param config Pointer to configuration structure. + */ +void USART_GetDefaultConfig(usart_config_t *config); + +/*! + * @brief Sets the USART instance baud rate. + * + * This function configures the USART module baud rate. This function is used to update + * the USART module baud rate after the USART module is initialized by the USART_Init. + * @code + * USART_SetBaudRate(USART1, 115200U, 20000000U); + * @endcode + * + * @param base USART peripheral base address. + * @param baudrate_Bps USART baudrate to be set. + * @param srcClock_Hz USART clock source frequency in HZ. + * @retval kStatus_USART_BaudrateNotSupport Baudrate is not support in current clock source. + * @retval kStatus_Success Set baudrate succeed. + * @retval kStatus_InvalidArgument One or more arguments are invalid. + */ +status_t USART_SetBaudRate(USART_Type *base, uint32_t baudrate_Bps, uint32_t srcClock_Hz); + +/*! + * @brief Enable 32 kHz mode which USART uses clock from the RTC oscillator as the clock source + * + * Please note that in order to use a 32 kHz clock to operate USART properly, the RTC oscillator + * and its 32 kHz output must be manully enabled by user, by calling RTC_Init and setting + * SYSCON_RTCOSCCTRL_EN bit to 1. + * And in 32kHz clocking mode the USART can only work at 9600 baudrate or at the baudrate that + * 9600 can evenly divide, eg: 4800, 3200. + * + * @param base USART peripheral base address. + * @param baudRate_Bps USART baudrate to be set.. + * @param enableMode32k true is 32k mode, false is normal mode. + * @param srcClock_Hz USART clock source frequency in HZ. + * @retval kStatus_USART_BaudrateNotSupport Baudrate is not support in current clock source. + * @retval kStatus_Success Set baudrate succeed. + * @retval kStatus_InvalidArgument One or more arguments are invalid. + */ +status_t USART_Enable32kMode(USART_Type *base, uint32_t baudRate_Bps, bool enableMode32k, uint32_t srcClock_Hz); + +/*! + * @brief Enable 9-bit data mode for USART. + * + * This function set the 9-bit mode for USART module. The 9th bit is not used for parity thus can be modified by user. + * + * @param base USART peripheral base address. + * @param enable true to enable, false to disable. + */ +void USART_Enable9bitMode(USART_Type *base, bool enable); + +/*! + * @brief Set the USART slave address. + * + * This function configures the address for USART module that works as slave in 9-bit data mode. When the address + * detection is enabled, the frame it receices with MSB being 1 is considered as an address frame, otherwise it is + * considered as data frame. Once the address frame matches slave's own addresses, this slave is addressed. This + * address frame and its following data frames are stored in the receive buffer, otherwise the frames will be discarded. + * To un-address a slave, just send an address frame with unmatched address. + * + * @note Any USART instance joined in the multi-slave system can work as slave. The position of the address mark is the + * same as the parity bit when parity is enabled for 8 bit and 9 bit data formats. + * + * @param base USART peripheral base address. + * @param address USART slave address. + */ +static inline void USART_SetMatchAddress(USART_Type *base, uint8_t address) +{ + /* Configure match address. */ + base->ADDR = (uint32_t)address; +} + +/*! + * @brief Enable the USART match address feature. + * + * @param base USART peripheral base address. + * @param match true to enable match address, false to disable. + */ +static inline void USART_EnableMatchAddress(USART_Type *base, bool match) +{ + /* Configure match address enable bit. */ + if (match) + { + base->CFG |= (uint32_t)USART_CFG_AUTOADDR_MASK; + base->CTL |= (uint32_t)USART_CTL_ADDRDET_MASK; + } + else + { + base->CFG &= ~(uint32_t)USART_CFG_AUTOADDR_MASK; + base->CTL &= ~(uint32_t)USART_CTL_ADDRDET_MASK; + } +} + +/*! @} */ + +/*! + * @name Status + * @{ + */ + +/*! + * @brief Get USART status flags. + * + * This function get all USART status flags, the flags are returned as the logical + * OR value of the enumerators @ref _usart_flags. To check a specific status, + * compare the return value with enumerators in @ref _usart_flags. + * For example, to check whether the TX is empty: + * @code + * if (kUSART_TxFifoNotFullFlag & USART_GetStatusFlags(USART1)) + * { + * ... + * } + * @endcode + * + * @param base USART peripheral base address. + * @return USART status flags which are ORed by the enumerators in the _usart_flags. + */ +static inline uint32_t USART_GetStatusFlags(USART_Type *base) +{ + return (base->FIFOSTAT & 0xFF0000FFUL) | (base->STAT & 0xFFUL) << 16U | (base->STAT & 0xFFFF00UL); +} + +/*! + * @brief Clear USART status flags. + * + * This function clear supported USART status flags + * Flags that can be cleared or set are: + * kUSART_TxError + * kUSART_RxError + * For example: + * @code + * USART_ClearStatusFlags(USART1, kUSART_TxError | kUSART_RxError) + * @endcode + * + * @param base USART peripheral base address. + * @param mask status flags to be cleared. + */ +static inline void USART_ClearStatusFlags(USART_Type *base, uint32_t mask) +{ + mask &= (uint32_t)kUSART_AllClearFlags; + /* Clear the clearable status in STAT register. */ + base->STAT = (mask & 0xFFFF00UL) | ((mask & 0xFF0000UL) >> 16U); + /* Only TXERR, RXERR fields support write. Remaining fields should be set to zero */ + base->FIFOSTAT = mask & (USART_FIFOSTAT_TXERR_MASK | USART_FIFOSTAT_RXERR_MASK); +} + +/*! @} */ + +/*! + * @name Interrupts + * @{ + */ +/*! + * @brief Enables USART interrupts according to the provided mask. + * + * This function enables the USART interrupts according to the provided mask. The mask + * is a logical OR of enumeration members. See @ref _usart_interrupt_enable. + * For example, to enable TX empty interrupt and RX full interrupt: + * @code + * USART_EnableInterrupts(USART1, kUSART_TxLevelInterruptEnable | kUSART_RxLevelInterruptEnable); + * @endcode + * + * @param base USART peripheral base address. + * @param mask The interrupts to enable. Logical OR of @ref _usart_interrupt_enable. + */ +static inline void USART_EnableInterrupts(USART_Type *base, uint32_t mask) +{ + mask &= (uint32_t)kUSART_AllInterruptEnables; + base->INTENSET = (mask & 0x1FF00UL) | ((mask & 0xFF0000UL) >> 16U); + base->FIFOINTENSET = mask & 0xF00000FUL; +} + +/*! + * @brief Disables USART interrupts according to a provided mask. + * + * This function disables the USART interrupts according to a provided mask. The mask + * is a logical OR of enumeration members. See @ref _usart_interrupt_enable. + * This example shows how to disable the TX empty interrupt and RX full interrupt: + * @code + * USART_DisableInterrupts(USART1, kUSART_TxLevelInterruptEnable | kUSART_RxLevelInterruptEnable); + * @endcode + * + * @param base USART peripheral base address. + * @param mask The interrupts to disable. Logical OR of @ref _usart_interrupt_enable. + */ +static inline void USART_DisableInterrupts(USART_Type *base, uint32_t mask) +{ + mask &= (uint32_t)kUSART_AllInterruptEnables; + base->INTENCLR = (mask & 0x1FF00UL) | ((mask & 0xFF0000UL) >> 16U); + base->FIFOINTENCLR = mask & 0xFUL; +} + +/*! + * @brief Returns enabled USART interrupts. + * + * This function returns the enabled USART interrupts. + * + * @param base USART peripheral base address. + */ +static inline uint32_t USART_GetEnabledInterrupts(USART_Type *base) +{ + return (base->INTENSET & 0x1FF00UL) | ((base->INTENSET & 0xFFUL) << 16UL) | (base->FIFOINTENSET & 0xFUL); +} + +/*! + * @brief Enable DMA for Tx + */ +static inline void USART_EnableTxDMA(USART_Type *base, bool enable) +{ + if (enable) + { + base->FIFOCFG |= USART_FIFOCFG_DMATX_MASK; + } + else + { + base->FIFOCFG &= ~(USART_FIFOCFG_DMATX_MASK); + } +} + +/*! + * @brief Enable DMA for Rx + */ +static inline void USART_EnableRxDMA(USART_Type *base, bool enable) +{ + if (enable) + { + base->FIFOCFG |= USART_FIFOCFG_DMARX_MASK; + } + else + { + base->FIFOCFG &= ~(USART_FIFOCFG_DMARX_MASK); + } +} + +/*! + * @brief Enable CTS. + * This function will determine whether CTS is used for flow control. + * + * @param base USART peripheral base address. + * @param enable Enable CTS or not, true for enable and false for disable. + */ +static inline void USART_EnableCTS(USART_Type *base, bool enable) +{ + if (enable) + { + base->CFG |= USART_CFG_CTSEN_MASK; + } + else + { + base->CFG &= ~USART_CFG_CTSEN_MASK; + } +} + +/*! + * @brief Continuous Clock generation. + * By default, SCLK is only output while data is being transmitted in synchronous mode. + * Enable this funciton, SCLK will run continuously in synchronous mode, allowing + * characters to be received on Un_RxD independently from transmission on Un_TXD). + * + * @param base USART peripheral base address. + * @param enable Enable Continuous Clock generation mode or not, true for enable and false for disable. + */ +static inline void USART_EnableContinuousSCLK(USART_Type *base, bool enable) +{ + if (enable) + { + base->CTL |= USART_CTL_CC_MASK; + } + else + { + base->CTL &= ~USART_CTL_CC_MASK; + } +} + +/*! + * @brief Enable Continuous Clock generation bit auto clear. + * While enable this cuntion, the Continuous Clock bit is automatically cleared when a complete + * character has been received. This bit is cleared at the same time. + * + * @param base USART peripheral base address. + * @param enable Enable auto clear or not, true for enable and false for disable. + */ +static inline void USART_EnableAutoClearSCLK(USART_Type *base, bool enable) +{ + if (enable) + { + base->CTL |= USART_CTL_CLRCCONRX_MASK; + } + else + { + base->CTL &= ~USART_CTL_CLRCCONRX_MASK; + } +} + +/*! + * @brief Sets the rx FIFO watermark. + * + * @param base USART peripheral base address. + * @param water Rx FIFO watermark. + */ +static inline void USART_SetRxFifoWatermark(USART_Type *base, uint8_t water) +{ + assert(water <= (USART_FIFOTRIG_RXLVL_MASK >> USART_FIFOTRIG_RXLVL_SHIFT)); + base->FIFOTRIG = (base->FIFOTRIG & ~USART_FIFOTRIG_RXLVL_MASK) | USART_FIFOTRIG_RXLVL(water); +} + +/*! + * @brief Sets the tx FIFO watermark. + * + * @param base USART peripheral base address. + * @param water Tx FIFO watermark. + */ +static inline void USART_SetTxFifoWatermark(USART_Type *base, uint8_t water) +{ + assert(water <= (USART_FIFOTRIG_TXLVL_MASK >> USART_FIFOTRIG_TXLVL_SHIFT)); + base->FIFOTRIG = (base->FIFOTRIG & ~USART_FIFOTRIG_TXLVL_MASK) | USART_FIFOTRIG_TXLVL(water); +} +/*! @} */ + +/*! + * @name Bus Operations + * @{ + */ + +/*! + * @brief Writes to the FIFOWR register. + * + * This function writes data to the txFIFO directly. The upper layer must ensure + * that txFIFO has space for data to write before calling this function. + * + * @param base USART peripheral base address. + * @param data The byte to write. + */ +static inline void USART_WriteByte(USART_Type *base, uint8_t data) +{ + base->FIFOWR = data; +} + +/*! + * @brief Reads the FIFORD register directly. + * + * This function reads data from the rxFIFO directly. The upper layer must + * ensure that the rxFIFO is not empty before calling this function. + * + * @param base USART peripheral base address. + * @return The byte read from USART data register. + */ +static inline uint8_t USART_ReadByte(USART_Type *base) +{ + return (uint8_t)base->FIFORD; +} + +/*! + * @brief Gets the rx FIFO data count. + * + * @param base USART peripheral base address. + * @return rx FIFO data count. + */ +static inline uint8_t USART_GetRxFifoCount(USART_Type *base) +{ + return (uint8_t)((base->FIFOSTAT & USART_FIFOSTAT_RXLVL_MASK) >> USART_FIFOSTAT_RXLVL_SHIFT); +} + +/*! + * @brief Gets the tx FIFO data count. + * + * @param base USART peripheral base address. + * @return tx FIFO data count. + */ +static inline uint8_t USART_GetTxFifoCount(USART_Type *base) +{ + return (uint8_t)((base->FIFOSTAT & USART_FIFOSTAT_TXLVL_MASK) >> USART_FIFOSTAT_TXLVL_SHIFT); +} + +/*! + * @brief Transmit an address frame in 9-bit data mode. + * + * @param base USART peripheral base address. + * @param address USART slave address. + */ +void USART_SendAddress(USART_Type *base, uint8_t address); + +/*! + * @brief Writes to the TX register using a blocking method. + * + * This function polls the TX register, waits for the TX register to be empty or for the TX FIFO + * to have room and writes data to the TX buffer. + * + * @param base USART peripheral base address. + * @param data Start address of the data to write. + * @param length Size of the data to write. + * @retval kStatus_USART_Timeout Transmission timed out and was aborted. + * @retval kStatus_InvalidArgument Invalid argument. + * @retval kStatus_Success Successfully wrote all data. + */ +status_t USART_WriteBlocking(USART_Type *base, const uint8_t *data, size_t length); + +/*! + * @brief Read RX data register using a blocking method. + * + * This function polls the RX register, waits for the RX register to be full or for RX FIFO to + * have data and read data from the TX register. + * + * @param base USART peripheral base address. + * @param data Start address of the buffer to store the received data. + * @param length Size of the buffer. + * @retval kStatus_USART_FramingError Receiver overrun happened while receiving data. + * @retval kStatus_USART_ParityError Noise error happened while receiving data. + * @retval kStatus_USART_NoiseError Framing error happened while receiving data. + * @retval kStatus_USART_RxError Overflow or underflow rxFIFO happened. + * @retval kStatus_USART_Timeout Transmission timed out and was aborted. + * @retval kStatus_Success Successfully received all data. + */ +status_t USART_ReadBlocking(USART_Type *base, uint8_t *data, size_t length); + +/*! @} */ + +/*! + * @name Transactional + * @{ + */ + +/*! + * @brief Initializes the USART handle. + * + * This function initializes the USART handle which can be used for other USART + * transactional APIs. Usually, for a specified USART instance, + * call this API once to get the initialized handle. + * + * @param base USART peripheral base address. + * @param handle USART handle pointer. + * @param callback The callback function. + * @param userData The parameter of the callback function. + */ +status_t USART_TransferCreateHandle(USART_Type *base, + usart_handle_t *handle, + usart_transfer_callback_t callback, + void *userData); + +/*! + * @brief Transmits a buffer of data using the interrupt method. + * + * This function sends data using an interrupt method. This is a non-blocking function, which + * returns directly without waiting for all data to be written to the TX register. When + * all data is written to the TX register in the IRQ handler, the USART driver calls the callback + * function and passes the @ref kStatus_USART_TxIdle as status parameter. + * + * @param base USART peripheral base address. + * @param handle USART handle pointer. + * @param xfer USART transfer structure. See #usart_transfer_t. + * @retval kStatus_Success Successfully start the data transmission. + * @retval kStatus_USART_TxBusy Previous transmission still not finished, data not all written to TX register yet. + * @retval kStatus_InvalidArgument Invalid argument. + */ +status_t USART_TransferSendNonBlocking(USART_Type *base, usart_handle_t *handle, usart_transfer_t *xfer); + +/*! + * @brief Sets up the RX ring buffer. + * + * This function sets up the RX ring buffer to a specific USART handle. + * + * When the RX ring buffer is used, data received are stored into the ring buffer even when the + * user doesn't call the USART_TransferReceiveNonBlocking() API. If there is already data received + * in the ring buffer, the user can get the received data from the ring buffer directly. + * + * @note When using the RX ring buffer, one byte is reserved for internal use. In other + * words, if @p ringBufferSize is 32, then only 31 bytes are used for saving data. + * + * @param base USART peripheral base address. + * @param handle USART handle pointer. + * @param ringBuffer Start address of the ring buffer for background receiving. Pass NULL to disable the ring buffer. + * @param ringBufferSize size of the ring buffer. + */ +void USART_TransferStartRingBuffer(USART_Type *base, + usart_handle_t *handle, + uint8_t *ringBuffer, + size_t ringBufferSize); + +/*! + * @brief Aborts the background transfer and uninstalls the ring buffer. + * + * This function aborts the background transfer and uninstalls the ring buffer. + * + * @param base USART peripheral base address. + * @param handle USART handle pointer. + */ +void USART_TransferStopRingBuffer(USART_Type *base, usart_handle_t *handle); + +/*! + * @brief Get the length of received data in RX ring buffer. + * + * @param handle USART handle pointer. + * @return Length of received data in RX ring buffer. + */ +size_t USART_TransferGetRxRingBufferLength(usart_handle_t *handle); + +/*! + * @brief Aborts the interrupt-driven data transmit. + * + * This function aborts the interrupt driven data sending. The user can get the remainBtyes to find out + * how many bytes are still not sent out. + * + * @param base USART peripheral base address. + * @param handle USART handle pointer. + */ +void USART_TransferAbortSend(USART_Type *base, usart_handle_t *handle); + +/*! + * @brief Get the number of bytes that have been sent out to bus. + * + * This function gets the number of bytes that have been sent out to bus by interrupt method. + * + * @param base USART peripheral base address. + * @param handle USART handle pointer. + * @param count Send bytes count. + * @retval kStatus_NoTransferInProgress No send in progress. + * @retval kStatus_InvalidArgument Parameter is invalid. + * @retval kStatus_Success Get successfully through the parameter \p count; + */ +status_t USART_TransferGetSendCount(USART_Type *base, usart_handle_t *handle, uint32_t *count); + +/*! + * @brief Receives a buffer of data using an interrupt method. + * + * This function receives data using an interrupt method. This is a non-blocking function, which + * returns without waiting for all data to be received. + * If the RX ring buffer is used and not empty, the data in the ring buffer is copied and + * the parameter @p receivedBytes shows how many bytes are copied from the ring buffer. + * After copying, if the data in the ring buffer is not enough to read, the receive + * request is saved by the USART driver. When the new data arrives, the receive request + * is serviced first. When all data is received, the USART driver notifies the upper layer + * through a callback function and passes the status parameter @ref kStatus_USART_RxIdle. + * For example, the upper layer needs 10 bytes but there are only 5 bytes in the ring buffer. + * The 5 bytes are copied to the xfer->data and this function returns with the + * parameter @p receivedBytes set to 5. For the left 5 bytes, newly arrived data is + * saved from the xfer->data[5]. When 5 bytes are received, the USART driver notifies the upper layer. + * If the RX ring buffer is not enabled, this function enables the RX and RX interrupt + * to receive data to the xfer->data. When all data is received, the upper layer is notified. + * + * @param base USART peripheral base address. + * @param handle USART handle pointer. + * @param xfer USART transfer structure, see #usart_transfer_t. + * @param receivedBytes Bytes received from the ring buffer directly. + * @retval kStatus_Success Successfully queue the transfer into transmit queue. + * @retval kStatus_USART_RxBusy Previous receive request is not finished. + * @retval kStatus_InvalidArgument Invalid argument. + */ +status_t USART_TransferReceiveNonBlocking(USART_Type *base, + usart_handle_t *handle, + usart_transfer_t *xfer, + size_t *receivedBytes); + +/*! + * @brief Aborts the interrupt-driven data receiving. + * + * This function aborts the interrupt-driven data receiving. The user can get the remainBytes to find out + * how many bytes not received yet. + * + * @param base USART peripheral base address. + * @param handle USART handle pointer. + */ +void USART_TransferAbortReceive(USART_Type *base, usart_handle_t *handle); + +/*! + * @brief Get the number of bytes that have been received. + * + * This function gets the number of bytes that have been received. + * + * @param base USART peripheral base address. + * @param handle USART handle pointer. + * @param count Receive bytes count. + * @retval kStatus_NoTransferInProgress No receive in progress. + * @retval kStatus_InvalidArgument Parameter is invalid. + * @retval kStatus_Success Get successfully through the parameter \p count; + */ +status_t USART_TransferGetReceiveCount(USART_Type *base, usart_handle_t *handle, uint32_t *count); + +/*! + * @brief USART IRQ handle function. + * + * This function handles the USART transmit and receive IRQ request. + * + * @param base USART peripheral base address. + * @param handle USART handle pointer. + */ +void USART_TransferHandleIRQ(USART_Type *base, usart_handle_t *handle); + +/*! @} */ + +#if defined(__cplusplus) +} +#endif + +/*! @}*/ + +#endif /* FSL_USART_H_ */ diff --git a/drivers/Inc/led.h b/drivers/Inc/led.h new file mode 100644 index 0000000..0037142 --- /dev/null +++ b/drivers/Inc/led.h @@ -0,0 +1,10 @@ +#ifndef __LED_H_ +#define __LED_H_ + +#include "fsl_device_registers.h" +void led_init(void); +void led_on(void); +void led_off(void); + + +#endif /* __LED__H__ */ diff --git a/drivers/Inc/uart.h b/drivers/Inc/uart.h new file mode 100644 index 0000000..7ce56c5 --- /dev/null +++ b/drivers/Inc/uart.h @@ -0,0 +1,7 @@ +#ifndef __UART_H__ +#define __UART_H__ + +extern void uart_init(void); + + +#endif /* __UART_H__ */ \ No newline at end of file diff --git a/drivers/Src/fsl_adapter_usart.c b/drivers/Src/fsl_adapter_usart.c new file mode 100644 index 0000000..e82731f --- /dev/null +++ b/drivers/Src/fsl_adapter_usart.c @@ -0,0 +1,1101 @@ +/* + * Copyright 2018 NXP + * All rights reserved. + * + * + * SPDX-License-Identifier: BSD-3-Clause + */ + +#include "fsl_common.h" +#include "fsl_usart.h" +#include "fsl_flexcomm.h" + +#include "fsl_adapter_uart.h" + +#if (defined(HAL_UART_DMA_ENABLE) && (HAL_UART_DMA_ENABLE > 0U)) +#include "fsl_component_timer_manager.h" +#include "fsl_usart_dma.h" +#endif /* HAL_UART_DMA_ENABLE */ + +/******************************************************************************* + * Definitions + ******************************************************************************/ +#ifndef NDEBUG +#if (defined(DEBUG_CONSOLE_ASSERT_DISABLE) && (DEBUG_CONSOLE_ASSERT_DISABLE > 0U)) +#undef assert +#define assert(n) +#endif +#endif + +#if (defined(HAL_UART_DMA_ENABLE) && (HAL_UART_DMA_ENABLE > 0U)) +/*! @brief uart RX state structure. */ +typedef struct _hal_uart_dma_receive_state +{ + uint8_t *volatile buffer; + volatile uint32_t bufferLength; + volatile uint32_t bufferSofar; + volatile uint32_t timeout; + volatile bool receiveAll; +} hal_uart_dma_receive_state_t; + +/*! @brief uart TX state structure. */ +typedef struct _hal_uart_dma_send_state +{ + uint8_t *volatile buffer; + volatile uint32_t bufferLength; + volatile uint32_t bufferSofar; + volatile uint32_t timeout; +} hal_uart_dma_send_state_t; + +typedef struct _hal_uart_dma_state +{ + struct _hal_uart_dma_state *next; + uint8_t instance; /* USART instance */ + hal_uart_dma_transfer_callback_t dma_callback; + void *dma_callback_param; + usart_dma_handle_t dmaHandle; + dma_handle_t txDmaHandle; + dma_handle_t rxDmaHandle; + hal_uart_dma_receive_state_t dma_rx; + hal_uart_dma_send_state_t dma_tx; +} hal_uart_dma_state_t; + +typedef struct _uart_dma_list +{ + TIMER_MANAGER_HANDLE_DEFINE(timerManagerHandle); + hal_uart_dma_state_t *dma_list; + volatile int8_t activeCount; +} hal_uart_dma_list_t; + +static hal_uart_dma_list_t s_dmaHandleList; +#endif /* HAL_UART_DMA_ENABLE */ + +#if (defined(UART_ADAPTER_NON_BLOCKING_MODE) && (UART_ADAPTER_NON_BLOCKING_MODE > 0U)) +/*! @brief uart RX state structure. */ +typedef struct _hal_uart_receive_state +{ + volatile uint8_t *buffer; + volatile uint32_t bufferLength; + volatile uint32_t bufferSofar; +} hal_uart_receive_state_t; + +/*! @brief uart TX state structure. */ +typedef struct _hal_uart_send_state +{ + volatile uint8_t *buffer; + volatile uint32_t bufferLength; + volatile uint32_t bufferSofar; +} hal_uart_send_state_t; +#endif +/*! @brief uart state structure. */ +typedef struct _hal_uart_state +{ +#if (defined(UART_ADAPTER_NON_BLOCKING_MODE) && (UART_ADAPTER_NON_BLOCKING_MODE > 0U)) + hal_uart_transfer_callback_t callback; + void *callbackParam; +#if (defined(HAL_UART_TRANSFER_MODE) && (HAL_UART_TRANSFER_MODE > 0U)) + usart_handle_t hardwareHandle; +#endif + hal_uart_receive_state_t rx; + hal_uart_send_state_t tx; +#endif + uint8_t instance; +#if (defined(HAL_UART_DMA_ENABLE) && (HAL_UART_DMA_ENABLE > 0U)) + hal_uart_dma_state_t *dmaHandle; +#endif /* HAL_UART_DMA_ENABLE */ +#if (defined(HAL_UART_ADAPTER_LOWPOWER) && (HAL_UART_ADAPTER_LOWPOWER > 0U)) + hal_uart_config_t config; +#endif +} hal_uart_state_t; + +/******************************************************************************* + * Prototypes + ******************************************************************************/ + +/******************************************************************************* + * Variables + ******************************************************************************/ +static USART_Type *const s_UsartAdapterBase[] = USART_BASE_PTRS; + +#if (defined(UART_ADAPTER_NON_BLOCKING_MODE) && (UART_ADAPTER_NON_BLOCKING_MODE > 0U)) + +#if !(defined(HAL_UART_TRANSFER_MODE) && (HAL_UART_TRANSFER_MODE > 0U)) +/* Array of USART IRQ number. */ +static const IRQn_Type s_UsartIRQ[] = USART_IRQS; +#endif + +#endif + +/******************************************************************************* + * Code + ******************************************************************************/ + +#if ((defined(HAL_UART_TRANSFER_MODE) && (HAL_UART_TRANSFER_MODE > 0U)) || \ + (defined(HAL_UART_DMA_ENABLE) && (HAL_UART_DMA_ENABLE > 0U))) +static hal_uart_status_t HAL_UartGetStatus(status_t status) +{ + hal_uart_status_t uartStatus = kStatus_HAL_UartError; + switch (status) + { + case kStatus_Success: + uartStatus = kStatus_HAL_UartSuccess; + break; + case kStatus_USART_TxBusy: + uartStatus = kStatus_HAL_UartTxBusy; + break; + case kStatus_USART_RxBusy: + uartStatus = kStatus_HAL_UartRxBusy; + break; + case kStatus_USART_TxIdle: + uartStatus = kStatus_HAL_UartTxIdle; + break; + case kStatus_USART_RxIdle: + uartStatus = kStatus_HAL_UartRxIdle; + break; + case kStatus_USART_BaudrateNotSupport: + uartStatus = kStatus_HAL_UartBaudrateNotSupport; + break; + case kStatus_USART_NoiseError: + case kStatus_USART_FramingError: + case kStatus_USART_ParityError: + uartStatus = kStatus_HAL_UartProtocolError; + break; + default: + /* This comments for MISRA C-2012 Rule 16.4 */ + break; + } + return uartStatus; +} +#else +static hal_uart_status_t HAL_UartGetStatus(status_t status) +{ + if (kStatus_Success == status) + { + return kStatus_HAL_UartSuccess; + } + else + { + return kStatus_HAL_UartError; + } +} +#endif + +#if (defined(UART_ADAPTER_NON_BLOCKING_MODE) && (UART_ADAPTER_NON_BLOCKING_MODE > 0U)) + +#if (defined(HAL_UART_TRANSFER_MODE) && (HAL_UART_TRANSFER_MODE > 0U)) +static void HAL_UartCallback(USART_Type *base, usart_handle_t *handle, status_t status, void *callbackParam) +{ + hal_uart_state_t *uartHandle; + hal_uart_status_t uartStatus = HAL_UartGetStatus(status); + assert(callbackParam); + + uartHandle = (hal_uart_state_t *)callbackParam; + + if (kStatus_HAL_UartProtocolError == uartStatus) + { + if (0U != uartHandle->hardwareHandle.rxDataSize) + { + uartStatus = kStatus_HAL_UartError; + } + } + + if (NULL != uartHandle->callback) + { + uartHandle->callback(uartHandle, uartStatus, uartHandle->callbackParam); + } +} + +#else +static void HAL_UartInterruptHandle(USART_Type *base, void *handle) +{ + hal_uart_state_t *uartHandle = (hal_uart_state_t *)handle; + uint32_t status; + uint8_t instance; + + if (NULL == uartHandle) + { + return; + } + instance = uartHandle->instance; + + status = USART_GetStatusFlags(s_UsartAdapterBase[instance]); + + /* Receive data register full */ + if ((0U != (USART_FIFOSTAT_RXNOTEMPTY_MASK & status)) && + (0U != (USART_GetEnabledInterrupts(s_UsartAdapterBase[instance]) & USART_FIFOINTENSET_RXLVL_MASK))) + { + if (NULL != uartHandle->rx.buffer) + { + uartHandle->rx.buffer[uartHandle->rx.bufferSofar++] = USART_ReadByte(s_UsartAdapterBase[instance]); + if (uartHandle->rx.bufferSofar >= uartHandle->rx.bufferLength) + { + USART_DisableInterrupts(s_UsartAdapterBase[instance], + USART_FIFOINTENCLR_RXLVL_MASK | USART_FIFOINTENCLR_RXERR_MASK); + uartHandle->rx.buffer = NULL; + if (NULL != uartHandle->callback) + { + uartHandle->callback(uartHandle, kStatus_HAL_UartRxIdle, uartHandle->callbackParam); + } + } + } + } + + /* Send data register empty and the interrupt is enabled. */ + if ((0U != (USART_FIFOSTAT_TXNOTFULL_MASK & status)) && + (0U != (USART_GetEnabledInterrupts(s_UsartAdapterBase[instance]) & USART_FIFOINTENSET_TXLVL_MASK))) + { + if (NULL != uartHandle->tx.buffer) + { + USART_WriteByte(s_UsartAdapterBase[instance], uartHandle->tx.buffer[uartHandle->tx.bufferSofar++]); + if (uartHandle->tx.bufferSofar >= uartHandle->tx.bufferLength) + { + USART_DisableInterrupts(s_UsartAdapterBase[instance], USART_FIFOINTENCLR_TXLVL_MASK); + uartHandle->tx.buffer = NULL; + if (NULL != uartHandle->callback) + { + uartHandle->callback(uartHandle, kStatus_HAL_UartTxIdle, uartHandle->callbackParam); + } + } + } + } + +#if 1 + USART_ClearStatusFlags(s_UsartAdapterBase[instance], status); +#endif +} + +static void HAL_UartInterruptHandle_Wapper(void *base, void *handle) +{ + HAL_UartInterruptHandle((USART_Type *)base, handle); +} +#endif + +#endif + +static hal_uart_status_t HAL_UartInitCommon(hal_uart_handle_t handle, const hal_uart_config_t *config) +{ + usart_config_t usartConfig; + status_t status; + + assert(handle); + assert(config); + assert(config->instance < (sizeof(s_UsartAdapterBase) / sizeof(USART_Type *))); + assert(s_UsartAdapterBase[config->instance]); + assert(HAL_UART_HANDLE_SIZE >= sizeof(hal_uart_state_t)); + + USART_GetDefaultConfig(&usartConfig); + usartConfig.baudRate_Bps = config->baudRate_Bps; + + if ((0U != config->enableRxRTS) || (0U != config->enableTxCTS)) + { + usartConfig.enableHardwareFlowControl = true; + } + + if (kHAL_UartParityEven == config->parityMode) + { + usartConfig.parityMode = kUSART_ParityEven; + } + else if (kHAL_UartParityOdd == config->parityMode) + { + usartConfig.parityMode = kUSART_ParityOdd; + } + else + { + usartConfig.parityMode = kUSART_ParityDisabled; + } + + if (kHAL_UartTwoStopBit == config->stopBitCount) + { + usartConfig.stopBitCount = kUSART_TwoStopBit; + } + else + { + usartConfig.stopBitCount = kUSART_OneStopBit; + } + usartConfig.enableRx = (bool)config->enableRx; + usartConfig.enableTx = (bool)config->enableTx; + usartConfig.txWatermark = kUSART_TxFifo0; + usartConfig.rxWatermark = kUSART_RxFifo1; + + status = USART_Init(s_UsartAdapterBase[config->instance], &usartConfig, config->srcClock_Hz); + + if (kStatus_Success != status) + { + return HAL_UartGetStatus(status); + } + + return kStatus_HAL_UartSuccess; +} + +hal_uart_status_t HAL_UartInit(hal_uart_handle_t handle, const hal_uart_config_t *uart_config) +{ + hal_uart_state_t *uartHandle; + hal_uart_status_t status; + + /* Init serial port */ + status = HAL_UartInitCommon(handle, uart_config); + if (kStatus_HAL_UartSuccess != status) + { + return status; + } + + uartHandle = (hal_uart_state_t *)handle; + uartHandle->instance = uart_config->instance; +#if (defined(HAL_UART_DMA_ENABLE) && (HAL_UART_DMA_ENABLE > 0U)) + uartHandle->dmaHandle = NULL; +#endif /* HAL_UART_DMA_ENABLE */ +#if (defined(HAL_UART_ADAPTER_LOWPOWER) && (HAL_UART_ADAPTER_LOWPOWER > 0U)) + (void)memcpy(&uartHandle->config, uart_config, sizeof(hal_uart_config_t)); +#endif + +#if (defined(UART_ADAPTER_NON_BLOCKING_MODE) && (UART_ADAPTER_NON_BLOCKING_MODE > 0U)) + +#if (defined(HAL_UART_TRANSFER_MODE) && (HAL_UART_TRANSFER_MODE > 0U)) + USART_TransferCreateHandle(s_UsartAdapterBase[uart_config->instance], &uartHandle->hardwareHandle, + (usart_transfer_callback_t)HAL_UartCallback, handle); +#else + /* Enable interrupt in NVIC. */ + FLEXCOMM_SetIRQHandler(s_UsartAdapterBase[uart_config->instance], HAL_UartInterruptHandle_Wapper, handle); + NVIC_SetPriority((IRQn_Type)s_UsartIRQ[uart_config->instance], HAL_UART_ISR_PRIORITY); + (void)EnableIRQ(s_UsartIRQ[uart_config->instance]); +#endif + +#endif + + return kStatus_HAL_UartSuccess; +} + +hal_uart_status_t HAL_UartDeinit(hal_uart_handle_t handle) +{ + hal_uart_state_t *uartHandle; + + assert(handle); + + uartHandle = (hal_uart_state_t *)handle; + + USART_Deinit(s_UsartAdapterBase[uartHandle->instance]); + + return kStatus_HAL_UartSuccess; +} + +hal_uart_status_t HAL_UartReceiveBlocking(hal_uart_handle_t handle, uint8_t *data, size_t length) +{ + hal_uart_state_t *uartHandle; + status_t status; + assert(handle); + assert(data); + assert(length); + + uartHandle = (hal_uart_state_t *)handle; + +#if (defined(UART_ADAPTER_NON_BLOCKING_MODE) && (UART_ADAPTER_NON_BLOCKING_MODE > 0U)) + if (NULL != uartHandle->rx.buffer) + { + return kStatus_HAL_UartRxBusy; + } +#endif + + status = USART_ReadBlocking(s_UsartAdapterBase[uartHandle->instance], data, length); + + return HAL_UartGetStatus(status); +} + +hal_uart_status_t HAL_UartSendBlocking(hal_uart_handle_t handle, const uint8_t *data, size_t length) +{ + hal_uart_state_t *uartHandle; + assert(handle); + assert(data); + assert(length); + + uartHandle = (hal_uart_state_t *)handle; + +#if (defined(UART_ADAPTER_NON_BLOCKING_MODE) && (UART_ADAPTER_NON_BLOCKING_MODE > 0U)) + if (NULL != uartHandle->tx.buffer) + { + return kStatus_HAL_UartTxBusy; + } +#endif + + (void)USART_WriteBlocking(s_UsartAdapterBase[uartHandle->instance], data, length); + + return kStatus_HAL_UartSuccess; +} + +hal_uart_status_t HAL_UartEnterLowpower(hal_uart_handle_t handle) +{ + assert(handle); + + return kStatus_HAL_UartSuccess; +} + +hal_uart_status_t HAL_UartExitLowpower(hal_uart_handle_t handle) +{ +#if (defined(HAL_UART_ADAPTER_LOWPOWER) && (HAL_UART_ADAPTER_LOWPOWER > 0U)) + hal_uart_state_t *uartHandle; + assert(handle); + + uartHandle = (hal_uart_state_t *)handle; + + (void)HAL_UartInit(handle, &uartHandle->config); +#if (defined(UART_ADAPTER_NON_BLOCKING_MODE) && (UART_ADAPTER_NON_BLOCKING_MODE > 0U)) + USART_EnableInterrupts(s_UsartAdapterBase[uartHandle->instance], USART_FIFOINTENSET_RXLVL_MASK); +#endif +#endif + return kStatus_HAL_UartSuccess; +} + +#if (defined(UART_ADAPTER_NON_BLOCKING_MODE) && (UART_ADAPTER_NON_BLOCKING_MODE > 0U)) + +#if (defined(HAL_UART_TRANSFER_MODE) && (HAL_UART_TRANSFER_MODE > 0U)) + +hal_uart_status_t HAL_UartTransferInstallCallback(hal_uart_handle_t handle, + hal_uart_transfer_callback_t callback, + void *callbackParam) +{ + hal_uart_state_t *uartHandle; + + assert(handle); + assert(0U != HAL_UART_TRANSFER_MODE); + + uartHandle = (hal_uart_state_t *)handle; + + uartHandle->callbackParam = callbackParam; + uartHandle->callback = callback; + + return kStatus_HAL_UartSuccess; +} + +hal_uart_status_t HAL_UartTransferReceiveNonBlocking(hal_uart_handle_t handle, hal_uart_transfer_t *transfer) +{ + hal_uart_state_t *uartHandle; + status_t status; + assert(handle); + assert(transfer); + assert(0U != HAL_UART_TRANSFER_MODE); + + uartHandle = (hal_uart_state_t *)handle; + + status = USART_TransferReceiveNonBlocking(s_UsartAdapterBase[uartHandle->instance], &uartHandle->hardwareHandle, + (usart_transfer_t *)transfer, NULL); + + return HAL_UartGetStatus(status); +} + +hal_uart_status_t HAL_UartTransferSendNonBlocking(hal_uart_handle_t handle, hal_uart_transfer_t *transfer) +{ + hal_uart_state_t *uartHandle; + status_t status; + assert(handle); + assert(transfer); + assert(0U != HAL_UART_TRANSFER_MODE); + + uartHandle = (hal_uart_state_t *)handle; + + status = USART_TransferSendNonBlocking(s_UsartAdapterBase[uartHandle->instance], &uartHandle->hardwareHandle, + (usart_transfer_t *)transfer); + + return HAL_UartGetStatus(status); +} + +hal_uart_status_t HAL_UartTransferGetReceiveCount(hal_uart_handle_t handle, uint32_t *count) +{ + hal_uart_state_t *uartHandle; + status_t status; + assert(handle); + assert(count); + assert(0U != HAL_UART_TRANSFER_MODE); + + uartHandle = (hal_uart_state_t *)handle; + + status = + USART_TransferGetReceiveCount(s_UsartAdapterBase[uartHandle->instance], &uartHandle->hardwareHandle, count); + + return HAL_UartGetStatus(status); +} + +hal_uart_status_t HAL_UartTransferGetSendCount(hal_uart_handle_t handle, uint32_t *count) +{ + hal_uart_state_t *uartHandle; + status_t status; + assert(handle); + assert(count); + assert(0U != HAL_UART_TRANSFER_MODE); + + uartHandle = (hal_uart_state_t *)handle; + + status = USART_TransferGetSendCount(s_UsartAdapterBase[uartHandle->instance], &uartHandle->hardwareHandle, count); + + return HAL_UartGetStatus(status); +} + +hal_uart_status_t HAL_UartTransferAbortReceive(hal_uart_handle_t handle) +{ + hal_uart_state_t *uartHandle; + assert(handle); + assert(0U != HAL_UART_TRANSFER_MODE); + + uartHandle = (hal_uart_state_t *)handle; + + USART_TransferAbortReceive(s_UsartAdapterBase[uartHandle->instance], &uartHandle->hardwareHandle); + + return kStatus_HAL_UartSuccess; +} + +hal_uart_status_t HAL_UartTransferAbortSend(hal_uart_handle_t handle) +{ + hal_uart_state_t *uartHandle; + assert(handle); + assert(0U != HAL_UART_TRANSFER_MODE); + + uartHandle = (hal_uart_state_t *)handle; + + USART_TransferAbortSend(s_UsartAdapterBase[uartHandle->instance], &uartHandle->hardwareHandle); + + return kStatus_HAL_UartSuccess; +} + +#else + +/* None transactional API with non-blocking mode. */ +hal_uart_status_t HAL_UartInstallCallback(hal_uart_handle_t handle, + hal_uart_transfer_callback_t callback, + void *callbackParam) +{ + hal_uart_state_t *uartHandle; + + assert(handle); + assert(0U == HAL_UART_TRANSFER_MODE); + + uartHandle = (hal_uart_state_t *)handle; + + uartHandle->callbackParam = callbackParam; + uartHandle->callback = callback; + + return kStatus_HAL_UartSuccess; +} + +hal_uart_status_t HAL_UartReceiveNonBlocking(hal_uart_handle_t handle, uint8_t *data, size_t length) +{ + hal_uart_state_t *uartHandle; + assert(handle); + assert(data); + assert(length); + assert(0U == HAL_UART_TRANSFER_MODE); + + uartHandle = (hal_uart_state_t *)handle; + + if (NULL != uartHandle->rx.buffer) + { + return kStatus_HAL_UartRxBusy; + } + + uartHandle->rx.bufferLength = length; + uartHandle->rx.bufferSofar = 0; + uartHandle->rx.buffer = data; + USART_EnableInterrupts(s_UsartAdapterBase[uartHandle->instance], USART_FIFOINTENSET_RXLVL_MASK); + return kStatus_HAL_UartSuccess; +} + +hal_uart_status_t HAL_UartSendNonBlocking(hal_uart_handle_t handle, uint8_t *data, size_t length) +{ + hal_uart_state_t *uartHandle; + assert(handle); + assert(data); + assert(length); + assert(0U == HAL_UART_TRANSFER_MODE); + + uartHandle = (hal_uart_state_t *)handle; + + if (NULL != uartHandle->tx.buffer) + { + return kStatus_HAL_UartTxBusy; + } + uartHandle->tx.bufferLength = length; + uartHandle->tx.bufferSofar = 0; + uartHandle->tx.buffer = (volatile uint8_t *)data; + USART_EnableInterrupts(s_UsartAdapterBase[uartHandle->instance], USART_FIFOINTENSET_TXLVL_MASK); + return kStatus_HAL_UartSuccess; +} + +hal_uart_status_t HAL_UartGetReceiveCount(hal_uart_handle_t handle, uint32_t *reCount) +{ + hal_uart_state_t *uartHandle; + assert(handle); + assert(reCount); + assert(0U == HAL_UART_TRANSFER_MODE); + + uartHandle = (hal_uart_state_t *)handle; + + if (NULL != uartHandle->rx.buffer) + { + *reCount = uartHandle->rx.bufferSofar; + return kStatus_HAL_UartSuccess; + } + return kStatus_HAL_UartError; +} + +hal_uart_status_t HAL_UartGetSendCount(hal_uart_handle_t handle, uint32_t *seCount) +{ + hal_uart_state_t *uartHandle; + assert(handle); + assert(seCount); + assert(0U == HAL_UART_TRANSFER_MODE); + + uartHandle = (hal_uart_state_t *)handle; + + if (NULL != uartHandle->tx.buffer) + { + *seCount = uartHandle->tx.bufferSofar; + return kStatus_HAL_UartSuccess; + } + return kStatus_HAL_UartError; +} + +hal_uart_status_t HAL_UartAbortReceive(hal_uart_handle_t handle) +{ + hal_uart_state_t *uartHandle; + assert(handle); + assert(0U == HAL_UART_TRANSFER_MODE); + + uartHandle = (hal_uart_state_t *)handle; + + if (NULL != uartHandle->rx.buffer) + { + USART_DisableInterrupts(s_UsartAdapterBase[uartHandle->instance], + USART_FIFOINTENCLR_RXLVL_MASK | USART_FIFOINTENCLR_RXERR_MASK); + uartHandle->rx.buffer = NULL; + } + + return kStatus_HAL_UartSuccess; +} + +hal_uart_status_t HAL_UartAbortSend(hal_uart_handle_t handle) +{ + hal_uart_state_t *uartHandle; + assert(handle); + assert(0U == HAL_UART_TRANSFER_MODE); + + uartHandle = (hal_uart_state_t *)handle; + + if (NULL != uartHandle->tx.buffer) + { + USART_DisableInterrupts(s_UsartAdapterBase[uartHandle->instance], USART_FIFOINTENCLR_TXLVL_MASK); + uartHandle->tx.buffer = NULL; + } + + return kStatus_HAL_UartSuccess; +} + +#endif + +#if (defined(HAL_UART_TRANSFER_MODE) && (HAL_UART_TRANSFER_MODE > 0U)) + +void HAL_UartIsrFunction(hal_uart_handle_t handle) +{ + hal_uart_state_t *uartHandle; + assert(handle); + assert(0U != HAL_UART_TRANSFER_MODE); + + uartHandle = (hal_uart_state_t *)handle; + +#if 0 + DisableIRQ(s_UsartIRQ[uartHandle->instance]); +#endif + USART_TransferHandleIRQ(s_UsartAdapterBase[uartHandle->instance], &uartHandle->hardwareHandle); +#if 0 + NVIC_SetPriority((IRQn_Type)s_UsartIRQ[uartHandle->instance], HAL_UART_ISR_PRIORITY); + EnableIRQ(s_UsartIRQ[uartHandle->instance]); +#endif +} + +#else + +void HAL_UartIsrFunction(hal_uart_handle_t handle) +{ + hal_uart_state_t *uartHandle; + assert(handle); + assert(0U == HAL_UART_TRANSFER_MODE); + + uartHandle = (hal_uart_state_t *)handle; + +#if 0 + DisableIRQ(s_UsartIRQ[uartHandle->instance]); +#endif + HAL_UartInterruptHandle(s_UsartAdapterBase[uartHandle->instance], (void *)uartHandle); +#if 0 + NVIC_SetPriority((IRQn_Type)s_UsartIRQ[uartHandle->instance], HAL_UART_ISR_PRIORITY); + EnableIRQ(s_UsartIRQ[uartHandle->instance]); +#endif +} + +#endif + +#endif + +#if (defined(HAL_UART_DMA_ENABLE) && (HAL_UART_DMA_ENABLE > 0U)) +static void USART_DMACallbacks(USART_Type *base, usart_dma_handle_t *handle, status_t status, void *userData) +{ + hal_uart_dma_state_t *uartDmaHandle; + hal_uart_status_t uartStatus = HAL_UartGetStatus(status); + hal_dma_callback_msg_t msg; + assert(handle); + + uartDmaHandle = (hal_uart_dma_state_t *)userData; + + if (NULL != uartDmaHandle->dma_callback) + { + if (kStatus_HAL_UartTxIdle == uartStatus) + { + msg.status = kStatus_HAL_UartDmaTxIdle; + msg.data = uartDmaHandle->dma_tx.buffer; + msg.dataSize = uartDmaHandle->dma_tx.bufferLength; + uartDmaHandle->dma_tx.buffer = NULL; + } + else if (kStatus_HAL_UartRxIdle == uartStatus) + { + msg.status = kStatus_HAL_UartDmaRxIdle; + msg.data = uartDmaHandle->dma_rx.buffer; + msg.dataSize = uartDmaHandle->dma_rx.bufferLength; + uartDmaHandle->dma_rx.buffer = NULL; + } + + uartDmaHandle->dma_callback(uartDmaHandle, &msg, uartDmaHandle->dma_callback_param); + } +} + +static void TimeoutTimer_Callbcak(void *param) +{ + hal_uart_dma_list_t *uartDmaHandleList; + hal_uart_dma_state_t *uartDmaHandle; + hal_dma_callback_msg_t msg; + uint32_t newReceived = 0U; + + uartDmaHandleList = &s_dmaHandleList; + uartDmaHandle = uartDmaHandleList->dma_list; + + while (NULL != uartDmaHandle) + { + if ((NULL != uartDmaHandle->dma_rx.buffer) && (false == uartDmaHandle->dma_rx.receiveAll)) + { + /* HAL_UartDMAGetReceiveCount(uartDmaHandle, &msg.dataSize); */ + USART_TransferGetReceiveCountDMA(s_UsartAdapterBase[uartDmaHandle->instance], &uartDmaHandle->dmaHandle, + &msg.dataSize); + newReceived = msg.dataSize - uartDmaHandle->dma_rx.bufferSofar; + uartDmaHandle->dma_rx.bufferSofar = msg.dataSize; + + /* 1, If it is in idle state. */ + if ((0U == newReceived) && (0U < uartDmaHandle->dma_rx.bufferSofar)) + { + uartDmaHandle->dma_rx.timeout++; + if (uartDmaHandle->dma_rx.timeout >= HAL_UART_DMA_IDLELINE_TIMEOUT) + { + /* HAL_UartDMAAbortReceive(uartDmaHandle); */ + USART_TransferAbortReceiveDMA(s_UsartAdapterBase[uartDmaHandle->instance], + &uartDmaHandle->dmaHandle); + msg.data = uartDmaHandle->dma_rx.buffer; + msg.status = kStatus_HAL_UartDmaIdleline; + uartDmaHandle->dma_rx.buffer = NULL; + uartDmaHandle->dma_callback(uartDmaHandle, &msg, uartDmaHandle->dma_callback_param); + } + } + /* 2, If got new data again. */ + if ((0U < newReceived) && (0U < uartDmaHandle->dma_rx.bufferSofar)) + { + uartDmaHandle->dma_rx.timeout = 0U; + } + } + + uartDmaHandle = uartDmaHandle->next; + } +} + +hal_uart_dma_status_t HAL_UartDMAInit(hal_uart_handle_t handle, + hal_uart_dma_handle_t dmaHandle, + hal_uart_dma_config_t *dmaConfig) +{ + hal_uart_state_t *uartHandle; + hal_uart_dma_state_t *uartDmaHandle; + + assert(handle); + assert(dmaHandle); + + /* DMA init process. */ + uartHandle = (hal_uart_state_t *)handle; + uartDmaHandle = (hal_uart_dma_state_t *)dmaHandle; + + uartHandle->dmaHandle = uartDmaHandle; + + uartDmaHandle->instance = dmaConfig->uart_instance; + + DMA_Type *dmaBases[] = DMA_BASE_PTRS; + DMA_EnableChannel(dmaBases[dmaConfig->dma_instance], dmaConfig->tx_channel); + DMA_EnableChannel(dmaBases[dmaConfig->dma_instance], dmaConfig->rx_channel); + + DMA_CreateHandle(&uartDmaHandle->txDmaHandle, dmaBases[dmaConfig->dma_instance], dmaConfig->tx_channel); + DMA_CreateHandle(&uartDmaHandle->rxDmaHandle, dmaBases[dmaConfig->dma_instance], dmaConfig->rx_channel); + + /* Timeout timer init. */ + if (0U == s_dmaHandleList.activeCount) + { + s_dmaHandleList.dma_list = uartDmaHandle; + uartDmaHandle->next = NULL; + s_dmaHandleList.activeCount++; + + timer_status_t timerStatus; + timerStatus = TM_Open((timer_handle_t)s_dmaHandleList.timerManagerHandle); + assert(kStatus_TimerSuccess == timerStatus); + + timerStatus = + TM_InstallCallback((timer_handle_t)s_dmaHandleList.timerManagerHandle, TimeoutTimer_Callbcak, NULL); + assert(kStatus_TimerSuccess == timerStatus); + + (void)TM_Start((timer_handle_t)s_dmaHandleList.timerManagerHandle, (uint8_t)kTimerModeIntervalTimer, 1); + + (void)timerStatus; + } + else + { + uartDmaHandle->next = s_dmaHandleList.dma_list; + s_dmaHandleList.dma_list = uartDmaHandle; + } + + return kStatus_HAL_UartDmaSuccess; +} + +hal_uart_dma_status_t HAL_UartDMADeinit(hal_uart_handle_t handle) +{ + hal_uart_state_t *uartHandle; + hal_uart_dma_state_t *uartDmaHandle; + hal_uart_dma_state_t *prev; + hal_uart_dma_state_t *curr; + + assert(handle); + + uartHandle = (hal_uart_state_t *)handle; + uartDmaHandle = uartHandle->dmaHandle; + + uartHandle->dmaHandle = NULL; + + assert(uartDmaHandle); + + /* Abort rx/tx */ + /* Here we should not abort before create transfer handle. */ + if (NULL != uartDmaHandle->dmaHandle.txDmaHandle) + { + USART_TransferAbortSendDMA(s_UsartAdapterBase[uartDmaHandle->instance], &uartDmaHandle->dmaHandle); + } + if (NULL != uartDmaHandle->dmaHandle.rxDmaHandle) + { + USART_TransferAbortReceiveDMA(s_UsartAdapterBase[uartDmaHandle->instance], &uartDmaHandle->dmaHandle); + } + + /* Disable rx/tx channels */ + /* Here we should not disable before create transfer handle. */ + if (NULL != uartDmaHandle->dmaHandle.txDmaHandle) + { + DMA_DisableChannel(uartDmaHandle->txDmaHandle.base, uartDmaHandle->txDmaHandle.channel); + } + if (NULL != uartDmaHandle->dmaHandle.rxDmaHandle) + { + DMA_DisableChannel(uartDmaHandle->rxDmaHandle.base, uartDmaHandle->rxDmaHandle.channel); + } + + /* Remove handle from list */ + prev = NULL; + curr = s_dmaHandleList.dma_list; + while (curr != NULL) + { + if (curr == uartDmaHandle) + { + /* 1, if it is the first one */ + if (prev == NULL) + { + s_dmaHandleList.dma_list = curr->next; + } + /* 2, if it is the last one */ + else if (curr->next == NULL) + { + prev->next = NULL; + } + /* 3, if it is in the middle */ + else + { + prev->next = curr->next; + } + break; + } + + prev = curr; + curr = curr->next; + } + + /* Reset all handle data. */ + (void)memset(uartDmaHandle, 0, sizeof(hal_uart_dma_state_t)); + + s_dmaHandleList.activeCount = (s_dmaHandleList.activeCount > 0) ? (s_dmaHandleList.activeCount - 1) : 0; + if (0 == s_dmaHandleList.activeCount) + { + (void)TM_Close((timer_handle_t)s_dmaHandleList.timerManagerHandle); + } + + return kStatus_HAL_UartDmaSuccess; +} + +hal_uart_dma_status_t HAL_UartDMATransferInstallCallback(hal_uart_handle_t handle, + hal_uart_dma_transfer_callback_t callback, + void *callbackParam) +{ + hal_uart_state_t *uartHandle; + hal_uart_dma_state_t *uartDmaHandle; + + assert(handle); + + uartHandle = (hal_uart_state_t *)handle; + uartDmaHandle = uartHandle->dmaHandle; + + assert(uartDmaHandle); + + uartDmaHandle->dma_callback = callback; + uartDmaHandle->dma_callback_param = callbackParam; + + USART_TransferCreateHandleDMA(s_UsartAdapterBase[uartDmaHandle->instance], &uartDmaHandle->dmaHandle, + USART_DMACallbacks, uartDmaHandle, &uartDmaHandle->txDmaHandle, + &uartDmaHandle->rxDmaHandle); + + return kStatus_HAL_UartDmaSuccess; +} + +hal_uart_dma_status_t HAL_UartDMATransferReceive(hal_uart_handle_t handle, + uint8_t *data, + size_t length, + bool receiveAll) +{ + hal_uart_state_t *uartHandle; + hal_uart_dma_state_t *uartDmaHandle; + usart_transfer_t xfer; + + assert(handle); + assert(data); + + uartHandle = (hal_uart_state_t *)handle; + uartDmaHandle = uartHandle->dmaHandle; + + assert(uartDmaHandle); + + if (NULL == uartDmaHandle->dma_rx.buffer) + { + uartDmaHandle->dma_rx.buffer = data; + uartDmaHandle->dma_rx.bufferLength = length; + uartDmaHandle->dma_rx.timeout = 0U; + uartDmaHandle->dma_rx.receiveAll = receiveAll; + } + else + { + /* Already in reading process. */ + return kStatus_HAL_UartDmaRxBusy; + } + + xfer.data = data; + xfer.dataSize = length; + + USART_TransferReceiveDMA(s_UsartAdapterBase[uartDmaHandle->instance], &uartDmaHandle->dmaHandle, &xfer); + + return kStatus_HAL_UartDmaSuccess; +} + +hal_uart_dma_status_t HAL_UartDMATransferSend(hal_uart_handle_t handle, uint8_t *data, size_t length) +{ + hal_uart_state_t *uartHandle; + hal_uart_dma_state_t *uartDmaHandle; + usart_transfer_t xfer; + + assert(handle); + assert(data); + + uartHandle = (hal_uart_state_t *)handle; + uartDmaHandle = uartHandle->dmaHandle; + + assert(uartDmaHandle); + + if (NULL == uartDmaHandle->dma_tx.buffer) + { + uartDmaHandle->dma_tx.buffer = data; + uartDmaHandle->dma_tx.bufferLength = length; + uartDmaHandle->dma_tx.bufferSofar = 0U; + uartDmaHandle->dma_tx.timeout = 0U; + } + else + { + /* Already in writing process. */ + return kStatus_HAL_UartDmaTxBusy; + } + + xfer.data = data; + xfer.dataSize = length; + + USART_TransferSendDMA(s_UsartAdapterBase[uartDmaHandle->instance], &uartDmaHandle->dmaHandle, &xfer); + + return kStatus_HAL_UartDmaSuccess; +} + +hal_uart_dma_status_t HAL_UartDMAGetReceiveCount(hal_uart_handle_t handle, uint32_t *reCount) +{ + hal_uart_state_t *uartHandle; + hal_uart_dma_state_t *uartDmaHandle; + + assert(handle); + + uartHandle = (hal_uart_state_t *)handle; + uartDmaHandle = uartHandle->dmaHandle; + + assert(uartDmaHandle); + + if (kStatus_Success != USART_TransferGetReceiveCountDMA(s_UsartAdapterBase[uartDmaHandle->instance], + &uartDmaHandle->dmaHandle, reCount)) + { + return kStatus_HAL_UartDmaError; + } + + return kStatus_HAL_UartDmaSuccess; +} + +hal_uart_dma_status_t HAL_UartDMAGetSendCount(hal_uart_handle_t handle, uint32_t *seCount) +{ + /* No get send count API */ + return kStatus_HAL_UartDmaError; +} + +hal_uart_dma_status_t HAL_UartDMAAbortReceive(hal_uart_handle_t handle) +{ + hal_uart_state_t *uartHandle; + hal_uart_dma_state_t *uartDmaHandle; + + assert(handle); + + uartHandle = (hal_uart_state_t *)handle; + uartDmaHandle = uartHandle->dmaHandle; + + assert(uartDmaHandle); + + USART_TransferAbortReceiveDMA(s_UsartAdapterBase[uartDmaHandle->instance], &uartDmaHandle->dmaHandle); + + return kStatus_HAL_UartDmaSuccess; +} + +hal_uart_dma_status_t HAL_UartDMAAbortSend(hal_uart_handle_t handle) +{ + hal_uart_state_t *uartHandle; + hal_uart_dma_state_t *uartDmaHandle; + + assert(handle); + + uartHandle = (hal_uart_state_t *)handle; + uartDmaHandle = uartHandle->dmaHandle; + + assert(uartDmaHandle); + + USART_TransferAbortSendDMA(s_UsartAdapterBase[uartDmaHandle->instance], &uartDmaHandle->dmaHandle); + + return kStatus_HAL_UartDmaSuccess; +} +#endif /* HAL_UART_DMA_ENABLE */ diff --git a/drivers/Src/fsl_assert.c b/drivers/Src/fsl_assert.c new file mode 100644 index 0000000..cf73a5f --- /dev/null +++ b/drivers/Src/fsl_assert.c @@ -0,0 +1,88 @@ +/* + * Copyright (c) 2015-2016, Freescale Semiconductor, Inc. + * Copyright 2016-2017, 2022-2023 NXP + * All rights reserved. + * + * + * SPDX-License-Identifier: BSD-3-Clause + */ + +#include "fsl_common.h" +#include "fsl_assert.h" +#include "fsl_debug_console.h" + +/* User can implement its own asser handler (dump logs, registers, etc) by reimplementing the function fsl_assert_hook() */ +__attribute__ ((weak)) int fsl_assert_hook(const char *failedExpr, const char *file, int line) +{ + (void)failedExpr; + (void)file; + (void)line; + + return 0; +} + +#ifndef NDEBUG +#if (defined(__CC_ARM)) || (defined(__ARMCC_VERSION)) || (defined(__ICCARM__)) +void __aeabi_assert(const char *failedExpr, const char *file, int line) +{ +#if SDK_DEBUGCONSOLE == DEBUGCONSOLE_DISABLE + PRINTF("ASSERT ERROR \" %s \": file \"%s\" Line \"%d\" \n", failedExpr, file, line); +#else + (void)PRINTF("ASSERT ERROR \" %s \": file \"%s\" Line \"%d\" \n", failedExpr, file, line); +#endif + + (void)fsl_assert_hook(failedExpr, file, line); + + for (;;) + { + __BKPT(0); + } +} +#elif (defined(__GNUC__)) +#if defined(__REDLIB__) +void __assertion_failed(char *failedExpr) +{ + const char *file = NULL; + int line = -1; + + (void)PRINTF("ASSERT ERROR \" %s \n", failedExpr); + + (void)fsl_assert_hook(failedExpr, file, line); + + for (;;) + { + __BKPT(0); + } +} +#else +void __assert_func(const char *file, int line, const char *func, const char *failedExpr) +{ + (void)PRINTF("ASSERT ERROR \" %s \": file \"%s\" Line \"%d\" function name \"%s\" \n", failedExpr, file, line, + func); + + (void)fsl_assert_hook(failedExpr, file, line); + + for (;;) + { + __BKPT(0); + } +} +#endif /* defined(__REDLIB__) */ +#else /* (defined(__CC_ARM) || (defined(__ICCARM__)) || (defined(__ARMCC_VERSION)) */ + +#if (defined(__DSC__) && defined(__CW__)) + +void __msl_assertion_failed(char const *failedExpr, char const *file, char const *func, int line) +{ + PRINTF("\r\nASSERT ERROR\r\n"); + PRINTF(" File : %s\r\n", file); + PRINTF(" Function : %s\r\n", func); /*compiler not support func name yet*/ + PRINTF(" Line : %u\r\n", (uint32_t)line); + PRINTF(" failedExpr: %s\r\n", failedExpr); + asm(DEBUGHLT); +} + +#endif /* (defined(__DSC__) && defined (__CW__)) */ + +#endif /* (defined(__CC_ARM) || (defined(__ICCARM__)) || (defined(__ARMCC_VERSION)) */ +#endif /* NDEBUG */ diff --git a/drivers/Src/fsl_clock.c b/drivers/Src/fsl_clock.c new file mode 100644 index 0000000..8a97b64 --- /dev/null +++ b/drivers/Src/fsl_clock.c @@ -0,0 +1,2137 @@ +/* + * Copyright 2017 - 2021 , NXP + * All rights reserved. + * + * SPDX-License-Identifier: BSD-3-Clause + */ + +#include "fsl_clock.h" +#include "fsl_power.h" +/******************************************************************************* + * Definitions + ******************************************************************************/ +/* Component ID definition, used by tools. */ +#ifndef FSL_COMPONENT_ID +#define FSL_COMPONENT_ID "platform.drivers.clock" +#endif +#define NVALMAX (0x100U) +#define PVALMAX (0x20U) +#define MVALMAX (0x10000U) + +#define PLL_MAX_N_DIV 0x100U + +/*-------------------------------------------------------------------------- +!!! If required these #defines can be moved to chip library file +----------------------------------------------------------------------------*/ + +#define PLL_SSCG1_MDEC_VAL_P (10U) /* MDEC is in bits 25 downto 10 */ +#define PLL_SSCG1_MDEC_VAL_M (0xFFFFULL << PLL_SSCG1_MDEC_VAL_P) +#define PLL_NDEC_VAL_P (0U) /* NDEC is in bits 9:0 */ +#define PLL_NDEC_VAL_M (0xFFUL << PLL_NDEC_VAL_P) +#define PLL_PDEC_VAL_P (0U) /*!< PDEC is in bits 6:0 */ +#define PLL_PDEC_VAL_M (0x1FUL << PLL_PDEC_VAL_P) + +#define PLL_MIN_CCO_FREQ_MHZ (275000000U) +#define PLL_MAX_CCO_FREQ_MHZ (550000000U) +#define PLL_LOWER_IN_LIMIT (2000U) /*!< Minimum PLL input rate */ +#define PLL_HIGHER_IN_LIMIT (150000000U) /*!< Maximum PLL input rate */ +#define PLL_MIN_IN_SSMODE (3000000U) +#define PLL_MAX_IN_SSMODE \ + (100000000U) /*!< Not find the value in UM, Just use the maximum frequency which device support */ + +/* PLL NDEC reg */ +#define PLL_NDEC_VAL_SET(value) (((unsigned long)(value) << PLL_NDEC_VAL_P) & PLL_NDEC_VAL_M) +/* PLL PDEC reg */ +#define PLL_PDEC_VAL_SET(value) (((unsigned long)(value) << PLL_PDEC_VAL_P) & PLL_PDEC_VAL_M) +/* SSCG control1 */ +#define PLL_SSCG1_MDEC_VAL_SET(value) (((uint64_t)(value) << PLL_SSCG1_MDEC_VAL_P) & PLL_SSCG1_MDEC_VAL_M) + +/* PLL0 SSCG control1 */ +#define PLL0_SSCG_MD_FRACT_P 0U +#define PLL0_SSCG_MD_INT_P 25U +#define PLL0_SSCG_MD_FRACT_M (0x1FFFFFFUL << PLL0_SSCG_MD_FRACT_P) +#define PLL0_SSCG_MD_INT_M ((uint64_t)0xFFUL << PLL0_SSCG_MD_INT_P) + +#define PLL0_SSCG_MD_FRACT_SET(value) (((uint64_t)(value) << PLL0_SSCG_MD_FRACT_P) & PLL0_SSCG_MD_FRACT_M) +#define PLL0_SSCG_MD_INT_SET(value) (((uint64_t)(value) << PLL0_SSCG_MD_INT_P) & PLL0_SSCG_MD_INT_M) + +/* Saved value of PLL output rate, computed whenever needed to save run-time + computation on each call to retrive the PLL rate. */ +static uint32_t s_Pll0_Freq; +static uint32_t s_Pll1_Freq; + +/** External clock rate on the CLKIN pin in Hz. If not used, + set this to 0. Otherwise, set it to the exact rate in Hz this pin is + being driven at. */ +static uint32_t s_Ext_Clk_Freq = 16000000U; +static uint32_t s_I2S_Mclk_Freq = 0U; +static uint32_t s_PLU_ClkIn_Freq = 0U; + +/******************************************************************************* + * Variables + ******************************************************************************/ + +/******************************************************************************* + * Prototypes + ******************************************************************************/ +/* Find SELP, SELI, and SELR values for raw M value, max M = MVALMAX */ +static void pllFindSel(uint32_t M, uint32_t *pSelP, uint32_t *pSelI, uint32_t *pSelR); +/* Get predivider (N) from PLL0 NDEC setting */ +static uint32_t findPll0PreDiv(void); +/* Get predivider (N) from PLL1 NDEC setting */ +static uint32_t findPll1PreDiv(void); +/* Get postdivider (P) from PLL0 PDEC setting */ +static uint32_t findPll0PostDiv(void); +/* Get multiplier (M) from PLL0 MDEC and SSCG settings */ +static float findPll0MMult(void); +/* Get the greatest common divisor */ +static uint32_t FindGreatestCommonDivisor(uint32_t m, uint32_t n); +/* Set PLL output based on desired output rate */ +static pll_error_t CLOCK_GetPll0Config(uint32_t finHz, uint32_t foutHz, pll_setup_t *pSetup, bool useSS); +/* Update local PLL rate variable */ +static void CLOCK_GetPLL0OutFromSetupUpdate(pll_setup_t *pSetup); + +/******************************************************************************* + * Code + ******************************************************************************/ + +/* Clock Selection for IP */ +/** + * brief Configure the clock selection muxes. + * param connection : Clock to be configured. + * return Nothing + */ +void CLOCK_AttachClk(clock_attach_id_t connection) +{ + uint8_t mux; + uint8_t sel; + uint16_t item; + uint32_t tmp32 = (uint32_t)connection; + uint32_t i; + volatile uint32_t *pClkSel; + + pClkSel = &(SYSCON->SYSTICKCLKSELX[0]); + + if (kNONE_to_NONE != connection) + { + for (i = 0U; i < 2U; i++) + { + if (tmp32 == 0U) + { + break; + } + item = (uint16_t)GET_ID_ITEM(tmp32); + if (item != 0U) + { + mux = GET_ID_ITEM_MUX(item); + sel = GET_ID_ITEM_SEL(item); + if (mux == CM_RTCOSC32KCLKSEL) + { + PMC->RTCOSC32K = (PMC->RTCOSC32K & ~PMC_RTCOSC32K_SEL_MASK) | PMC_RTCOSC32K_SEL(sel); + } + else + { + pClkSel[mux] = sel; + } + } + tmp32 = GET_ID_NEXT_ITEM(tmp32); /* pick up next descriptor */ + } + } +} + +/* Return the actual clock attach id */ +/** + * brief Get the actual clock attach id. + * This fuction uses the offset in input attach id, then it reads the actual source value in + * the register and combine the offset to obtain an actual attach id. + * param attachId : Clock attach id to get. + * return Clock source value. + */ +clock_attach_id_t CLOCK_GetClockAttachId(clock_attach_id_t attachId) +{ + uint8_t mux; + uint8_t actualSel; + uint32_t tmp32 = (uint32_t)attachId; + uint32_t i; + uint32_t actualAttachId = 0U; + uint32_t selector = GET_ID_SELECTOR(tmp32); + volatile uint32_t *pClkSel; + + pClkSel = &(SYSCON->SYSTICKCLKSELX[0]); + + if (kNONE_to_NONE == attachId) + { + return kNONE_to_NONE; + } + + for (i = 0U; i < 2U; i++) + { + mux = GET_ID_ITEM_MUX(tmp32); + if (tmp32 != 0UL) + { + if (mux == CM_RTCOSC32KCLKSEL) + { + actualSel = (uint8_t)(PMC->RTCOSC32K); + } + else + { + actualSel = (uint8_t)(pClkSel[mux]); + } + + /* Consider the combination of two registers */ + actualAttachId |= CLK_ATTACH_ID(mux, actualSel, i); + } + tmp32 = GET_ID_NEXT_ITEM(tmp32); /*!< pick up next descriptor */ + } + + actualAttachId |= selector; + + return (clock_attach_id_t)actualAttachId; +} + +/* Set IP Clock Divider */ +/** + * brief Setup peripheral clock dividers. + * param div_name : Clock divider name + * param divided_by_value: Value to be divided + * param reset : Whether to reset the divider counter. + * return Nothing + */ +void CLOCK_SetClkDiv(clock_div_name_t div_name, uint32_t divided_by_value, bool reset) +{ + volatile uint32_t *pClkDiv; + + pClkDiv = &(SYSCON->SYSTICKCLKDIV0); + if ((div_name >= kCLOCK_DivFlexFrg0) && (div_name <= kCLOCK_DivFlexFrg7)) + { + /*!< Flexcomm Interface function clock = (clock selected via FCCLKSEL) / (1+ MULT /DIV), DIV = 0xFF */ + ((volatile uint32_t *)pClkDiv)[(uint8_t)div_name] = + SYSCON_FLEXFRG0CTRL_DIV_MASK | SYSCON_FLEXFRG0CTRL_MULT(divided_by_value); + } + else + { + if (reset) + { + ((volatile uint32_t *)pClkDiv)[(uint32_t)div_name] = 1UL << 29U; + } + if (divided_by_value == 0U) /*!< halt */ + { + ((volatile uint32_t *)pClkDiv)[(uint32_t)div_name] = 1UL << 30U; + } + else + { + ((volatile uint32_t *)pClkDiv)[(uint32_t)div_name] = (divided_by_value - 1U); + } + } +} + +/* Set RTC 1KHz Clock Divider */ +/** + * brief Setup rtc 1khz clock divider. + * param divided_by_value: Value to be divided + * return Nothing + */ +void CLOCK_SetRtc1khzClkDiv(uint32_t divided_by_value) +{ + PMC->RTCOSC32K |= (((divided_by_value - 28U) << PMC_RTCOSC32K_CLK1KHZDIV_SHIFT) | PMC_RTCOSC32K_CLK1KHZDIV_MASK); +} + +/* Set RTC 1KHz Clock Divider */ +/** + * brief Setup rtc 1hz clock divider. + * param divided_by_value: Value to be divided + * return Nothing + */ +void CLOCK_SetRtc1hzClkDiv(uint32_t divided_by_value) +{ + if (divided_by_value == 0U) /*!< halt */ + { + PMC->RTCOSC32K |= (1UL << PMC_RTCOSC32K_CLK1HZDIVHALT_SHIFT); + } + else + { + PMC->RTCOSC32K |= + (((divided_by_value - 31744U) << PMC_RTCOSC32K_CLK1HZDIV_SHIFT) | PMC_RTCOSC32K_CLK1HZDIV_MASK); + } +} + +/* Set FRO Clocking */ +/** + * brief Initialize the Core clock to given frequency (12, 48 or 96 MHz). + * Turns on FRO and uses default CCO, if freq is 12000000, then high speed output is off, else high speed output is + * enabled. + * param iFreq : Desired frequency (must be one of #CLK_FRO_12MHZ or #CLK_FRO_48MHZ or #CLK_FRO_96MHZ) + * return returns success or fail status. + */ +status_t CLOCK_SetupFROClocking(uint32_t iFreq) +{ + if ((iFreq != 12000000U) && (iFreq != 48000000U) && (iFreq != 96000000U)) + { + return kStatus_Fail; + } + /* Enable Analog Control module */ + SYSCON->PRESETCTRLCLR[2] = (1UL << SYSCON_PRESETCTRL2_ANALOG_CTRL_RST_SHIFT); + SYSCON->AHBCLKCTRLSET[2] = SYSCON_AHBCLKCTRL2_ANALOG_CTRL_MASK; + /* Power up the FRO192M */ + POWER_DisablePD(kPDRUNCFG_PD_FRO192M); + + if (iFreq == 96000000U) + { + ANACTRL->FRO192M_CTRL |= ANACTRL_FRO192M_CTRL_ENA_96MHZCLK(1); + } + /* always enable + else if (iFreq == 48000000U) + { + ANACTRL->FRO192M_CTRL |= ANACTRL_FRO192M_CTRL_ENA_48MHZCLK(1); + }*/ + else + { + ANACTRL->FRO192M_CTRL |= ANACTRL_FRO192M_CTRL_ENA_12MHZCLK(1); + } + return kStatus_Success; +} + +/* Set the FLASH wait states for the passed frequency */ +/** + * brief Set the flash wait states for the input freuqency. + * param iFreq: Input frequency + * return Nothing + */ +void CLOCK_SetFLASHAccessCyclesForFreq(uint32_t iFreq) +{ + uint32_t num_wait_states; /* Flash Controller & FMC internal number of Wait States (minus 1) */ + uint32_t prefetch_enable_mask = SYSCON->FMCCR & SYSCON_FMCCR_PREFEN_MASK; + + if (iFreq <= 11000000UL) + { + /* [0 - 11 MHz] */ + num_wait_states = 0UL; + } + else if (iFreq <= 22000000UL) + { + /* [11 MHz - 22 MHz] */ + num_wait_states = 1UL; + } + else if (iFreq <= 33000000UL) + { + /* [22 MHz - 33 MHz] */ + num_wait_states = 2UL; + } + else if (iFreq <= 44000000UL) + { + /* [33 MHz - 44 MHz] */ + num_wait_states = 3UL; + } + else if (iFreq <= 55000000UL) + { + /* [44 MHz - 55 MHz] */ + num_wait_states = 4UL; + } + else if (iFreq <= 66000000UL) + { + /* [55 MHz - 662 MHz] */ + num_wait_states = 5UL; + } + else if (iFreq <= 77000000UL) + { + /* [66 MHz - 77 MHz] */ + num_wait_states = 6UL; + } + else if (iFreq <= 88000000UL) + { + /* [77 MHz - 88 MHz] */ + num_wait_states = 7UL; + } + else if (iFreq <= 100000000UL) + { + /* [88 MHz - 100 MHz] */ + num_wait_states = 8UL; + } + else if (iFreq <= 115000000UL) + { + /* [100 MHz - 115 MHz] */ + num_wait_states = 9UL; + } + else if (iFreq <= 130000000UL) + { + /* [115 MHz - 130 MHz] */ + num_wait_states = 10UL; + } + else if (iFreq <= 150000000UL) + { + /* [130 MHz - 150 MHz] */ + num_wait_states = 11UL; + } + else + { + /* Above 150 MHz */ + num_wait_states = 12UL; + } + + /*The prefetch bit must be disabled before any flash commands*/ + SYSCON->FMCCR &= ~SYSCON_FMCCR_PREFEN_MASK; + + FLASH->INT_CLR_STATUS = 0x1FUL; /* Clear all status flags */ + + FLASH->DATAW[0] = (FLASH->DATAW[0] & 0xFFFFFFF0UL) | + (num_wait_states & (SYSCON_FMCCR_FLASHTIM_MASK >> SYSCON_FMCCR_FLASHTIM_SHIFT)); + + FLASH->CMD = 0x2; /* CMD_SET_READ_MODE */ + + /* Wait until the cmd is completed (without error) */ + while (0UL == (FLASH->INT_STATUS & FLASH_INT_STATUS_DONE_MASK)) + { + ; + } + + /* Adjust FMC waiting time cycles (num_wait_states) */ + SYSCON->FMCCR = (SYSCON->FMCCR & ~SYSCON_FMCCR_FLASHTIM_MASK) | + ((num_wait_states << SYSCON_FMCCR_FLASHTIM_SHIFT) & SYSCON_FMCCR_FLASHTIM_MASK); + + /* restore prefetch enable */ + SYSCON->FMCCR |= prefetch_enable_mask; +} + +/* Set EXT OSC Clk */ +/** + * brief Initialize the external osc clock to given frequency. + * Crystal oscillator with an operating frequency of 12 MHz to 32 MHz. + * Option for external clock input (bypass mode) for clock frequencies of up to 25 MHz. + * param iFreq : Desired frequency (must be equal to exact rate in Hz) + * return returns success or fail status. + */ +status_t CLOCK_SetupExtClocking(uint32_t iFreq) +{ + if (iFreq > 32000000U) + { + return kStatus_Fail; + } + /* Turn on power for crystal 32 MHz */ + POWER_DisablePD(kPDRUNCFG_PD_XTAL32M); + POWER_DisablePD(kPDRUNCFG_PD_LDOXO32M); + /* Enable clock_in clock for clock module. */ + SYSCON->CLOCK_CTRL |= SYSCON_CLOCK_CTRL_CLKIN_ENA_MASK; + + /* Wait for external osc clock to be valid. */ + while((ANACTRL->XO32M_STATUS & ANACTRL_XO32M_STATUS_XO_READY_MASK) == 0U) + { + } + + s_Ext_Clk_Freq = iFreq; + return kStatus_Success; +} + +/* Set I2S MCLK Clk */ +/** + * brief Initialize the I2S MCLK clock to given frequency. + * param iFreq : Desired frequency (must be equal to exact rate in Hz) + * return returns success or fail status. + */ +status_t CLOCK_SetupI2SMClkClocking(uint32_t iFreq) +{ + s_I2S_Mclk_Freq = iFreq; + return kStatus_Success; +} + +/* Set PLU CLKIN Clk */ +/** + * brief Initialize the PLU CLKIN clock to given frequency. + * param iFreq : Desired frequency (must be equal to exact rate in Hz) + * return returns success or fail status. + */ +status_t CLOCK_SetupPLUClkInClocking(uint32_t iFreq) +{ + s_PLU_ClkIn_Freq = iFreq; + return kStatus_Success; +} + +/* Get CLOCK OUT Clk */ +/*! brief Return Frequency of ClockOut + * return Frequency of ClockOut + */ +uint32_t CLOCK_GetClockOutClkFreq(void) +{ + uint32_t freq = 0U; + + switch (SYSCON->CLKOUTSEL) + { + case 0U: + freq = CLOCK_GetCoreSysClkFreq(); + break; + + case 1U: + freq = CLOCK_GetPll0OutFreq(); + break; + + case 2U: + freq = CLOCK_GetExtClkFreq(); + break; + + case 3U: + freq = CLOCK_GetFroHfFreq(); + break; + + case 4U: + freq = CLOCK_GetFro1MFreq(); + break; + + case 5U: + freq = CLOCK_GetPll1OutFreq(); + break; + + case 6U: + freq = CLOCK_GetOsc32KFreq(); + break; + + case 7U: + freq = 0U; + break; + + default: + assert(false); + break; + } + return freq / ((SYSCON->CLKOUTDIV & 0xffU) + 1U); +} + +/* Get ADC Clk */ +/*! brief Return Frequency of Adc Clock + * return Frequency of Adc. + */ +uint32_t CLOCK_GetAdcClkFreq(void) +{ + uint32_t freq = 0U; + + switch (SYSCON->ADCCLKSEL) + { + case 0U: + freq = CLOCK_GetCoreSysClkFreq(); + break; + case 1U: + freq = CLOCK_GetPll0OutFreq(); + break; + case 2U: + freq = CLOCK_GetFroHfFreq(); + break; + case 7U: + freq = 0U; + break; + + default: + assert(false); + break; + } + + return freq / ((SYSCON->ADCCLKDIV & SYSCON_ADCCLKDIV_DIV_MASK) + 1U); +} + +/* Get USB0 Clk */ +/*! brief Return Frequency of Usb0 Clock + * return Frequency of Usb0 Clock. + */ +uint32_t CLOCK_GetUsb0ClkFreq(void) +{ + uint32_t freq = 0U; + + switch (SYSCON->USB0CLKSEL) + { + case 0U: + freq = CLOCK_GetCoreSysClkFreq(); + break; + case 1U: + freq = CLOCK_GetPll0OutFreq(); + break; + case 3U: + freq = CLOCK_GetFroHfFreq(); + break; + case 5U: + freq = CLOCK_GetPll1OutFreq(); + break; + case 7U: + freq = 0U; + break; + + default: + assert(false); + break; + } + + return freq / ((SYSCON->USB0CLKDIV & 0xffU) + 1U); +} + +/* Get USB1 Clk */ +/*! brief Return Frequency of Usb1 Clock + * return Frequency of Usb1 Clock. + */ +uint32_t CLOCK_GetUsb1ClkFreq(void) +{ + return ((ANACTRL->XO32M_CTRL & ANACTRL_XO32M_CTRL_ENABLE_PLL_USB_OUT_MASK) != 0UL) ? s_Ext_Clk_Freq : 0U; +} + +/* Get MCLK Clk */ +/*! brief Return Frequency of MClk Clock + * return Frequency of MClk Clock. + */ +uint32_t CLOCK_GetMclkClkFreq(void) +{ + uint32_t freq = 0U; + + switch (SYSCON->MCLKCLKSEL) + { + case 0U: + freq = CLOCK_GetFroHfFreq(); + break; + case 1U: + freq = CLOCK_GetPll0OutFreq(); + break; + case 7U: + freq = 0U; + break; + + default: + assert(false); + break; + } + + return freq / ((SYSCON->MCLKDIV & 0xffU) + 1U); +} + +/* Get SCTIMER Clk */ +/*! brief Return Frequency of SCTimer Clock + * return Frequency of SCTimer Clock. + */ +uint32_t CLOCK_GetSctClkFreq(void) +{ + uint32_t freq = 0U; + + switch (SYSCON->SCTCLKSEL) + { + case 0U: + freq = CLOCK_GetCoreSysClkFreq(); + break; + case 1U: + freq = CLOCK_GetPll0OutFreq(); + break; + case 2U: + freq = CLOCK_GetExtClkFreq(); + break; + case 3U: + freq = CLOCK_GetFroHfFreq(); + break; + case 5U: + freq = CLOCK_GetI2SMClkFreq(); + break; + case 7U: + freq = 0U; + break; + + default: + assert(false); + break; + } + + return freq / ((SYSCON->SCTCLKDIV & 0xffU) + 1U); +} + +/* Get SDIO Clk */ +/*! brief Return Frequency of SDIO Clock + * return Frequency of SDIO Clock. + */ +uint32_t CLOCK_GetSdioClkFreq(void) +{ + uint32_t freq = 0U; + + switch (SYSCON->SDIOCLKSEL) + { + case 0U: + freq = CLOCK_GetCoreSysClkFreq(); + break; + case 1U: + freq = CLOCK_GetPll0OutFreq(); + break; + case 3U: + freq = CLOCK_GetFroHfFreq(); + break; + case 5U: + freq = CLOCK_GetPll1OutFreq(); + break; + case 7U: + freq = 0U; + break; + default: + assert(false); + break; + } + + return freq / ((SYSCON->SDIOCLKDIV & 0xffU) + 1U); +} + +/* Get FRO 12M Clk */ +/*! brief Return Frequency of FRO 12MHz + * return Frequency of FRO 12MHz + */ +uint32_t CLOCK_GetFro12MFreq(void) +{ + return ((ANACTRL->FRO192M_CTRL & ANACTRL_FRO192M_CTRL_ENA_12MHZCLK_MASK) != 0UL) ? 12000000U : 0U; +} + +/* Get FRO 1M Clk */ +/*! brief Return Frequency of FRO 1MHz + * return Frequency of FRO 1MHz + */ +uint32_t CLOCK_GetFro1MFreq(void) +{ + return ((SYSCON->CLOCK_CTRL & SYSCON_CLOCK_CTRL_FRO1MHZ_CLK_ENA_MASK) != 0UL) ? 1000000U : 0U; +} + +/* Get EXT OSC Clk */ +/*! brief Return Frequency of External Clock + * return Frequency of External Clock. If no external clock is used returns 0. + */ +uint32_t CLOCK_GetExtClkFreq(void) +{ + return ((ANACTRL->XO32M_CTRL & ANACTRL_XO32M_CTRL_ENABLE_SYSTEM_CLK_OUT_MASK) != 0UL) ? s_Ext_Clk_Freq : 0U; +} + +/* Get WATCH DOG Clk */ +/*! brief Return Frequency of Watchdog + * return Frequency of Watchdog + */ +uint32_t CLOCK_GetWdtClkFreq(void) +{ + return CLOCK_GetFro1MFreq() / ((SYSCON->WDTCLKDIV & SYSCON_WDTCLKDIV_DIV_MASK) + 1U); +} + +/* Get HF FRO Clk */ +/*! brief Return Frequency of High-Freq output of FRO + * return Frequency of High-Freq output of FRO + */ +uint32_t CLOCK_GetFroHfFreq(void) +{ + return ((ANACTRL->FRO192M_CTRL & ANACTRL_FRO192M_CTRL_ENA_96MHZCLK_MASK) != 0UL) ? 96000000U : 0U; +} + +/* Get SYSTEM PLL Clk */ +/*! brief Return Frequency of PLL + * return Frequency of PLL + */ +uint32_t CLOCK_GetPll0OutFreq(void) +{ + return s_Pll0_Freq; +} + +/* Get USB PLL Clk */ +/*! brief Return Frequency of USB PLL + * return Frequency of PLL + */ +uint32_t CLOCK_GetPll1OutFreq(void) +{ + return s_Pll1_Freq; +} + +/* Get RTC OSC Clk */ +/*! brief Return Frequency of 32kHz osc + * return Frequency of 32kHz osc + */ +uint32_t CLOCK_GetOsc32KFreq(void) +{ + return ((0UL == (PMC->PDRUNCFG0 & PMC_PDRUNCFG0_PDEN_FRO32K_MASK)) && + (0UL == (PMC->RTCOSC32K & PMC_RTCOSC32K_SEL_MASK))) ? + CLK_RTC_32K_CLK : + ((0UL == (PMC->PDRUNCFG0 & PMC_PDRUNCFG0_PDEN_XTAL32K_MASK)) && + (0UL != (PMC->RTCOSC32K & PMC_RTCOSC32K_SEL_MASK))) ? + CLK_RTC_32K_CLK : + 0U; +} + +/* Get MAIN Clk */ +/*! brief Return Frequency of Core System + * return Frequency of Core System + */ +uint32_t CLOCK_GetCoreSysClkFreq(void) +{ + uint32_t freq = 0U; + + switch (SYSCON->MAINCLKSELB) + { + case 0U: + if (SYSCON->MAINCLKSELA == 0U) + { + freq = CLOCK_GetFro12MFreq(); + } + else if (SYSCON->MAINCLKSELA == 1U) + { + freq = CLOCK_GetExtClkFreq(); + } + else if (SYSCON->MAINCLKSELA == 2U) + { + freq = CLOCK_GetFro1MFreq(); + } + else if (SYSCON->MAINCLKSELA == 3U) + { + freq = CLOCK_GetFroHfFreq(); + } + else + { + /* Add comments to prevent the case of MISRA C-2012 rule 15.7. */ + } + break; + case 1U: + freq = CLOCK_GetPll0OutFreq(); + break; + case 2U: + freq = CLOCK_GetPll1OutFreq(); + break; + + case 3U: + freq = CLOCK_GetOsc32KFreq(); + break; + + default: + freq = 0U; + break; + } + + return freq; +} + +/* Get I2S MCLK Clk */ +/*! brief Return Frequency of I2S MCLK Clock + * return Frequency of I2S MCLK Clock + */ +uint32_t CLOCK_GetI2SMClkFreq(void) +{ + return s_I2S_Mclk_Freq; +} + +/* Get PLU CLKIN Clk */ +/*! brief Return Frequency of PLU CLKIN Clock + * return Frequency of PLU CLKIN Clock + */ +uint32_t CLOCK_GetPLUClkInFreq(void) +{ + return s_PLU_ClkIn_Freq; +} + +/* Get FLEXCOMM input clock */ +/*! brief Return Frequency of flexcomm input clock + * param id : flexcomm instance id + * return Frequency value + */ +uint32_t CLOCK_GetFlexCommInputClock(uint32_t id) +{ + uint32_t freq = 0U; + + switch (SYSCON->FCCLKSELX[id]) + { + case 0U: + freq = CLOCK_GetCoreSysClkFreq(); + break; + case 1U: + freq = CLOCK_GetPll0OutFreq() / ((SYSCON->PLL0CLKDIV & 0xffU) + 1U); + break; + case 2U: + freq = CLOCK_GetFro12MFreq(); + break; + case 3U: + freq = CLOCK_GetFroHfFreq() / ((SYSCON->FROHFDIV & 0xffU) + 1U); + break; + case 4U: + freq = CLOCK_GetFro1MFreq(); + break; + case 5U: + freq = CLOCK_GetI2SMClkFreq(); + break; + case 6U: + freq = CLOCK_GetOsc32KFreq(); + break; + case 7U: + freq = 0U; + break; + + default: + assert(false); + break; + } + + return freq; +} + +/* Get FLEXCOMM Clk */ +uint32_t CLOCK_GetFlexCommClkFreq(uint32_t id) +{ + uint32_t freq = 0U; + uint32_t frgMul = 0U; + uint32_t frgDiv = 0U; + + freq = CLOCK_GetFlexCommInputClock(id); + frgMul = (SYSCON->FLEXFRGXCTRL[id] & SYSCON_FLEXFRG0CTRL_MULT_MASK) >> 8U; + frgDiv = SYSCON->FLEXFRGXCTRL[id] & SYSCON_FLEXFRG0CTRL_DIV_MASK; + return (uint32_t)(((uint64_t)freq * ((uint64_t)frgDiv + 1ULL)) / (frgMul + frgDiv + 1UL)); +} + +/* Get HS_LPSI Clk */ +uint32_t CLOCK_GetHsLspiClkFreq(void) +{ + uint32_t freq = 0U; + + switch (SYSCON->HSLSPICLKSEL) + { + case 0U: + freq = CLOCK_GetCoreSysClkFreq(); + break; + case 1U: + freq = CLOCK_GetPll0OutFreq() / ((SYSCON->PLL0CLKDIV & 0xffU) + 1U); + break; + case 2U: + freq = CLOCK_GetFro12MFreq(); + break; + case 3U: + freq = CLOCK_GetFroHfFreq() / ((SYSCON->FROHFDIV & 0xffU) + 1U); + break; + case 4U: + freq = CLOCK_GetFro1MFreq(); + break; + case 6U: + freq = CLOCK_GetOsc32KFreq(); + break; + case 7U: + freq = 0U; + break; + + default: + assert(false); + break; + } + + return freq; +} + +/* Get CTimer Clk */ +/*! brief Return Frequency of CTimer functional Clock + * return Frequency of CTimer functional Clock + */ +uint32_t CLOCK_GetCTimerClkFreq(uint32_t id) +{ + uint32_t freq = 0U; + + switch (SYSCON->CTIMERCLKSELX[id]) + { + case 0U: + freq = CLOCK_GetCoreSysClkFreq(); + break; + case 1U: + freq = CLOCK_GetPll0OutFreq(); + break; + case 3U: + freq = CLOCK_GetFroHfFreq(); + break; + case 4U: + freq = CLOCK_GetFro1MFreq(); + break; + case 5U: + freq = CLOCK_GetI2SMClkFreq(); + break; + case 6U: + freq = CLOCK_GetOsc32KFreq(); + break; + case 7U: + freq = 0U; + break; + + default: + assert(false); + break; + } + + return freq; +} + +/* Get Systick Clk */ +/*! brief Return Frequency of SystickClock + * return Frequency of Systick Clock + */ +uint32_t CLOCK_GetSystickClkFreq(uint32_t id) +{ + volatile uint32_t *pSystickClkDiv; + pSystickClkDiv = &(SYSCON->SYSTICKCLKDIV0); + uint32_t freq = 0U; + + switch (SYSCON->SYSTICKCLKSELX[id]) + { + case 0U: + freq = CLOCK_GetCoreSysClkFreq() / ((((volatile uint32_t *)pSystickClkDiv)[(uint32_t)id] & 0xffU) + 1U); + break; + case 1U: + freq = CLOCK_GetFro1MFreq(); + break; + case 2U: + freq = CLOCK_GetOsc32KFreq(); + break; + case 7U: + freq = 0U; + break; + + default: + freq = 0U; + break; + } + + return freq; +} + +/* Set FlexComm Clock */ +/** + * brief Set the flexcomm output frequency. + * param id : flexcomm instance id + * freq : output frequency + * return 0 : the frequency range is out of range. + * 1 : switch successfully. + */ +uint32_t CLOCK_SetFlexCommClock(uint32_t id, uint32_t freq) +{ + uint32_t input = CLOCK_GetFlexCommClkFreq(id); + uint32_t mul; + + if ((freq > 48000000UL) || (freq > input) || (input / freq >= 2UL)) + { + /* FRG output frequency should be less than equal to 48MHz */ + return 0UL; + } + else + { + mul = (uint32_t)((((uint64_t)input - freq) * 256ULL) / ((uint64_t)freq)); + SYSCON->FLEXFRGXCTRL[id] = (mul << 8U) | 0xFFU; + return 1UL; + } +} + +/* Get IP Clk */ +/*! brief Return Frequency of selected clock + * return Frequency of selected clock + */ +uint32_t CLOCK_GetFreq(clock_name_t clockName) +{ + uint32_t freq; + switch (clockName) + { + case kCLOCK_CoreSysClk: + freq = CLOCK_GetCoreSysClkFreq(); + break; + case kCLOCK_BusClk: + freq = CLOCK_GetCoreSysClkFreq() / ((SYSCON->AHBCLKDIV & 0xffU) + 1U); + break; + case kCLOCK_ClockOut: + freq = CLOCK_GetClockOutClkFreq(); + break; + case kCLOCK_Pll1Out: + freq = CLOCK_GetPll1OutFreq(); + break; + case kCLOCK_Mclk: + freq = CLOCK_GetMclkClkFreq(); + break; + case kCLOCK_FroHf: + freq = CLOCK_GetFroHfFreq(); + break; + case kCLOCK_Fro12M: + freq = CLOCK_GetFro12MFreq(); + break; + case kCLOCK_ExtClk: + freq = CLOCK_GetExtClkFreq(); + break; + case kCLOCK_Pll0Out: + freq = CLOCK_GetPll0OutFreq(); + break; + case kCLOCK_FlexI2S: + freq = CLOCK_GetI2SMClkFreq(); + break; + default: + freq = 0U; + break; + } + return freq; +} + +/* Find SELP, SELI, and SELR values for raw M value, max M = MVALMAX */ +static void pllFindSel(uint32_t M, uint32_t *pSelP, uint32_t *pSelI, uint32_t *pSelR) +{ + uint32_t seli, selp; + /* bandwidth: compute selP from Multiplier */ + if ((SYSCON->PLL0SSCG1 & SYSCON_PLL0SSCG1_SEL_EXT_MASK) != 0UL) /* normal mode */ + { + selp = (M >> 2U) + 1U; + if (selp >= 31U) + { + selp = 31U; + } + *pSelP = selp; + + if (M >= 8000UL) + { + seli = 1UL; + } + else if (M >= 122UL) + { + seli = (uint32_t)(8000UL / M); /*floor(8000/M) */ + } + else + { + seli = 2UL * ((uint32_t)(M / 4UL)) + 3UL; /* 2*floor(M/4) + 3 */ + } + + if (seli >= 63UL) + { + seli = 63UL; + } + *pSelI = seli; + + *pSelR = 0U; + } + else + { + /* Note: If the spread spectrum mode, choose N to ensure 3 MHz < Fin/N < 5 MHz */ + *pSelP = 3U; + *pSelI = 4U; + *pSelR = 4U; + } +} + +/* Get predivider (N) from PLL0 NDEC setting */ +static uint32_t findPll0PreDiv(void) +{ + uint32_t preDiv = 1UL; + + /* Direct input is not used? */ + if ((SYSCON->PLL0CTRL & SYSCON_PLL0CTRL_BYPASSPREDIV_MASK) == 0UL) + { + preDiv = SYSCON->PLL0NDEC & SYSCON_PLL0NDEC_NDIV_MASK; + if (preDiv == 0UL) + { + preDiv = 1UL; + } + } + return preDiv; +} + +/* Get predivider (N) from PLL1 NDEC setting */ +static uint32_t findPll1PreDiv(void) +{ + uint32_t preDiv = 1UL; + + /* Direct input is not used? */ + if ((SYSCON->PLL1CTRL & SYSCON_PLL1CTRL_BYPASSPREDIV_MASK) == 0UL) + { + preDiv = SYSCON->PLL1NDEC & SYSCON_PLL1NDEC_NDIV_MASK; + if (preDiv == 0UL) + { + preDiv = 1UL; + } + } + return preDiv; +} + +/* Get postdivider (P) from PLL0 PDEC setting */ +static uint32_t findPll0PostDiv(void) +{ + uint32_t postDiv = 1UL; + + if ((SYSCON->PLL0CTRL & SYSCON_PLL0CTRL_BYPASSPOSTDIV_MASK) == 0UL) + { + if ((SYSCON->PLL0CTRL & SYSCON_PLL0CTRL_BYPASSPOSTDIV2_MASK) != 0UL) + { + postDiv = SYSCON->PLL0PDEC & SYSCON_PLL0PDEC_PDIV_MASK; + } + else + { + postDiv = 2UL * (SYSCON->PLL0PDEC & SYSCON_PLL0PDEC_PDIV_MASK); + } + if (postDiv == 0UL) + { + postDiv = 2UL; + } + } + return postDiv; +} + +/* Get multiplier (M) from PLL0 SSCG and SEL_EXT settings */ +static float findPll0MMult(void) +{ + float mMult = 1.0F; + float mMult_fract; + uint32_t mMult_int; + + if ((SYSCON->PLL0SSCG1 & SYSCON_PLL0SSCG1_SEL_EXT_MASK) != 0UL) + { + mMult = + (float)(uint32_t)((SYSCON->PLL0SSCG1 & SYSCON_PLL0SSCG1_MDIV_EXT_MASK) >> SYSCON_PLL0SSCG1_MDIV_EXT_SHIFT); + } + else + { + mMult_int = ((SYSCON->PLL0SSCG1 & SYSCON_PLL0SSCG1_MD_MBS_MASK) << 7U); + mMult_int = mMult_int | ((SYSCON->PLL0SSCG0) >> PLL0_SSCG_MD_INT_P); + mMult_fract = ((float)(uint32_t)((SYSCON->PLL0SSCG0) & PLL0_SSCG_MD_FRACT_M) / + (float)(uint32_t)(1UL << PLL0_SSCG_MD_INT_P)); + mMult = (float)mMult_int + mMult_fract; + } + if (0ULL == ((uint64_t)mMult)) + { + mMult = 1.0F; + } + return mMult; +} + +/* Find greatest common divisor between m and n */ +static uint32_t FindGreatestCommonDivisor(uint32_t m, uint32_t n) +{ + uint32_t tmp; + + while (n != 0U) + { + tmp = n; + n = m % n; + m = tmp; + } + + return m; +} + +/* + * Set PLL0 output based on desired output rate. + * In this function, the it calculates the PLL0 setting for output frequency from input clock + * frequency. The calculation would cost a few time. So it is not recommaned to use it frequently. + * the "pllctrl", "pllndec", "pllpdec", "pllmdec" would updated in this function. + */ +static pll_error_t CLOCK_GetPll0ConfigInternal(uint32_t finHz, uint32_t foutHz, pll_setup_t *pSetup, bool useSS) +{ + uint32_t nDivOutHz, fccoHz; + uint32_t pllPreDivider, pllMultiplier, pllPostDivider; + uint32_t pllDirectInput, pllDirectOutput; + uint32_t pllSelP, pllSelI, pllSelR, uplimoff; + + /* Baseline parameters (no input or output dividers) */ + pllPreDivider = 1U; /* 1 implies pre-divider will be disabled */ + pllPostDivider = 1U; /* 1 implies post-divider will be disabled */ + pllDirectOutput = 1U; + + /* Verify output rate parameter */ + if (foutHz > PLL_MAX_CCO_FREQ_MHZ) + { + /* Maximum PLL output with post divider=1 cannot go above this frequency */ + return kStatus_PLL_OutputTooHigh; + } + if (foutHz < (PLL_MIN_CCO_FREQ_MHZ / (PVALMAX << 1U))) + { + /* Minmum PLL output with maximum post divider cannot go below this frequency */ + return kStatus_PLL_OutputTooLow; + } + + /* If using SS mode, input clock needs to be between 3MHz and 20MHz */ + if (useSS) + { + /* Verify input rate parameter */ + if (finHz < PLL_MIN_IN_SSMODE) + { + /* Input clock into the PLL cannot be lower than this */ + return kStatus_PLL_InputTooLow; + } + /* PLL input in SS mode must be under 20MHz */ + if (finHz > (PLL_MAX_IN_SSMODE * NVALMAX)) + { + return kStatus_PLL_InputTooHigh; + } + } + else + { + /* Verify input rate parameter */ + if (finHz < PLL_LOWER_IN_LIMIT) + { + /* Input clock into the PLL cannot be lower than this */ + return kStatus_PLL_InputTooLow; + } + if (finHz > PLL_HIGHER_IN_LIMIT) + { + /* Input clock into the PLL cannot be higher than this */ + return kStatus_PLL_InputTooHigh; + } + } + + /* Find the optimal CCO frequency for the output and input that + will keep it inside the PLL CCO range. This may require + tweaking the post-divider for the PLL. */ + fccoHz = foutHz; + while (fccoHz < PLL_MIN_CCO_FREQ_MHZ) + { + /* CCO output is less than minimum CCO range, so the CCO output + needs to be bumped up and the post-divider is used to bring + the PLL output back down. */ + pllPostDivider++; + if (pllPostDivider > PVALMAX) + { + return kStatus_PLL_OutsideIntLimit; + } + + /* Target CCO goes up, PLL output goes down */ + /* divide-by-2 divider in the post-divider is always work*/ + fccoHz = foutHz * (pllPostDivider * 2U); + pllDirectOutput = 0U; + } + + /* Determine if a pre-divider is needed to get the best frequency */ + if ((finHz > PLL_LOWER_IN_LIMIT) && (fccoHz >= finHz) && (useSS == false)) + { + uint32_t a = FindGreatestCommonDivisor(fccoHz, finHz); + + if (a > PLL_LOWER_IN_LIMIT) + { + a = finHz / a; + if ((a != 0U) && (a < PLL_MAX_N_DIV)) + { + pllPreDivider = a; + } + } + } + + /* Bypass pre-divider hardware if pre-divider is 1 */ + if (pllPreDivider > 1U) + { + pllDirectInput = 0U; + } + else + { + pllDirectInput = 1U; + } + + /* Determine PLL multipler */ + nDivOutHz = (finHz / pllPreDivider); + pllMultiplier = (fccoHz / nDivOutHz); + + /* Find optimal values for filter */ + if (useSS == false) + { + /* Will bumping up M by 1 get us closer to the desired CCO frequency? */ + if ((nDivOutHz * ((pllMultiplier * 2U) + 1U)) < (fccoHz * 2U)) + { + pllMultiplier++; + } + + /* Setup filtering */ + pllFindSel(pllMultiplier, &pllSelP, &pllSelI, &pllSelR); + uplimoff = 0U; + + /* Get encoded value for M (mult) and use manual filter, disable SS mode */ + pSetup->pllsscg[1] = + (uint32_t)((PLL_SSCG1_MDEC_VAL_SET(pllMultiplier)) | (1UL << SYSCON_PLL0SSCG1_SEL_EXT_SHIFT)); + } + else + { + uint64_t fc; + + /* Filtering will be handled by SSC */ + pllSelR = 0U; + pllSelI = 0U; + pllSelP = 0U; + uplimoff = 1U; + + /* The PLL multiplier will get very close and slightly under the + desired target frequency. A small fractional component can be + added to fine tune the frequency upwards to the target. */ + fc = (((uint64_t)fccoHz % (uint64_t)nDivOutHz) << 25U) / nDivOutHz; + + /* Set multiplier */ + pSetup->pllsscg[0] = (uint32_t)(PLL0_SSCG_MD_INT_SET(pllMultiplier) | PLL0_SSCG_MD_FRACT_SET((uint32_t)fc)); + pSetup->pllsscg[1] = (uint32_t)(PLL0_SSCG_MD_INT_SET(pllMultiplier) >> 32U); + } + + /* Get encoded values for N (prediv) and P (postdiv) */ + pSetup->pllndec = PLL_NDEC_VAL_SET(pllPreDivider); + pSetup->pllpdec = PLL_PDEC_VAL_SET(pllPostDivider); + + /* PLL control */ + pSetup->pllctrl = (pllSelR << SYSCON_PLL0CTRL_SELR_SHIFT) | /* Filter coefficient */ + (pllSelI << SYSCON_PLL0CTRL_SELI_SHIFT) | /* Filter coefficient */ + (pllSelP << SYSCON_PLL0CTRL_SELP_SHIFT) | /* Filter coefficient */ + (0UL << SYSCON_PLL0CTRL_BYPASSPLL_SHIFT) | /* PLL bypass mode disabled */ + (uplimoff << SYSCON_PLL0CTRL_LIMUPOFF_SHIFT) | /* SS/fractional mode disabled */ + (pllDirectInput << SYSCON_PLL0CTRL_BYPASSPREDIV_SHIFT) | /* Bypass pre-divider? */ + (pllDirectOutput << SYSCON_PLL0CTRL_BYPASSPOSTDIV_SHIFT) | /* Bypass post-divider? */ + (1UL << SYSCON_PLL0CTRL_CLKEN_SHIFT); /* Ensure the PLL clock output */ + + return kStatus_PLL_Success; +} + +#if (defined(CLOCK_USR_CFG_PLL_CONFIG_CACHE_COUNT) && CLOCK_USR_CFG_PLL_CONFIG_CACHE_COUNT) +/* Alloct the static buffer for cache. */ +static pll_setup_t s_PllSetupCacheStruct[CLOCK_USR_CFG_PLL_CONFIG_CACHE_COUNT]; +static uint32_t s_FinHzCache[CLOCK_USR_CFG_PLL_CONFIG_CACHE_COUNT] = {0}; +static uint32_t s_FoutHzCache[CLOCK_USR_CFG_PLL_CONFIG_CACHE_COUNT] = {0}; +static bool s_UseSSCache[CLOCK_USR_CFG_PLL_CONFIG_CACHE_COUNT] = {false}; +static uint32_t s_PllSetupCacheIdx = 0U; +#endif /* CLOCK_USR_CFG_PLL_CONFIG_CACHE_COUNT */ + +/* + * Calculate the PLL setting values from input clock freq to output freq. + */ +static pll_error_t CLOCK_GetPll0Config(uint32_t finHz, uint32_t foutHz, pll_setup_t *pSetup, bool useSS) +{ + pll_error_t retErr; +#if (defined(CLOCK_USR_CFG_PLL_CONFIG_CACHE_COUNT) && CLOCK_USR_CFG_PLL_CONFIG_CACHE_COUNT) + uint32_t i; + + for (i = 0U; i < CLOCK_USR_CFG_PLL_CONFIG_CACHE_COUNT; i++) + { + if ((finHz == s_FinHzCache[i]) && (foutHz == s_FoutHzCache[i]) && (useSS == s_UseSSCache[i])) + { + /* Hit the target in cache buffer. */ + pSetup->pllctrl = s_PllSetupCacheStruct[i].pllctrl; + pSetup->pllndec = s_PllSetupCacheStruct[i].pllndec; + pSetup->pllpdec = s_PllSetupCacheStruct[i].pllpdec; + pSetup->pllsscg[0] = s_PllSetupCacheStruct[i].pllsscg[0]; + pSetup->pllsscg[1] = s_PllSetupCacheStruct[i].pllsscg[1]; + retErr = kStatus_PLL_Success; + break; + } + } + + if (i < CLOCK_USR_CFG_PLL_CONFIG_CACHE_COUNT) + { + return retErr; + } +#endif /* CLOCK_USR_CFG_PLL_CONFIG_CACHE_COUNT */ + + retErr = CLOCK_GetPll0ConfigInternal(finHz, foutHz, pSetup, useSS); + +#if (defined(CLOCK_USR_CFG_PLL_CONFIG_CACHE_COUNT) && CLOCK_USR_CFG_PLL_CONFIG_CACHE_COUNT) + /* Cache the most recent calulation result into buffer. */ + s_FinHzCache[s_PllSetupCacheIdx] = finHz; + s_FoutHzCache[s_PllSetupCacheIdx] = foutHz; + s_UseSSCache[s_PllSetupCacheIdx] = useSS; + + s_PllSetupCacheStruct[s_PllSetupCacheIdx].pllctrl = pSetup->pllctrl; + s_PllSetupCacheStruct[s_PllSetupCacheIdx].pllndec = pSetup->pllndec; + s_PllSetupCacheStruct[s_PllSetupCacheIdx].pllpdec = pSetup->pllpdec; + s_PllSetupCacheStruct[s_PllSetupCacheIdx].pllsscg[0] = pSetup->pllsscg[0]; + s_PllSetupCacheStruct[s_PllSetupCacheIdx].pllsscg[1] = pSetup->pllsscg[1]; + /* Update the index for next available buffer. */ + s_PllSetupCacheIdx = (s_PllSetupCacheIdx + 1U) % CLOCK_USR_CFG_PLL_CONFIG_CACHE_COUNT; +#endif /* CLOCK_USR_CFG_PLL_CONFIG_CACHE_COUNT */ + + return retErr; +} + +/* Update local PLL rate variable */ +static void CLOCK_GetPLL0OutFromSetupUpdate(pll_setup_t *pSetup) +{ + s_Pll0_Freq = CLOCK_GetPLL0OutFromSetup(pSetup); +} + +/* Return System PLL input clock rate */ +/*! brief Return PLL0 input clock rate + * return PLL0 input clock rate + */ +uint32_t CLOCK_GetPLL0InClockRate(void) +{ + uint32_t clkRate = 0U; + + switch ((SYSCON->PLL0CLKSEL & SYSCON_PLL0CLKSEL_SEL_MASK)) + { + case 0x00U: + clkRate = CLK_FRO_12MHZ; + break; + + case 0x01U: + clkRate = CLOCK_GetExtClkFreq(); + break; + + case 0x02U: + clkRate = CLOCK_GetFro1MFreq(); + break; + + case 0x03U: + clkRate = CLOCK_GetOsc32KFreq(); + break; + + default: + clkRate = 0U; + break; + } + + return clkRate; +} + +/* Return PLL1 input clock rate */ +uint32_t CLOCK_GetPLL1InClockRate(void) +{ + uint32_t clkRate = 0U; + + switch ((SYSCON->PLL1CLKSEL & SYSCON_PLL1CLKSEL_SEL_MASK)) + { + case 0x00U: + clkRate = CLK_FRO_12MHZ; + break; + + case 0x01U: + clkRate = CLOCK_GetExtClkFreq(); + break; + + case 0x02U: + clkRate = CLOCK_GetFro1MFreq(); + break; + + case 0x03U: + clkRate = CLOCK_GetOsc32KFreq(); + break; + + default: + clkRate = 0U; + break; + } + + return clkRate; +} + +/* Return PLL0 output clock rate from setup structure */ +/*! brief Return PLL0 output clock rate from setup structure + * param pSetup : Pointer to a PLL setup structure + * return PLL0 output clock rate the setup structure will generate + */ +uint32_t CLOCK_GetPLL0OutFromSetup(pll_setup_t *pSetup) +{ + uint32_t clkRate = 0; + uint32_t prediv, postdiv; + float workRate = 0.0F; + + /* Get the input clock frequency of PLL. */ + clkRate = CLOCK_GetPLL0InClockRate(); + + if (((pSetup->pllctrl & SYSCON_PLL0CTRL_BYPASSPLL_MASK) == 0UL) && + ((pSetup->pllctrl & SYSCON_PLL0CTRL_CLKEN_MASK) != 0UL) && + ((PMC->PDRUNCFG0 & PMC_PDRUNCFG0_PDEN_PLL0_MASK) == 0UL) && + ((PMC->PDRUNCFG0 & PMC_PDRUNCFG0_PDEN_PLL0_SSCG_MASK) == 0UL)) + { + prediv = findPll0PreDiv(); + postdiv = findPll0PostDiv(); + /* Adjust input clock */ + clkRate = clkRate / prediv; + /* MDEC used for rate */ + workRate = (float)clkRate * (float)findPll0MMult(); + workRate /= (float)postdiv; + } + + return (uint32_t)workRate; +} + +/* Set the current PLL0 Rate */ +/*! brief Store the current PLL rate + * param rate: Current rate of the PLL + * return Nothing + **/ +void CLOCK_SetStoredPLL0ClockRate(uint32_t rate) +{ + s_Pll0_Freq = rate; +} + +/* Return PLL0 output clock rate */ +/*! brief Return PLL0 output clock rate + * param recompute : Forces a PLL rate recomputation if true + * return PLL0 output clock rate + * note The PLL rate is cached in the driver in a variable as + * the rate computation function can take some time to perform. It + * is recommended to use 'false' with the 'recompute' parameter. + */ +uint32_t CLOCK_GetPLL0OutClockRate(bool recompute) +{ + pll_setup_t Setup; + uint32_t rate; + + if ((recompute) || (s_Pll0_Freq == 0U)) + { + Setup.pllctrl = SYSCON->PLL0CTRL; + Setup.pllndec = SYSCON->PLL0NDEC; + Setup.pllpdec = SYSCON->PLL0PDEC; + Setup.pllsscg[0] = SYSCON->PLL0SSCG0; + Setup.pllsscg[1] = SYSCON->PLL0SSCG1; + + CLOCK_GetPLL0OutFromSetupUpdate(&Setup); + } + + rate = s_Pll0_Freq; + + return rate; +} + +/* Set PLL0 output based on the passed PLL setup data */ +/*! brief Set PLL output based on the passed PLL setup data + * param pControl : Pointer to populated PLL control structure to generate setup with + * param pSetup : Pointer to PLL setup structure to be filled + * return PLL_ERROR_SUCCESS on success, or PLL setup error code + * note Actual frequency for setup may vary from the desired frequency based on the + * accuracy of input clocks, rounding, non-fractional PLL mode, etc. + */ +pll_error_t CLOCK_SetupPLL0Data(pll_config_t *pControl, pll_setup_t *pSetup) +{ + uint32_t inRate; + bool useSS = ((pControl->flags & PLL_CONFIGFLAG_FORCENOFRACT) == 0U); + + pll_error_t pllError; + + /* Determine input rate for the PLL */ + if ((pControl->flags & PLL_CONFIGFLAG_USEINRATE) != 0U) + { + inRate = pControl->inputRate; + } + else + { + inRate = CLOCK_GetPLL0InClockRate(); + } + + /* PLL flag options */ + pllError = CLOCK_GetPll0Config(inRate, pControl->desiredRate, pSetup, useSS); + if ((useSS) && (pllError == kStatus_PLL_Success)) + { + /* If using SS mode, then some tweaks are made to the generated setup */ + pSetup->pllsscg[1] |= (uint32_t)pControl->ss_mf | (uint32_t)pControl->ss_mr | (uint32_t)pControl->ss_mc; + if (pControl->mfDither) + { + pSetup->pllsscg[1] |= (1UL << SYSCON_PLL0SSCG1_DITHER_SHIFT); + } + } + + return pllError; +} + +/* Set PLL0 output from PLL setup structure */ +/*! brief Set PLL output from PLL setup structure (precise frequency) + * param pSetup : Pointer to populated PLL setup structure + * param flagcfg : Flag configuration for PLL config structure + * return PLL_ERROR_SUCCESS on success, or PLL setup error code + * note This function will power off the PLL, setup the PLL with the + * new setup data, and then optionally powerup the PLL, wait for PLL lock, + * and adjust system voltages to the new PLL rate. The function will not + * alter any source clocks (ie, main systen clock) that may use the PLL, + * so these should be setup prior to and after exiting the function. + */ +pll_error_t CLOCK_SetupPLL0Prec(pll_setup_t *pSetup, uint32_t flagcfg) +{ + uint32_t inRate, clkRate, prediv; + uint32_t pll_lock_wait_time = 0U; + uint32_t max_pll_lock_wait_time = 0U; + /* Power off PLL during setup changes */ + POWER_EnablePD(kPDRUNCFG_PD_PLL0); + POWER_EnablePD(kPDRUNCFG_PD_PLL0_SSCG); + + pSetup->flags = flagcfg; + + /* Write PLL setup data */ + SYSCON->PLL0CTRL = pSetup->pllctrl; + SYSCON->PLL0NDEC = pSetup->pllndec; + SYSCON->PLL0NDEC = pSetup->pllndec | (1UL << SYSCON_PLL0NDEC_NREQ_SHIFT); /* latch */ + SYSCON->PLL0PDEC = pSetup->pllpdec; + SYSCON->PLL0PDEC = pSetup->pllpdec | (1UL << SYSCON_PLL0PDEC_PREQ_SHIFT); /* latch */ + SYSCON->PLL0SSCG0 = pSetup->pllsscg[0]; + SYSCON->PLL0SSCG1 = pSetup->pllsscg[1]; + SYSCON->PLL0SSCG1 = + pSetup->pllsscg[1] | (1UL << SYSCON_PLL0SSCG1_MREQ_SHIFT) | (1UL << SYSCON_PLL0SSCG1_MD_REQ_SHIFT); /* latch */ + + POWER_DisablePD(kPDRUNCFG_PD_PLL0); + POWER_DisablePD(kPDRUNCFG_PD_PLL0_SSCG); + + if ((pSetup->flags & PLL_SETUPFLAG_WAITLOCK) != 0U) + { + if ((SYSCON->PLL0SSCG1 & SYSCON_PLL0SSCG1_SEL_EXT_MASK) != 0UL) /* normal mode */ + { + inRate = CLOCK_GetPLL0InClockRate(); + prediv = findPll0PreDiv(); + /* Adjust input clock */ + clkRate = inRate / prediv; + + /* Need wait at least (500us + 400/Fref) (Fref in Hz result in s) to ensure the PLL is stable. + The lock bit could be used to shorten the wait time when freq<20MHZ */ + max_pll_lock_wait_time = 500U + (400000000U / clkRate); + + if (clkRate < 20000000UL) + { + pll_lock_wait_time = 0U; + while ((CLOCK_IsPLL0Locked() == false) && (pll_lock_wait_time < max_pll_lock_wait_time)) + { + pll_lock_wait_time += 100U; + SDK_DelayAtLeastUs(100U, SDK_DEVICE_MAXIMUM_CPU_CLOCK_FREQUENCY); + } + } + else + { + SDK_DelayAtLeastUs(max_pll_lock_wait_time, SDK_DEVICE_MAXIMUM_CPU_CLOCK_FREQUENCY); + } + } + else /* spread spectrum mode */ + { + SDK_DelayAtLeastUs(6000U, + SDK_DEVICE_MAXIMUM_CPU_CLOCK_FREQUENCY); /* software should use a 6 ms time interval + to insure the PLL will be stable */ + } + } + + /* Update current programmed PLL rate var */ + CLOCK_GetPLL0OutFromSetupUpdate(pSetup); + + /* System voltage adjustment, occurs prior to setting main system clock */ + if ((pSetup->flags & PLL_SETUPFLAG_ADGVOLT) != 0U) + { + POWER_SetVoltageForFreq(s_Pll0_Freq); + } + + return kStatus_PLL_Success; +} + +/* Setup PLL Frequency from pre-calculated value */ +/** + * brief Set PLL0 output from PLL setup structure (precise frequency) + * param pSetup : Pointer to populated PLL setup structure + * return kStatus_PLL_Success on success, or PLL setup error code + * note This function will power off the PLL, setup the PLL with the + * new setup data, and then optionally powerup the PLL, wait for PLL lock, + * and adjust system voltages to the new PLL rate. The function will not + * alter any source clocks (ie, main systen clock) that may use the PLL, + * so these should be setup prior to and after exiting the function. + */ +pll_error_t CLOCK_SetPLL0Freq(const pll_setup_t *pSetup) +{ + uint32_t inRate, clkRate, prediv; + uint32_t pll_lock_wait_time = 0U; + uint32_t max_pll_lock_wait_time = 0U; + /* Power off PLL during setup changes */ + POWER_EnablePD(kPDRUNCFG_PD_PLL0); + POWER_EnablePD(kPDRUNCFG_PD_PLL0_SSCG); + + /* Write PLL setup data */ + SYSCON->PLL0CTRL = pSetup->pllctrl; + SYSCON->PLL0NDEC = pSetup->pllndec; + SYSCON->PLL0NDEC = pSetup->pllndec | (1UL << SYSCON_PLL0NDEC_NREQ_SHIFT); /* latch */ + SYSCON->PLL0PDEC = pSetup->pllpdec; + SYSCON->PLL0PDEC = pSetup->pllpdec | (1UL << SYSCON_PLL0PDEC_PREQ_SHIFT); /* latch */ + SYSCON->PLL0SSCG0 = pSetup->pllsscg[0]; + SYSCON->PLL0SSCG1 = pSetup->pllsscg[1]; + SYSCON->PLL0SSCG1 = + pSetup->pllsscg[1] | (1UL << SYSCON_PLL0SSCG1_MD_REQ_SHIFT) | (1UL << SYSCON_PLL0SSCG1_MREQ_SHIFT); /* latch */ + + POWER_DisablePD(kPDRUNCFG_PD_PLL0); + POWER_DisablePD(kPDRUNCFG_PD_PLL0_SSCG); + + if ((pSetup->flags & PLL_SETUPFLAG_WAITLOCK) != 0U) + { + if ((SYSCON->PLL0SSCG1 & SYSCON_PLL0SSCG1_SEL_EXT_MASK) != 0UL) /* normal mode */ + { + inRate = CLOCK_GetPLL0InClockRate(); + prediv = findPll0PreDiv(); + /* Adjust input clock */ + clkRate = inRate / prediv; + + /* Need wait at least (500us + 400/Fref) (Fref in Hz result in s) to ensure the PLL is + stable. The lock bit could be used to shorten the wait time when freq<20MHZ */ + max_pll_lock_wait_time = 500U + (400000000U / clkRate); + + if (clkRate < 20000000UL) + { + pll_lock_wait_time = 0U; + while ((CLOCK_IsPLL0Locked() == false) && (pll_lock_wait_time < max_pll_lock_wait_time)) + { + pll_lock_wait_time += 100U; + SDK_DelayAtLeastUs(100U, SDK_DEVICE_MAXIMUM_CPU_CLOCK_FREQUENCY); + } + } + else + { + SDK_DelayAtLeastUs(max_pll_lock_wait_time, SDK_DEVICE_MAXIMUM_CPU_CLOCK_FREQUENCY); + } + } + else /* spread spectrum mode */ + { + SDK_DelayAtLeastUs(6000U, + SDK_DEVICE_MAXIMUM_CPU_CLOCK_FREQUENCY); /* software should use a 6 ms time interval + to insure the PLL will be stable */ + } + } + + /* Update current programmed PLL rate var */ + s_Pll0_Freq = pSetup->pllRate; + + return kStatus_PLL_Success; +} + +/* Setup PLL1 Frequency from pre-calculated value */ +/** + * brief Set PLL1 output from PLL setup structure (precise frequency) + * param pSetup : Pointer to populated PLL setup structure + * return kStatus_PLL_Success on success, or PLL setup error code + * note This function will power off the PLL, setup the PLL with the + * new setup data, and then optionally powerup the PLL, wait for PLL lock, + * and adjust system voltages to the new PLL rate. The function will not + * alter any source clocks (ie, main systen clock) that may use the PLL, + * so these should be setup prior to and after exiting the function. + */ +pll_error_t CLOCK_SetPLL1Freq(const pll_setup_t *pSetup) +{ + uint32_t inRate, clkRate, prediv; + uint32_t pll_lock_wait_time = 0U; + uint32_t max_pll_lock_wait_time = 0U; + /* Power off PLL during setup changes */ + POWER_EnablePD(kPDRUNCFG_PD_PLL1); + + /* Write PLL setup data */ + SYSCON->PLL1CTRL = pSetup->pllctrl; + SYSCON->PLL1NDEC = pSetup->pllndec; + SYSCON->PLL1NDEC = pSetup->pllndec | (1UL << SYSCON_PLL1NDEC_NREQ_SHIFT); /* latch */ + SYSCON->PLL1PDEC = pSetup->pllpdec; + SYSCON->PLL1PDEC = pSetup->pllpdec | (1UL << SYSCON_PLL1PDEC_PREQ_SHIFT); /* latch */ + SYSCON->PLL1MDEC = pSetup->pllmdec; + SYSCON->PLL1MDEC = pSetup->pllmdec | (1UL << SYSCON_PLL1MDEC_MREQ_SHIFT); /* latch */ + + POWER_DisablePD(kPDRUNCFG_PD_PLL1); + + if ((pSetup->flags & PLL_SETUPFLAG_WAITLOCK) != 0U) + { + inRate = CLOCK_GetPLL1InClockRate(); + prediv = findPll1PreDiv(); + /* Adjust input clock */ + clkRate = inRate / prediv; + + /* Need wait at least (500us + 400/Fref) (Fref in Hz result in s) to ensure the PLL is stable. + The lock bit could be used to shorten the wait time when freq<20MHZ */ + max_pll_lock_wait_time = 500U + (400000000U / clkRate); + + if (clkRate < 20000000UL) + { + pll_lock_wait_time = 0U; + while ((CLOCK_IsPLL1Locked() == false) && (pll_lock_wait_time < max_pll_lock_wait_time)) + { + pll_lock_wait_time += 100U; + SDK_DelayAtLeastUs(100U, SDK_DEVICE_MAXIMUM_CPU_CLOCK_FREQUENCY); + } + } + else + { + SDK_DelayAtLeastUs(max_pll_lock_wait_time, SDK_DEVICE_MAXIMUM_CPU_CLOCK_FREQUENCY); + } + } + + /* Update current programmed PLL rate var */ + s_Pll1_Freq = pSetup->pllRate; + + return kStatus_PLL_Success; +} + +/* Set PLL0 clock based on the input frequency and multiplier */ +/*! brief Set PLL0 output based on the multiplier and input frequency + * param multiply_by : multiplier + * param input_freq : Clock input frequency of the PLL + * return Nothing + * note Unlike the Chip_Clock_SetupSystemPLLPrec() function, this + * function does not disable or enable PLL power, wait for PLL lock, + * or adjust system voltages. These must be done in the application. + * The function will not alter any source clocks (ie, main systen clock) + * that may use the PLL, so these should be setup prior to and after + * exiting the function. + */ +void CLOCK_SetupPLL0Mult(uint32_t multiply_by, uint32_t input_freq) +{ + uint32_t cco_freq = input_freq * multiply_by; + uint32_t pdec = 1U; + uint32_t selr; + uint32_t seli; + uint32_t selp; + uint32_t mdec, ndec; + + while (cco_freq < 275000000U) + { + multiply_by <<= 1U; /* double value in each iteration */ + pdec <<= 1U; /* correspondingly double pdec to cancel effect of double msel */ + cco_freq = input_freq * multiply_by; + } + + selr = 0U; + + if (multiply_by >= 8000UL) + { + seli = 1UL; + } + else if (multiply_by >= 122UL) + { + seli = (uint32_t)(8000UL / multiply_by); /*floor(8000/M) */ + } + else + { + seli = 2UL * ((uint32_t)(multiply_by / 4UL)) + 3UL; /* 2*floor(M/4) + 3 */ + } + + if (seli >= 63U) + { + seli = 63U; + } + + { + selp = 31U; + } + + if (pdec > 1U) + { + pdec = pdec / 2U; /* Account for minus 1 encoding */ + /* Translate P value */ + } + + mdec = (uint32_t)PLL_SSCG1_MDEC_VAL_SET(multiply_by); + ndec = 0x1U; /* pre divide by 1 (hardcoded) */ + + SYSCON->PLL0CTRL = SYSCON_PLL0CTRL_CLKEN_MASK | SYSCON_PLL0CTRL_BYPASSPOSTDIV(0) | + SYSCON_PLL0CTRL_BYPASSPOSTDIV2(0) | (selr << SYSCON_PLL0CTRL_SELR_SHIFT) | + (seli << SYSCON_PLL0CTRL_SELI_SHIFT) | (selp << SYSCON_PLL0CTRL_SELP_SHIFT); + SYSCON->PLL0PDEC = pdec | (1UL << SYSCON_PLL0PDEC_PREQ_SHIFT); /* set Pdec value and assert preq */ + SYSCON->PLL0NDEC = ndec | (1UL << SYSCON_PLL0NDEC_NREQ_SHIFT); /* set Pdec value and assert preq */ + SYSCON->PLL0SSCG1 = + mdec | (1UL << SYSCON_PLL0SSCG1_MREQ_SHIFT); /* select non sscg MDEC value, assert mreq and select mdec value */ +} + +/* Enable USB DEVICE FULL SPEED clock */ +/*! brief Enable USB Device FS clock. + * param src : clock source + * param freq: clock frequency + * Enable USB Device Full Speed clock. + */ +bool CLOCK_EnableUsbfs0DeviceClock(clock_usbfs_src_t src, uint32_t freq) +{ + bool ret = true; + + CLOCK_DisableClock(kCLOCK_Usbd0); + + if (kCLOCK_UsbfsSrcFro == src) + { + switch (freq) + { + case 96000000U: + CLOCK_SetClkDiv(kCLOCK_DivUsb0Clk, 2, false); /*!< Div by 2 to get 48MHz, no divider reset */ + break; + + default: + ret = false; + break; + } + /* Turn ON FRO HF */ + POWER_DisablePD(kPDRUNCFG_PD_FRO192M); + /* Enable FRO 96MHz output */ + ANACTRL->FRO192M_CTRL = + ANACTRL->FRO192M_CTRL | ANACTRL_FRO192M_CTRL_ENA_96MHZCLK_MASK | ANACTRL_FRO192M_CTRL_USBCLKADJ_MASK; + /* Select FRO 96 or 48 MHz */ + CLOCK_AttachClk(kFRO_HF_to_USB0_CLK); + } + else + { + /*!< Configure XTAL32M */ + POWER_DisablePD(kPDRUNCFG_PD_XTAL32M); /* Ensure XTAL32M is powered */ + POWER_DisablePD(kPDRUNCFG_PD_LDOXO32M); /* Ensure XTAL32M is powered */ + (void)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 */ + + /*!< Set up PLL1 */ + POWER_DisablePD(kPDRUNCFG_PD_PLL1); + CLOCK_AttachClk(kEXT_CLK_to_PLL1); /*!< Switch PLL1CLKSEL to EXT_CLK */ + const pll_setup_t pll1Setup = { + .pllctrl = SYSCON_PLL1CTRL_CLKEN_MASK | SYSCON_PLL1CTRL_SELI(19U) | SYSCON_PLL1CTRL_SELP(9U), + .pllndec = SYSCON_PLL1NDEC_NDIV(1U), + .pllpdec = SYSCON_PLL1PDEC_PDIV(5U), + .pllmdec = SYSCON_PLL1MDEC_MDIV(30U), + .pllRate = 48000000U, + .flags = PLL_SETUPFLAG_WAITLOCK}; + (void)CLOCK_SetPLL1Freq(&pll1Setup); + + CLOCK_SetClkDiv(kCLOCK_DivUsb0Clk, 1U, false); + CLOCK_AttachClk(kPLL1_to_USB0_CLK); + SDK_DelayAtLeastUs(50U, SDK_DEVICE_MAXIMUM_CPU_CLOCK_FREQUENCY); + } + CLOCK_EnableClock(kCLOCK_Usbd0); + CLOCK_EnableClock(kCLOCK_UsbRam1); + + return ret; +} + +/* Enable USB HOST FULL SPEED clock */ +/*! brief Enable USB HOST FS clock. + * param src : clock source + * param freq: clock frequency + * Enable USB HOST Full Speed clock. + */ +bool CLOCK_EnableUsbfs0HostClock(clock_usbfs_src_t src, uint32_t freq) +{ + bool ret = true; + + CLOCK_DisableClock(kCLOCK_Usbhmr0); + CLOCK_DisableClock(kCLOCK_Usbhsl0); + + if (kCLOCK_UsbfsSrcFro == src) + { + switch (freq) + { + case 96000000U: + CLOCK_SetClkDiv(kCLOCK_DivUsb0Clk, 2, false); /*!< Div by 2 to get 48MHz, no divider reset */ + break; + + default: + ret = false; + break; + } + /* Turn ON FRO HF */ + POWER_DisablePD(kPDRUNCFG_PD_FRO192M); + /* Enable FRO 96MHz output */ + ANACTRL->FRO192M_CTRL = ANACTRL->FRO192M_CTRL | ANACTRL_FRO192M_CTRL_ENA_96MHZCLK_MASK; + /* Select FRO 96 MHz */ + CLOCK_AttachClk(kFRO_HF_to_USB0_CLK); + } + else + { + /*!< Configure XTAL32M */ + POWER_DisablePD(kPDRUNCFG_PD_XTAL32M); /* Ensure XTAL32M is powered */ + POWER_DisablePD(kPDRUNCFG_PD_LDOXO32M); /* Ensure XTAL32M is powered */ + (void)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 */ + + /*!< Set up PLL1 */ + POWER_DisablePD(kPDRUNCFG_PD_PLL1); + CLOCK_AttachClk(kEXT_CLK_to_PLL1); /*!< Switch PLL1CLKSEL to EXT_CLK */ + const pll_setup_t pll1Setup = { + .pllctrl = SYSCON_PLL1CTRL_CLKEN_MASK | SYSCON_PLL1CTRL_SELI(19U) | SYSCON_PLL1CTRL_SELP(9U), + .pllndec = SYSCON_PLL1NDEC_NDIV(1U), + .pllpdec = SYSCON_PLL1PDEC_PDIV(5U), + .pllmdec = SYSCON_PLL1MDEC_MDIV(30U), + .pllRate = 48000000U, + .flags = PLL_SETUPFLAG_WAITLOCK}; + (void)CLOCK_SetPLL1Freq(&pll1Setup); + + CLOCK_SetClkDiv(kCLOCK_DivUsb0Clk, 1U, false); + CLOCK_AttachClk(kPLL1_to_USB0_CLK); + SDK_DelayAtLeastUs(50U, SDK_DEVICE_MAXIMUM_CPU_CLOCK_FREQUENCY); + } + CLOCK_EnableClock(kCLOCK_Usbhmr0); + CLOCK_EnableClock(kCLOCK_Usbhsl0); + CLOCK_EnableClock(kCLOCK_UsbRam1); + + return ret; +} + +/* Enable USB PHY clock */ +bool CLOCK_EnableUsbhs0PhyPllClock(clock_usb_phy_src_t src, uint32_t freq) +{ + volatile uint32_t i; + uint32_t phyPllDiv = 0U; + uint16_t multiplier = 0U; + bool ret = true; + + POWER_DisablePD(kPDRUNCFG_PD_XTAL32M); + POWER_DisablePD(kPDRUNCFG_PD_LDOXO32M); + POWER_DisablePD(kPDRUNCFG_PD_FRO32K); /*!< Ensure FRO32k is on */ + POWER_DisablePD(kPDRUNCFG_PD_XTAL32K); /*!< Ensure xtal32k is on */ + POWER_DisablePD(kPDRUNCFG_PD_USB1_PHY); /*!< Ensure xtal32k is on */ + POWER_DisablePD(kPDRUNCFG_PD_LDOUSBHS); /*!< Ensure xtal32k is on */ + + SYSCON->AHBCLKCTRLSET[2] = SYSCON_AHBCLKCTRL2_ANALOG_CTRL(1); + SYSCON->AHBCLKCTRLSET[2] = SYSCON_AHBCLKCTRL2_USB1_PHY(1); + + /* wait to make sure PHY power is fully up */ + i = 100000U; + while ((i--) != 0U) + { + __ASM("nop"); + } + + USBPHY->CTRL_CLR = USBPHY_CTRL_SFTRST_MASK; + + multiplier = (uint16_t)(480000000UL / freq); + + switch (multiplier) + { + case 15U: + { + phyPllDiv = USBPHY_PLL_SIC_PLL_DIV_SEL(0U); + break; + } + case 16U: + { + phyPllDiv = USBPHY_PLL_SIC_PLL_DIV_SEL(1U); + break; + } + case 20U: + { + phyPllDiv = USBPHY_PLL_SIC_PLL_DIV_SEL(2U); + break; + } + case 24U: + { + phyPllDiv = USBPHY_PLL_SIC_PLL_DIV_SEL(4U); + break; + } + case 25U: + { + phyPllDiv = USBPHY_PLL_SIC_PLL_DIV_SEL(5U); + break; + } + case 30U: + { + phyPllDiv = USBPHY_PLL_SIC_PLL_DIV_SEL(6U); + break; + } + case 40U: + { + phyPllDiv = USBPHY_PLL_SIC_PLL_DIV_SEL(7U); + break; + } + default: + { + ret = false; + break; + } + } + + if (ret) + { + USBPHY->PLL_SIC = (USBPHY->PLL_SIC & ~USBPHY_PLL_SIC_PLL_DIV_SEL(0x7)) | phyPllDiv; + USBPHY->PLL_SIC_SET = USBPHY_PLL_SIC_SET_PLL_REG_ENABLE_MASK; + USBPHY->PLL_SIC_CLR = (1UL << 16U); // Reserved. User must set this bit to 0x0 + USBPHY->PLL_SIC_SET = USBPHY_PLL_SIC_SET_PLL_POWER_MASK; + USBPHY->PLL_SIC_SET = USBPHY_PLL_SIC_SET_PLL_EN_USB_CLKS_MASK; + + USBPHY->CTRL_CLR = USBPHY_CTRL_CLR_CLKGATE_MASK; + } + + return ret; +} + +/* Enable USB DEVICE HIGH SPEED clock */ +bool CLOCK_EnableUsbhs0DeviceClock(clock_usbhs_src_t src, uint32_t freq) +{ + SYSCON->AHBCLKCTRLSET[2] = SYSCON_AHBCLKCTRL2_USB1_RAM(1); + SYSCON->AHBCLKCTRLSET[2] = SYSCON_AHBCLKCTRL2_USB1_DEV(1); + + /* 16 MHz will be driven by the tb on the xtal1 pin of XTAL32M */ + SYSCON->CLOCK_CTRL |= SYSCON_CLOCK_CTRL_CLKIN_ENA_MASK; /* Enable clock_in clock for clock module. */ + ANACTRL->XO32M_CTRL |= ANACTRL_XO32M_CTRL_ENABLE_PLL_USB_OUT(1); + return true; +} + +/* Enable USB HOST HIGH SPEED clock */ +bool CLOCK_EnableUsbhs0HostClock(clock_usbhs_src_t src, uint32_t freq) +{ + SYSCON->AHBCLKCTRLSET[2] = SYSCON_AHBCLKCTRL2_USB1_RAM(1); + SYSCON->AHBCLKCTRLSET[2] = SYSCON_AHBCLKCTRL2_USB1_HOST(1); + + /* 16 MHz will be driven by the tb on the xtal1 pin of XTAL32M */ + SYSCON->CLOCK_CTRL |= SYSCON_CLOCK_CTRL_CLKIN_ENA_MASK; /* Enable clock_in clock for clock module. */ + ANACTRL->XO32M_CTRL |= ANACTRL_XO32M_CTRL_ENABLE_PLL_USB_OUT(1); + + return true; +} + +/*! @brief Enable the OSTIMER 32k clock. + * @return Nothing + */ +void CLOCK_EnableOstimer32kClock(void) +{ + PMC->OSTIMERr |= PMC_OSTIMER_CLOCKENABLE_MASK; +} diff --git a/drivers/Src/fsl_common.c b/drivers/Src/fsl_common.c new file mode 100644 index 0000000..d3af9fd --- /dev/null +++ b/drivers/Src/fsl_common.c @@ -0,0 +1,85 @@ +/* + * Copyright (c) 2015-2016, Freescale Semiconductor, Inc. + * Copyright 2016-2021 NXP + * All rights reserved. + * + * SPDX-License-Identifier: BSD-3-Clause + */ + +#include "fsl_common.h" + +#define SDK_MEM_MAGIC_NUMBER 12345U + +typedef struct _mem_align_control_block +{ + uint16_t identifier; /*!< Identifier for the memory control block. */ + uint16_t offset; /*!< offset from aligned address to real address */ +} mem_align_cb_t; + +/* Component ID definition, used by tools. */ +#ifndef FSL_COMPONENT_ID +#define FSL_COMPONENT_ID "platform.drivers.common" +#endif + +#if !((defined(__DSC__) && defined(__CW__))) +void *SDK_Malloc(size_t size, size_t alignbytes) +{ + mem_align_cb_t *p_cb = NULL; + uint32_t alignedsize; + + /* Check overflow. */ + alignedsize = (uint32_t)(unsigned int)SDK_SIZEALIGN(size, alignbytes); + if (alignedsize < size) + { + return NULL; + } + + if (alignedsize > SIZE_MAX - alignbytes - sizeof(mem_align_cb_t)) + { + return NULL; + } + + alignedsize += alignbytes + (uint32_t)sizeof(mem_align_cb_t); + + union + { + void *pointer_value; + uintptr_t unsigned_value; + } p_align_addr, p_addr; + + p_addr.pointer_value = malloc((size_t)alignedsize); + + if (p_addr.pointer_value == NULL) + { + return NULL; + } + + p_align_addr.unsigned_value = SDK_SIZEALIGN(p_addr.unsigned_value + sizeof(mem_align_cb_t), alignbytes); + + p_cb = (mem_align_cb_t *)(p_align_addr.unsigned_value - 4U); + p_cb->identifier = SDK_MEM_MAGIC_NUMBER; + p_cb->offset = (uint16_t)(p_align_addr.unsigned_value - p_addr.unsigned_value); + + return p_align_addr.pointer_value; +} + +void SDK_Free(void *ptr) +{ + union + { + void *pointer_value; + uintptr_t unsigned_value; + } p_free; + p_free.pointer_value = ptr; + mem_align_cb_t *p_cb = (mem_align_cb_t *)(p_free.unsigned_value - 4U); + + if (p_cb->identifier != SDK_MEM_MAGIC_NUMBER) + { + return; + } + + p_free.unsigned_value = p_free.unsigned_value - p_cb->offset; + + free(p_free.pointer_value); +} +#endif diff --git a/drivers/Src/fsl_common_arm.c b/drivers/Src/fsl_common_arm.c new file mode 100644 index 0000000..e9f32aa --- /dev/null +++ b/drivers/Src/fsl_common_arm.c @@ -0,0 +1,257 @@ +/* + * Copyright (c) 2015-2016, Freescale Semiconductor, Inc. + * Copyright 2016-2021, 2023 NXP + * All rights reserved. + * + * SPDX-License-Identifier: BSD-3-Clause + */ + +#include "fsl_common.h" + +/* Component ID definition, used by tools. */ +#ifndef FSL_COMPONENT_ID +#define FSL_COMPONENT_ID "platform.drivers.common_arm" +#endif + +#ifndef __GIC_PRIO_BITS +#if defined(ENABLE_RAM_VECTOR_TABLE) +uint32_t InstallIRQHandler(IRQn_Type irq, uint32_t irqHandler) +{ +#ifdef __VECTOR_TABLE +#undef __VECTOR_TABLE +#endif + +/* Addresses for VECTOR_TABLE and VECTOR_RAM come from the linker file */ +#if defined(__CC_ARM) || defined(__ARMCC_VERSION) + extern uint32_t Image$$VECTOR_ROM$$Base[]; + extern uint32_t Image$$VECTOR_RAM$$Base[]; + extern uint32_t Image$$VECTOR_RAM$$ZI$$Limit[]; + +#define __VECTOR_TABLE Image$$VECTOR_ROM$$Base +#define __VECTOR_RAM Image$$VECTOR_RAM$$Base +#define __RAM_VECTOR_TABLE_SIZE (((uint32_t)Image$$VECTOR_RAM$$ZI$$Limit - (uint32_t)Image$$VECTOR_RAM$$Base)) +#elif defined(__ICCARM__) + extern uint32_t __RAM_VECTOR_TABLE_SIZE[]; + extern uint32_t __VECTOR_TABLE[]; + extern uint32_t __VECTOR_RAM[]; +#elif defined(__GNUC__) + extern uint32_t __VECTOR_TABLE[]; + extern uint32_t __VECTOR_RAM[]; + extern uint32_t __RAM_VECTOR_TABLE_SIZE_BYTES[]; + uint32_t __RAM_VECTOR_TABLE_SIZE = (uint32_t)(__RAM_VECTOR_TABLE_SIZE_BYTES); +#endif /* defined(__CC_ARM) || defined(__ARMCC_VERSION) */ + uint32_t n; + uint32_t ret; + uint32_t irqMaskValue; + + irqMaskValue = DisableGlobalIRQ(); + if (SCB->VTOR != (uint32_t)__VECTOR_RAM) + { + /* Copy the vector table from ROM to RAM */ + for (n = 0; n < ((uint32_t)__RAM_VECTOR_TABLE_SIZE) / sizeof(uint32_t); n++) + { + __VECTOR_RAM[n] = __VECTOR_TABLE[n]; + } + /* Point the VTOR to the position of vector table */ + SCB->VTOR = (uint32_t)__VECTOR_RAM; + } + + ret = __VECTOR_RAM[(int32_t)irq + 16]; + /* make sure the __VECTOR_RAM is noncachable */ + __VECTOR_RAM[(int32_t)irq + 16] = irqHandler; + + EnableGlobalIRQ(irqMaskValue); + + return ret; +} +#endif /* ENABLE_RAM_VECTOR_TABLE. */ +#endif /* __GIC_PRIO_BITS. */ + +#if (defined(FSL_FEATURE_SOC_SYSCON_COUNT) && (FSL_FEATURE_SOC_SYSCON_COUNT > 0)) + +/* + * When FSL_FEATURE_POWERLIB_EXTEND is defined to non-zero value, + * powerlib should be used instead of these functions. + */ +#if !(defined(FSL_FEATURE_POWERLIB_EXTEND) && (FSL_FEATURE_POWERLIB_EXTEND != 0)) + +/* + * When the SYSCON STARTER registers are discontinuous, these functions are + * implemented in fsl_power.c. + */ +#if !(defined(FSL_FEATURE_SYSCON_STARTER_DISCONTINUOUS) && FSL_FEATURE_SYSCON_STARTER_DISCONTINUOUS) + +void EnableDeepSleepIRQ(IRQn_Type interrupt) +{ + uint32_t intNumber = (uint32_t)interrupt; + + uint32_t index = 0; + + while (intNumber >= 32u) + { + index++; + intNumber -= 32u; + } + + SYSCON->STARTERSET[index] = 1UL << intNumber; + (void)EnableIRQ(interrupt); /* also enable interrupt at NVIC */ +} + +void DisableDeepSleepIRQ(IRQn_Type interrupt) +{ + uint32_t intNumber = (uint32_t)interrupt; + + (void)DisableIRQ(interrupt); /* also disable interrupt at NVIC */ + uint32_t index = 0; + + while (intNumber >= 32u) + { + index++; + intNumber -= 32u; + } + + SYSCON->STARTERCLR[index] = 1UL << intNumber; +} +#endif /* FSL_FEATURE_SYSCON_STARTER_DISCONTINUOUS */ +#endif /* FSL_FEATURE_POWERLIB_EXTEND */ +#endif /* FSL_FEATURE_SOC_SYSCON_COUNT */ + +#if defined(DWT) +/* Use WDT. */ +void MSDK_EnableCpuCycleCounter(void) +{ + /* Make sure the DWT trace fucntion is enabled. */ + if (CoreDebug_DEMCR_TRCENA_Msk != (CoreDebug_DEMCR_TRCENA_Msk & CoreDebug->DEMCR)) + { + CoreDebug->DEMCR |= CoreDebug_DEMCR_TRCENA_Msk; + } + + /* CYCCNT not supported on this device. */ + assert(DWT_CTRL_NOCYCCNT_Msk != (DWT->CTRL & DWT_CTRL_NOCYCCNT_Msk)); + + /* Read CYCCNT directly if CYCCENT has already been enabled, otherwise enable CYCCENT first. */ + if (DWT_CTRL_CYCCNTENA_Msk != (DWT_CTRL_CYCCNTENA_Msk & DWT->CTRL)) + { + DWT->CTRL |= DWT_CTRL_CYCCNTENA_Msk; + } +} + +uint32_t MSDK_GetCpuCycleCount(void) +{ + return DWT->CYCCNT; +} +#endif /* defined(DWT) */ + +#if !(defined(SDK_DELAY_USE_DWT) && defined(DWT)) +/* Use software loop. */ +#if defined(__CC_ARM) /* This macro is arm v5 specific */ +/* clang-format off */ +__ASM static void DelayLoop(uint32_t count) +{ +loop + SUBS R0, R0, #1 + CMP R0, #0 + BNE loop + BX LR +} +#elif defined(__ARM_ARCH_8A__) /* This macro is ARMv8-A specific */ +static void DelayLoop(uint32_t count) +{ + __ASM volatile(" MOV X0, %0" : : "r"(count)); + __ASM volatile( + "loop%=: \n" + " SUB X0, X0, #1 \n" + " CMP X0, #0 \n" + + " BNE loop%= \n" + : + : + : "r0"); +} +/* clang-format on */ +#elif defined(__ARMCC_VERSION) || defined(__ICCARM__) || defined(__GNUC__) +/* Cortex-M0 has a smaller instruction set, SUBS isn't supported in thumb-16 mode reported from __GNUC__ compiler, + * use SUB and CMP here for compatibility */ +static void DelayLoop(uint32_t count) +{ + __ASM volatile(" MOV R0, %0" : : "r"(count)); + __ASM volatile( + "loop%=: \n" +#if defined(__GNUC__) && !defined(__ARMCC_VERSION) + " SUB R0, R0, #1 \n" +#else + " SUBS R0, R0, #1 \n" +#endif + " CMP R0, #0 \n" + + " BNE loop%= \n" + : + : + : "r0"); +} +#endif /* defined(__CC_ARM) */ +#endif /* defined(SDK_DELAY_USE_DWT) && defined(DWT) */ + +/*! + * @brief Delay at least for some time. + * Please note that, if not uses DWT, this API will use while loop for delay, different run-time environments have + * effect on the delay time. If precise delay is needed, please enable DWT delay. The two parmeters delayTime_us and + * coreClock_Hz have limitation. For example, in the platform with 1GHz coreClock_Hz, the delayTime_us only supports + * up to 4294967 in current code. If long time delay is needed, please implement a new delay function. + * + * @param delayTime_us Delay time in unit of microsecond. + * @param coreClock_Hz Core clock frequency with Hz. + */ +void SDK_DelayAtLeastUs(uint32_t delayTime_us, uint32_t coreClock_Hz) +{ + uint64_t count; + + if (delayTime_us > 0U) + { + count = USEC_TO_COUNT(delayTime_us, coreClock_Hz); + + assert(count <= UINT32_MAX); + +#if defined(SDK_DELAY_USE_DWT) && defined(DWT) /* Use DWT for better accuracy */ + + MSDK_EnableCpuCycleCounter(); + /* Calculate the count ticks. */ + count += MSDK_GetCpuCycleCount(); + + if (count > UINT32_MAX) + { + count -= UINT32_MAX; + /* Wait for cyccnt overflow. */ + while (count < MSDK_GetCpuCycleCount()) + { + } + } + + /* Wait for cyccnt reach count value. */ + while (count > MSDK_GetCpuCycleCount()) + { + } +#else +#if defined(__CORTEX_Axx) && ((__CORTEX_Axx == 53) || (__CORTEX_Axx == 55)) + /* + * Cortex-A53/A55 execution throughput: + * - SUB/CMP: 2 instructions per cycle + * - BNE: 1 instruction per cycle + * So, each loop takes 2 CPU cycles. + */ + count = count / 2U; +#elif (__CORTEX_M == 7) + /* Divide value may be different in various environment to ensure delay is precise. + * Every loop count includes three instructions, due to Cortex-M7 sometimes executes + * two instructions in one period, through test here set divide 1.5. Other M cores use + * divide 4. By the way, divide 1.5 or 4 could let the count lose precision, but it does + * not matter because other instructions outside while loop is enough to fill the time. + */ + count = count / 3U * 2U; +#else + count = count / 4U; +#endif + DelayLoop((uint32_t)count); +#endif /* defined(SDK_DELAY_USE_DWT) && defined(DWT) */ + } +} diff --git a/drivers/Src/fsl_component_generic_list.c b/drivers/Src/fsl_component_generic_list.c new file mode 100644 index 0000000..5644f38 --- /dev/null +++ b/drivers/Src/fsl_component_generic_list.c @@ -0,0 +1,499 @@ +/* + * Copyright 2018-2019, 2022 NXP + * All rights reserved. + * + * + * SPDX-License-Identifier: BSD-3-Clause + */ + +/*! ********************************************************************************* +************************************************************************************* +* Include +************************************************************************************* +********************************************************************************** */ +#include "fsl_component_generic_list.h" + +#if defined(OSA_USED) +#include "fsl_os_abstraction.h" +#if (defined(USE_RTOS) && (USE_RTOS > 0U)) +#define LIST_ENTER_CRITICAL() \ + OSA_SR_ALLOC(); \ + OSA_ENTER_CRITICAL() +#define LIST_EXIT_CRITICAL() OSA_EXIT_CRITICAL() +#else +#define LIST_ENTER_CRITICAL() uint32_t regPrimask = DisableGlobalIRQ(); +#define LIST_EXIT_CRITICAL() EnableGlobalIRQ(regPrimask); +#endif +#else +#define LIST_ENTER_CRITICAL() uint32_t regPrimask = DisableGlobalIRQ(); +#define LIST_EXIT_CRITICAL() EnableGlobalIRQ(regPrimask); +#endif + +static list_status_t LIST_Error_Check(list_handle_t list, list_element_handle_t newElement) +{ + list_status_t listStatus = kLIST_Ok; +#if (defined(GENERIC_LIST_DUPLICATED_CHECKING) && (GENERIC_LIST_DUPLICATED_CHECKING > 0U)) + list_element_handle_t element = list->head; +#endif + if ((list->max != 0U) && (list->max == list->size)) + { + listStatus = kLIST_Full; /*List is full*/ + } +#if (defined(GENERIC_LIST_DUPLICATED_CHECKING) && (GENERIC_LIST_DUPLICATED_CHECKING > 0U)) + else + { + while (element != NULL) /*Scan list*/ + { + /* Determine if element is duplicated */ + if (element == newElement) + { + listStatus = kLIST_DuplicateError; + break; + } + element = element->next; + } + } +#endif + return listStatus; +} + +/*! ********************************************************************************* +************************************************************************************* +* Public functions +************************************************************************************* +********************************************************************************** */ +/*! ********************************************************************************* + * \brief Initializes the list descriptor. + * + * \param[in] list - LIST_ handle to init. + * max - Maximum number of elements in list. 0 for unlimited. + * + * \return void. + * + * \pre + * + * \post + * + * \remarks + * + ********************************************************************************** */ +void LIST_Init(list_handle_t list, uint32_t max) +{ + list->head = NULL; + list->tail = NULL; + list->max = max; + list->size = 0; +} + +/*! ********************************************************************************* + * \brief Gets the list that contains the given element. + * + * \param[in] element - Handle of the element. + * + * \return NULL if element is orphan. + * Handle of the list the element is inserted into. + * + * \pre + * + * \post + * + * \remarks + * + ********************************************************************************** */ +list_handle_t LIST_GetList(list_element_handle_t listElement) +{ + return listElement->list; +} + +/*! ********************************************************************************* + * \brief Links element to the tail of the list. + * + * \param[in] list - ID of list to insert into. + * element - element to add + * + * \return kLIST_Full if list is full. + * kLIST_Ok if insertion was successful. + * + * \pre + * + * \post + * + * \remarks + * + ********************************************************************************** */ +list_status_t LIST_AddTail(list_handle_t list, list_element_handle_t listElement) +{ + LIST_ENTER_CRITICAL(); + list_status_t listStatus = kLIST_Ok; + + listStatus = LIST_Error_Check(list, listElement); + if (listStatus == kLIST_Ok) /* Avoiding list status error */ + { + if (list->size == 0U) + { + list->head = listElement; + } + else + { + list->tail->next = listElement; + } +#if (defined(GENERIC_LIST_LIGHT) && (GENERIC_LIST_LIGHT > 0U)) +#else + listElement->prev = list->tail; +#endif + listElement->list = list; + listElement->next = NULL; + list->tail = listElement; + list->size++; + } + + LIST_EXIT_CRITICAL(); + return listStatus; +} + +/*! ********************************************************************************* + * \brief Links element to the head of the list. + * + * \param[in] list - ID of list to insert into. + * element - element to add + * + * \return kLIST_Full if list is full. + * kLIST_Ok if insertion was successful. + * + * \pre + * + * \post + * + * \remarks + * + ********************************************************************************** */ +list_status_t LIST_AddHead(list_handle_t list, list_element_handle_t listElement) +{ + LIST_ENTER_CRITICAL(); + list_status_t listStatus = kLIST_Ok; + + listStatus = LIST_Error_Check(list, listElement); + if (listStatus == kLIST_Ok) /* Avoiding list status error */ + { + /* Links element to the head of the list */ + if (list->size == 0U) + { + list->tail = listElement; + } +#if (defined(GENERIC_LIST_LIGHT) && (GENERIC_LIST_LIGHT > 0U)) +#else + else + { + list->head->prev = listElement; + } + listElement->prev = NULL; +#endif + listElement->list = list; + listElement->next = list->head; + list->head = listElement; + list->size++; + } + + LIST_EXIT_CRITICAL(); + return listStatus; +} + +/*! ********************************************************************************* + * \brief Unlinks element from the head of the list. + * + * \param[in] list - ID of list to remove from. + * + * \return NULL if list is empty. + * ID of removed element(pointer) if removal was successful. + * + * \pre + * + * \post + * + * \remarks + * + ********************************************************************************** */ +list_element_handle_t LIST_RemoveHead(list_handle_t list) +{ + list_element_handle_t listElement; + + LIST_ENTER_CRITICAL(); + + if ((NULL == list) || (list->size == 0U)) + { + listElement = NULL; /*LIST_ is empty*/ + } + else + { + listElement = list->head; + list->size--; + if (list->size == 0U) + { + list->tail = NULL; + } +#if (defined(GENERIC_LIST_LIGHT) && (GENERIC_LIST_LIGHT > 0U)) +#else + else + { + listElement->next->prev = NULL; + } +#endif + listElement->list = NULL; + list->head = listElement->next; /*Is NULL if element is head*/ + } + + LIST_EXIT_CRITICAL(); + return listElement; +} + +/*! ********************************************************************************* + * \brief Gets head element ID. + * + * \param[in] list - ID of list. + * + * \return NULL if list is empty. + * ID of head element if list is not empty. + * + * \pre + * + * \post + * + * \remarks + * + ********************************************************************************** */ +list_element_handle_t LIST_GetHead(list_handle_t list) +{ + return list->head; +} + +/*! ********************************************************************************* + * \brief Gets next element ID. + * + * \param[in] element - ID of the element. + * + * \return NULL if element is tail. + * ID of next element if exists. + * + * \pre + * + * \post + * + * \remarks + * + ********************************************************************************** */ +list_element_handle_t LIST_GetNext(list_element_handle_t listElement) +{ + return listElement->next; +} + +/*! ********************************************************************************* + * \brief Gets previous element ID. + * + * \param[in] element - ID of the element. + * + * \return NULL if element is head. + * ID of previous element if exists. + * + * \pre + * + * \post + * + * \remarks + * + ********************************************************************************** */ +list_element_handle_t LIST_GetPrev(list_element_handle_t listElement) +{ +#if (defined(GENERIC_LIST_LIGHT) && (GENERIC_LIST_LIGHT > 0U)) + return NULL; +#else + return listElement->prev; +#endif +} + +/*! ********************************************************************************* + * \brief Unlinks an element from its list. + * + * \param[in] element - ID of the element to remove. + * + * \return kLIST_OrphanElement if element is not part of any list. + * kLIST_Ok if removal was successful. + * + * \pre + * + * \post + * + * \remarks + * + ********************************************************************************** */ +list_status_t LIST_RemoveElement(list_element_handle_t listElement) +{ + list_status_t listStatus = kLIST_Ok; + LIST_ENTER_CRITICAL(); + + if (listElement->list == NULL) + { + listStatus = kLIST_OrphanElement; /*Element was previusly removed or never added*/ + } + else + { +#if (defined(GENERIC_LIST_LIGHT) && (GENERIC_LIST_LIGHT > 0U)) + list_element_handle_t element_list = listElement->list->head; + list_element_handle_t element_Prev = NULL; + while (NULL != element_list) + { + if (listElement->list->head == listElement) + { + listElement->list->head = element_list->next; + break; + } + if (element_list->next == listElement) + { + element_Prev = element_list; + element_list->next = listElement->next; + break; + } + element_list = element_list->next; + } + if (listElement->next == NULL) + { + listElement->list->tail = element_Prev; + } +#else + if (listElement->prev == NULL) /*Element is head or solo*/ + { + listElement->list->head = listElement->next; /*is null if solo*/ + } + if (listElement->next == NULL) /*Element is tail or solo*/ + { + listElement->list->tail = listElement->prev; /*is null if solo*/ + } + if (listElement->prev != NULL) /*Element is not head*/ + { + listElement->prev->next = listElement->next; + } + if (listElement->next != NULL) /*Element is not tail*/ + { + listElement->next->prev = listElement->prev; + } +#endif + listElement->list->size--; + listElement->list = NULL; + } + + LIST_EXIT_CRITICAL(); + return listStatus; +} + +/*! ********************************************************************************* + * \brief Links an element in the previous position relative to a given member + * of a list. + * + * \param[in] element - ID of a member of a list. + * newElement - new element to insert before the given member. + * + * \return kLIST_OrphanElement if element is not part of any list. + * kLIST_Full if list is full. + * kLIST_Ok if insertion was successful. + * + * \pre + * + * \post + * + * \remarks + * + ********************************************************************************** */ +list_status_t LIST_AddPrevElement(list_element_handle_t listElement, list_element_handle_t newElement) +{ + list_status_t listStatus = kLIST_Ok; + LIST_ENTER_CRITICAL(); + + if (listElement->list == NULL) + { + listStatus = kLIST_OrphanElement; /*Element was previusly removed or never added*/ + } + else + { + listStatus = LIST_Error_Check(listElement->list, newElement); + if (listStatus == kLIST_Ok) + { +#if (defined(GENERIC_LIST_LIGHT) && (GENERIC_LIST_LIGHT > 0U)) + list_element_handle_t element_list = listElement->list->head; + while (NULL != element_list) + { + if ((element_list->next == listElement) || (element_list == listElement)) + { + if (element_list == listElement) + { + listElement->list->head = newElement; + } + else + { + element_list->next = newElement; + } + newElement->list = listElement->list; + newElement->next = listElement; + listElement->list->size++; + break; + } + element_list = element_list->next; + } + +#else + if (listElement->prev == NULL) /*Element is list head*/ + { + listElement->list->head = newElement; + } + else + { + listElement->prev->next = newElement; + } + newElement->list = listElement->list; + listElement->list->size++; + newElement->next = listElement; + newElement->prev = listElement->prev; + listElement->prev = newElement; +#endif + } + } + + LIST_EXIT_CRITICAL(); + return listStatus; +} + +/*! ********************************************************************************* + * \brief Gets the current size of a list. + * + * \param[in] list - ID of the list. + * + * \return Current size of the list. + * + * \pre + * + * \post + * + * \remarks + * + ********************************************************************************** */ +uint32_t LIST_GetSize(list_handle_t list) +{ + return list->size; +} + +/*! ********************************************************************************* + * \brief Gets the number of free places in the list. + * + * \param[in] list - ID of the list. + * + * \return Available size of the list. + * + * \pre + * + * \post + * + * \remarks + * + ********************************************************************************** */ +uint32_t LIST_GetAvailableSize(list_handle_t list) +{ + return (list->max - list->size); /*Gets the number of free places in the list*/ +} diff --git a/drivers/Src/fsl_debug_console.c b/drivers/Src/fsl_debug_console.c new file mode 100644 index 0000000..faaf3e0 --- /dev/null +++ b/drivers/Src/fsl_debug_console.c @@ -0,0 +1,1450 @@ +/* + * Copyright 2017-2018, 2020, 2022NXP + * All rights reserved. + * + * + * SPDX-License-Identifier: BSD-3-Clause + * + */ + +#include +#include +#if defined(__CC_ARM) || defined(__ARMCC_VERSION) +#include +#endif +#include +#include "fsl_debug_console.h" +#include "fsl_adapter_uart.h" +#include "fsl_str.h" + +/*! @brief Keil: suppress ellipsis warning in va_arg usage below. */ +#if defined(__CC_ARM) +#pragma diag_suppress 1256 +#endif /* __CC_ARM */ + +/******************************************************************************* + * Definitions + ******************************************************************************/ + +/*! @brief This definition is maximum line that debugconsole can scanf each time.*/ +#define IO_MAXLINE 20U + +/*! @brief The overflow value.*/ +#ifndef HUGE_VAL +#define HUGE_VAL (99.e99) +#endif /* HUGE_VAL */ + +/*! @brief State structure storing debug console. */ +typedef struct DebugConsoleState +{ + uint8_t uartHandleBuffer[HAL_UART_HANDLE_SIZE]; + hal_uart_status_t (*putChar)(hal_uart_handle_t handle, + const uint8_t *data, + size_t length); /*!< put char function pointer */ + hal_uart_status_t (*getChar)(hal_uart_handle_t handle, + uint8_t *data, + size_t length); /*!< get char function pointer */ + serial_port_type_t serial_port_type; /*!< The initialized port of the debug console. */ +} debug_console_state_t; + +/*! @brief Type of KSDK printf function pointer. */ +typedef int (*PUTCHAR_FUNC)(int a); + +/******************************************************************************* + * Variables + ******************************************************************************/ +#if ((SDK_DEBUGCONSOLE == DEBUGCONSOLE_REDIRECT_TO_SDK) || defined(SDK_DEBUGCONSOLE_UART)) +/*! @brief Debug UART state information. */ +static debug_console_state_t s_debugConsole; +#endif + +/******************************************************************************* + * Prototypes + ******************************************************************************/ +#if (defined(SDK_DEBUGCONSOLE) && (SDK_DEBUGCONSOLE == DEBUGCONSOLE_REDIRECT_TO_SDK)) +static int DbgConsole_PrintfFormattedData(PUTCHAR_FUNC func_ptr, const char *fmt, va_list ap); +#endif /* SDK_DEBUGCONSOLE */ + +/******************************************************************************* + * Code + ******************************************************************************/ + +/*************Code for DbgConsole Init, Deinit, Printf, Scanf *******************************/ + +#if ((SDK_DEBUGCONSOLE == DEBUGCONSOLE_REDIRECT_TO_SDK) || defined(SDK_DEBUGCONSOLE_UART)) +/* See fsl_debug_console.h for documentation of this function. */ +status_t DbgConsole_Init(uint8_t instance, uint32_t baudRate, serial_port_type_t device, uint32_t clkSrcFreq) +{ + hal_uart_config_t usrtConfig; + + if (kSerialPort_Uart != device) + { + return kStatus_Fail; + } + + /* Set debug console to initialized to avoid duplicated initialized operation. */ + s_debugConsole.serial_port_type = device; + + usrtConfig.srcClock_Hz = clkSrcFreq; + usrtConfig.baudRate_Bps = baudRate; + usrtConfig.parityMode = kHAL_UartParityDisabled; + usrtConfig.stopBitCount = kHAL_UartOneStopBit; + usrtConfig.enableRx = 1U; + usrtConfig.enableTx = 1U; + usrtConfig.enableRxRTS = 0U; + usrtConfig.enableTxCTS = 0U; + usrtConfig.instance = instance; +#if (defined(HAL_UART_ADAPTER_FIFO) && (HAL_UART_ADAPTER_FIFO > 0u)) + usrtConfig.txFifoWatermark = 0U; + usrtConfig.rxFifoWatermark = 0U; +#endif + /* Enable clock and initial UART module follow user configure structure. */ + (void)HAL_UartInit((hal_uart_handle_t)&s_debugConsole.uartHandleBuffer[0], &usrtConfig); + /* Set the function pointer for send and receive for this kind of device. */ + s_debugConsole.putChar = HAL_UartSendBlocking; + s_debugConsole.getChar = HAL_UartReceiveBlocking; + + return kStatus_Success; +} + +/* See fsl_debug_console.h for documentation of this function. */ +status_t DbgConsole_Deinit(void) +{ + if (kSerialPort_None == s_debugConsole.serial_port_type) + { + return kStatus_Success; + } + + (void)HAL_UartDeinit((hal_uart_handle_t)&s_debugConsole.uartHandleBuffer[0]); + + s_debugConsole.serial_port_type = kSerialPort_None; + return kStatus_Success; +} + +/* See fsl_debug_console.h for documentation of this function. */ +status_t DbgConsole_EnterLowpower(void) +{ + hal_uart_status_t DbgConsoleUartStatus = kStatus_HAL_UartError; + if (kSerialPort_Uart == s_debugConsole.serial_port_type) + { + DbgConsoleUartStatus = HAL_UartEnterLowpower((hal_uart_handle_t)&s_debugConsole.uartHandleBuffer[0]); + } + return (status_t)DbgConsoleUartStatus; +} + +/* See fsl_debug_console.h for documentation of this function. */ +status_t DbgConsole_ExitLowpower(void) +{ + hal_uart_status_t DbgConsoleUartStatus = kStatus_HAL_UartError; + if (kSerialPort_Uart == s_debugConsole.serial_port_type) + { + DbgConsoleUartStatus = HAL_UartExitLowpower((hal_uart_handle_t)&s_debugConsole.uartHandleBuffer[0]); + } + return (status_t)DbgConsoleUartStatus; +} + +#endif /* DEBUGCONSOLE_REDIRECT_TO_SDK */ + +#if (defined(SDK_DEBUGCONSOLE) && (SDK_DEBUGCONSOLE == DEBUGCONSOLE_REDIRECT_TO_SDK)) +/* See fsl_debug_console.h for documentation of this function. */ +int DbgConsole_Printf(const char *fmt_s, ...) +{ + va_list ap; + int result = 0; + + va_start(ap, fmt_s); + result = DbgConsole_Vprintf(fmt_s, ap); + va_end(ap); + + return result; +} + +/* See fsl_debug_console.h for documentation of this function. */ +int DbgConsole_Vprintf(const char *fmt_s, va_list formatStringArg) +{ + int result = 0; + + /* Do nothing if the debug UART is not initialized. */ + if (kSerialPort_None == s_debugConsole.serial_port_type) + { + return -1; + } + + result = DbgConsole_PrintfFormattedData(DbgConsole_Putchar, fmt_s, formatStringArg); + + return result; +} + +/* See fsl_debug_console.h for documentation of this function. */ +int DbgConsole_Putchar(int dbgConsoleCh) +{ + /* Do nothing if the debug UART is not initialized. */ + if (kSerialPort_None == s_debugConsole.serial_port_type) + { + return -1; + } + (void)s_debugConsole.putChar((hal_uart_handle_t)&s_debugConsole.uartHandleBuffer[0], (uint8_t *)(&dbgConsoleCh), 1); + + return 1; +} + +/* See fsl_debug_console.h for documentation of this function. */ +int DbgConsole_Scanf(char *fmt_s, ...) +{ + /* Plus one to store end of string char */ + char temp_buf[IO_MAXLINE + 1]; + va_list ap; + int32_t i; + char result; + + /* Do nothing if the debug UART is not initialized. */ + if (kSerialPort_None == s_debugConsole.serial_port_type) + { + return -1; + } + va_start(ap, fmt_s); + temp_buf[0] = '\0'; + + i = 0; + while (true) + { + if (i >= (int32_t)IO_MAXLINE) + { + break; + } + + result = (char)DbgConsole_Getchar(); + temp_buf[i] = result; + + if ((result == '\r') || (result == '\n')) + { + /* End of Line. */ + if (i == 0) + { + temp_buf[i] = '\0'; + i = -1; + } + else + { + break; + } + } + + i++; + } + + if (i == (int32_t)IO_MAXLINE) + { + temp_buf[i] = '\0'; + } + else + { + temp_buf[i + 1] = '\0'; + } + result = (char)StrFormatScanf(temp_buf, fmt_s, ap); + va_end(ap); + + return (int)result; +} + +/* See fsl_debug_console.h for documentation of this function. */ +int DbgConsole_Getchar(void) +{ + char dbgConsoleCh; + /* Do nothing if the debug UART is not initialized. */ + if (kSerialPort_None == s_debugConsole.serial_port_type) + { + return -1; + } + while (kStatus_HAL_UartSuccess != + s_debugConsole.getChar((hal_uart_handle_t)&s_debugConsole.uartHandleBuffer[0], (uint8_t *)(&dbgConsoleCh), 1)) + { + return -1; + } + + return (int)dbgConsoleCh; +} + +/*************Code for process formatted data*******************************/ +/*! + * @brief This function puts padding character. + * + * @param[in] c Padding character. + * @param[in] curlen Length of current formatted string . + * @param[in] width Width of expected formatted string. + * @param[in] count Number of characters. + * @param[in] func_ptr Function to put character out. + */ +static void DbgConsole_PrintfPaddingCharacter( + char c, int32_t curlen, int32_t width, int32_t *count, PUTCHAR_FUNC func_ptr) +{ + int32_t i; + + for (i = curlen; i < width; i++) + { + (void)func_ptr(c); + (*count)++; + } +} + +/*! + * @brief Converts a radix number to a string and return its length. + * + * @param[in] numstr Converted string of the number. + * @param[in] nump Pointer to the number. + * @param[in] neg Polarity of the number. + * @param[in] radix The radix to be converted to. + * @param[in] use_caps Used to identify %x/X output format. + + * @return Length of the converted string. + */ +static int32_t DbgConsole_ConvertRadixNumToString(char *numstr, void *nump, int32_t neg, int32_t radix, bool use_caps) +{ +#if PRINTF_ADVANCED_ENABLE + long long int a; + long long int b; + long long int c; + + unsigned long long int ua; + unsigned long long int ub; + unsigned long long int uc; + unsigned long long int uc_param; +#else + int a; + int b; + int c; + + unsigned int ua; + unsigned int ub; + unsigned int uc; + unsigned int uc_param; +#endif /* PRINTF_ADVANCED_ENABLE */ + + int32_t nlen; + char *nstrp; + + nlen = 0; + nstrp = numstr; + *nstrp++ = '\0'; + +#if !(PRINTF_ADVANCED_ENABLE > 0) + neg = 0; +#endif + +#if PRINTF_ADVANCED_ENABLE + a = 0; + b = 0; + c = 0; + ua = 0ULL; + ub = 0ULL; + uc = 0ULL; + uc_param = 0ULL; +#else + a = 0; + b = 0; + c = 0; + ua = 0U; + ub = 0U; + uc = 0U; + uc_param = 0U; +#endif /* PRINTF_ADVANCED_ENABLE */ + + (void)a; + (void)b; + (void)c; + (void)ua; + (void)ub; + (void)uc; + (void)uc_param; + (void)neg; + /* + * Fix MISRA issue: CID 15985711 (#15 of 15): MISRA C-2012 Control Flow Expressions (MISRA C-2012 Rule 14.3) + * misra_c_2012_rule_14_3_violation: Execution cannot reach this statement: a = *((int *)nump); + */ +#if PRINTF_ADVANCED_ENABLE + if (0 != neg) + { +#if PRINTF_ADVANCED_ENABLE + a = *(long long int *)nump; +#else + a = *(int *)nump; +#endif /* PRINTF_ADVANCED_ENABLE */ + if (a == 0) + { + *nstrp = '0'; + ++nlen; + return nlen; + } + while (a != 0) + { +#if PRINTF_ADVANCED_ENABLE + b = (long long int)a / (long long int)radix; + c = (long long int)a - ((long long int)b * (long long int)radix); + if (c < 0) + { + uc = (unsigned long long int)c; + uc_param = ~uc; + c = (long long int)uc_param + 1 + (long long int)'0'; + } +#else + b = (int)a / (int)radix; + c = (int)a - ((int)b * (int)radix); + if (c < 0) + { + uc = (unsigned int)c; + uc_param = ~uc; + c = (int)uc_param + 1 + (int)'0'; + } +#endif /* PRINTF_ADVANCED_ENABLE */ + else + { + c = c + (int)'0'; + } + a = b; + *nstrp++ = (char)c; + ++nlen; + } + } + else +#endif /* PRINTF_ADVANCED_ENABLE */ + { +#if PRINTF_ADVANCED_ENABLE + ua = *(unsigned long long int *)nump; +#else + ua = *(unsigned int *)nump; +#endif /* PRINTF_ADVANCED_ENABLE */ + if (ua == 0U) + { + *nstrp = '0'; + ++nlen; + return nlen; + } + while (ua != 0U) + { +#if PRINTF_ADVANCED_ENABLE + ub = (unsigned long long int)ua / (unsigned long long int)radix; + uc = (unsigned long long int)ua - ((unsigned long long int)ub * (unsigned long long int)radix); +#else + ub = ua / (unsigned int)radix; + uc = ua - (ub * (unsigned int)radix); +#endif /* PRINTF_ADVANCED_ENABLE */ + + if (uc < 10U) + { + uc = uc + (unsigned int)'0'; + } + else + { + uc = uc - 10U + (unsigned int)(use_caps ? 'A' : 'a'); + } + ua = ub; + *nstrp++ = (char)uc; + ++nlen; + } + } + return nlen; +} + +#if PRINTF_FLOAT_ENABLE +/*! + * @brief Converts a floating radix number to a string and return its length. + * + * @param[in] numstr Converted string of the number. + * @param[in] nump Pointer to the number. + * @param[in] radix The radix to be converted to. + * @param[in] precision_width Specify the precision width. + + * @return Length of the converted string. + */ +static int32_t DbgConsole_ConvertFloatRadixNumToString(char *numstr, + void *nump, + int32_t radix, + uint32_t precision_width) +{ + int32_t a; + int32_t b; + int32_t c; + uint32_t i; + double fa; + double dc; + double fb; + double r; + double fractpart; + double intpart; + + int32_t nlen; + char *nstrp; + nlen = 0; + nstrp = numstr; + *nstrp++ = '\0'; + r = *(double *)nump; + if (0.0 == r) + { + *nstrp = '0'; + ++nlen; + return nlen; + } + fractpart = modf((double)r, (double *)&intpart); + /* Process fractional part. */ + for (i = 0; i < precision_width; i++) + { + fractpart *= (double)radix; + } + if (r >= 0.0) + { + fa = fractpart + (double)0.5; + if (fa >= pow((double)10, (double)precision_width)) + { + intpart++; + } + } + else + { + fa = fractpart - (double)0.5; + if (fa <= -pow((double)10, (double)precision_width)) + { + intpart--; + } + } + for (i = 0; i < precision_width; i++) + { + fb = fa / (double)radix; + dc = (fa - (double)(long long int)fb * (double)radix); + c = (int32_t)dc; + if (c < 0) + { + c = (int32_t)'0' - c; + } + else + { + c = c + '0'; + } + fa = fb; + *nstrp++ = (char)c; + ++nlen; + } + *nstrp++ = (char)'.'; + ++nlen; + a = (int32_t)intpart; + if (a == 0) + { + *nstrp++ = '0'; + ++nlen; + } + else + { + while (a != 0) + { + b = (int32_t)a / (int32_t)radix; + c = (int32_t)a - ((int32_t)b * (int32_t)radix); + if (c < 0) + { + c = (int32_t)'0' - c; + } + else + { + c = c + '0'; + } + a = b; + *nstrp++ = (char)c; + ++nlen; + } + } + return nlen; +} +#endif /* PRINTF_FLOAT_ENABLE */ + +/*! + * @brief This function outputs its parameters according to a formatted string. + * + * @note I/O is performed by calling given function pointer using following + * (*func_ptr)(c); + * + * @param[in] func_ptr Function to put character out. + * @param[in] fmt Format string for printf. + * @param[in] ap Arguments to printf. + * + * @return Number of characters + */ +static int DbgConsole_PrintfFormattedData(PUTCHAR_FUNC func_ptr, const char *fmt, va_list ap) +{ + /* va_list ap; */ + const char *p; + char c; + + char vstr[33]; + char *vstrp = NULL; + int32_t vlen = 0; + + bool done; + int32_t count = 0; + + uint32_t field_width; + uint32_t precision_width; + char *sval; + int32_t cval; + bool use_caps; + uint8_t radix = 0; + +#if PRINTF_ADVANCED_ENABLE + uint32_t flags_used; + char schar; + bool dschar; + long long int ival; + unsigned long long int uval = 0; + bool valid_precision_width; +#else + int ival; + unsigned int uval = 0; +#endif /* PRINTF_ADVANCED_ENABLE */ + +#if PRINTF_FLOAT_ENABLE + double fval; +#endif /* PRINTF_FLOAT_ENABLE */ + + /* Start parsing apart the format string and display appropriate formats and data. */ + p = fmt; + while (true) + { + if ('\0' == *p) + { + break; + } + c = *p; + /* + * All formats begin with a '%' marker. Special chars like + * '\n' or '\t' are normally converted to the appropriate + * character by the __compiler__. Thus, no need for this + * routine to account for the '\' character. + */ + if (c != '%') + { + (void)func_ptr(c); + count++; + p++; + /* By using 'continue', the next iteration of the loop is used, skipping the code that follows. */ + continue; + } + + use_caps = true; + +#if PRINTF_ADVANCED_ENABLE + /* First check for specification modifier flags. */ + flags_used = 0; + done = false; + while (!done) + { + switch (*++p) + { + case '-': + flags_used |= (uint32_t)kPRINTF_Minus; + break; + case '+': + flags_used |= (uint32_t)kPRINTF_Plus; + break; + case ' ': + flags_used |= (uint32_t)kPRINTF_Space; + break; + case '0': + flags_used |= (uint32_t)kPRINTF_Zero; + break; + case '#': + flags_used |= (uint32_t)kPRINTF_Pound; + break; + default: + /* We've gone one char too far. */ + --p; + done = true; + break; + } + } +#endif /* PRINTF_ADVANCED_ENABLE */ + + /* Next check for minimum field width. */ + field_width = 0; + done = false; + while (!done) + { + c = *++p; + if ((c >= '0') && (c <= '9')) + { + field_width = (field_width * 10U) + ((uint32_t)c - (uint32_t)'0'); + } +#if PRINTF_ADVANCED_ENABLE + else if (c == '*') + { + field_width = (uint32_t)va_arg(ap, unsigned int); + } +#endif /* PRINTF_ADVANCED_ENABLE */ + else + { + /* We've gone one char too far. */ + --p; + done = true; + } + } + /* Next check for the width and precision field separator. */ +#if (PRINTF_ADVANCED_ENABLE || PRINTF_FLOAT_ENABLE) + precision_width = 6U; /* MISRA C-2012 Rule 2.2 */ +#endif +#if PRINTF_ADVANCED_ENABLE + valid_precision_width = false; +#endif /* PRINTF_ADVANCED_ENABLE */ + if (*++p == '.') + { + /* Must get precision field width, if present. */ + precision_width = 0U; + done = false; + while (!done) + { + c = *++p; + if ((c >= '0') && (c <= '9')) + { + precision_width = (precision_width * 10U) + ((uint32_t)c - (uint32_t)'0'); +#if PRINTF_ADVANCED_ENABLE + valid_precision_width = true; +#endif /* PRINTF_ADVANCED_ENABLE */ + } +#if PRINTF_ADVANCED_ENABLE + else if (c == '*') + { + precision_width = (uint32_t)va_arg(ap, unsigned int); + valid_precision_width = true; + } +#endif /* PRINTF_ADVANCED_ENABLE */ + else + { + /* We've gone one char too far. */ + --p; + done = true; + } + } + } + else + { + /* We've gone one char too far. */ + --p; + } +#if PRINTF_ADVANCED_ENABLE + /* + * Check for the length modifier. + */ + switch (/* c = */ *++p) + { + case 'h': + if (*++p != 'h') + { + flags_used |= (uint32_t)kPRINTF_LengthShortInt; + --p; + } + else + { + flags_used |= (uint32_t)kPRINTF_LengthChar; + } + break; + case 'l': + if (*++p != 'l') + { + flags_used |= (uint32_t)kPRINTF_LengthLongInt; + --p; + } + else + { + flags_used |= (uint32_t)kPRINTF_LengthLongLongInt; + } + break; + case 'z': + if (sizeof(size_t) == sizeof(uint32_t)) + { + flags_used |= (uint32_t)kPRINTF_LengthLongInt; + } + else if (sizeof(size_t) == (2U * sizeof(uint32_t))) + { + flags_used |= (uint32_t)kPRINTF_LengthLongLongInt; + } + else if (sizeof(size_t) == sizeof(uint16_t)) + { + flags_used |= (uint32_t)kPRINTF_LengthShortInt; + } + else + { + /* MISRA C-2012 Rule 15.7 */ + } + break; + default: + /* we've gone one char too far */ + --p; + break; + } +#endif /* PRINTF_ADVANCED_ENABLE */ + /* Now we're ready to examine the format. */ + c = *++p; + { + if ((c == 'd') || (c == 'i') || (c == 'f') || (c == 'F') || (c == 'x') || (c == 'X') || (c == 'o') || + (c == 'b') || (c == 'p') || (c == 'u')) + { + if ((c == 'd') || (c == 'i')) + { +#if PRINTF_ADVANCED_ENABLE + if (0U != (flags_used & (uint32_t)kPRINTF_LengthLongLongInt)) + { + ival = (long long int)va_arg(ap, long long int); + } + else if (0U != (flags_used & (uint32_t)kPRINTF_LengthLongInt)) + { + ival = (long int)va_arg(ap, long int); + } + else +#endif /* PRINTF_ADVANCED_ENABLE */ + { + ival = (int)va_arg(ap, int); + } + vlen = DbgConsole_ConvertRadixNumToString(vstr, &ival, 1, 10, use_caps); + vstrp = &vstr[vlen]; +#if PRINTF_ADVANCED_ENABLE + if (ival < 0) + { + schar = '-'; + ++vlen; + } + else + { + if (0U != (flags_used & (uint32_t)kPRINTF_Plus)) + { + schar = '+'; + ++vlen; + } + else + { + if (0U != (flags_used & (uint32_t)kPRINTF_Space)) + { + schar = ' '; + ++vlen; + } + else + { + schar = '\0'; + } + } + } + dschar = false; + /* Do the ZERO pad. */ + if (0U != (flags_used & (uint32_t)kPRINTF_Zero)) + { + if ('\0' != schar) + { + (void)func_ptr(schar); + count++; + } + dschar = true; + + DbgConsole_PrintfPaddingCharacter('0', vlen, (int32_t)field_width, &count, func_ptr); + vlen = (int32_t)field_width; + } + else + { + if (0U == (flags_used & (uint32_t)kPRINTF_Minus)) + { + DbgConsole_PrintfPaddingCharacter(' ', vlen, (int32_t)field_width, &count, func_ptr); + if ('\0' != schar) + { + (void)func_ptr(schar); + count++; + } + dschar = true; + } + } + /* The string was built in reverse order, now display in correct order. */ + if ((!dschar) && ('\0' != schar)) + { + (void)func_ptr(schar); + count++; + } +#endif /* PRINTF_ADVANCED_ENABLE */ + } + +#if PRINTF_FLOAT_ENABLE + if ((c == 'f') || (c == 'F')) + { + fval = (double)va_arg(ap, double); + vlen = DbgConsole_ConvertFloatRadixNumToString(vstr, &fval, 10, precision_width); + vstrp = &vstr[vlen]; + +#if PRINTF_ADVANCED_ENABLE + if (fval < 0.0) + { + schar = '-'; + ++vlen; + } + else + { + if (0U != (flags_used & (uint32_t)kPRINTF_Plus)) + { + schar = '+'; + ++vlen; + } + else + { + if (0U != (flags_used & (uint32_t)kPRINTF_Space)) + { + schar = ' '; + ++vlen; + } + else + { + schar = '\0'; + } + } + } + dschar = false; + if (0U != (flags_used & (uint32_t)kPRINTF_Zero)) + { + if ('\0' != schar) + { + (void)func_ptr(schar); + count++; + } + dschar = true; + DbgConsole_PrintfPaddingCharacter('0', vlen, (int32_t)field_width, &count, func_ptr); + vlen = (int32_t)field_width; + } + else + { + if (0U == (flags_used & (uint32_t)kPRINTF_Minus)) + { + DbgConsole_PrintfPaddingCharacter(' ', vlen, (int32_t)field_width, &count, func_ptr); + if ('\0' != schar) + { + (void)func_ptr(schar); + count++; + } + dschar = true; + } + } + if ((!dschar) && ('\0' != schar)) + { + (void)func_ptr(schar); + count++; + } +#endif /* PRINTF_ADVANCED_ENABLE */ + } +#endif /* PRINTF_FLOAT_ENABLE */ + if ((c == 'X') || (c == 'x')) + { + if (c == 'x') + { + use_caps = false; + } +#if PRINTF_ADVANCED_ENABLE + if (0U != (flags_used & (uint32_t)kPRINTF_LengthLongLongInt)) + { + uval = (unsigned long long int)va_arg(ap, unsigned long long int); + } + else if (0U != (flags_used & (uint32_t)kPRINTF_LengthLongInt)) + { + uval = (unsigned long int)va_arg(ap, unsigned long int); + } + else +#endif /* PRINTF_ADVANCED_ENABLE */ + { + uval = (unsigned int)va_arg(ap, unsigned int); + } + vlen = DbgConsole_ConvertRadixNumToString(vstr, &uval, 0, 16, use_caps); + vstrp = &vstr[vlen]; + +#if PRINTF_ADVANCED_ENABLE + dschar = false; + if (0U != (flags_used & (uint32_t)kPRINTF_Zero)) + { + if (0U != (flags_used & (uint32_t)kPRINTF_Pound)) + { + (void)func_ptr('0'); + (void)func_ptr((use_caps ? 'X' : 'x')); + count += 2; + /*vlen += 2;*/ + dschar = true; + } + DbgConsole_PrintfPaddingCharacter('0', vlen, (int32_t)field_width, &count, func_ptr); + vlen = (int32_t)field_width; + } + else + { + if (0U == (flags_used & (uint32_t)kPRINTF_Minus)) + { + if (0U != (flags_used & (uint32_t)kPRINTF_Pound)) + { + vlen += 2; + } + DbgConsole_PrintfPaddingCharacter(' ', vlen, (int32_t)field_width, &count, func_ptr); + if (0U != (flags_used & (uint32_t)kPRINTF_Pound)) + { + (void)func_ptr('0'); + (void)func_ptr(use_caps ? 'X' : 'x'); + count += 2; + + dschar = true; + } + } + } + + if ((0U != (flags_used & (uint32_t)kPRINTF_Pound)) && (!dschar)) + { + (void)func_ptr('0'); + (void)func_ptr(use_caps ? 'X' : 'x'); + count += 2; + vlen += 2; + } +#endif /* PRINTF_ADVANCED_ENABLE */ + } + if ((c == 'o') || (c == 'b') || (c == 'p') || (c == 'u')) + { + if ('p' == c) + { + /* + * Fix MISRA issue: CID 16209727 (#15 of 15): MISRA C-2012 Pointer Type Conversions (MISRA + * C-2012 Rule 11.6) + * 1. misra_c_2012_rule_11_6_violation: The expression va_arg (ap, void *) of type void * is + * cast to type unsigned int. + * + * Orignal code: uval = (unsigned int)va_arg(ap, void *); + */ + void *pval; + pval = (void *)va_arg(ap, void *); + (void)memcpy((void *)&uval, (void *)&pval, sizeof(void *)); + } + else + { +#if PRINTF_ADVANCED_ENABLE + if (0U != (flags_used & (uint32_t)kPRINTF_LengthLongLongInt)) + { + uval = (unsigned long long int)va_arg(ap, unsigned long long int); + } + else if (0U != (flags_used & (uint32_t)kPRINTF_LengthLongInt)) + { + uval = (unsigned long int)va_arg(ap, unsigned long int); + } + else +#endif /* PRINTF_ADVANCED_ENABLE */ + { + uval = (unsigned int)va_arg(ap, unsigned int); + } + } + switch (c) + { + case 'o': + radix = 8; + break; + case 'b': + radix = 2; + break; + case 'p': + radix = 16; + break; + case 'u': + radix = 10; + break; + default: + /* MISRA C-2012 Rule 16.4 */ + break; + } + vlen = DbgConsole_ConvertRadixNumToString(vstr, &uval, 0, (int32_t)radix, use_caps); + vstrp = &vstr[vlen]; +#if PRINTF_ADVANCED_ENABLE + if (0U != (flags_used & (uint32_t)kPRINTF_Zero)) + { + DbgConsole_PrintfPaddingCharacter('0', vlen, (int32_t)field_width, &count, func_ptr); + vlen = (int32_t)field_width; + } + else + { + if (0U == (flags_used & (uint32_t)kPRINTF_Minus)) + { + DbgConsole_PrintfPaddingCharacter(' ', vlen, (int32_t)field_width, &count, func_ptr); + } + } +#endif /* PRINTF_ADVANCED_ENABLE */ + } +#if !PRINTF_ADVANCED_ENABLE + DbgConsole_PrintfPaddingCharacter(' ', vlen, (int32_t)field_width, &count, func_ptr); +#endif /* !PRINTF_ADVANCED_ENABLE */ + if (vstrp != NULL) + { + while ('\0' != *vstrp) + { + (void)func_ptr(*vstrp--); + count++; + } + } +#if PRINTF_ADVANCED_ENABLE + if (0U != (flags_used & (uint32_t)kPRINTF_Minus)) + { + DbgConsole_PrintfPaddingCharacter(' ', vlen, (int32_t)field_width, &count, func_ptr); + } +#endif /* PRINTF_ADVANCED_ENABLE */ + } + else if (c == 'c') + { + cval = (int32_t)va_arg(ap, unsigned int); + (void)func_ptr(cval); + count++; + } + else if (c == 's') + { + sval = (char *)va_arg(ap, char *); + if (NULL != sval) + { +#if PRINTF_ADVANCED_ENABLE + if (valid_precision_width) + { + vlen = (int32_t)precision_width; + } + else + { + vlen = (int32_t)strlen(sval); + } +#else + vlen = (int32_t)strlen(sval); +#endif /* PRINTF_ADVANCED_ENABLE */ +#if PRINTF_ADVANCED_ENABLE + if (0U == (flags_used & (uint32_t)kPRINTF_Minus)) +#endif /* PRINTF_ADVANCED_ENABLE */ + { + DbgConsole_PrintfPaddingCharacter(' ', vlen, (int32_t)field_width, &count, func_ptr); + } + +#if PRINTF_ADVANCED_ENABLE + if (valid_precision_width) + { + while (('\0' != *sval) && (vlen > 0)) + { + (void)func_ptr(*sval++); + count++; + vlen--; + } + /* In case that vlen sval is shorter than vlen */ + vlen = (int32_t)precision_width - vlen; + } + else + { +#endif /* PRINTF_ADVANCED_ENABLE */ + while ('\0' != *sval) + { + (void)func_ptr(*sval++); + count++; + } +#if PRINTF_ADVANCED_ENABLE + } +#endif /* PRINTF_ADVANCED_ENABLE */ + +#if PRINTF_ADVANCED_ENABLE + if (0U != (flags_used & (uint32_t)kPRINTF_Minus)) + { + DbgConsole_PrintfPaddingCharacter(' ', vlen, (int32_t)field_width, &count, func_ptr); + } +#endif /* PRINTF_ADVANCED_ENABLE */ + } + } + else + { + (void)func_ptr(c); + count++; + } + } + p++; + } + return count; +} + +#endif /* SDK_DEBUGCONSOLE */ + +/*************Code to support toolchain's printf, scanf *******************************/ +/* These function __write and __read is used to support IAR toolchain to printf and scanf*/ +#if (defined(__ICCARM__)) +#if defined(SDK_DEBUGCONSOLE_UART) +#pragma weak __write +size_t __write(int handle, const unsigned char *buffer, size_t size); +size_t __write(int handle, const unsigned char *buffer, size_t size) +{ + size_t ret; + if (NULL == buffer) + { + /* + * This means that we should flush internal buffers. Since we don't we just return. + * (Remember, "handle" == -1 means that all handles should be flushed.) + */ + ret = (size_t)0; + } + else if ((handle != 1) && (handle != 2)) + { + /* This function only writes to "standard out" and "standard err" for all other file handles it returns failure. + */ + ret = (size_t)-1; + } + else if (kSerialPort_None == s_debugConsole.serial_port_type) + { + /* Do nothing if the debug UART is not initialized. */ + ret = (size_t)-1; + } + else + { + /* Send data. */ + (void)s_debugConsole.putChar((hal_uart_handle_t)&s_debugConsole.uartHandleBuffer[0], buffer, size); + ret = size; + } + return ret; +} + +#pragma weak __read +size_t __read(int handle, unsigned char *buffer, size_t size); +size_t __read(int handle, unsigned char *buffer, size_t size) +{ + size_t ret; + /* This function only reads from "standard in", for all other file handles it returns failure. */ + if (handle != 0) + { + ret = ((size_t)-1); + } + else if (kSerialPort_None == s_debugConsole.serial_port_type) + { + /* Do nothing if the debug UART is not initialized. */ + ret = ((size_t)-1); + } + else + { + /* Receive data. */ + (void)s_debugConsole.getChar((hal_uart_handle_t)&s_debugConsole.uartHandleBuffer[0], buffer, size); + ret = size; + } + return ret; +} +#endif /* SDK_DEBUGCONSOLE_UART */ + +/* support LPC Xpresso with RedLib */ +#elif (defined(__REDLIB__)) + +#if (defined(SDK_DEBUGCONSOLE_UART)) +int __attribute__((weak)) __sys_write(int handle, char *buffer, int size) +{ + if (NULL == buffer) + { + /* return -1 if error. */ + return -1; + } + + /* This function only writes to "standard out" and "standard err" for all other file handles it returns failure. */ + if ((handle != 1) && (handle != 2)) + { + return -1; + } + + /* Do nothing if the debug UART is not initialized. */ + if (kSerialPort_None == s_debugConsole.serial_port_type) + { + return -1; + } + + /* Send data. */ + (void)s_debugConsole.putChar((hal_uart_handle_t)&s_debugConsole.uartHandleBuffer[0], (uint8_t *)buffer, size); + + return 0; +} + +int __attribute__((weak)) __sys_readc(void) +{ + char tmp; + /* Do nothing if the debug UART is not initialized. */ + if (kSerialPort_None == s_debugConsole.serial_port_type) + { + return -1; + } + + /* Receive data. */ + s_debugConsole.getChar((hal_uart_handle_t)&s_debugConsole.uartHandleBuffer[0], (uint8_t *)&tmp, sizeof(tmp)); + + return tmp; +} +#endif /* SDK_DEBUGCONSOLE_UART */ + +/* These function fputc and fgetc is used to support KEIL toolchain to printf and scanf*/ +#elif defined(__CC_ARM) || defined(__ARMCC_VERSION) +#if defined(SDK_DEBUGCONSOLE_UART) +#if defined(__CC_ARM) +struct __FILE +{ + int handle; + /* + * Whatever you require here. If the only file you are using is standard output using printf() for debugging, + * no file handling is required. + */ +}; +#endif + +/* FILE is typedef in stdio.h. */ +#pragma weak __stdout +#pragma weak __stdin +FILE __stdout; +FILE __stdin; + +#pragma weak fputc +int fputc(int ch, FILE *f) +{ + /* Do nothing if the debug UART is not initialized. */ + if (kSerialPort_None == s_debugConsole.serial_port_type) + { + return -1; + } + + /* Send data. */ + (void)s_debugConsole.putChar((hal_uart_handle_t)&s_debugConsole.uartHandleBuffer[0], (uint8_t *)(&ch), 1); + return 1; +} + +#pragma weak fgetc +int fgetc(FILE *f) +{ + char ch; + /* Do nothing if the debug UART is not initialized. */ + if (kSerialPort_None == s_debugConsole.serial_port_type) + { + return -1; + } + + /* Receive data. */ + s_debugConsole.getChar((hal_uart_handle_t)&s_debugConsole.uartHandleBuffer[0], (uint8_t *)(&ch), 1); + return ch; +} + +/* + * Terminate the program, passing a return code back to the user. + * This function may not return. + */ +void _sys_exit(int returncode) +{ + while (1) + { + } +} + +/* + * Writes a character to the output channel. This function is used + * for last-resort error message output. + */ +void _ttywrch(int ch) +{ + char ench = ch; + /* Send data. */ + s_debugConsole.putChar((hal_uart_handle_t)&s_debugConsole.uartHandleBuffer[0], (uint8_t *)(&ench), 1); +} + +char *_sys_command_string(char *cmd, int len) +{ + return (cmd); +} +#endif /* SDK_DEBUGCONSOLE_UART */ + +/* These function __write_r and __read_r are used to support Xtensa Clang toolchain to printf and scanf */ +#elif defined(__XTENSA__) && defined(__XT_CLANG__) +#if defined(SDK_DEBUGCONSOLE_UART) + +int __attribute__((weak)) _write_r(void *ptr, int handle, char *buffer, int size); +int __attribute__((weak)) _write_r(void *ptr, int handle, char *buffer, int size) +{ + if (NULL == buffer) + { + /* return -1 if error. */ + return -1; + } + + /* This function only writes to "standard out" and "standard err" for all other file handles it returns failure. */ + if ((handle != 1) && (handle != 2)) + { + return -1; + } + + /* Do nothing if the debug UART is not initialized. */ + if (kSerialPort_None == s_debugConsole.serial_port_type) + { + return -1; + } + + /* Send data. */ + (void)s_debugConsole.putChar((hal_uart_handle_t)&s_debugConsole.uartHandleBuffer[0], (uint8_t *)buffer, size); + + return size; +} + +int __attribute__((weak)) _read_r(void *ptr, int handle, char *buffer, int size); +int __attribute__((weak)) _read_r(void *ptr, int handle, char *buffer, int size) +{ + /* This function only reads from "standard in", for all other file handles it returns failure. */ + if (handle != 0) + { + return -1; + } + + /* Do nothing if the debug UART is not initialized. */ + if (kSerialPort_None == s_debugConsole.serial_port_type) + { + return -1; + } + + /* Receive data. */ + (void)s_debugConsole.getChar((hal_uart_handle_t)&s_debugConsole.uartHandleBuffer[0], (uint8_t *)buffer, size); + return size; +} +#endif /* SDK_DEBUGCONSOLE_UART */ + +/* These function __write and __read is used to support ARM_GCC, KDS, Atollic toolchains to printf and scanf*/ +#elif (defined(__GNUC__)) + +#if ((defined(__GNUC__) && (!defined(__MCUXPRESSO)) && (defined(SDK_DEBUGCONSOLE_UART))) || \ + (defined(__MCUXPRESSO) && (defined(SDK_DEBUGCONSOLE_UART)))) +int __attribute__((weak)) _write(int handle, char *buffer, int size); +int __attribute__((weak)) _write(int handle, char *buffer, int size) +{ + if (NULL == buffer) + { + /* return -1 if error. */ + return -1; + } + + /* This function only writes to "standard out" and "standard err" for all other file handles it returns failure. */ + if ((handle != 1) && (handle != 2)) + { + return -1; + } + + /* Do nothing if the debug UART is not initialized. */ + if (kSerialPort_None == s_debugConsole.serial_port_type) + { + return -1; + } + + /* Send data. */ + (void)s_debugConsole.putChar((hal_uart_handle_t)&s_debugConsole.uartHandleBuffer[0], (uint8_t *)buffer, size); + + return size; +} + +int __attribute__((weak)) _read(int handle, char *buffer, int size); +int __attribute__((weak)) _read(int handle, char *buffer, int size) +{ + /* This function only reads from "standard in", for all other file handles it returns failure. */ + if (handle != 0) + { + return -1; + } + + /* Do nothing if the debug UART is not initialized. */ + if (kSerialPort_None == s_debugConsole.serial_port_type) + { + return -1; + } + + /* Receive data. */ + (void)s_debugConsole.getChar((hal_uart_handle_t)&s_debugConsole.uartHandleBuffer[0], (uint8_t *)buffer, size); + return size; +} +#endif + +#endif /* __ICCARM__ */ diff --git a/drivers/Src/fsl_flexcomm.c b/drivers/Src/fsl_flexcomm.c new file mode 100644 index 0000000..890f8bf --- /dev/null +++ b/drivers/Src/fsl_flexcomm.c @@ -0,0 +1,401 @@ +/* + * Copyright (c) 2016, Freescale Semiconductor, Inc. + * Copyright 2016-2019 NXP + * All rights reserved. + * + * SPDX-License-Identifier: BSD-3-Clause + */ + +#include "fsl_common.h" +#include "fsl_flexcomm.h" + +/******************************************************************************* + * Definitions + ******************************************************************************/ + +/* Component ID definition, used by tools. */ +#ifndef FSL_COMPONENT_ID +#define FSL_COMPONENT_ID "platform.drivers.flexcomm" +#endif + +/******************************************************************************* + * Prototypes + ******************************************************************************/ +/*! @brief Set the FLEXCOMM mode . */ +static status_t FLEXCOMM_SetPeriph(FLEXCOMM_Type *base, FLEXCOMM_PERIPH_T periph, int lock); + +/*! @brief check whether flexcomm supports peripheral type */ +static bool FLEXCOMM_PeripheralIsPresent(FLEXCOMM_Type *base, FLEXCOMM_PERIPH_T periph); + +/******************************************************************************* + * Variables + ******************************************************************************/ + +/*! @brief Array to map FLEXCOMM instance number to base address. */ +static const uint32_t s_flexcommBaseAddrs[] = FLEXCOMM_BASE_ADDRS; + +/*! @brief Pointers to real IRQ handlers installed by drivers for each instance. */ +static flexcomm_irq_handler_t s_flexcommIrqHandler[ARRAY_SIZE(s_flexcommBaseAddrs)]; + +/*! @brief Pointers to handles for each instance to provide context to interrupt routines */ +static void *s_flexcommHandle[ARRAY_SIZE(s_flexcommBaseAddrs)]; + +/*! @brief Array to map FLEXCOMM instance number to IRQ number. */ +IRQn_Type const kFlexcommIrqs[] = FLEXCOMM_IRQS; + +#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) +/*! @brief IDs of clock for each FLEXCOMM module */ +static const clock_ip_name_t s_flexcommClocks[] = FLEXCOMM_CLOCKS; +#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */ + +#if !(defined(FSL_FEATURE_FLEXCOMM_HAS_NO_RESET) && FSL_FEATURE_FLEXCOMM_HAS_NO_RESET) +/*! @brief Pointers to FLEXCOMM resets for each instance. */ +static const reset_ip_name_t s_flexcommResets[] = FLEXCOMM_RSTS; +#endif + +/******************************************************************************* + * Code + ******************************************************************************/ + +/* check whether flexcomm supports peripheral type */ +static bool FLEXCOMM_PeripheralIsPresent(FLEXCOMM_Type *base, FLEXCOMM_PERIPH_T periph) +{ + if (periph == FLEXCOMM_PERIPH_NONE) + { + return true; + } + else if (periph <= FLEXCOMM_PERIPH_I2S_TX) + { + return (base->PSELID & (1UL << ((uint32_t)periph + 3U))) > 0UL ? true : false; + } + else if (periph == FLEXCOMM_PERIPH_I2S_RX) + { + return (base->PSELID & (1U << 7U)) > (uint32_t)0U ? true : false; + } + else + { + return false; + } +} + +/* Get the index corresponding to the FLEXCOMM */ +/*! brief Returns instance number for FLEXCOMM module with given base address. */ +uint32_t FLEXCOMM_GetInstance(void *base) +{ + uint32_t i; + + for (i = 0U; i < (uint32_t)FSL_FEATURE_SOC_FLEXCOMM_COUNT; i++) + { + if ((uintptr_t)(uint8_t*)base == s_flexcommBaseAddrs[i]) + { + break; + } + } + + assert(i < (uint32_t)FSL_FEATURE_SOC_FLEXCOMM_COUNT); + return i; +} + +/* Changes FLEXCOMM mode */ +static status_t FLEXCOMM_SetPeriph(FLEXCOMM_Type *base, FLEXCOMM_PERIPH_T periph, int lock) +{ + /* Check whether peripheral type is present */ + if (!FLEXCOMM_PeripheralIsPresent(base, periph)) + { + return kStatus_OutOfRange; + } + + /* Flexcomm is locked to different peripheral type than expected */ + if (((base->PSELID & FLEXCOMM_PSELID_LOCK_MASK) != 0U) && + ((base->PSELID & FLEXCOMM_PSELID_PERSEL_MASK) != (uint32_t)periph)) + { + return kStatus_Fail; + } + + /* Check if we are asked to lock */ + if (lock != 0) + { + base->PSELID = (uint32_t)periph | FLEXCOMM_PSELID_LOCK_MASK; + } + else + { + base->PSELID = (uint32_t)periph; + } + + return kStatus_Success; +} + +/*! brief Initializes FLEXCOMM and selects peripheral mode according to the second parameter. */ +status_t FLEXCOMM_Init(void *base, FLEXCOMM_PERIPH_T periph) +{ + uint32_t idx = FLEXCOMM_GetInstance(base); + +#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) + /* Enable the peripheral clock */ + CLOCK_EnableClock(s_flexcommClocks[idx]); +#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */ + +#if !(defined(FSL_FEATURE_FLEXCOMM_HAS_NO_RESET) && FSL_FEATURE_FLEXCOMM_HAS_NO_RESET) + /* Reset the FLEXCOMM module */ + RESET_PeripheralReset(s_flexcommResets[idx]); +#endif + + /* Set the FLEXCOMM to given peripheral */ + return FLEXCOMM_SetPeriph((FLEXCOMM_Type *)base, periph, 0); +} + +/*! brief Sets IRQ handler for given FLEXCOMM module. It is used by drivers register IRQ handler according to FLEXCOMM + * mode */ +void FLEXCOMM_SetIRQHandler(void *base, flexcomm_irq_handler_t handler, void *flexcommHandle) +{ + uint32_t instance; + + /* Look up instance number */ + instance = FLEXCOMM_GetInstance(base); + + /* Clear handler first to avoid execution of the handler with wrong handle */ + s_flexcommIrqHandler[instance] = NULL; + s_flexcommHandle[instance] = flexcommHandle; + s_flexcommIrqHandler[instance] = handler; + SDK_ISR_EXIT_BARRIER; +} + +/* IRQ handler functions overloading weak symbols in the startup */ +#if defined(FLEXCOMM0) +void FLEXCOMM0_DriverIRQHandler(void); +void FLEXCOMM0_DriverIRQHandler(void) +{ + uint32_t instance; + + /* Look up instance number */ + instance = FLEXCOMM_GetInstance(FLEXCOMM0); + assert(s_flexcommIrqHandler[instance] != NULL); + s_flexcommIrqHandler[instance]((uint32_t *)s_flexcommBaseAddrs[instance], s_flexcommHandle[instance]); + SDK_ISR_EXIT_BARRIER; +} +#endif + +#if defined(FLEXCOMM1) +void FLEXCOMM1_DriverIRQHandler(void); +void FLEXCOMM1_DriverIRQHandler(void) +{ + uint32_t instance; + + /* Look up instance number */ + instance = FLEXCOMM_GetInstance(FLEXCOMM1); + assert(s_flexcommIrqHandler[instance] != NULL); + s_flexcommIrqHandler[instance]((uint32_t *)s_flexcommBaseAddrs[instance], s_flexcommHandle[instance]); + SDK_ISR_EXIT_BARRIER; +} +#endif + +#if defined(FLEXCOMM2) +void FLEXCOMM2_DriverIRQHandler(void); +void FLEXCOMM2_DriverIRQHandler(void) +{ + uint32_t instance; + + /* Look up instance number */ + instance = FLEXCOMM_GetInstance(FLEXCOMM2); + assert(s_flexcommIrqHandler[instance] != NULL); + s_flexcommIrqHandler[instance]((uint32_t *)s_flexcommBaseAddrs[instance], s_flexcommHandle[instance]); + SDK_ISR_EXIT_BARRIER; +} +#endif + +#if defined(FLEXCOMM3) +void FLEXCOMM3_DriverIRQHandler(void); +void FLEXCOMM3_DriverIRQHandler(void) +{ + uint32_t instance; + + /* Look up instance number */ + instance = FLEXCOMM_GetInstance(FLEXCOMM3); + assert(s_flexcommIrqHandler[instance] != NULL); + s_flexcommIrqHandler[instance]((uint32_t *)s_flexcommBaseAddrs[instance], s_flexcommHandle[instance]); + SDK_ISR_EXIT_BARRIER; +} +#endif + +#if defined(FLEXCOMM4) +void FLEXCOMM4_DriverIRQHandler(void); +void FLEXCOMM4_DriverIRQHandler(void) +{ + uint32_t instance; + + /* Look up instance number */ + instance = FLEXCOMM_GetInstance(FLEXCOMM4); + assert(s_flexcommIrqHandler[instance] != NULL); + s_flexcommIrqHandler[instance]((uint32_t *)s_flexcommBaseAddrs[instance], s_flexcommHandle[instance]); + SDK_ISR_EXIT_BARRIER; +} + +#endif + +#if defined(FLEXCOMM5) +void FLEXCOMM5_DriverIRQHandler(void); +void FLEXCOMM5_DriverIRQHandler(void) +{ + uint32_t instance; + + /* Look up instance number */ + instance = FLEXCOMM_GetInstance(FLEXCOMM5); + assert(s_flexcommIrqHandler[instance] != NULL); + s_flexcommIrqHandler[instance]((uint32_t *)s_flexcommBaseAddrs[instance], s_flexcommHandle[instance]); + SDK_ISR_EXIT_BARRIER; +} +#endif + +#if defined(FLEXCOMM6) +void FLEXCOMM6_DriverIRQHandler(void); +void FLEXCOMM6_DriverIRQHandler(void) +{ + uint32_t instance; + + /* Look up instance number */ + instance = FLEXCOMM_GetInstance(FLEXCOMM6); + assert(s_flexcommIrqHandler[instance] != NULL); + s_flexcommIrqHandler[instance]((uint32_t *)s_flexcommBaseAddrs[instance], s_flexcommHandle[instance]); + SDK_ISR_EXIT_BARRIER; +} +#endif + +#if defined(FLEXCOMM7) +void FLEXCOMM7_DriverIRQHandler(void); +void FLEXCOMM7_DriverIRQHandler(void) +{ + uint32_t instance; + + /* Look up instance number */ + instance = FLEXCOMM_GetInstance(FLEXCOMM7); + assert(s_flexcommIrqHandler[instance] != NULL); + s_flexcommIrqHandler[instance]((uint32_t *)s_flexcommBaseAddrs[instance], s_flexcommHandle[instance]); + SDK_ISR_EXIT_BARRIER; +} +#endif + +#if defined(FLEXCOMM8) +void FLEXCOMM8_DriverIRQHandler(void); +void FLEXCOMM8_DriverIRQHandler(void) +{ + uint32_t instance; + + /* Look up instance number */ + instance = FLEXCOMM_GetInstance(FLEXCOMM8); + assert(s_flexcommIrqHandler[instance] != NULL); + s_flexcommIrqHandler[instance]((uint32_t *)s_flexcommBaseAddrs[instance], s_flexcommHandle[instance]); + SDK_ISR_EXIT_BARRIER; +} +#endif + +#if defined(FLEXCOMM9) +void FLEXCOMM9_DriverIRQHandler(void); +void FLEXCOMM9_DriverIRQHandler(void) +{ + uint32_t instance; + + /* Look up instance number */ + instance = FLEXCOMM_GetInstance(FLEXCOMM9); + assert(s_flexcommIrqHandler[instance] != NULL); + s_flexcommIrqHandler[instance]((uint32_t *)s_flexcommBaseAddrs[instance], s_flexcommHandle[instance]); + SDK_ISR_EXIT_BARRIER; +} +#endif + +#if defined(FLEXCOMM10) +void FLEXCOMM10_DriverIRQHandler(void); +void FLEXCOMM10_DriverIRQHandler(void) +{ + uint32_t instance; + + /* Look up instance number */ + instance = FLEXCOMM_GetInstance(FLEXCOMM10); + assert(s_flexcommIrqHandler[instance] != NULL); + s_flexcommIrqHandler[instance]((uint32_t *)s_flexcommBaseAddrs[instance], s_flexcommHandle[instance]); + SDK_ISR_EXIT_BARRIER; +} +#endif + +#if defined(FLEXCOMM11) +void FLEXCOMM11_DriverIRQHandler(void); +void FLEXCOMM11_DriverIRQHandler(void) +{ + uint32_t instance; + + /* Look up instance number */ + instance = FLEXCOMM_GetInstance(FLEXCOMM11); + assert(s_flexcommIrqHandler[instance] != NULL); + s_flexcommIrqHandler[instance]((uint32_t *)s_flexcommBaseAddrs[instance], s_flexcommHandle[instance]); + SDK_ISR_EXIT_BARRIER; +} +#endif + +#if defined(FLEXCOMM12) +void FLEXCOMM12_DriverIRQHandler(void); +void FLEXCOMM12_DriverIRQHandler(void) +{ + uint32_t instance; + + /* Look up instance number */ + instance = FLEXCOMM_GetInstance(FLEXCOMM12); + assert(s_flexcommIrqHandler[instance] != NULL); + s_flexcommIrqHandler[instance]((uint32_t *)s_flexcommBaseAddrs[instance], s_flexcommHandle[instance]); + SDK_ISR_EXIT_BARRIER; +} +#endif + +#if defined(FLEXCOMM13) +void FLEXCOMM13_DriverIRQHandler(void); +void FLEXCOMM13_DriverIRQHandler(void) +{ + uint32_t instance; + + /* Look up instance number */ + instance = FLEXCOMM_GetInstance(FLEXCOMM13); + assert(s_flexcommIrqHandler[instance] != NULL); + s_flexcommIrqHandler[instance]((uint32_t *)s_flexcommBaseAddrs[instance], s_flexcommHandle[instance]); + SDK_ISR_EXIT_BARRIER; +} +#endif + +#if defined(FLEXCOMM14) +void FLEXCOMM14_DriverIRQHandler(void); +void FLEXCOMM14_DriverIRQHandler(void) +{ + uint32_t instance; + + /* Look up instance number */ + instance = FLEXCOMM_GetInstance(FLEXCOMM14); + assert(s_flexcommIrqHandler[instance] != NULL); + s_flexcommIrqHandler[instance]((uint32_t *)s_flexcommBaseAddrs[instance], s_flexcommHandle[instance]); + SDK_ISR_EXIT_BARRIER; +} +#endif + +#if defined(FLEXCOMM15) +void FLEXCOMM15_DriverIRQHandler(void); +void FLEXCOMM15_DriverIRQHandler(void) +{ + uint32_t instance; + + /* Look up instance number */ + instance = FLEXCOMM_GetInstance(FLEXCOMM15); + assert(s_flexcommIrqHandler[instance] != NULL); + s_flexcommIrqHandler[instance]((uint32_t *)s_flexcommBaseAddrs[instance], s_flexcommHandle[instance]); + SDK_ISR_EXIT_BARRIER; +} +#endif + +#if defined(FLEXCOMM16) +void FLEXCOMM16_DriverIRQHandler(void); +void FLEXCOMM16_DriverIRQHandler(void) +{ + uint32_t instance; + + /* Look up instance number */ + instance = FLEXCOMM_GetInstance(FLEXCOMM16); + assert(s_flexcommIrqHandler[instance] != NULL); + s_flexcommIrqHandler[instance]((uint32_t *)s_flexcommBaseAddrs[instance], s_flexcommHandle[instance]); + SDK_ISR_EXIT_BARRIER; +} +#endif diff --git a/drivers/Src/fsl_power.c b/drivers/Src/fsl_power.c new file mode 100644 index 0000000..bda4cc0 --- /dev/null +++ b/drivers/Src/fsl_power.c @@ -0,0 +1,1831 @@ +/* + * Copyright (c) 2016, Freescale Semiconductor, Inc. + * Copyright 2016, NXP + * All rights reserved. + * + * SPDX-License-Identifier: BSD-3-Clause + */ +#include "fsl_common.h" +#include "fsl_power.h" +/* Component ID definition, used by tools. */ +#ifndef FSL_COMPONENT_ID +#define FSL_COMPONENT_ID "platform.drivers.power" +#endif + +/******************************************************************************* + * Variables + ******************************************************************************/ + +/******************************************************************************* + * Definitions + ******************************************************************************/ +/** @brief Low Power main structure */ +typedef enum +{ + VD_AON = 0x0, /*!< Digital Always On power domain */ + VD_MEM = 0x1, /*!< Memories (SRAM) power domain */ + VD_DCDC = 0x2, /*!< Core logic power domain */ + VD_DEEPSLEEP = 0x3 /*!< Core logic power domain */ +} LPC_POWER_DOMAIN_T; + +/** + * @brief LDO_FLASH_NV & LDO_USB voltage settings + */ +typedef enum _v_flashnv +{ + V_LDOFLASHNV_1P650 = 0, /*!< 0.95 V */ + V_LDOFLASHNV_1P700 = 1, /*!< 0.975 V */ + V_LDOFLASHNV_1P750 = 2, /*!< 1 V */ + V_LDOFLASHNV_0P800 = 3, /*!< 1.025 V */ + V_LDOFLASHNV_1P850 = 4, /*!< 1.050 V */ + V_LDOFLASHNV_1P900 = 5, /*!< 1.075 V */ + V_LDOFLASHNV_1P950 = 6, /*!< 1.1 V */ + V_LDOFLASHNV_2P000 = 7 /*!< 1.125 V */ +} v_flashnv_t; + +/** @brief Low Power main structure */ +typedef struct +{ /* */ + __IO uint32_t CFG; /*!< Low Power Mode Configuration, and miscallenous options */ + __IO uint32_t PDCTRL0; /*!< Power Down control : controls power of various modules + in the different Low power modes, including ROM */ + __IO uint32_t SRAMRETCTRL; /*!< Power Down control : controls power SRAM instances + in the different Low power modes */ + __IO uint32_t CPURETCTRL; /*!< CPU0 retention control : controls CPU retention parameters in POWER DOWN modes */ + __IO uint64_t VOLTAGE; /*!< Voltage control in Low Power Modes */ + __IO uint64_t WAKEUPSRC; /*!< Wake up sources control for sleepcon */ + __IO uint64_t WAKEUPINT; /*!< Wake up sources control for ARM */ + __IO uint32_t HWWAKE; /*!< Interrupt that can postpone power down modes + in case an interrupt is pending when the processor request deepsleep */ + __IO uint32_t WAKEUPIOSRC; /*!< Wake up I/O sources in DEEP POWER DOWN mode */ + __IO uint32_t TIMERCFG; /*!< Wake up timers configuration */ + __IO uint32_t TIMERCOUNT; /*!< Wake up Timer count*/ + __IO uint32_t POWERCYCLE; /*!< Cancels entry in Low Power mode if set with 0xDEADABBA (might be used by some + interrupt handlers)*/ +} LPC_LOWPOWER_T; + +/* */ +#define LOWPOWER_POWERCYCLE_CANCELLED 0xDEADABBAUL /*!< */ + +/** + * @brief SRAM Low Power Modes + */ +#define LOWPOWER_SRAM_LPMODE_MASK (0xFUL) +#define LOWPOWER_SRAM_LPMODE_ACTIVE (0x6UL) /*!< SRAM functional mode */ +#define LOWPOWER_SRAM_LPMODE_SLEEP (0xFUL) /*!< SRAM Sleep mode (Data retention, fast wake up) */ +#define LOWPOWER_SRAM_LPMODE_DEEPSLEEP (0x8UL) /*!< SRAM Deep Sleep mode (Data retention, slow wake up) */ +#define LOWPOWER_SRAM_LPMODE_SHUTDOWN (0x9UL) /*!< SRAM Shut Down mode (no data retention) */ +#define LOWPOWER_SRAM_LPMODE_POWERUP (0xAUL) /*!< SRAM is powering up */ + +/** + * @brief Wake up timers configuration in Low Power Modes + */ +#define LOWPOWER_TIMERCFG_CTRL_INDEX 0 +#define LOWPOWER_TIMERCFG_CTRL_MASK (0x1UL << LOWPOWER_TIMERCFG_CTRL_INDEX) +#define LOWPOWER_TIMERCFG_TIMER_INDEX 1 +#define LOWPOWER_TIMERCFG_TIMER_MASK (0x7UL << LOWPOWER_TIMERCFG_TIMER_INDEX) +#define LOWPOWER_TIMERCFG_OSC32K_INDEX 4 +#define LOWPOWER_TIMERCFG_OSC32K_MASK (0x1UL << LOWPOWER_TIMERCFG_OSC32K_INDEX) + +#define LOWPOWER_TIMERCFG_CTRL_DISABLE 0 /*!< Wake Timer Disable */ +#define LOWPOWER_TIMERCFG_CTRL_ENABLE 1 /*!< Wake Timer Enable */ + +/** + * @brief Primary Wake up timers configuration in Low Power Modes + */ +#define LOWPOWER_TIMERCFG_TIMER_RTC1KHZ 0 /*!< 1 KHz Real Time Counter (RTC) used as wake up source */ +#define LOWPOWER_TIMERCFG_TIMER_RTC1HZ 1 /*!< 1 Hz Real Time Counter (RTC) used as wake up source */ +#define LOWPOWER_TIMERCFG_TIMER_OSTIMER 2 /*!< OS Event Timer used as wake up source */ + +#define LOWPOWER_TIMERCFG_OSC32K_FRO32KHZ 0 /*!< Wake up Timers uses FRO 32 KHz as clock source */ +#define LOWPOWER_TIMERCFG_OSC32K_XTAL32KHZ 1 /*!< Wake up Timers uses Chrystal 32 KHz as clock source */ + +//! @brief Interface for lowpower functions +typedef struct LowpowerDriverInterface +{ + void (*power_cycle_cpu_and_flash)(void); + void (*set_lowpower_mode)(LPC_LOWPOWER_T *p_lowpower_cfg); +} lowpower_driver_interface_t; + +/**< DCDC Power Profiles */ +typedef enum +{ + DCDC_POWER_PROFILE_LOW, /**< LOW (for CPU frequencies below DCDC_POWER_PROFILE_LOW_MAX_FREQ_HZ) */ + DCDC_POWER_PROFILE_MEDIUM, /**< MEDIUM (for CPU frequencies between DCDC_POWER_PROFILE_LOW_MAX_FREQ_HZ and + DCDC_POWER_PROFILE_MEDIUM_MAX_FREQ_HZ) */ + DCDC_POWER_PROFILE_HIGH, /**< HIGH (for CPU frequencies between DCDC_POWER_PROFILE_MEDIUM_MAX_FREQ_HZ and + DCDC_POWER_PROFILE_HIGH_MAX_FREQ_HZ) */ +} lowpower_dcdc_power_profile_enum; + +/**< Manufacturing Process Corners */ +typedef enum +{ + PROCESS_CORNER_SSS, /**< Slow Corner Process */ + PROCESS_CORNER_NNN, /**< Nominal Corner Process */ + PROCESS_CORNER_FFF, /**< Fast Corner Process */ + PROCESS_CORNER_OTHERS, /**< SFN, SNF, NFS, Poly Res ... Corner Process */ +} lowpower_process_corner_enum; + +/** + * @brief DCDC voltage settings + */ +typedef enum _v_dcdc +{ + V_DCDC_0P950 = 0, /*!< 0.95 V */ + V_DCDC_0P975 = 1, /*!< 0.975 V */ + V_DCDC_1P000 = 2, /*!< 1 V */ + V_DCDC_1P025 = 3, /*!< 1.025 V */ + V_DCDC_1P050 = 4, /*!< 1.050 V */ + V_DCDC_1P075 = 5, /*!< 1.075 V */ + V_DCDC_1P100 = 6, /*!< 1.1 V */ + V_DCDC_1P125 = 7, /*!< 1.125 V */ + V_DCDC_1P150 = 8, /*!< 1.150 V */ + V_DCDC_1P175 = 9, /*!< 1.175 V */ + V_DCDC_1P200 = 10 /*!< 1.2 V */ +} v_dcdc_t; + +/** + * @brief Deep Sleep LDO voltage settings + */ +typedef enum _v_deepsleep +{ + V_DEEPSLEEP_0P900 = 0, /*!< 0.9 V */ + V_DEEPSLEEP_0P925 = 1, /*!< 0.925 V */ + V_DEEPSLEEP_0P950 = 2, /*!< 0.95 V */ + V_DEEPSLEEP_0P975 = 3, /*!< 0.975 V */ + V_DEEPSLEEP_1P000 = 4, /*!< 1.000 V */ + V_DEEPSLEEP_1P025 = 5, /*!< 1.025 V */ + V_DEEPSLEEP_1P050 = 6, /*!< 1.050 V */ + V_DEEPSLEEP_1P075 = 7 /*!< 1.075 V */ +} v_deepsleep_t; + +/** + * @brief Always On and Memories LDO voltage settings + */ +typedef enum _v_ao +{ + V_AO_0P700 = 1, /*!< 0.7 V */ + V_AO_0P725 = 2, /*!< 0.725 V */ + V_AO_0P750 = 3, /*!< 0.75 V */ + V_AO_0P775 = 4, /*!< 0.775 V */ + V_AO_0P800 = 5, /*!< 0.8 V */ + V_AO_0P825 = 6, /*!< 0.825 V */ + V_AO_0P850 = 7, /*!< 0.85 V */ + V_AO_0P875 = 8, /*!< 0.875 V */ + V_AO_0P900 = 9, /*!< 0.9 V */ + V_AO_0P960 = 10, /*!< 0.96 V */ + V_AO_0P970 = 11, /*!< 0.97 V */ + V_AO_0P980 = 12, /*!< 0.98 V */ + V_AO_0P990 = 13, /*!< 0.99 V */ + V_AO_1P000 = 14, /*!< 1 V */ + V_AO_1P010 = 15, /*!< 1.01 V */ + V_AO_1P020 = 16, /*!< 1.02 V */ + V_AO_1P030 = 17, /*!< 1.03 V */ + V_AO_1P040 = 18, /*!< 1.04 V */ + V_AO_1P050 = 19, /*!< 1.05 V */ + V_AO_1P060 = 20, /*!< 1.06 V */ + V_AO_1P070 = 21, /*!< 1.07 V */ + V_AO_1P080 = 22, /*!< 1.08 V */ + V_AO_1P090 = 23, /*!< 1.09 V */ + V_AO_1P100 = 24, /*!< 1.1 V */ + V_AO_1P110 = 25, /*!< 1.11 V */ + V_AO_1P120 = 26, /*!< 1.12 V */ + V_AO_1P130 = 27, /*!< 1.13 V */ + V_AO_1P140 = 28, /*!< 1.14 V */ + V_AO_1P150 = 29, /*!< 1.15 V */ + V_AO_1P160 = 30, /*!< 1.16 V */ + V_AO_1P220 = 31 /*!< 1.22 V */ +} v_ao_t; + +/* Low Power modes */ +#define LOWPOWER_CFG_LPMODE_INDEX 0 +#define LOWPOWER_CFG_LPMODE_MASK (0x3UL << LOWPOWER_CFG_LPMODE_INDEX) +#define LOWPOWER_CFG_SELCLOCK_INDEX 2 +#define LOWPOWER_CFG_SELCLOCK_MASK (0x1UL << LOWPOWER_CFG_SELCLOCK_INDEX) +#define LOWPOWER_CFG_SELMEMSUPPLY_INDEX 3 +#define LOWPOWER_CFG_SELMEMSUPPLY_MASK (0x1UL << LOWPOWER_CFG_SELMEMSUPPLY_INDEX) +#define LOWPOWER_CFG_MEMLOWPOWERMODE_INDEX 4 +#define LOWPOWER_CFG_MEMLOWPOWERMODE_MASK (0x1UL << LOWPOWER_CFG_MEMLOWPOWERMODE_INDEX) +#define LOWPOWER_CFG_LDODEEPSLEEPREF_INDEX 5 +#define LOWPOWER_CFG_LDODEEPSLEEPREF_MASK (0x1UL << LOWPOWER_CFG_LDODEEPSLEEPREF_INDEX) + +#define LOWPOWER_CFG_LPMODE_ACTIVE 0 /*!< ACTIVE mode */ +#define LOWPOWER_CFG_LPMODE_DEEPSLEEP 1 /*!< DEEP SLEEP mode */ +#define LOWPOWER_CFG_LPMODE_POWERDOWN 2 /*!< POWER DOWN mode */ +#define LOWPOWER_CFG_LPMODE_DEEPPOWERDOWN 3 /*!< DEEP POWER DOWN mode */ +#define LOWPOWER_CFG_LPMODE_SLEEP 4 /*!< SLEEP mode */ + +#define LOWPOWER_CFG_SELCLOCK_1MHZ 0 /*!< The 1 MHz clock is used during the configuration of the PMC */ +#define LOWPOWER_CFG_SELCLOCK_12MHZ \ + 1 /*!< The 12 MHz clock is used during the configuration of the PMC (to speed up PMC configuration process)*/ + +#define LOWPOWER_CFG_SELMEMSUPPLY_LDOMEM 0 /*!< In DEEP SLEEP power mode, the Memories are supplied by the LDO_MEM */ +#define LOWPOWER_CFG_SELMEMSUPPLY_LDODEEPSLEEP \ + 1 /*!< In DEEP SLEEP power mode, the Memories are supplied by the LDO_DEEP_SLEEP (or DCDC) */ + +#define LOWPOWER_CFG_MEMLOWPOWERMODE_SOURCEBIASING \ + 0 /*!< All SRAM instances use "Source Biasing" as low power mode technic (it is recommended to set LDO_MEM as high \ + as possible -- 1.1V typical -- during low power mode) */ +#define LOWPOWER_CFG_MEMLOWPOWERMODE_VOLTAGESCALING \ + 1 /*!< All SRAM instances use "Voltage Scaling" as low power mode technic (it is recommended to set LDO_MEM as low \ + as possible -- down to 0.7V -- during low power mode) */ + +#define LOWPOWER_CFG_LDODEEPSLEEPREF_FLASHBUFFER 0 /*!< LDO DEEP SLEEP uses Flash Buffer as reference */ +#define LOWPOWER_CFG_LDODEEPSLEEPREF_BANDGAG0P8V 1 /*!< LDO DEEP SLEEP uses Band Gap 0.8V as reference */ + +/* CPU Retention Control*/ +#define LOWPOWER_CPURETCTRL_ENA_INDEX 0 +#define LOWPOWER_CPURETCTRL_ENA_MASK (0x1UL << LOWPOWER_CPURETCTRL_ENA_INDEX) +#define LOWPOWER_CPURETCTRL_MEMBASE_INDEX 1 +#define LOWPOWER_CPURETCTRL_MEMBASE_MASK (0x1FFFUL << LOWPOWER_CPURETCTRL_MEMBASE_INDEX) +#define LOWPOWER_CPURETCTRL_RETDATALENGTH_INDEX 14 +#define LOWPOWER_CPURETCTRL_RETDATALENGTH_MASK (0x3FFUL << LOWPOWER_CPURETCTRL_RETDATALENGTH_INDEX) + +/* Voltgae setting*/ +#define DCDC_POWER_PROFILE_LOW_MAX_FREQ_HZ \ + (100000000U) /* Maximum System Frequency allowed with DCDC Power Profile LOW */ +#define DCDC_POWER_PROFILE_MEDIUM_MAX_FREQ_HZ \ + (130000000U) /* Maximum System Frequency allowed with DCDC Power Profile MEDIUM */ +#define DCDC_POWER_PROFILE_HIGH_MAX_FREQ_HZ \ + (150000000U) /* Maximum System Frequency allowed with DCDC Power Profile HIGH */ +#define PROCESS_NNN_AVG_HZ (19300000U) /* Average Ring OScillator value for Nominal (NNN) Manufacturing Process */ +#define PROCESS_NNN_STD_HZ \ + (400000U) /* Standard Deviation Ring OScillator value for Nominal (NNN) Manufacturing Process */ +#define PROCESS_NNN_LIMITS \ + (6U) /* Nominal (NNN) Manufacturing Process Ring Oscillator values limit (with respect to the Average value) */ +#define PROCESS_NNN_MIN_HZ \ + (PROCESS_NNN_AVG_HZ - \ + (PROCESS_NNN_LIMITS * \ + PROCESS_NNN_STD_HZ)) /* Minimum Ring OScillator value for Nominal (NNN) Manufacturing Process */ +#define PROCESS_NNN_MAX_HZ \ + (PROCESS_NNN_AVG_HZ + \ + (PROCESS_NNN_LIMITS * \ + PROCESS_NNN_STD_HZ)) /* Maximum Ring OScillator value for Nominal (NNN) Manufacturing Process */ +#define VOLTAGE_SSS_LOW_MV (1075U) /* Voltage Settings for : Process=SSS, DCDC Power Profile=LOW */ +#define VOLTAGE_SSS_MED_MV (1150U) /* Voltage Settings for : Process=SSS, DCDC Power Profile=MEDIUM */ +#define VOLTAGE_SSS_HIG_MV (1200U) /* Voltage Settings for : Process=SSS, DCDC Power Profile=HIGH */ +#define VOLTAGE_NNN_LOW_MV (1000U) /* Voltage Settings for : Process=NNN, DCDC Power Profile=LOW */ +#define VOLTAGE_NNN_MED_MV (1100U) /* Voltage Settings for : Process=NNN, DCDC Power Profile=MEDIUM */ +#define VOLTAGE_NNN_HIG_MV (1150U) /* Voltage Settings for : Process=NNN, DCDC Power Profile=HIGH */ +#define VOLTAGE_FFF_LOW_MV (1000U) /* Voltage Settings for : Process=FFF, DCDC Power Profile=LOW */ +#define VOLTAGE_FFF_MED_MV (1025U) /* Voltage Settings for : Process=FFF, DCDC Power Profile=MEDIUM */ +#define VOLTAGE_FFF_HIG_MV (1050U) /* Voltage Settings for : Process=FFF, DCDC Power Profile=HIGH */ + +/** + * @brief LDO Voltage control in Low Power Modes + */ +#define LOWPOWER_VOLTAGE_LDO_PMU_INDEX 0 +#define LOWPOWER_VOLTAGE_LDO_PMU_MASK (0x1FULL << LOWPOWER_VOLTAGE_LDO_PMU_INDEX) +#define LOWPOWER_VOLTAGE_LDO_MEM_INDEX 5 +#define LOWPOWER_VOLTAGE_LDO_MEM_MASK (0x1FULL << LOWPOWER_VOLTAGE_LDO_MEM_INDEX) +#define LOWPOWER_VOLTAGE_LDO_DEEP_SLEEP_INDEX 10 +#define LOWPOWER_VOLTAGE_LDO_DEEP_SLEEP_MASK (0x7ULL << LOWPOWER_VOLTAGE_LDO_DEEP_SLEEP_INDEX) +#define LOWPOWER_VOLTAGE_LDO_PMU_BOOST_INDEX 19 +#define LOWPOWER_VOLTAGE_LDO_PMU_BOOST_MASK (0x1FULL << LOWPOWER_VOLTAGE_LDO_PMU_BOOST_INDEX) +#define LOWPOWER_VOLTAGE_LDO_MEM_BOOST_INDEX 24 +#define LOWPOWER_VOLTAGE_LDO_MEM_BOOST_MASK (0x1FULL << LOWPOWER_VOLTAGE_LDO_MEM_BOOST_INDEX) +#define LOWPOWER_VOLTAGE_DCDC_INDEX 29 +#define LOWPOWER_VOLTAGE_DCDC_MASK (0xFULL << LOWPOWER_VOLTAGE_DCDC_INDEX) + +/*! @brief set and clear bit MACRO's. */ +#define U32_SET_BITS(P, B) ((*(uint32_t *)P) |= (B)) +#define U32_CLR_BITS(P, B) ((*(uint32_t *)P) &= ~(B)) +/* Return values from Config (N-2) page of flash */ +#define GET_16MXO_TRIM() (*(uint32_t *)0x9FCC8) +#define GET_32KXO_TRIM() (*(uint32_t *)0x9FCCC) + +#define CPU_RETENTION_RAMX_STORAGE_START_ADDR (0x04006000) + +#define XO_SLAVE_EN (1) +/******************************************************************************* + * Codes + ******************************************************************************/ + +/******************************************************************************* + * LOCAL FUNCTIONS PROTOTYPES + ******************************************************************************/ +static void lf_get_deepsleep_core_supply_cfg(uint32_t exclude_from_pd, uint32_t *dcdc_voltage); +static uint32_t lf_set_ldo_ao_ldo_mem_voltage(uint32_t p_lp_mode, uint32_t p_dcdc_voltage); +static uint32_t lf_wakeup_io_ctrl(uint32_t p_wakeup_io_ctrl); +static uint8_t CLOCK_u8OscCapConvert(uint8_t u8OscCap, uint8_t u8CapBankDiscontinuity); + +static void lowpower_set_dcdc_power_profile(lowpower_dcdc_power_profile_enum dcdc_power_profile); +static lowpower_process_corner_enum lowpower_get_part_process_corner(void); +static void lowpower_set_voltage_for_process(lowpower_dcdc_power_profile_enum dcdc_power_profile); + +/** + * @brief Configures and enters in low power mode + * @param p_lowpower_cfg: pointer to a structure that contains all low power mode parameters + * @return Nothing + * + * !!! IMPORTANT NOTES : + * 1 - CPU Interrupt Enable registers are updated with p_lowpower_cfg->WAKEUPINT. They are NOT restored by the + * API. + * 2 - The Non Maskable Interrupt (NMI) should be disable before calling this API (otherwise, there is a risk + * of Dead Lock). + * 3 - The HARD FAULT handler should execute from SRAM. (The Hard fault handler should initiate a full chip + * reset) + */ +static void POWER_EnterLowPower(LPC_LOWPOWER_T *p_lowpower_cfg); + +/** + * @brief + * @param + * @return + */ +static void lf_set_dcdc_power_profile_low(void) +{ +#define DCDC_POWER_PROFILE_LOW_0_ADDRS (0x9FCE0U) +#define DCDC_POWER_PROFILE_LOW_1_ADDRS (0x9FCE4U) + + uint32_t dcdcTrimValue0 = (*((volatile unsigned int *)(DCDC_POWER_PROFILE_LOW_0_ADDRS))); + uint32_t dcdcTrimValue1 = (*((volatile unsigned int *)(DCDC_POWER_PROFILE_LOW_1_ADDRS))); + + if (0UL != (dcdcTrimValue0 & 0x1UL)) + { + PMC->DCDC0 = dcdcTrimValue0 >> 1; + PMC->DCDC1 = dcdcTrimValue1; + } +} + +/** + * @brief Configures and enters in low power mode + * @param : p_lowpower_cfg + * @return Nothing + */ +static void POWER_EnterLowPower(LPC_LOWPOWER_T *p_lowpower_cfg) +{ + lowpower_driver_interface_t *s_lowpowerDriver; + /* Judging the core and call the corresponding API base address*/ + if (0UL == Chip_GetVersion()) + { + s_lowpowerDriver = (lowpower_driver_interface_t *)(0x130010d4UL); + } + else + { + s_lowpowerDriver = (lowpower_driver_interface_t *)(0x13001204UL); + } + /* PMC clk set to 12 MHZ */ + p_lowpower_cfg->CFG |= (uint32_t)LOWPOWER_CFG_SELCLOCK_12MHZ << LOWPOWER_CFG_SELCLOCK_INDEX; + + /* Enable Analog References fast wake-up in case of wake-up from a low power mode (DEEP SLEEP, POWER DOWN and DEEP + * POWER DOWN) and Hardware Pin reset */ + PMC->REFFASTWKUP = (PMC->REFFASTWKUP & (~PMC_REFFASTWKUP_LPWKUP_MASK) & (~PMC_REFFASTWKUP_HWWKUP_MASK)) | + PMC_REFFASTWKUP_LPWKUP(1) | PMC_REFFASTWKUP_HWWKUP(1); + + /* SRAM uses Voltage Scaling in all Low Power modes */ + PMC->SRAMCTRL = (PMC->SRAMCTRL & (~PMC_SRAMCTRL_SMB_MASK)) | PMC_SRAMCTRL_SMB(3); + + /* CPU Retention configuration : preserve the value of FUNCRETENTIONCTRL.RET_LENTH which is a Hardware defined + * parameter. */ + p_lowpower_cfg->CPURETCTRL = (SYSCON->FUNCRETENTIONCTRL & SYSCON_FUNCRETENTIONCTRL_RET_LENTH_MASK) | + (p_lowpower_cfg->CPURETCTRL & (~SYSCON_FUNCRETENTIONCTRL_RET_LENTH_MASK)); + + /* Switch System Clock to FRO12Mhz (the configuration before calling this function will not be restored back) */ + CLOCK_AttachClk(kFRO12M_to_MAIN_CLK); /* Switch main clock to FRO12MHz */ + CLOCK_SetClkDiv(kCLOCK_DivAhbClk, 1U, false); /* Main clock divided by 1 */ + SYSCON->FMCCR = (SYSCON->FMCCR & 0xFFFF0000UL) | 0x201AUL; /* Adjust FMC waiting time cycles */ + lf_set_dcdc_power_profile_low(); /* Align DCDC Power profile with the 12 MHz clock (DCDC Power Profile LOW) */ + + (*(s_lowpowerDriver->set_lowpower_mode))(p_lowpower_cfg); + + /* Restore the configuration of the MISCCTRL Register : LOWPWR_FLASH_BUF = 0, LDOMEMBLEEDDSLP = 0, LDOMEMHIGHZMODE = + * 0 */ + PMC->MISCCTRL &= (~PMC_MISCCTRL_LOWPWR_FLASH_BUF_MASK) & (~PMC_MISCCTRL_DISABLE_BLEED_MASK) & + (~PMC_MISCCTRL_LDOMEMHIGHZMODE_MASK); +} + +/** + * @brief Shut off the Flash and execute the _WFI(), then power up the Flash after wake-up event + * @param None + * @return Nothing + */ +void POWER_CycleCpuAndFlash(void) +{ + /* Judging the core and call the corresponding API base address*/ + lowpower_driver_interface_t *s_lowpowerDriver; + if (0UL == Chip_GetVersion()) + { + s_lowpowerDriver = (lowpower_driver_interface_t *)(0x130010d4UL); + } + else + { + s_lowpowerDriver = (lowpower_driver_interface_t *)(0x13001204UL); + } + (*(s_lowpowerDriver->power_cycle_cpu_and_flash))(); +}; + +/** + * brief PMC Deep Sleep function call + * return nothing + */ +void POWER_EnterDeepSleep(uint32_t exclude_from_pd, + uint32_t sram_retention_ctrl, + uint64_t wakeup_interrupts, + uint32_t hardware_wake_ctrl) +{ + static LPC_LOWPOWER_T lv_low_power_mode_cfg; /* Low Power Mode configuration structure */ + uint32_t cpu0_nmi_enable; + uint32_t cpu0_int_enable_0; + uint32_t cpu0_int_enable_1; + uint32_t dcdc_voltage; + uint32_t pmc_reset_ctrl; + /* Clear Low Power Mode configuration variable */ + (void)memset(&lv_low_power_mode_cfg, 0x0, sizeof(LPC_LOWPOWER_T)); + + /* Configure Low Power Mode configuration variable */ + lv_low_power_mode_cfg.CFG |= (uint32_t)LOWPOWER_CFG_LPMODE_DEEPSLEEP + << LOWPOWER_CFG_LPMODE_INDEX; /* DEEPSLEEP mode */ + + lf_get_deepsleep_core_supply_cfg(exclude_from_pd, &dcdc_voltage); + + if (((exclude_from_pd & (uint32_t)kPDRUNCFG_PD_USB1_PHY) != 0UL) && + ((exclude_from_pd & (uint32_t)kPDRUNCFG_PD_LDOUSBHS) != 0UL)) + { + /* USB High Speed is required as wake-up source in Deep Sleep mode: make sure LDO FLASH NV stays powered during + * deep-sleep */ + exclude_from_pd = exclude_from_pd | (uint32_t)kPDRUNCFG_PD_LDOFLASHNV; + } + + /* DCDC will be always used during Deep Sleep (instead of LDO Deep Sleep); Make sure LDO MEM & Analog references + * will stay powered, Shut down ROM */ + lv_low_power_mode_cfg.PDCTRL0 = (~exclude_from_pd & ~(uint32_t)kPDRUNCFG_PD_DCDC & ~(uint32_t)kPDRUNCFG_PD_LDOMEM & + ~(uint32_t)kPDRUNCFG_PD_BIAS) | + (uint32_t)kPDRUNCFG_PD_LDODEEPSLEEP | (uint32_t)kPDRUNCFG_PD_ROM; + + /* Voltage control in DeepSleep Low Power Modes */ + /* The Memories Voltage settings below are for voltage scaling */ + lv_low_power_mode_cfg.VOLTAGE = lf_set_ldo_ao_ldo_mem_voltage(LOWPOWER_CFG_LPMODE_POWERDOWN, dcdc_voltage); + + /* SRAM retention control during POWERDOWN */ + lv_low_power_mode_cfg.SRAMRETCTRL = sram_retention_ctrl; + + /* CPU Wake up & Interrupt sources control */ + lv_low_power_mode_cfg.WAKEUPINT = wakeup_interrupts; + lv_low_power_mode_cfg.WAKEUPSRC = wakeup_interrupts; + + /* Interrupts that allow DMA transfers with Flexcomm without waking up the Processor */ + if (0UL != (hardware_wake_ctrl & (LOWPOWER_HWWAKE_PERIPHERALS | LOWPOWER_HWWAKE_SDMA0 | LOWPOWER_HWWAKE_SDMA1))) + { + lv_low_power_mode_cfg.HWWAKE = (hardware_wake_ctrl & ~LOWPOWER_HWWAKE_FORCED) | LOWPOWER_HWWAKE_ENABLE_FRO192M; + } + + cpu0_nmi_enable = SYSCON->NMISRC & SYSCON_NMISRC_NMIENCPU0_MASK; /* Save the configuration of the NMI Register */ + SYSCON->NMISRC &= ~SYSCON_NMISRC_NMIENCPU0_MASK; /* Disable NMI of CPU0 */ + + /* Save the configuration of the CPU interrupt enable Registers (because they are overwritten inside the low power + * API */ + cpu0_int_enable_0 = NVIC->ISER[0]; + cpu0_int_enable_1 = NVIC->ISER[1]; + + pmc_reset_ctrl = PMC->RESETCTRL; + if (0UL != (pmc_reset_ctrl & PMC_RESETCTRL_BODCORERESETENABLE_MASK)) + { + /* BoD CORE reset is activated, so make sure BoD Core won't be shutdown */ + lv_low_power_mode_cfg.PDCTRL0 &= ~(uint32_t)kPDRUNCFG_PD_BODCORE; + } + if (0UL != (pmc_reset_ctrl & PMC_RESETCTRL_BODVBATRESETENABLE_MASK)) + { + /* BoD VBAT reset is activated, so make sure BoD VBAT won't be shutdown */ + lv_low_power_mode_cfg.PDCTRL0 &= ~(uint32_t)kPDRUNCFG_PD_BODVBAT; + } + + /* Enter low power mode */ + POWER_EnterLowPower(&lv_low_power_mode_cfg); + + /* Restore the configuration of the NMI Register */ + SYSCON->NMISRC |= cpu0_nmi_enable; + + /* Restore the configuration of the CPU interrupt enable Registers (because they have been overwritten inside the + * low power API */ + NVIC->ISER[0] = cpu0_int_enable_0; + NVIC->ISER[1] = cpu0_int_enable_1; +} + +/** + * brief PMC power Down function call + * return nothing + */ +void POWER_EnterPowerDown(uint32_t exclude_from_pd, + uint32_t sram_retention_ctrl, + uint64_t wakeup_interrupts, + uint32_t cpu_retention_ctrl) +{ + LPC_LOWPOWER_T lv_low_power_mode_cfg; /* Low Power Mode configuration structure */ + uint32_t cpu0_nmi_enable; + uint32_t cpu0_int_enable_0; + uint32_t cpu0_int_enable_1; + uint64_t wakeup_src_int; + uint32_t pmc_reset_ctrl; + + uint32_t analog_ctrl_regs[12]; /* To store Analog Controller Regristers */ + + /* Clear Low Power Mode configuration variable */ + (void)memset(&lv_low_power_mode_cfg, 0x0, sizeof(LPC_LOWPOWER_T)); + + /* Configure Low Power Mode configuration variable */ + lv_low_power_mode_cfg.CFG |= (uint32_t)LOWPOWER_CFG_LPMODE_POWERDOWN + << LOWPOWER_CFG_LPMODE_INDEX; /* POWER DOWN mode */ + + /* Only FRO32K, XTAL32K, COMP, BIAS and LDO_MEM can be stay powered during POWERDOWN (valid from application point + * of view; Hardware allows BODVBAT, LDODEEPSLEEP and FRO1M to stay powered, that's why they are excluded below) */ + lv_low_power_mode_cfg.PDCTRL0 = (~exclude_from_pd) | (uint32_t)kPDRUNCFG_PD_BODVBAT | (uint32_t)kPDRUNCFG_PD_FRO1M | + (uint32_t)kPDRUNCFG_PD_LDODEEPSLEEP; + + /* SRAM retention control during POWERDOWN */ + lv_low_power_mode_cfg.SRAMRETCTRL = sram_retention_ctrl; + + /* Sanity check: If retention is required for any of SRAM instances, make sure LDO MEM will stay powered */ + if ((sram_retention_ctrl & 0x7FFFUL) != 0UL) + { + lv_low_power_mode_cfg.PDCTRL0 &= ~(uint32_t)kPDRUNCFG_PD_LDOMEM; + } + + /* Voltage control in Low Power Modes */ + /* The Memories Voltage settings below are for voltage scaling */ + lv_low_power_mode_cfg.VOLTAGE = lf_set_ldo_ao_ldo_mem_voltage(LOWPOWER_CFG_LPMODE_POWERDOWN, 0); + + /* CPU0 retention Ctrl. + * For the time being, we do not allow customer to relocate the CPU retention area in SRAMX, meaning that the + * retention area range is [0x0400_6000 - 0x0400_6600] (beginning of RAMX2) If required by customer, + * cpu_retention_ctrl[13:1] will be used for that to modify the default retention area + */ + lv_low_power_mode_cfg.CPURETCTRL = + (cpu_retention_ctrl & LOWPOWER_CPURETCTRL_ENA_MASK) | + ((((uint32_t)CPU_RETENTION_RAMX_STORAGE_START_ADDR >> 2UL) << LOWPOWER_CPURETCTRL_MEMBASE_INDEX) & + LOWPOWER_CPURETCTRL_MEMBASE_MASK); + if (0UL != (cpu_retention_ctrl & 0x1UL)) + { + /* CPU retention is required: store Analog Controller Registers */ + analog_ctrl_regs[0] = ANACTRL->FRO192M_CTRL; + analog_ctrl_regs[1] = ANACTRL->ANALOG_CTRL_CFG; + analog_ctrl_regs[2] = ANACTRL->ADC_CTRL; + analog_ctrl_regs[3] = ANACTRL->XO32M_CTRL; + analog_ctrl_regs[4] = ANACTRL->BOD_DCDC_INT_CTRL; + analog_ctrl_regs[5] = ANACTRL->RINGO0_CTRL; + analog_ctrl_regs[6] = ANACTRL->RINGO1_CTRL; + analog_ctrl_regs[7] = ANACTRL->RINGO2_CTRL; + analog_ctrl_regs[8] = ANACTRL->LDO_XO32M; + analog_ctrl_regs[9] = ANACTRL->AUX_BIAS; + analog_ctrl_regs[10] = ANACTRL->USBHS_PHY_CTRL; + analog_ctrl_regs[11] = ANACTRL->USBHS_PHY_TRIM; + } + + /* CPU Wake up & Interrupt sources control : only WAKEUP_GPIO_GLOBALINT0, WAKEUP_GPIO_GLOBALINT1, WAKEUP_FLEXCOMM3, + * WAKEUP_ACMP_CAPT, WAKEUP_RTC_LITE_ALARM_WAKEUP, WAKEUP_OS_EVENT_TIMER, WAKEUP_ALLWAKEUPIOS */ + wakeup_src_int = (uint64_t)(WAKEUP_GPIO_GLOBALINT0 | WAKEUP_GPIO_GLOBALINT1 | WAKEUP_FLEXCOMM3 | WAKEUP_ACMP_CAPT | + WAKEUP_RTC_LITE_ALARM_WAKEUP | WAKEUP_OS_EVENT_TIMER | WAKEUP_ALLWAKEUPIOS); + lv_low_power_mode_cfg.WAKEUPINT = wakeup_interrupts & wakeup_src_int; + lv_low_power_mode_cfg.WAKEUPSRC = wakeup_interrupts & wakeup_src_int; + + cpu0_nmi_enable = SYSCON->NMISRC & SYSCON_NMISRC_NMIENCPU0_MASK; /* Save the configuration of the NMI Register */ + SYSCON->NMISRC &= ~SYSCON_NMISRC_NMIENCPU0_MASK; /* Disable NMI of CPU0 */ + + /* Save the configuration of the CPU interrupt enable Registers (because they are overwritten inside the low power + * API */ + cpu0_int_enable_0 = NVIC->ISER[0]; + cpu0_int_enable_1 = NVIC->ISER[1]; + + pmc_reset_ctrl = PMC->RESETCTRL; + /* Disable BoD VBAT and BoD Core resets */ + PMC->RESETCTRL = + pmc_reset_ctrl & (~(PMC_RESETCTRL_BODVBATRESETENABLE_MASK | PMC_RESETCTRL_BODCORERESETENABLE_MASK)); + + /* Enter low power mode */ + POWER_EnterLowPower(&lv_low_power_mode_cfg); + + /*** We'll reach this point in case of POWERDOWN with CPU retention or if the POWERDOWN has not been taken (for + instance because an interrupt is pending). In case of CPU retention, assumption is that the SRAM containing the + stack used to call this function shall be preserved during low power ***/ + + /* Restore the configuration of the NMI Register */ + SYSCON->NMISRC |= cpu0_nmi_enable; + + /* Restore PMC RESETCTRL register */ + PMC->RESETCTRL = pmc_reset_ctrl; + + /* Restore the configuration of the CPU interrupt enable Registers (because they have been overwritten inside the + * low power API */ + NVIC->ISER[0] = cpu0_int_enable_0; + NVIC->ISER[1] = cpu0_int_enable_1; + + if (0UL != (cpu_retention_ctrl & 0x1UL)) + { + /* Restore Analog Controller Registers */ + ANACTRL->FRO192M_CTRL = analog_ctrl_regs[0] | ANACTRL_FRO192M_CTRL_WRTRIM_MASK; + ANACTRL->ANALOG_CTRL_CFG = analog_ctrl_regs[1]; + ANACTRL->ADC_CTRL = analog_ctrl_regs[2]; + ANACTRL->XO32M_CTRL = analog_ctrl_regs[3]; + ANACTRL->BOD_DCDC_INT_CTRL = analog_ctrl_regs[4]; + ANACTRL->RINGO0_CTRL = analog_ctrl_regs[5]; + ANACTRL->RINGO1_CTRL = analog_ctrl_regs[6]; + ANACTRL->RINGO2_CTRL = analog_ctrl_regs[7]; + ANACTRL->LDO_XO32M = analog_ctrl_regs[8]; + ANACTRL->AUX_BIAS = analog_ctrl_regs[9]; + ANACTRL->USBHS_PHY_CTRL = analog_ctrl_regs[10]; + ANACTRL->USBHS_PHY_TRIM = analog_ctrl_regs[11]; + } +} + +/** + * brief PMC Deep Sleep Power Down function call + * return nothing + */ +void POWER_EnterDeepPowerDown(uint32_t exclude_from_pd, + uint32_t sram_retention_ctrl, + uint64_t wakeup_interrupts, + uint32_t wakeup_io_ctrl) +{ + LPC_LOWPOWER_T lv_low_power_mode_cfg; /* Low Power Mode configuration structure */ + uint32_t cpu0_nmi_enable; + uint32_t cpu0_int_enable_0; + uint32_t cpu0_int_enable_1; + uint32_t pmc_reset_ctrl; + + /* Clear Low Power Mode configuration variable */ + (void)memset(&lv_low_power_mode_cfg, 0x0, sizeof(LPC_LOWPOWER_T)); + + /* Configure Low Power Mode configuration variable */ + lv_low_power_mode_cfg.CFG |= (uint32_t)LOWPOWER_CFG_LPMODE_DEEPPOWERDOWN + << LOWPOWER_CFG_LPMODE_INDEX; /* DEEP POWER DOWN mode */ + + /* Only FRO32K, XTAL32K and LDO_MEM can be stay powered during DEEPPOWERDOWN (valid from application point of view; + * Hardware allows BODVBAT, BIAS FRO1M and COMP to stay powered, that's why they are excluded below) */ + lv_low_power_mode_cfg.PDCTRL0 = (~exclude_from_pd) | (uint32_t)kPDRUNCFG_PD_BIAS | (uint32_t)kPDRUNCFG_PD_BODVBAT | + (uint32_t)kPDRUNCFG_PD_FRO1M | (uint32_t)kPDRUNCFG_PD_COMP; + + /* SRAM retention control during DEEPPOWERDOWN */ + sram_retention_ctrl = + sram_retention_ctrl & + (~(LOWPOWER_SRAMRETCTRL_RETEN_RAMX0 | LOWPOWER_SRAMRETCTRL_RETEN_RAMX1 | LOWPOWER_SRAMRETCTRL_RETEN_RAM00)); + + /* SRAM retention control during DEEPPOWERDOWN */ + lv_low_power_mode_cfg.SRAMRETCTRL = sram_retention_ctrl; + + /* Sanity check: If retention is required for any of SRAM instances, make sure LDO MEM will stay powered */ + if ((sram_retention_ctrl & 0x7FFFUL) != 0UL) + { + lv_low_power_mode_cfg.PDCTRL0 &= ~(uint32_t)kPDRUNCFG_PD_LDOMEM; + } + + /* Voltage control in Low Power Modes */ + /* The Memories Voltage settings below are for voltage scaling */ + lv_low_power_mode_cfg.VOLTAGE = lf_set_ldo_ao_ldo_mem_voltage(LOWPOWER_CFG_LPMODE_DEEPPOWERDOWN, 0); + + lv_low_power_mode_cfg.WAKEUPINT = + wakeup_interrupts & (WAKEUP_RTC_LITE_ALARM_WAKEUP | + WAKEUP_OS_EVENT_TIMER); /* CPU Wake up sources control : only WAKEUP_RTC_LITE_ALARM_WAKEUP, + WAKEUP_OS_EVENT_TIMER */ + lv_low_power_mode_cfg.WAKEUPSRC = + wakeup_interrupts & + (WAKEUP_RTC_LITE_ALARM_WAKEUP | WAKEUP_OS_EVENT_TIMER | + WAKEUP_ALLWAKEUPIOS); /*!< Hardware Wake up sources control: : only WAKEUP_RTC_LITE_ALARM_WAKEUP, + WAKEUP_OS_EVENT_TIMER and WAKEUP_ALLWAKEUPIOS */ + + /* Wake up I/O sources */ + lv_low_power_mode_cfg.WAKEUPIOSRC = lf_wakeup_io_ctrl(wakeup_io_ctrl); + + cpu0_nmi_enable = SYSCON->NMISRC & SYSCON_NMISRC_NMIENCPU0_MASK; /* Save the configuration of the NMI Register */ + SYSCON->NMISRC &= ~SYSCON_NMISRC_NMIENCPU0_MASK; /* Disable NMI of CPU0 */ + + /* Save the configuration of the CPU interrupt enable Registers */ + cpu0_int_enable_0 = NVIC->ISER[0]; + cpu0_int_enable_1 = NVIC->ISER[1]; + + /* Save the configuration of the PMC RESETCTRL register */ + pmc_reset_ctrl = PMC->RESETCTRL; + /* Disable BoD VBAT and BoD Core resets */ + PMC->RESETCTRL = + pmc_reset_ctrl & (~(PMC_RESETCTRL_BODVBATRESETENABLE_MASK | PMC_RESETCTRL_BODCORERESETENABLE_MASK)); + + /* Disable LDO MEM bleed current */ + // PMC->MISCCTRL |= PMC_MISCCTRL_DISABLE_BLEED_MASK; + + /* Enter low power mode */ + POWER_EnterLowPower(&lv_low_power_mode_cfg); + + /* Restore the configuration of the NMI Register */ + SYSCON->NMISRC |= cpu0_nmi_enable; + + /* Restore PMC RESETCTRL register */ + PMC->RESETCTRL = pmc_reset_ctrl; + + /* Restore the configuration of the CPU interrupt enable Registers */ + NVIC->ISER[0] = cpu0_int_enable_0; + NVIC->ISER[1] = cpu0_int_enable_1; +} + +/** + * brief PMC Sleep function call + * return nothing + */ +void POWER_EnterSleep(void) +{ + uint32_t pmsk; + pmsk = __get_PRIMASK(); + __disable_irq(); + SCB->SCR &= ~SCB_SCR_SLEEPDEEP_Msk; + __WFI(); + __set_PRIMASK(pmsk); +} + +/** + * @brief Get Digital Core logic supply source to be used during Deep Sleep. + * @param [in] exclude_from_pd: COmpoenents NOT to be powered down during Deep Sleep + * @param [out] core_supply: 0 = LDO DEEPSLEEP will be used / 1 = DCDC will be used + * @param [out] dcdc_voltage: as defined by V_DCDC_* in fsl_power.h + + * @return Nothing + */ +static void lf_get_deepsleep_core_supply_cfg(uint32_t exclude_from_pd, uint32_t *dcdc_voltage) +{ + *dcdc_voltage = (uint32_t)V_DCDC_0P950; /* Default value */ + + if (((exclude_from_pd & (uint32_t)kPDRUNCFG_PD_USB1_PHY) != 0UL) && + ((exclude_from_pd & (uint32_t)kPDRUNCFG_PD_LDOUSBHS) != 0UL)) + { + /* USB High Speed is required as wake-up source in Deep Sleep mode */ + PMC->MISCCTRL |= PMC_MISCCTRL_LOWPWR_FLASH_BUF_MASK; /* Force flash buffer in low power mode */ + *dcdc_voltage = + (uint32_t)V_DCDC_1P000; /* Set DCDC voltage to be 1.000 V (USB HS IP cannot work below 0.990 V) */ + } +} + +/** + * @brief + * @param + * @return + */ +static uint32_t lf_set_ldo_ao_ldo_mem_voltage(uint32_t p_lp_mode, uint32_t p_dcdc_voltage) +{ +#define FLASH_NMPA_LDO_AO_ADDRS (0x9FCF4U) +#define FLASH_NMPA_LDO_AO_DSLP_TRIM_VALID_MASK (0x100U) +#define FLASH_NMPA_LDO_AO_DSLP_TRIM_MASK (0x3E00U) +#define FLASH_NMPA_LDO_AO_DSLP_TRIM_SHIFT (9U) +#define FLASH_NMPA_LDO_AO_PDWN_TRIM_VALID_MASK (0x10000U) +#define FLASH_NMPA_LDO_AO_PDWN_TRIM_MASK (0x3E0000U) +#define FLASH_NMPA_LDO_AO_PDWN_TRIM_SHIFT (17U) +#define FLASH_NMPA_LDO_AO_DPDW_TRIM_VALID_MASK (0x1000000U) +#define FLASH_NMPA_LDO_AO_DPDW_TRIM_MASK (0x3E000000U) +#define FLASH_NMPA_LDO_AO_DPDW_TRIM_SHIFT (25U) + + uint32_t ldo_ao_trim, voltage; + uint32_t lv_v_ldo_pmu, lv_v_ldo_pmu_boost; + + ldo_ao_trim = (*((volatile unsigned int *)(FLASH_NMPA_LDO_AO_ADDRS))); + + switch (p_lp_mode) + { + case LOWPOWER_CFG_LPMODE_DEEPSLEEP: + { + if ((ldo_ao_trim & FLASH_NMPA_LDO_AO_DSLP_TRIM_VALID_MASK) != 0UL) + { + /* Apply settings coming from Flash */ + lv_v_ldo_pmu = (ldo_ao_trim & FLASH_NMPA_LDO_AO_DSLP_TRIM_MASK) >> FLASH_NMPA_LDO_AO_DSLP_TRIM_SHIFT; + lv_v_ldo_pmu_boost = lv_v_ldo_pmu - 2UL; /* - 50 mV */ + } + else + { + /* Apply default settings */ + lv_v_ldo_pmu = (uint32_t)V_AO_0P900; + lv_v_ldo_pmu_boost = (uint32_t)V_AO_0P850; + } + } + break; + + case LOWPOWER_CFG_LPMODE_POWERDOWN: + { + if ((ldo_ao_trim & FLASH_NMPA_LDO_AO_PDWN_TRIM_VALID_MASK) != 0UL) + { + /* Apply settings coming from Flash */ + lv_v_ldo_pmu = (ldo_ao_trim & FLASH_NMPA_LDO_AO_PDWN_TRIM_MASK) >> FLASH_NMPA_LDO_AO_PDWN_TRIM_SHIFT; + lv_v_ldo_pmu_boost = lv_v_ldo_pmu - 2UL; /* - 50 mV */ + } + else + { + /* Apply default settings */ + lv_v_ldo_pmu = (uint32_t)V_AO_0P800; + lv_v_ldo_pmu_boost = (uint32_t)V_AO_0P750; + } + } + break; + + case LOWPOWER_CFG_LPMODE_DEEPPOWERDOWN: + { + if ((ldo_ao_trim & FLASH_NMPA_LDO_AO_DPDW_TRIM_VALID_MASK) != 0UL) + { + /* Apply settings coming from Flash */ + lv_v_ldo_pmu = (ldo_ao_trim & FLASH_NMPA_LDO_AO_DPDW_TRIM_MASK) >> FLASH_NMPA_LDO_AO_DPDW_TRIM_SHIFT; + lv_v_ldo_pmu_boost = lv_v_ldo_pmu - 2UL; /* - 50 mV */ + } + else + { + /* Apply default settings */ + lv_v_ldo_pmu = (uint32_t)V_AO_0P800; + lv_v_ldo_pmu_boost = (uint32_t)V_AO_0P750; + } + } + break; + + default: + /* Should never reach this point */ + lv_v_ldo_pmu = (uint32_t)V_AO_1P100; + lv_v_ldo_pmu_boost = (uint32_t)V_AO_1P050; + break; + } + + /* The Memories Voltage settings below are for voltage scaling */ + voltage = + (lv_v_ldo_pmu << LOWPOWER_VOLTAGE_LDO_PMU_INDEX) | /* */ + (lv_v_ldo_pmu_boost << LOWPOWER_VOLTAGE_LDO_PMU_BOOST_INDEX) | /* */ + ((uint32_t)V_AO_0P750 << LOWPOWER_VOLTAGE_LDO_MEM_INDEX) | /* Set to 0.75V (voltage Scaling) */ + ((uint32_t)V_AO_0P700 << LOWPOWER_VOLTAGE_LDO_MEM_BOOST_INDEX) | /* Set to 0.7V (voltage Scaling) */ + ((uint32_t)V_DEEPSLEEP_0P900 + << LOWPOWER_VOLTAGE_LDO_DEEP_SLEEP_INDEX) | /* Set to 0.90 V (Not used because LDO_DEEP_SLEEP is disabled)*/ + (p_dcdc_voltage << LOWPOWER_VOLTAGE_DCDC_INDEX) /* */ + ; + + return (voltage); +} + +/** + * @brief + * @param + * @return + */ +static uint32_t lf_wakeup_io_ctrl(uint32_t p_wakeup_io_ctrl) +{ + uint32_t wake_up_type; + uint32_t misc_ctrl_reg; + uint8_t use_external_pullupdown = 0; + + /* Configure Pull up & Pull down based on the required wake-up edge */ + CLOCK_EnableClock(kCLOCK_Iocon); + + misc_ctrl_reg = 0UL; + + /* Wake-up I/O 0 */ + wake_up_type = (p_wakeup_io_ctrl & 0x3UL) >> LOWPOWER_WAKEUPIOSRC_PIO0_INDEX; + use_external_pullupdown = (uint8_t)((p_wakeup_io_ctrl & LOWPOWER_WAKEUPIO_PIO0_USEEXTERNALPULLUPDOWN_MASK) >> + LOWPOWER_WAKEUPIO_PIO0_USEEXTERNALPULLUPDOWN_INDEX); + + if (use_external_pullupdown == 0UL) + { + if ((wake_up_type == 1UL) || (wake_up_type == 3UL)) + { + /* Rising edge and both rising and falling edges */ + IOCON->PIO[1][1] = IOCON_PIO_DIGIMODE(1) | IOCON_PIO_MODE(1); /* Pull down */ + misc_ctrl_reg |= LOWPOWER_WAKEUPIO_PIO0_PULLUPDOWN_MASK; + p_wakeup_io_ctrl &= ~LOWPOWER_WAKEUPIO_PIO0_PULLUPDOWN_MASK; + } + else + { + if (wake_up_type == 2UL) + { + /* Falling edge only */ + IOCON->PIO[1][1] = IOCON_PIO_DIGIMODE(1) | IOCON_PIO_MODE(2); /* Pull up */ + misc_ctrl_reg &= ~LOWPOWER_WAKEUPIO_PIO0_PULLUPDOWN_MASK; + p_wakeup_io_ctrl |= LOWPOWER_WAKEUPIO_PIO0_PULLUPDOWN_MASK; + } + else + { + /* Wake-up I/O is disabled : set it as required by the user */ + if ((p_wakeup_io_ctrl & LOWPOWER_WAKEUPIO_PIO0_DISABLEPULLUPDOWN_MASK) != 0UL) + { + /* Wake-up I/O is configured as Plain Input */ + p_wakeup_io_ctrl &= ~LOWPOWER_WAKEUPIO_PIO0_PULLUPDOWN_MASK; + } + else + { + /* Wake-up I/O is configured as pull-up or pull-down */ + misc_ctrl_reg |= (~p_wakeup_io_ctrl) & LOWPOWER_WAKEUPIO_PIO0_PULLUPDOWN_MASK; + } + } + } + } + else + { + /* MISCCTRL[8]:WAKEUPIOCTRL[8]:00 -no pullup,pulldown, 10 - pulldown, 01 - pullup, 11 - reserved */ + p_wakeup_io_ctrl &= ~LOWPOWER_WAKEUPIO_PIO0_PULLUPDOWN_MASK; + misc_ctrl_reg &= ~LOWPOWER_WAKEUPIO_PIO0_PULLUPDOWN_MASK; + } + + /* Wake-up I/O 1 */ + wake_up_type = (p_wakeup_io_ctrl & 0xCUL) >> LOWPOWER_WAKEUPIOSRC_PIO1_INDEX; + use_external_pullupdown = (uint8_t)((p_wakeup_io_ctrl & LOWPOWER_WAKEUPIO_PIO1_USEEXTERNALPULLUPDOWN_MASK) >> + LOWPOWER_WAKEUPIO_PIO1_USEEXTERNALPULLUPDOWN_INDEX); + + if (use_external_pullupdown == 0UL) + { + if ((wake_up_type == 1UL) || (wake_up_type == 3UL)) + { + /* Rising edge and both rising and falling edges */ + IOCON->PIO[0][28] = IOCON_PIO_DIGIMODE(1) | IOCON_PIO_MODE(1); /* Pull down */ + misc_ctrl_reg |= LOWPOWER_WAKEUPIO_PIO1_PULLUPDOWN_MASK; + p_wakeup_io_ctrl &= ~LOWPOWER_WAKEUPIO_PIO1_PULLUPDOWN_MASK; + } + else + { + if (wake_up_type == 2UL) + { + /* Falling edge only */ + IOCON->PIO[0][28] = IOCON_PIO_DIGIMODE(1) | IOCON_PIO_MODE(2); /* Pull up */ + misc_ctrl_reg &= ~LOWPOWER_WAKEUPIO_PIO1_PULLUPDOWN_MASK; + p_wakeup_io_ctrl |= LOWPOWER_WAKEUPIO_PIO1_PULLUPDOWN_MASK; + } + else + { + /* Wake-up I/O is disabled : set it as required by the user */ + if ((p_wakeup_io_ctrl & LOWPOWER_WAKEUPIO_PIO1_DISABLEPULLUPDOWN_MASK) != 0UL) + { + /* Wake-up I/O is configured as Plain Input */ + p_wakeup_io_ctrl &= ~LOWPOWER_WAKEUPIO_PIO1_PULLUPDOWN_MASK; + } + else + { + /* Wake-up I/O is configured as pull-up or pull-down */ + misc_ctrl_reg |= (~p_wakeup_io_ctrl) & LOWPOWER_WAKEUPIO_PIO1_PULLUPDOWN_MASK; + } + } + } + } + else + { + /* MISCCTRL[9]:WAKEUPIOCTRL[9]:00 -no pullup,pulldown, 10 - pulldown, 01 - pullup, 11 - reserved */ + p_wakeup_io_ctrl &= ~LOWPOWER_WAKEUPIO_PIO1_PULLUPDOWN_MASK; + misc_ctrl_reg &= ~LOWPOWER_WAKEUPIO_PIO1_PULLUPDOWN_MASK; + } + + /* Wake-up I/O 2 */ + wake_up_type = (p_wakeup_io_ctrl & 0x30UL) >> LOWPOWER_WAKEUPIOSRC_PIO2_INDEX; + use_external_pullupdown = (uint8_t)((p_wakeup_io_ctrl & LOWPOWER_WAKEUPIO_PIO2_USEEXTERNALPULLUPDOWN_MASK) >> + LOWPOWER_WAKEUPIO_PIO2_USEEXTERNALPULLUPDOWN_INDEX); + + if (use_external_pullupdown == 0UL) + { + if ((wake_up_type == 1UL) || (wake_up_type == 3UL)) + { + /* Rising edge and both rising and falling edges */ + IOCON->PIO[1][18] = IOCON_PIO_DIGIMODE(1) | IOCON_PIO_MODE(1); /* Pull down */ + misc_ctrl_reg |= LOWPOWER_WAKEUPIO_PIO2_PULLUPDOWN_MASK; + p_wakeup_io_ctrl &= ~LOWPOWER_WAKEUPIO_PIO2_PULLUPDOWN_MASK; + } + else + { + if (wake_up_type == 2UL) + { + /* Falling edge only */ + IOCON->PIO[1][18] = IOCON_PIO_DIGIMODE(1) | IOCON_PIO_MODE(2); /* Pull up */ + misc_ctrl_reg &= ~LOWPOWER_WAKEUPIO_PIO2_PULLUPDOWN_MASK; + p_wakeup_io_ctrl |= LOWPOWER_WAKEUPIO_PIO2_PULLUPDOWN_MASK; + } + else + { + /* Wake-up I/O is disabled : set it as required by the user */ + if ((p_wakeup_io_ctrl & LOWPOWER_WAKEUPIO_PIO2_DISABLEPULLUPDOWN_MASK) != 0UL) + { + /* Wake-up I/O is configured as Plain Input */ + p_wakeup_io_ctrl &= ~LOWPOWER_WAKEUPIO_PIO2_PULLUPDOWN_MASK; + } + else + { + /* Wake-up I/O is configured as pull-up or pull-down */ + misc_ctrl_reg |= (~p_wakeup_io_ctrl) & LOWPOWER_WAKEUPIO_PIO2_PULLUPDOWN_MASK; + } + } + } + } + else + { + /* MISCCTRL[10]:WAKEUPIOCTRL[10]:00 -no pullup,pulldown, 10 - pulldown, 01 - pullup, 11 - reserved */ + p_wakeup_io_ctrl &= ~LOWPOWER_WAKEUPIO_PIO2_PULLUPDOWN_MASK; + misc_ctrl_reg &= ~LOWPOWER_WAKEUPIO_PIO2_PULLUPDOWN_MASK; + } + + /* Wake-up I/O 3 */ + wake_up_type = (p_wakeup_io_ctrl & 0xC0UL) >> LOWPOWER_WAKEUPIOSRC_PIO3_INDEX; + use_external_pullupdown = (uint8_t)((p_wakeup_io_ctrl & LOWPOWER_WAKEUPIO_PIO3_USEEXTERNALPULLUPDOWN_MASK) >> + LOWPOWER_WAKEUPIO_PIO3_USEEXTERNALPULLUPDOWN_INDEX); + + if (use_external_pullupdown == 0UL) + { + if ((wake_up_type == 1UL) || (wake_up_type == 3UL)) + { + /* Rising edge and both rising and falling edges */ + IOCON->PIO[1][30] = IOCON_PIO_DIGIMODE(1) | IOCON_PIO_MODE(1); /* Pull down */ + misc_ctrl_reg |= LOWPOWER_WAKEUPIO_PIO3_PULLUPDOWN_MASK; + p_wakeup_io_ctrl &= ~LOWPOWER_WAKEUPIO_PIO3_PULLUPDOWN_MASK; + } + else + { + if (wake_up_type == 2UL) + { + /* Falling edge only */ + IOCON->PIO[1][30] = IOCON_PIO_DIGIMODE(1) | IOCON_PIO_MODE(2); /* Pull up */ + misc_ctrl_reg &= ~LOWPOWER_WAKEUPIO_PIO3_PULLUPDOWN_MASK; + p_wakeup_io_ctrl |= LOWPOWER_WAKEUPIO_PIO3_PULLUPDOWN_MASK; + } + else + { + /* Wake-up I/O is disabled : set it as required by the user */ + if ((p_wakeup_io_ctrl & LOWPOWER_WAKEUPIO_PIO3_DISABLEPULLUPDOWN_MASK) != 0UL) + { + /* Wake-up I/O is configured as Plain Input */ + p_wakeup_io_ctrl &= ~LOWPOWER_WAKEUPIO_PIO3_PULLUPDOWN_MASK; + } + else + { + /* Wake-up I/O is configured as pull-up or pull-down */ + misc_ctrl_reg |= (~p_wakeup_io_ctrl) & LOWPOWER_WAKEUPIO_PIO3_PULLUPDOWN_MASK; + } + } + } + } + else + { + /* MISCCTRL[11]:WAKEUPIOCTRL[11]:00 -no pullup,pulldown, 10 - pulldown, 01 - pullup, 11 - reserved */ + p_wakeup_io_ctrl &= ~LOWPOWER_WAKEUPIO_PIO3_PULLUPDOWN_MASK; + misc_ctrl_reg &= ~LOWPOWER_WAKEUPIO_PIO3_PULLUPDOWN_MASK; + } + + PMC->MISCCTRL = (PMC->MISCCTRL & 0xFFFFF0FFUL) | misc_ctrl_reg; + PMC->WAKEUPIOCTRL = p_wakeup_io_ctrl & 0xFFFUL; + + /* + * Defined according to : + * - LOWPOWER_WAKEUPIOSRC_ in fsl_power.h + * - LOWPOWER_WAKEUPIO_PIO0_PULLUPDOWN_<...> in fsl_power.h + */ + return (p_wakeup_io_ctrl & 0xFFFUL); +} + +/** + * @brief + * @param + * @return + */ +static uint8_t CLOCK_u8OscCapConvert(uint8_t u8OscCap, uint8_t u8CapBankDiscontinuity) +{ + /* Compensate for discontinuity in the capacitor banks */ + if (u8OscCap < 64U) + { + if (u8OscCap >= u8CapBankDiscontinuity) + { + u8OscCap -= u8CapBankDiscontinuity; + } + else + { + u8OscCap = 0U; + } + } + else + { + if (u8OscCap <= (127U - u8CapBankDiscontinuity)) + { + u8OscCap += u8CapBankDiscontinuity; + } + else + { + u8OscCap = 127U; + } + } + return u8OscCap; +} + +/** + * @brief Described in fsl_common.h + * @param + * @return + */ +static void lowpower_set_system_voltage(uint32_t system_voltage_mv) +{ + /* + * Set system voltage + */ + uint32_t lv_ldo_ao = (uint32_t)V_AO_1P100; /* */ + uint32_t lv_ldo_ao_boost = (uint32_t)V_AO_1P150; /* */ + uint32_t lv_dcdc = (uint32_t)V_DCDC_1P100; /* */ + + if (system_voltage_mv <= 950UL) + { + lv_dcdc = (uint32_t)V_DCDC_0P950; + lv_ldo_ao = (uint32_t)V_AO_0P960; + lv_ldo_ao_boost = (uint32_t)V_AO_1P010; + } + else if (system_voltage_mv <= 975UL) + { + lv_dcdc = (uint32_t)V_DCDC_0P975; + lv_ldo_ao = (uint32_t)V_AO_0P980; + lv_ldo_ao_boost = (uint32_t)V_AO_1P030; + } + else if (system_voltage_mv <= 1000UL) + { + lv_dcdc = (uint32_t)V_DCDC_1P000; + lv_ldo_ao = (uint32_t)V_AO_1P000; + lv_ldo_ao_boost = (uint32_t)V_AO_1P050; + } + else if (system_voltage_mv <= 1025UL) + { + lv_dcdc = (uint32_t)V_DCDC_1P025; + lv_ldo_ao = (uint32_t)V_AO_1P030; + lv_ldo_ao_boost = (uint32_t)V_AO_1P080; + } + else if (system_voltage_mv <= 1050UL) + { + lv_dcdc = (uint32_t)V_DCDC_1P050; + lv_ldo_ao = (uint32_t)V_AO_1P060; + lv_ldo_ao_boost = (uint32_t)V_AO_1P110; + } + else if (system_voltage_mv <= 1075UL) + { + lv_dcdc = (uint32_t)V_DCDC_1P075; + lv_ldo_ao = (uint32_t)V_AO_1P080; + lv_ldo_ao_boost = (uint32_t)V_AO_1P130; + } + else if (system_voltage_mv <= 1100UL) + { + lv_dcdc = (uint32_t)V_DCDC_1P100; + lv_ldo_ao = (uint32_t)V_AO_1P100; + lv_ldo_ao_boost = (uint32_t)V_AO_1P150; + } + else if (system_voltage_mv <= 1125UL) + { + lv_dcdc = (uint32_t)V_DCDC_1P125; + lv_ldo_ao = (uint32_t)V_AO_1P130; + lv_ldo_ao_boost = (uint32_t)V_AO_1P160; + } + else if (system_voltage_mv <= 1150UL) + { + lv_dcdc = (uint32_t)V_DCDC_1P150; + lv_ldo_ao = (uint32_t)V_AO_1P160; + lv_ldo_ao_boost = (uint32_t)V_AO_1P220; + } + else if (system_voltage_mv <= 1175UL) + { + lv_dcdc = (uint32_t)V_DCDC_1P175; + lv_ldo_ao = (uint32_t)V_AO_1P160; + lv_ldo_ao_boost = (uint32_t)V_AO_1P220; + } + else + { + lv_dcdc = (uint32_t)V_DCDC_1P200; + lv_ldo_ao = (uint32_t)V_AO_1P160; + lv_ldo_ao_boost = (uint32_t)V_AO_1P220; + } + + /* Set up LDO Always-On voltages */ + PMC->LDOPMU = (PMC->LDOPMU & (~PMC_LDOPMU_VADJ_MASK) & (~PMC_LDOPMU_VADJ_BOOST_MASK)) | PMC_LDOPMU_VADJ(lv_ldo_ao) | + PMC_LDOPMU_VADJ_BOOST(lv_ldo_ao_boost); + + /* Set up DCDC voltage */ + PMC->DCDC0 = (PMC->DCDC0 & (~PMC_DCDC0_VOUT_MASK)) | PMC_DCDC0_VOUT(lv_dcdc); +} + +/** + * @brief Described in fsl_common.h + * @param + * @return + */ +static void lowpower_set_dcdc_power_profile(lowpower_dcdc_power_profile_enum dcdc_power_profile) +{ +#define FLASH_NMPA_BASE (0x9FC00u) +#define FLASH_NMPA_DCDC_POWER_PROFILE_LOW_0_ADDRS (FLASH_NMPA_BASE + 0xE0U) // (0x9FCE0U) +#define FLASH_NMPA_DCDC_POWER_PROFILE_LOW_1_ADDRS (FLASH_NMPA_BASE + 0xE4U) // (0x9FCE4U) +#define FLASH_NMPA_DCDC_POWER_PROFILE_MEDIUM_0_ADDRS (FLASH_NMPA_BASE + 0xE8U) // (0x9FCE8U) +#define FLASH_NMPA_DCDC_POWER_PROFILE_MEDIUM_1_ADDRS (FLASH_NMPA_BASE + 0xECU) // (0x9FCECU) +#define FLASH_NMPA_DCDC_POWER_PROFILE_HIGH_0_ADDRS (FLASH_NMPA_BASE + 0xD8U) // (0x9FCD8U) +#define FLASH_NMPA_DCDC_POWER_PROFILE_HIGH_1_ADDRS (FLASH_NMPA_BASE + 0xDCU) // (0x9FCDCU) + + const uint32_t PMC_DCDC0_DEFAULT = 0x010C4E68; + const uint32_t PMC_DCDC1_DEFAULT = 0x01803A98; + + uint32_t dcdcTrimValue0; + uint32_t dcdcTrimValue1; + + switch (dcdc_power_profile) + { + case DCDC_POWER_PROFILE_LOW: + /* Low */ + dcdcTrimValue0 = (*((volatile unsigned int *)(FLASH_NMPA_DCDC_POWER_PROFILE_LOW_0_ADDRS))); + dcdcTrimValue1 = (*((volatile unsigned int *)(FLASH_NMPA_DCDC_POWER_PROFILE_LOW_1_ADDRS))); + + if (0UL != (dcdcTrimValue0 & 0x1UL)) + { + dcdcTrimValue0 = dcdcTrimValue0 >> 1; + + PMC->DCDC0 = dcdcTrimValue0; + PMC->DCDC1 = dcdcTrimValue1; +#if (defined(NIOBE_DEBUG_LEVEL) && (NIOBE_DEBUG_LEVEL >= 1)) + PRINTF( + "\nINFO : DCDC Power Profile set to " + "LOW" + "\n"); +#endif + } + break; + + case DCDC_POWER_PROFILE_MEDIUM: + /* Medium */ + dcdcTrimValue0 = (*((volatile unsigned int *)(FLASH_NMPA_DCDC_POWER_PROFILE_MEDIUM_0_ADDRS))); + dcdcTrimValue1 = (*((volatile unsigned int *)(FLASH_NMPA_DCDC_POWER_PROFILE_MEDIUM_1_ADDRS))); + + if (0UL != (dcdcTrimValue0 & 0x1UL)) + { + dcdcTrimValue0 = dcdcTrimValue0 >> 1; + + PMC->DCDC0 = dcdcTrimValue0; + PMC->DCDC1 = dcdcTrimValue1; +#if (defined(NIOBE_DEBUG_LEVEL) && (NIOBE_DEBUG_LEVEL >= 1)) + PRINTF( + "\nINFO : DCDC Power Profile set to " + "MEDIUM" + "\n"); +#endif + } + break; + + case DCDC_POWER_PROFILE_HIGH: + /* High */ + dcdcTrimValue0 = (*((volatile unsigned int *)(FLASH_NMPA_DCDC_POWER_PROFILE_HIGH_0_ADDRS))); + dcdcTrimValue1 = (*((volatile unsigned int *)(FLASH_NMPA_DCDC_POWER_PROFILE_HIGH_1_ADDRS))); + + if (0UL != (dcdcTrimValue0 & 0x1UL)) + { + dcdcTrimValue0 = dcdcTrimValue0 >> 1; + + PMC->DCDC0 = dcdcTrimValue0; + PMC->DCDC1 = dcdcTrimValue1; +#if (defined(NIOBE_DEBUG_LEVEL) && (NIOBE_DEBUG_LEVEL >= 1)) + PRINTF( + "\nINFO : DCDC Power Profile set to " + "HIGH" + "\n"); +#endif + } + break; + + default: + /* Low */ + PMC->DCDC0 = PMC_DCDC0_DEFAULT; + PMC->DCDC1 = PMC_DCDC1_DEFAULT; +#if (defined(NIOBE_DEBUG_LEVEL) && (NIOBE_DEBUG_LEVEL >= 1)) + PRINTF( + "\nINFO : DCDC Power Profile set to " + "LOW" + "\n"); +#endif + break; + } +} + +/** + * @brief + * @param + * @return + */ +static lowpower_process_corner_enum lowpower_get_part_process_corner(void) +{ +#define FLASH_NMPA_PVT_MONITOR_0_RINGO_ADDRS (FLASH_NMPA_BASE + 0x130U) +#define FLASH_NMPA_PVT_MONITOR_1_RINGO_ADDRS (FLASH_NMPA_BASE + 0x140U) + + lowpower_process_corner_enum part_process_corner; + uint32_t pvt_ringo_hz; + uint32_t pvt_ringo_0 = (*((volatile unsigned int *)(FLASH_NMPA_PVT_MONITOR_0_RINGO_ADDRS))); + uint32_t pvt_ringo_1 = (*((volatile unsigned int *)(FLASH_NMPA_PVT_MONITOR_1_RINGO_ADDRS))); + + /* + * Check that the PVT Monitors Trimmings in flash are valid. + */ + if (0UL != (pvt_ringo_0 & 0x1UL)) + { + /* PVT Trimmings in Flash are valid */ + pvt_ringo_0 = pvt_ringo_0 >> 1; + } + else + { + /* PVT Trimmings in Flash are NOT valid (average value assumed) */ + pvt_ringo_0 = PROCESS_NNN_AVG_HZ; + } + + if (0UL != (pvt_ringo_1 & 0x1UL)) + { + /* PVT Trimmings in Flash are valid */ + pvt_ringo_1 = pvt_ringo_1 >> 1; + } + else + { + /* PVT Trimmings in Flash are NOT valid (average value assumed) */ + pvt_ringo_1 = PROCESS_NNN_AVG_HZ; + } + + if (pvt_ringo_1 <= pvt_ringo_0) + { + pvt_ringo_hz = pvt_ringo_1; + } + else + { + pvt_ringo_hz = pvt_ringo_0; + } + + /* + * Determine the process corner based on the value of the Ring Oscillator frequency + */ + if (pvt_ringo_hz <= PROCESS_NNN_MIN_HZ) + { + /* SSS Process Corner */ + part_process_corner = PROCESS_CORNER_SSS; +#if (defined(NIOBE_DEBUG_LEVEL) && (NIOBE_DEBUG_LEVEL >= 1)) + PRINTF( + "\nINFO : Process Corner : " + "SSS" + "\n"); +#endif + } + else + { + if (pvt_ringo_hz <= PROCESS_NNN_MAX_HZ) + { + /* NNN Process Corner */ + part_process_corner = PROCESS_CORNER_NNN; +#if (defined(NIOBE_DEBUG_LEVEL) && (NIOBE_DEBUG_LEVEL >= 1)) + PRINTF( + "\nINFO : Process Corner : " + "NNN" + "\n"); +#endif + } + else + { + /* FFF Process Corner */ + part_process_corner = PROCESS_CORNER_FFF; +#if (defined(NIOBE_DEBUG_LEVEL) && (NIOBE_DEBUG_LEVEL >= 1)) + PRINTF( + "\nINFO : Process Corner : " + "FFF" + "\n"); +#endif + } + } + + return (part_process_corner); +} + +/** + * @brief Described in fsl_common.h + * @param + * @return + */ +static void lowpower_set_voltage_for_process(lowpower_dcdc_power_profile_enum dcdc_power_profile) +{ + /* Get Sample Process Corner */ + lowpower_process_corner_enum part_process_corner = lowpower_get_part_process_corner(); + + switch (part_process_corner) + { + case PROCESS_CORNER_SSS: + /* Slow Corner */ + { + switch (dcdc_power_profile) + { + case DCDC_POWER_PROFILE_MEDIUM: + /* Medium */ + lowpower_set_system_voltage(VOLTAGE_SSS_MED_MV); + break; + + case DCDC_POWER_PROFILE_HIGH: + /* High */ + lowpower_set_system_voltage(VOLTAGE_SSS_HIG_MV); + break; + + default: + /* DCDC_POWER_PROFILE_LOW */ + lowpower_set_system_voltage(VOLTAGE_SSS_LOW_MV); + break; + } // switch(dcdc_power_profile) + } + break; + + case PROCESS_CORNER_FFF: + /* Fast Corner */ + { + switch (dcdc_power_profile) + { + case DCDC_POWER_PROFILE_MEDIUM: + /* Medium */ + lowpower_set_system_voltage(VOLTAGE_FFF_MED_MV); + break; + + case DCDC_POWER_PROFILE_HIGH: + /* High */ + lowpower_set_system_voltage(VOLTAGE_FFF_HIG_MV); + break; + + default: + /* DCDC_POWER_PROFILE_LOW */ + lowpower_set_system_voltage(VOLTAGE_FFF_LOW_MV); + break; + } // switch(dcdc_power_profile) + } + break; + + default: + /* Nominal (NNN) and all others Process Corners : assume Nominal Corner */ + { + switch (dcdc_power_profile) + { + case DCDC_POWER_PROFILE_MEDIUM: + /* Medium */ + lowpower_set_system_voltage(VOLTAGE_NNN_MED_MV); + break; + + case DCDC_POWER_PROFILE_HIGH: + /* High */ + lowpower_set_system_voltage(VOLTAGE_NNN_HIG_MV); + break; + + default: + /* DCDC_POWER_PROFILE_LOW */ + lowpower_set_system_voltage(VOLTAGE_NNN_LOW_MV); + break; + } // switch(dcdc_power_profile) + break; + } + } // switch(part_process_corner) +} + +/** + * @brief Described in fsl_common.h + * @param + * @return + */ +void POWER_SetVoltageForFreq(uint32_t system_freq_hz) +{ + if (system_freq_hz <= DCDC_POWER_PROFILE_LOW_MAX_FREQ_HZ) + { + /* [0 Hz - DCDC_POWER_PROFILE_LOW_MAX_FREQ_HZ Hz] */ + lowpower_set_dcdc_power_profile(DCDC_POWER_PROFILE_LOW); /* DCDC VOUT = 1.05 V by default */ + lowpower_set_voltage_for_process(DCDC_POWER_PROFILE_LOW); + } + else + { + if (system_freq_hz <= DCDC_POWER_PROFILE_MEDIUM_MAX_FREQ_HZ) + { + /* ]DCDC_POWER_PROFILE_LOW_MAX_FREQ_HZ Hz - DCDC_POWER_PROFILE_MEDIUM_MAX_FREQ_HZ Hz] */ + lowpower_set_dcdc_power_profile(DCDC_POWER_PROFILE_MEDIUM); /* DCDC VOUT = 1.15 V by default */ + lowpower_set_voltage_for_process(DCDC_POWER_PROFILE_MEDIUM); + } + else + { + /* > DCDC_POWER_PROFILE_MEDIUM_MAX_FREQ_HZ Hz */ + lowpower_set_dcdc_power_profile(DCDC_POWER_PROFILE_HIGH); /* DCDC VOUT = 1.2 V by default */ + lowpower_set_voltage_for_process(DCDC_POWER_PROFILE_HIGH); + } + } +} + +void POWER_Xtal16mhzCapabankTrim(int32_t pi32_16MfXtalIecLoadpF_x100, + int32_t pi32_16MfXtalPPcbParCappF_x100, + int32_t pi32_16MfXtalNPcbParCappF_x100) +{ + uint32_t u32XOTrimValue; + uint8_t u8IECXinCapCal6pF, u8IECXinCapCal8pF, u8IECXoutCapCal6pF, u8IECXoutCapCal8pF, u8XOSlave; + int32_t iaXin_x4, ibXin, iaXout_x4, ibXout; + int32_t iXOCapInpF_x100, iXOCapOutpF_x100; + uint8_t u8XOCapInCtrl, u8XOCapOutCtrl; + uint32_t u32RegVal; + int32_t i32Tmp; + + /* Enable and set LDO, if not already done */ + POWER_SetXtal16mhzLdo(); + /* Get Cal values from Flash */ + u32XOTrimValue = GET_16MXO_TRIM(); + /* Check validity and apply */ + if ((0UL != (u32XOTrimValue & 1UL)) && (0UL != ((u32XOTrimValue >> 15UL) & 1UL))) + { + /* These fields are 7 bits, unsigned */ + u8IECXinCapCal6pF = (uint8_t)((u32XOTrimValue >> 1UL) & 0x7fUL); + u8IECXinCapCal8pF = (uint8_t)((u32XOTrimValue >> 8UL) & 0x7fUL); + u8IECXoutCapCal6pF = (uint8_t)((u32XOTrimValue >> 16UL) & 0x7fUL); + u8IECXoutCapCal8pF = (uint8_t)((u32XOTrimValue >> 23UL) & 0x7fUL); + /* This field is 1 bit */ + u8XOSlave = (uint8_t)((u32XOTrimValue >> 30UL) & 0x1UL); + /* Linear fit coefficients calculation */ + iaXin_x4 = (int)u8IECXinCapCal8pF - (int)u8IECXinCapCal6pF; + ibXin = (int)u8IECXinCapCal6pF - iaXin_x4 * 3; + iaXout_x4 = (int)u8IECXoutCapCal8pF - (int)u8IECXoutCapCal6pF; + ibXout = (int)u8IECXoutCapCal6pF - iaXout_x4 * 3; + } + else + { + iaXin_x4 = 20; // gain in LSB/pF + ibXin = -9; // offset in LSB + iaXout_x4 = 20; // gain in LSB/pF + ibXout = -13; // offset in LSB + u8XOSlave = 0; + } + /* In & out load cap calculation with derating */ + iXOCapInpF_x100 = 2 * pi32_16MfXtalIecLoadpF_x100 - pi32_16MfXtalNPcbParCappF_x100 + + 39 * ((int32_t)XO_SLAVE_EN - (int32_t)u8XOSlave) - 15; + iXOCapOutpF_x100 = 2 * pi32_16MfXtalIecLoadpF_x100 - pi32_16MfXtalPPcbParCappF_x100 - 21; + /* In & out XO_OSC_CAP_Code_CTRL calculation, with rounding */ + i32Tmp = ((iXOCapInpF_x100 * iaXin_x4 + ibXin * 400) + 200) / 400; + u8XOCapInCtrl = (uint8_t)i32Tmp; + i32Tmp = ((iXOCapOutpF_x100 * iaXout_x4 + ibXout * 400) + 200) / 400; + u8XOCapOutCtrl = (uint8_t)i32Tmp; + /* Read register and clear fields to be written */ + u32RegVal = ANACTRL->XO32M_CTRL; + u32RegVal &= ~(ANACTRL_XO32M_CTRL_OSC_CAP_IN_MASK | ANACTRL_XO32M_CTRL_OSC_CAP_OUT_MASK); + /* Configuration of 32 MHz XO output buffers */ +#if (XO_SLAVE_EN == 0) + u32RegVal &= ~(ANACTRL_XO32M_CTRL_SLAVE_MASK | ANACTRL_XO32M_CTRL_ACBUF_PASS_ENABLE_MASK); +#else + u32RegVal |= ANACTRL_XO32M_CTRL_SLAVE_MASK | ANACTRL_XO32M_CTRL_ACBUF_PASS_ENABLE_MASK; +#endif + /* XO_OSC_CAP_Code_CTRL to XO_OSC_CAP_Code conversion */ + u32RegVal |= (uint32_t)CLOCK_u8OscCapConvert(u8XOCapInCtrl, 13) << ANACTRL_XO32M_CTRL_OSC_CAP_IN_SHIFT; + u32RegVal |= (uint32_t)CLOCK_u8OscCapConvert(u8XOCapOutCtrl, 13) << ANACTRL_XO32M_CTRL_OSC_CAP_OUT_SHIFT; + /* Write back to register */ + ANACTRL->XO32M_CTRL = u32RegVal; +} + +void POWER_Xtal32khzCapabankTrim(int32_t pi32_32kfXtalIecLoadpF_x100, + int32_t pi32_32kfXtalPPcbParCappF_x100, + int32_t pi32_32kfXtalNPcbParCappF_x100) +{ + uint32_t u32XOTrimValue; + uint8_t u8IECXinCapCal6pF, u8IECXinCapCal8pF, u8IECXoutCapCal6pF, u8IECXoutCapCal8pF; + int32_t iaXin_x4, ibXin, iaXout_x4, ibXout; + int32_t iXOCapInpF_x100, iXOCapOutpF_x100; + uint8_t u8XOCapInCtrl, u8XOCapOutCtrl; + uint32_t u32RegVal; + int32_t i32Tmp; + /* Get Cal values from Flash */ + u32XOTrimValue = GET_32KXO_TRIM(); + /* check validity and apply */ + if ((0UL != (u32XOTrimValue & 1UL)) && (0UL != ((u32XOTrimValue >> 15UL) & 1UL))) + { + /* These fields are 7 bits, unsigned */ + u8IECXinCapCal6pF = (uint8_t)((u32XOTrimValue >> 1UL) & 0x7fUL); + u8IECXinCapCal8pF = (uint8_t)((u32XOTrimValue >> 8UL) & 0x7fUL); + u8IECXoutCapCal6pF = (uint8_t)((u32XOTrimValue >> 16UL) & 0x7fUL); + u8IECXoutCapCal8pF = (uint8_t)((u32XOTrimValue >> 23UL) & 0x7fUL); + /* Linear fit coefficients calculation */ + iaXin_x4 = (int)u8IECXinCapCal8pF - (int)u8IECXinCapCal6pF; + ibXin = (int)u8IECXinCapCal6pF - iaXin_x4 * 3; + iaXout_x4 = (int)u8IECXoutCapCal8pF - (int)u8IECXoutCapCal6pF; + ibXout = (int)u8IECXoutCapCal6pF - iaXout_x4 * 3; + } + else + { + iaXin_x4 = 16; // gain in LSB/pF + ibXin = 12; // offset in LSB + iaXout_x4 = 16; // gain in LSB/pF + ibXout = 11; // offset in LSB + } + + /* In & out load cap calculation with derating */ + iXOCapInpF_x100 = 2 * pi32_32kfXtalIecLoadpF_x100 - pi32_32kfXtalNPcbParCappF_x100 - 130; + iXOCapOutpF_x100 = 2 * pi32_32kfXtalIecLoadpF_x100 - pi32_32kfXtalPPcbParCappF_x100 - 41; + + /* In & out XO_OSC_CAP_Code_CTRL calculation, with rounding */ + i32Tmp = ((iXOCapInpF_x100 * iaXin_x4 + ibXin * 400) + 200) / 400; + u8XOCapInCtrl = (uint8_t)i32Tmp; + i32Tmp = ((iXOCapOutpF_x100 * iaXout_x4 + ibXout * 400) + 200) / 400; + u8XOCapOutCtrl = (uint8_t)i32Tmp; + + /* Read register and clear fields to be written */ + u32RegVal = PMC->XTAL32K; + u32RegVal &= ~(PMC_XTAL32K_CAPBANKIN_MASK | PMC_XTAL32K_CAPBANKOUT_MASK); + + /* XO_OSC_CAP_Code_CTRL to XO_OSC_CAP_Code conversion */ + u32RegVal |= (uint32_t)CLOCK_u8OscCapConvert(u8XOCapInCtrl, 23) << PMC_XTAL32K_CAPBANKIN_SHIFT; + u32RegVal |= (uint32_t)CLOCK_u8OscCapConvert(u8XOCapOutCtrl, 23) << PMC_XTAL32K_CAPBANKOUT_SHIFT; + + /* Write back to register */ + PMC->XTAL32K = u32RegVal; +} + +void POWER_SetXtal16mhzLdo(void) +{ + uint32_t temp; + const uint32_t u32Mask = + (ANACTRL_LDO_XO32M_VOUT_MASK | ANACTRL_LDO_XO32M_IBIAS_MASK | ANACTRL_LDO_XO32M_STABMODE_MASK); + + const uint32_t u32Value = + (ANACTRL_LDO_XO32M_VOUT(0x5) | ANACTRL_LDO_XO32M_IBIAS(0x2) | ANACTRL_LDO_XO32M_STABMODE(0x1)); + + /* Enable & set-up XTAL 32 MHz clock LDO */ + temp = ANACTRL->LDO_XO32M; + + if ((temp & u32Mask) != u32Value) + { + temp &= ~u32Mask; + + /* + * Enable the XTAL32M LDO + * Adjust the output voltage level, 0x5 for 1.1V + * Adjust the biasing current, 0x2 value + * Stability configuration, 0x1 default mode + */ + temp |= u32Value; + + ANACTRL->LDO_XO32M = temp; + + /* Delay for LDO to be up */ + // CLOCK_uDelay(20); + } + + /* Enable LDO XO32M */ + PMC->PDRUNCFGCLR0 = PMC_PDRUNCFG0_PDEN_LDOXO32M_MASK; +} + +/** + * @brief Return some key information related to the device reset causes / wake-up sources, for all power modes. + * @param p_reset_cause : the device reset cause, according to the definition of power_device_reset_cause_t type. + * @param p_boot_mode : the device boot mode, according to the definition of power_device_boot_mode_t type. + * @param p_wakeupio_cause: the wake-up pin sources, according to the definition of register PMC->WAKEIOCAUSE[3:0]. + + * @return Nothing + * + * !!! IMPORTANT ERRATA - IMPORTANT ERRATA - IMPORTANT ERRATA !!! + * !!! valid ONLY for LPC55S69 (not for LPC55S16 and LPC55S06) !!! + * !!! when FALLING EDGE DETECTION is enabled on wake-up pins: !!! + * - 1. p_wakeupio_cause is NOT ACCURATE + * - 2. Spurious kRESET_CAUSE_DPDRESET_WAKEUPIO* event is reported when + * several wake-up sources are enabled during DEEP-POWER-DOWN + * (like enabling wake-up on RTC and Falling edge wake-up pins) + * + */ +void POWER_GetWakeUpCause(power_device_reset_cause_t *p_reset_cause, + power_device_boot_mode_t *p_boot_mode, + uint32_t *p_wakeupio_cause) +{ + uint32_t reset_cause_reg; + uint32_t boot_mode_reg; + +#if (defined(LPC55S06_SERIES) || defined(LPC55S04_SERIES) || defined(LPC5506_SERIES) || defined(LPC5504_SERIES) || \ + defined(LPC5502_SERIES) || defined(LPC55S16_SERIES) || defined(LPC55S14_SERIES) || defined(LPC5516_SERIES) || \ + defined(LPC5514_SERIES) || defined(LPC5512_SERIES)) + reset_cause_reg = (PMC->AOREG1) & 0x3FF0UL; +#else /* LPC55S69/28 */ + reset_cause_reg = (PMC->AOREG1) & 0x1FF0UL; +#endif + + /* + * Prioritize interrupts source with respect to their critical level + */ +#if (defined(LPC55S06_SERIES) || defined(LPC55S04_SERIES) || defined(LPC5506_SERIES) || defined(LPC5504_SERIES) || \ + defined(LPC5502_SERIES) || defined(LPC55S16_SERIES) || defined(LPC55S14_SERIES) || defined(LPC5516_SERIES) || \ + defined(LPC5514_SERIES) || defined(LPC5512_SERIES)) + if (0UL != (reset_cause_reg & PMC_AOREG1_CDOGRESET_MASK)) + { /* Code Watchdog Reset */ + *p_reset_cause = kRESET_CAUSE_CDOGRESET; + *p_boot_mode = kBOOT_MODE_POWER_UP; + *p_wakeupio_cause = 0; /* Device has not been waked-up by any wake-up pins */ + } + else +#endif + { + if (0UL != (reset_cause_reg & PMC_AOREG1_WDTRESET_MASK)) + { /* Watchdog Timer Reset */ + *p_reset_cause = kRESET_CAUSE_WDTRESET; + *p_boot_mode = kBOOT_MODE_POWER_UP; + *p_wakeupio_cause = 0; /* Device has not been waked-up by any wake-up pins */ + } + else + { + if (0UL != (reset_cause_reg & PMC_AOREG1_SYSTEMRESET_MASK)) + { /* ARM System Reset */ + *p_reset_cause = kRESET_CAUSE_ARMSYSTEMRESET; + *p_boot_mode = kBOOT_MODE_POWER_UP; + *p_wakeupio_cause = 0; /* Device has not been waked-up by any wake-up pins */ + } + else + { + boot_mode_reg = (PMC->STATUS & PMC_STATUS_BOOTMODE_MASK) >> PMC_STATUS_BOOTMODE_SHIFT; + + if (boot_mode_reg == 0UL) /* POWER-UP: Power On Reset, Pin reset, Brown Out Detectors, Software Reset */ + { + *p_boot_mode = kBOOT_MODE_POWER_UP; /* All non wake-up from a Low Power mode */ + *p_wakeupio_cause = 0; /* Device has not been waked-up by any wake-up pins */ + + /* + * Prioritise Reset causes, starting from the strongest (Power On Reset) + */ + if (0UL != (reset_cause_reg & PMC_AOREG1_POR_MASK)) + { /* Power On Reset */ + *p_reset_cause = kRESET_CAUSE_POR; + } + else + { + if (0UL != (reset_cause_reg & PMC_AOREG1_BODRESET_MASK)) + { /* Brown-out Detector reset (either BODVBAT or BODCORE) */ + *p_reset_cause = kRESET_CAUSE_BODRESET; + } + else + { + if (0UL != (reset_cause_reg & PMC_AOREG1_PADRESET_MASK)) + { /* Hardware Pin Reset */ + *p_reset_cause = kRESET_CAUSE_PADRESET; + } + else + { + if (0UL != (reset_cause_reg & PMC_AOREG1_SWRRESET_MASK)) + { /* Software triggered Reset */ + *p_reset_cause = kRESET_CAUSE_SWRRESET; + } + else + { /* Unknown Reset Cause */ + *p_reset_cause = kRESET_CAUSE_NOT_DETERMINISTIC; + } + } + } + } + +#if (defined(LPC55S06_SERIES) || defined(LPC55S04_SERIES) || defined(LPC5506_SERIES) || defined(LPC5504_SERIES) || \ + defined(LPC5502_SERIES) || defined(LPC55S16_SERIES) || defined(LPC55S14_SERIES) || defined(LPC5516_SERIES) || \ + defined(LPC5514_SERIES) || defined(LPC5512_SERIES)) + /* Transfer the control of the 4 wake-up pins to IOCON (instead of the Power Management Controller + */ + PMC->WAKEUPIOCTRL = PMC->WAKEUPIOCTRL & (~PMC_WAKEUPIOCTRL_WAKEUPIO_ENABLE_CTRL_MASK); +#endif + } + else /* DEEP-SLEEP, POWER-DOWN and DEEP-POWER-DOWN */ + { + /* + * 1- First, save wakeup_io_cause register ... + */ + *p_wakeupio_cause = PMC->WAKEIOCAUSE; + + if (boot_mode_reg == 3UL) /* DEEP-POWER-DOWN */ + { + *p_boot_mode = kBOOT_MODE_LP_DEEP_POWER_DOWN; + + switch (((reset_cause_reg >> PMC_AOREG1_DPDRESET_WAKEUPIO_SHIFT) & 0x7UL)) + { + case 1: + *p_reset_cause = kRESET_CAUSE_DPDRESET_WAKEUPIO; + break; + case 2: + *p_reset_cause = kRESET_CAUSE_DPDRESET_RTC; + break; + case 3: + *p_reset_cause = kRESET_CAUSE_DPDRESET_WAKEUPIO_RTC; + break; + case 4: + *p_reset_cause = kRESET_CAUSE_DPDRESET_OSTIMER; + break; + case 5: + *p_reset_cause = kRESET_CAUSE_DPDRESET_WAKEUPIO_OSTIMER; + break; + case 6: + *p_reset_cause = kRESET_CAUSE_DPDRESET_RTC_OSTIMER; + break; + case 7: + *p_reset_cause = kRESET_CAUSE_DPDRESET_WAKEUPIO_RTC_OSTIMER; + break; + default: + /* Unknown Reset Cause */ + *p_reset_cause = kRESET_CAUSE_NOT_DETERMINISTIC; + break; + } + +#if (defined(LPC55S06_SERIES) || defined(LPC55S04_SERIES) || defined(LPC5506_SERIES) || defined(LPC5504_SERIES) || \ + defined(LPC5502_SERIES) || defined(LPC55S16_SERIES) || defined(LPC55S14_SERIES) || defined(LPC5516_SERIES) || \ + defined(LPC5514_SERIES) || defined(LPC5512_SERIES)) + /* + * 2- Next, transfer the control of the 4 wake-up pins + * to IOCON (instead of the Power Management Controller) + */ + PMC->WAKEUPIOCTRL = PMC->WAKEUPIOCTRL & (~PMC_WAKEUPIOCTRL_WAKEUPIO_ENABLE_CTRL_MASK); +#endif + } + else /* DEEP-SLEEP and POWER-DOWN */ + { + *p_reset_cause = kRESET_CAUSE_NOT_RELEVANT; + + /* + * The control of the 4 wake-up pins is already in IOCON, + * so there is nothing special to do. + */ + + if (boot_mode_reg == 1UL) /* DEEP-SLEEP */ + { + *p_boot_mode = kBOOT_MODE_LP_DEEP_SLEEP; + } + else /* POWER-DOWN */ + { + *p_boot_mode = kBOOT_MODE_LP_POWER_DOWN; + + } /* if ( boot_mode_reg == 1 ) DEEP-SLEEP */ + + } /* if ( boot_mode == 3 ) DEEP-POWER-DOWN */ + + } /* if ( boot_mode == 0 ) POWER-UP */ + + } /* if ( reset_cause_reg & PMC_AOREG1_CDOGRESET_MASK ) */ + + } /* if ( reset_cause_reg & PMC_AOREG1_WDTRESET_MASK ) */ + + } /* if ( reset_cause_reg & PMC_AOREG1_SYSTEMRESET_MASK ) */ +} diff --git a/drivers/Src/fsl_reset.c b/drivers/Src/fsl_reset.c new file mode 100644 index 0000000..4326e0d --- /dev/null +++ b/drivers/Src/fsl_reset.c @@ -0,0 +1,99 @@ +/* + * Copyright (c) 2016, Freescale Semiconductor, Inc. + * Copyright 2016, NXP + * All rights reserved. + * + * SPDX-License-Identifier: BSD-3-Clause + */ + +#include "fsl_common.h" +#include "fsl_reset.h" + +/******************************************************************************* + * Definitions + ******************************************************************************/ +/* Component ID definition, used by tools. */ +#ifndef FSL_COMPONENT_ID +#define FSL_COMPONENT_ID "platform.drivers.reset" +#endif + +/******************************************************************************* + * Variables + ******************************************************************************/ + +/******************************************************************************* + * Prototypes + ******************************************************************************/ + +/******************************************************************************* + * Code + ******************************************************************************/ + +#if (defined(FSL_FEATURE_SOC_SYSCON_COUNT) && (FSL_FEATURE_SOC_SYSCON_COUNT > 0)) + +/*! + * brief Assert reset to peripheral. + * + * Asserts reset signal to specified peripheral module. + * + * param peripheral Assert reset to this peripheral. The enum argument contains encoding of reset register + * and reset bit position in the reset register. + */ +void RESET_SetPeripheralReset(reset_ip_name_t peripheral) +{ + const uint32_t regIndex = ((uint32_t)peripheral & 0xFFFF0000u) >> 16; + const uint32_t bitPos = ((uint32_t)peripheral & 0x0000FFFFu); + const uint32_t bitMask = 1UL << bitPos; + + assert(bitPos < 32u); + + /* reset register is in SYSCON */ + /* set bit */ + SYSCON->PRESETCTRLSET[regIndex] = bitMask; + /* wait until it reads 0b1 */ + while (0u == (SYSCON->PRESETCTRLX[regIndex] & bitMask)) + { + } +} + +/*! + * brief Clear reset to peripheral. + * + * Clears reset signal to specified peripheral module, allows it to operate. + * + * param peripheral Clear reset to this peripheral. The enum argument contains encoding of reset register + * and reset bit position in the reset register. + */ +void RESET_ClearPeripheralReset(reset_ip_name_t peripheral) +{ + const uint32_t regIndex = ((uint32_t)peripheral & 0xFFFF0000u) >> 16; + const uint32_t bitPos = ((uint32_t)peripheral & 0x0000FFFFu); + const uint32_t bitMask = 1UL << bitPos; + + assert(bitPos < 32u); + + /* reset register is in SYSCON */ + + /* clear bit */ + SYSCON->PRESETCTRLCLR[regIndex] = bitMask; + /* wait until it reads 0b0 */ + while (bitMask == (SYSCON->PRESETCTRLX[regIndex] & bitMask)) + { + } +} + +/*! + * brief Reset peripheral module. + * + * Reset peripheral module. + * + * param peripheral Peripheral to reset. The enum argument contains encoding of reset register + * and reset bit position in the reset register. + */ +void RESET_PeripheralReset(reset_ip_name_t peripheral) +{ + RESET_SetPeripheralReset(peripheral); + RESET_ClearPeripheralReset(peripheral); +} + +#endif /* FSL_FEATURE_SOC_SYSCON_COUNT || FSL_FEATURE_SOC_ASYNC_SYSCON_COUNT */ diff --git a/drivers/Src/fsl_str.c b/drivers/Src/fsl_str.c new file mode 100644 index 0000000..433d07a --- /dev/null +++ b/drivers/Src/fsl_str.c @@ -0,0 +1,1707 @@ +/* + * Copyright 2017, 2020, 2022-2023 NXP + * All rights reserved. + * + * + * SPDX-License-Identifier: BSD-3-Clause + * + */ + +#include +#include +#include +#include /* MISRA C-2012 Rule 22.9 */ +#include "fsl_str.h" + +/******************************************************************************* + * Definitions + ******************************************************************************/ + +/*! @brief The overflow value.*/ +#ifndef HUGE_VAL +#define HUGE_VAL (99.e99) +#endif /* HUGE_VAL */ + +#ifndef MAX_FIELD_WIDTH +#define MAX_FIELD_WIDTH 99U +#endif + +/*! @brief Keil: suppress ellipsis warning in va_arg usage below. */ +#if defined(__CC_ARM) +#pragma diag_suppress 1256 +#endif /* __CC_ARM */ + +#if (defined(PRINTF_ADVANCED_ENABLE) && (PRINTF_ADVANCED_ENABLE > 0U)) +#define STR_FORMAT_PRINTF_UVAL_TYPE unsigned long long int +#define STR_FORMAT_PRINTF_IVAL_TYPE long long int +#else +#define STR_FORMAT_PRINTF_UVAL_TYPE unsigned int +#define STR_FORMAT_PRINTF_IVAL_TYPE int +#endif +/******************************************************************************* + * Prototypes + ******************************************************************************/ +/*! + * @brief Scanline function which ignores white spaces. + * + * @param[in] s The address of the string pointer to update. + * @return String without white spaces. + */ +static uint32_t ScanIgnoreWhiteSpace(const char **s); + +/*! + * @brief Converts a radix number to a string and return its length. + * + * @param[in] numstr Converted string of the number. + * @param[in] nump Pointer to the number. + * @param[in] neg Polarity of the number. + * @param[in] radix The radix to be converted to. + * @param[in] use_caps Used to identify %x/X output format. + + * @return Length of the converted string. + */ +static int32_t ConvertRadixNumToString(char *numstr, void *nump, unsigned int neg, unsigned int radix, bool use_caps); + +#if (defined(PRINTF_FLOAT_ENABLE) && (PRINTF_FLOAT_ENABLE > 0U)) +/*! + * @brief Converts a floating radix number to a string and return its length. + * + * @param[in] numstr Converted string of the number. + * @param[in] nump Pointer to the number. + * @param[in] radix The radix to be converted to. + * @param[in] precision_width Specify the precision width. + + * @return Length of the converted string. + */ +static int32_t ConvertFloatRadixNumToString(char *numstr, void *nump, int32_t radix, uint32_t precision_width); + +#endif /* PRINTF_FLOAT_ENABLE */ + +/*************Code for process formatted data*******************************/ +#if (defined(PRINTF_ADVANCED_ENABLE) && (PRINTF_ADVANCED_ENABLE > 0U)) +static uint8_t PrintGetSignChar(long long int ival, uint32_t flags_used, char *schar) +{ + uint8_t len = 1U; + if (ival < 0) + { + *schar = '-'; + } + else + { + if (0U != (flags_used & (uint32_t)kPRINTF_Plus)) + { + *schar = '+'; + } + else if (0U != (flags_used & (uint32_t)kPRINTF_Space)) + { + *schar = ' '; + } + else + { + *schar = '\0'; + len = 0U; + } + } + return len; +} +#endif /* PRINTF_ADVANCED_ENABLE */ + +static uint32_t PrintGetWidth(const char **p, va_list *ap) +{ + uint32_t field_width = 0; + uint8_t done = 0U; + char c; + + while (0U == done) + { + c = *(++(*p)); + if ((c >= '0') && (c <= '9')) + { + (field_width) = ((field_width)*10U) + ((uint32_t)c - (uint32_t)'0'); + } +#if (defined(PRINTF_ADVANCED_ENABLE) && (PRINTF_ADVANCED_ENABLE > 0U)) + else if (c == '*') + { + (field_width) = (uint32_t)va_arg(*ap, uint32_t); + } +#endif /* PRINTF_ADVANCED_ENABLE */ + else + { + /* We've gone one char too far. */ + --(*p); + done = 1U; + } + } + return field_width; +} + +static uint32_t PrintGetPrecision(const char **s, va_list *ap, bool *valid_precision_width) +{ + const char *p = *s; + uint32_t precision_width = 6U; + uint8_t done = 0U; + +#if (defined(PRINTF_ADVANCED_ENABLE) && (PRINTF_ADVANCED_ENABLE > 0U)) + if (NULL != valid_precision_width) + { + *valid_precision_width = false; + } +#endif /* PRINTF_ADVANCED_ENABLE */ + if (*++p == '.') + { + /* Must get precision field width, if present. */ + precision_width = 0U; + done = 0U; + while (0U == done) + { + char c = *++p; + if ((c >= '0') && (c <= '9')) + { + precision_width = (precision_width * 10U) + ((uint32_t)c - (uint32_t)'0'); +#if (defined(PRINTF_ADVANCED_ENABLE) && (PRINTF_ADVANCED_ENABLE > 0U)) + if (NULL != valid_precision_width) + { + *valid_precision_width = true; + } +#endif /* PRINTF_ADVANCED_ENABLE */ + } +#if (defined(PRINTF_ADVANCED_ENABLE) && (PRINTF_ADVANCED_ENABLE > 0U)) + else if (c == '*') + { + precision_width = (uint32_t)va_arg(*ap, uint32_t); + if (NULL != valid_precision_width) + { + *valid_precision_width = true; + } + } +#endif /* PRINTF_ADVANCED_ENABLE */ + else + { + /* We've gone one char too far. */ + --p; + done = 1U; + } + } + } + else + { + /* We've gone one char too far. */ + --p; + } + *s = p; + return precision_width; +} + +static uint32_t PrintIsobpu(const char c) +{ + uint32_t ret = 0U; + if ((c == 'o') || (c == 'b') || (c == 'p') || (c == 'u')) + { + ret = 1U; + } + return ret; +} + +static uint32_t PrintIsdi(const char c) +{ + uint32_t ret = 0U; + if ((c == 'd') || (c == 'i')) + { + ret = 1U; + } + return ret; +} + +static void PrintOutputdifFobpu(uint32_t flags_used, + uint32_t field_width, + uint32_t vlen, + char schar, + char *vstrp, + printfCb cb, + char *buf, + int32_t *count) +{ +#if (defined(PRINTF_ADVANCED_ENABLE) && (PRINTF_ADVANCED_ENABLE > 0U)) + /* Do the ZERO pad. */ + if (0U != (flags_used & (uint32_t)kPRINTF_Zero)) + { + if ('\0' != schar) + { + cb(buf, count, schar, 1); + schar = '\0'; + } + cb(buf, count, '0', (int)field_width - (int)vlen); + vlen = field_width; + } + else + { + if (0U == (flags_used & (uint32_t)kPRINTF_Minus)) + { + cb(buf, count, ' ', (int)field_width - (int)vlen); + if ('\0' != schar) + { + cb(buf, count, schar, 1); + schar = '\0'; + } + } + } + /* The string was built in reverse order, now display in correct order. */ + if ('\0' != schar) + { + cb(buf, count, schar, 1); + } +#else + cb(buf, count, ' ', (int)field_width - (int)vlen); +#endif /* PRINTF_ADVANCED_ENABLE */ + while ('\0' != (*vstrp)) + { + cb(buf, count, *vstrp--, 1); + } +#if (defined(PRINTF_ADVANCED_ENABLE) && (PRINTF_ADVANCED_ENABLE > 0U)) + if (0U != (flags_used & (uint32_t)kPRINTF_Minus)) + { + cb(buf, count, ' ', (int)field_width - (int)vlen); + } +#endif /* PRINTF_ADVANCED_ENABLE */ +} + +static void PrintOutputxX(uint32_t flags_used, + uint32_t field_width, + uint32_t vlen, + bool use_caps, + char *vstrp, + printfCb cb, + char *buf, + int32_t *count) +{ +#if (defined(PRINTF_ADVANCED_ENABLE) && (PRINTF_ADVANCED_ENABLE > 0U)) + uint8_t dschar = 0; + if (0U != (flags_used & (uint32_t)kPRINTF_Zero)) + { + if (0U != (flags_used & (uint32_t)kPRINTF_Pound)) + { + cb(buf, count, '0', 1); + cb(buf, count, (use_caps ? 'X' : 'x'), 1); + dschar = 1U; + } + cb(buf, count, '0', (int)field_width - (int)vlen); + vlen = field_width; + } + else + { + if (0U == (flags_used & (uint32_t)kPRINTF_Minus)) + { + if (0U != (flags_used & (uint32_t)kPRINTF_Pound)) + { + vlen += 2U; + } + cb(buf, count, ' ', (int)field_width - (int)vlen); + if (0U != (flags_used & (uint32_t)kPRINTF_Pound)) + { + cb(buf, count, '0', 1); + cb(buf, count, (use_caps ? 'X' : 'x'), 1); + dschar = 1U; + } + } + } + + if ((0U != (flags_used & (uint32_t)kPRINTF_Pound)) && (0U == dschar)) + { + cb(buf, count, '0', 1); + cb(buf, count, (use_caps ? 'X' : 'x'), 1); + vlen += 2U; + } +#else + cb(buf, count, ' ', (int)field_width - (int)vlen); +#endif /* PRINTF_ADVANCED_ENABLE */ + while ('\0' != (*vstrp)) + { + cb(buf, count, *vstrp--, 1); + } +#if (defined(PRINTF_ADVANCED_ENABLE) && (PRINTF_ADVANCED_ENABLE > 0U)) + if (0U != (flags_used & (uint32_t)kPRINTF_Minus)) + { + cb(buf, count, ' ', (int)field_width - (int)vlen); + } +#endif /* PRINTF_ADVANCED_ENABLE */ +} + +static uint32_t PrintIsfF(const char c) +{ + uint32_t ret = 0U; + if ((c == 'f') || (c == 'F')) + { + ret = 1U; + } + return ret; +} + +static uint32_t PrintIsxX(const char c) +{ + uint32_t ret = 0U; + if ((c == 'x') || (c == 'X')) + { + ret = 1U; + } + return ret; +} + +#if (defined(PRINTF_ADVANCED_ENABLE) && (PRINTF_ADVANCED_ENABLE > 0U)) +static uint32_t PrintCheckFlags(const char **s) +{ + const char *p = *s; + /* First check for specification modifier flags. */ + uint32_t flags_used = 0U; + bool done = false; + while (false == done) + { + switch (*++p) + { + case '-': + flags_used |= (uint32_t)kPRINTF_Minus; + break; + case '+': + flags_used |= (uint32_t)kPRINTF_Plus; + break; + case ' ': + flags_used |= (uint32_t)kPRINTF_Space; + break; + case '0': + flags_used |= (uint32_t)kPRINTF_Zero; + break; + case '#': + flags_used |= (uint32_t)kPRINTF_Pound; + break; + default: + /* We've gone one char too far. */ + --p; + done = true; + break; + } + } + *s = p; + return flags_used; +} +#endif /* PRINTF_ADVANCED_ENABLE */ + +#if (defined(PRINTF_ADVANCED_ENABLE) && (PRINTF_ADVANCED_ENABLE > 0U)) +/* + * Check for the length modifier. + */ +static uint32_t PrintGetLengthFlag(const char **s) +{ + const char *p = *s; + /* First check for specification modifier flags. */ + uint32_t flags_used = 0U; + + switch (/* c = */ *++p) + { + case 'h': + if (*++p != 'h') + { + flags_used |= (uint32_t)kPRINTF_LengthShortInt; + --p; + } + else + { + flags_used |= (uint32_t)kPRINTF_LengthChar; + } + break; + case 'l': + if (*++p != 'l') + { + flags_used |= (uint32_t)kPRINTF_LengthLongInt; + --p; + } + else + { + flags_used |= (uint32_t)kPRINTF_LengthLongLongInt; + } + break; + case 'z': + if (sizeof(size_t) == sizeof(uint32_t)) + { + flags_used |= (uint32_t)kPRINTF_LengthLongInt; + } + else if (sizeof(size_t) == (2U * sizeof(uint32_t))) + { + flags_used |= (uint32_t)kPRINTF_LengthLongLongInt; + } + else if (sizeof(size_t) == sizeof(uint16_t)) + { + flags_used |= (uint32_t)kPRINTF_LengthShortInt; + } + else + { + /* MISRA C-2012 Rule 15.7 */ + } + break; + default: + /* we've gone one char too far */ + --p; + break; + } + *s = p; + return flags_used; +} +#else +static void PrintFilterLengthFlag(const char **s) +{ + const char *p = *s; + char strCh; + + do + { + strCh = *++p; + } while ((strCh == 'h') || (strCh == 'l')); + + *s = --p; +} +#endif /* PRINTF_ADVANCED_ENABLE */ + +static uint8_t PrintGetRadixFromobpu(const char c) +{ + uint8_t radix; + + if (c == 'o') + { + radix = 8U; + } + else if (c == 'b') + { + radix = 2U; + } + else if (c == 'p') + { + radix = 16U; + } + else + { + radix = 10U; + } + return radix; +} + +static uint32_t ScanIsWhiteSpace(const char c) +{ + uint32_t ret = 0U; + if ((c == ' ') || (c == '\t') || (c == '\n') || (c == '\r') || (c == '\v') || (c == '\f')) + { + ret = 1U; + } + return ret; +} + +static uint32_t ScanIgnoreWhiteSpace(const char **s) +{ + uint32_t count = 0U; + char c; + + c = **s; + while (1U == ScanIsWhiteSpace(c)) + { + count++; + (*s)++; + c = **s; + } + return count; +} + +static int32_t ConvertRadixNumToString(char *numstr, void *nump, unsigned int neg, unsigned int radix, bool use_caps) +{ +#if (defined(PRINTF_ADVANCED_ENABLE) && (PRINTF_ADVANCED_ENABLE > 0U)) + long long int a; + long long int b; + long long int c; + + unsigned long long int ua; + unsigned long long int ub; + unsigned long long int uc; + unsigned long long int uc_param; +#else + int a; + int b; + int c; + + unsigned int ua; + unsigned int ub; + unsigned int uc; + unsigned int uc_param; +#endif /* PRINTF_ADVANCED_ENABLE */ + + int32_t nlen; + char *nstrp; + + nlen = 0; + nstrp = numstr; + *nstrp++ = '\0'; + +#if !(defined(PRINTF_ADVANCED_ENABLE) && (PRINTF_ADVANCED_ENABLE > 0u)) + neg = 0U; +#endif + +#if (defined(PRINTF_ADVANCED_ENABLE) && (PRINTF_ADVANCED_ENABLE > 0U)) + a = 0; + b = 0; + c = 0; + ua = 0ULL; + ub = 0ULL; + uc = 0ULL; + uc_param = 0ULL; +#else + a = 0; + b = 0; + c = 0; + ua = 0U; + ub = 0U; + uc = 0U; + uc_param = 0U; +#endif /* PRINTF_ADVANCED_ENABLE */ + + (void)a; + (void)b; + (void)c; + (void)ua; + (void)ub; + (void)uc; + (void)uc_param; + (void)neg; + /* + * Fix MISRA issue: CID 15972928 (#15 of 15): MISRA C-2012 Control Flow Expressions (MISRA C-2012 Rule 14.3) + * misra_c_2012_rule_14_3_violation: Execution cannot reach this statement: a = *((int *)nump); + */ +#if (defined(PRINTF_ADVANCED_ENABLE) && (PRINTF_ADVANCED_ENABLE > 0U)) + if (0U != neg) + { +#if (defined(PRINTF_ADVANCED_ENABLE) && (PRINTF_ADVANCED_ENABLE > 0U)) + a = *(long long int *)nump; +#else + a = *(int *)nump; +#endif /* PRINTF_ADVANCED_ENABLE */ + if (a == 0) + { + *nstrp = '0'; + ++nlen; + return nlen; + } + while (a != 0) + { +#if (defined(PRINTF_ADVANCED_ENABLE) && (PRINTF_ADVANCED_ENABLE > 0U)) + b = (long long int)a / (long long int)radix; + c = (long long int)a - ((long long int)b * (long long int)radix); + if (c < 0) + { + uc = (unsigned long long int)c; + uc_param = ~uc; + c = (long long int)uc_param + 1 + (long long int)'0'; + } +#else + b = (int)a / (int)radix; + c = (int)a - ((int)b * (int)radix); + if (c < 0) + { + uc = (unsigned int)c; + uc_param = ~uc; + c = (int)uc_param + 1 + (int)'0'; + } +#endif /* PRINTF_ADVANCED_ENABLE */ + else + { + c = c + (int)'0'; + } + a = b; + *nstrp++ = (char)c; + ++nlen; + } + } + else +#endif /* PRINTF_ADVANCED_ENABLE */ + { +#if (defined(PRINTF_ADVANCED_ENABLE) && (PRINTF_ADVANCED_ENABLE > 0U)) + ua = *(unsigned long long int *)nump; +#else + ua = *(unsigned int *)nump; +#endif /* PRINTF_ADVANCED_ENABLE */ + if (ua == 0U) + { + *nstrp = '0'; + ++nlen; + return nlen; + } + while (ua != 0U) + { +#if (defined(PRINTF_ADVANCED_ENABLE) && (PRINTF_ADVANCED_ENABLE > 0U)) + ub = (unsigned long long int)ua / (unsigned long long int)radix; + uc = (unsigned long long int)ua - ((unsigned long long int)ub * (unsigned long long int)radix); +#else + ub = ua / (unsigned int)radix; + uc = ua - (ub * (unsigned int)radix); +#endif /* PRINTF_ADVANCED_ENABLE */ + + if (uc < 10U) + { + uc = uc + (unsigned int)'0'; + } + else + { + uc = uc - 10U + (unsigned int)(use_caps ? 'A' : 'a'); + } + ua = ub; + *nstrp++ = (char)uc; + ++nlen; + } + } + return nlen; +} + +#if (defined(PRINTF_FLOAT_ENABLE) && (PRINTF_FLOAT_ENABLE > 0U)) +static int32_t ConvertFloatRadixNumToString(char *numstr, void *nump, int32_t radix, uint32_t precision_width) +{ + int32_t a; + int32_t b; + int32_t c; + int32_t i; + uint32_t uc; + double fa; + double dc; + double fb; + double r; + double fractpart; + double intpart; + + int32_t nlen; + char *nstrp; + nlen = 0; + nstrp = numstr; + *nstrp++ = '\0'; + r = *(double *)nump; + if (0.0 == r) + { + *nstrp = '0'; + ++nlen; + return nlen; + } + fractpart = modf((double)r, (double *)&intpart); + /* Process fractional part. */ + for (i = 0; i < (int32_t)precision_width; i++) + { + fractpart *= (double)radix; + } + if (r >= (double)0.0) + { + fa = fractpart + (double)0.5; + if (fa >= pow((double)10, (double)precision_width)) + { + intpart++; + } + } + else + { + fa = fractpart - (double)0.5; + if (fa <= -pow((double)10, (double)precision_width)) + { + intpart--; + } + } + for (i = 0; i < (int32_t)precision_width; i++) + { + fb = fa / (double)radix; + dc = (fa - (double)(long long int)fb * (double)radix); + c = (int32_t)dc; + if (c < 0) + { + uc = (uint32_t)c; + uc = ~uc; + c = (int32_t)uc; + c += (int32_t)1; + c += (int32_t)'0'; + } + else + { + c = c + '0'; + } + fa = fb; + *nstrp++ = (char)c; + ++nlen; + } + *nstrp++ = (char)'.'; + ++nlen; + a = (int32_t)intpart; + if (a == 0) + { + *nstrp++ = '0'; + ++nlen; + } + else + { + while (a != 0) + { + b = (int32_t)a / (int32_t)radix; + c = (int32_t)a - ((int32_t)b * (int32_t)radix); + if (c < 0) + { + uc = (uint32_t)c; + uc = ~uc; + c = (int32_t)uc; + c += (int32_t)1; + c += (int32_t)'0'; + } + else + { + c = c + '0'; + } + a = b; + *nstrp++ = (char)c; + ++nlen; + } + } + return nlen; +} +#endif /* PRINTF_FLOAT_ENABLE */ + +#if (defined(PRINTF_ADVANCED_ENABLE) && (PRINTF_ADVANCED_ENABLE > 0U)) +static void StrFormatExaminedi(uint32_t *flags_used, long long int *ival, va_list *ap) +#else +static void StrFormatExaminedi(int *ival, va_list *ap) +#endif +{ +#if (defined(PRINTF_ADVANCED_ENABLE) && (PRINTF_ADVANCED_ENABLE > 0U)) + if (0U != (*flags_used & (uint32_t)kPRINTF_LengthLongLongInt)) + { + *ival = (long long int)va_arg(*ap, long long int); + } + else if (0U != (*flags_used & (uint32_t)kPRINTF_LengthLongInt)) + { + *ival = (long long int)va_arg(*ap, long int); + } + else +#endif /* PRINTF_ADVANCED_ENABLE */ + { + *ival = (STR_FORMAT_PRINTF_IVAL_TYPE)va_arg(*ap, int); + } +} + +#if (defined(PRINTF_ADVANCED_ENABLE) && (PRINTF_ADVANCED_ENABLE > 0U)) +static void StrFormatExaminexX(uint32_t *flags_used, unsigned long long int *uval, va_list *ap) +#else +static void StrFormatExaminexX(unsigned int *uval, va_list *ap) +#endif +{ +#if (defined(PRINTF_ADVANCED_ENABLE) && (PRINTF_ADVANCED_ENABLE > 0U)) + if (0U != (*flags_used & (unsigned int)kPRINTF_LengthLongLongInt)) + { + *uval = (unsigned long long int)va_arg(*ap, unsigned long long int); + } + else if (0U != (*flags_used & (unsigned int)kPRINTF_LengthLongInt)) + { + *uval = (unsigned long long int)va_arg(*ap, unsigned long int); + } + else +#endif /* PRINTF_ADVANCED_ENABLE */ + { + *uval = (STR_FORMAT_PRINTF_UVAL_TYPE)va_arg(*ap, unsigned int); + } +} + +#if (defined(PRINTF_ADVANCED_ENABLE) && (PRINTF_ADVANCED_ENABLE > 0U)) +static void StrFormatExamineobpu(uint32_t *flags_used, unsigned long long int *uval, va_list *ap) +#else +static void StrFormatExamineobpu(unsigned int *uval, va_list *ap) +#endif +{ +#if (defined(PRINTF_ADVANCED_ENABLE) && (PRINTF_ADVANCED_ENABLE > 0U)) + if (0U != (*flags_used & (unsigned int)kPRINTF_LengthLongLongInt)) + { + *uval = (unsigned long long int)va_arg(*ap, unsigned long long int); + } + else if (0U != (*flags_used & (unsigned int)kPRINTF_LengthLongInt)) + { + *uval = (unsigned long long int)va_arg(*ap, unsigned long int); + } + else +#endif /* PRINTF_ADVANCED_ENABLE */ + { + *uval = (STR_FORMAT_PRINTF_UVAL_TYPE)va_arg(*ap, unsigned int); + } +} +#if (defined(PRINTF_ADVANCED_ENABLE) && (PRINTF_ADVANCED_ENABLE > 0U)) +static int32_t ConvertPrecisionWidthToLength(bool valid_precision_width, uint32_t precision_width, char *sval) +#else +static int32_t ConvertPrecisionWidthToLength(char *sval) +#endif +{ + int32_t vlen = 0; +#if (defined(PRINTF_ADVANCED_ENABLE) && (PRINTF_ADVANCED_ENABLE > 0U)) + if (valid_precision_width) + { + vlen = (int)precision_width; + } + else + { + vlen = (int)strlen(sval); + } +#else + vlen = (int32_t)strlen(sval); +#endif /* PRINTF_ADVANCED_ENABLE */ + + return vlen; +} + +/*! + * brief This function outputs its parameters according to a formatted string. + * + * note I/O is performed by calling given function pointer using following + * (*func_ptr)(c); + * + * param[in] fmt Format string for printf. + * param[in] ap Arguments to printf. + * param[in] buf pointer to the buffer + * param cb print callback function pointer + * + * return Number of characters to be print + */ +int StrFormatPrintf(const char *fmt, va_list ap, char *buf, printfCb cb) +{ + /* va_list ap; */ + const char *p; + char c; + + char vstr[33]; + char *vstrp = NULL; + int32_t vlen = 0; + + int32_t count = 0; + + uint32_t field_width; + uint32_t precision_width; + char *sval; + int32_t cval; + bool use_caps; + unsigned int radix = 0; + +#if (defined(PRINTF_ADVANCED_ENABLE) && (PRINTF_ADVANCED_ENABLE > 0U)) + uint32_t flags_used; + char schar; + long long int ival; + unsigned long long int uval = 0; + bool valid_precision_width; +#else + int ival; + unsigned int uval = 0; +#endif /* PRINTF_ADVANCED_ENABLE */ + +#if (defined(PRINTF_FLOAT_ENABLE) && (PRINTF_FLOAT_ENABLE > 0U)) + double fval; +#endif /* PRINTF_FLOAT_ENABLE */ + + /* Start parsing apart the format string and display appropriate formats and data. */ + p = fmt; + while (true) + { + if ('\0' == *p) + { + break; + } + c = *p; + /* + * All formats begin with a '%' marker. Special chars like + * '\n' or '\t' are normally converted to the appropriate + * character by the __compiler__. Thus, no need for this + * routine to account for the '\' character. + */ + if (c != '%') + { + cb(buf, &count, c, 1); + p++; + /* By using 'continue', the next iteration of the loop is used, skipping the code that follows. */ + continue; + } + + use_caps = true; + +#if (defined(PRINTF_ADVANCED_ENABLE) && (PRINTF_ADVANCED_ENABLE > 0U)) + /* First check for specification modifier flags. */ + flags_used = PrintCheckFlags(&p); +#endif /* PRINTF_ADVANCED_ENABLE */ + + /* Next check for minimum field width. */ + field_width = PrintGetWidth(&p, &ap); + + /* Next check for the width and precision field separator. */ +#if (defined(PRINTF_ADVANCED_ENABLE) && (PRINTF_ADVANCED_ENABLE > 0U)) + precision_width = PrintGetPrecision(&p, &ap, &valid_precision_width); +#else + precision_width = PrintGetPrecision(&p, &ap, NULL); + (void)precision_width; +#endif + +#if (defined(PRINTF_ADVANCED_ENABLE) && (PRINTF_ADVANCED_ENABLE > 0U)) + /* Check for the length modifier. */ + flags_used |= PrintGetLengthFlag(&p); +#else + /* Filter length modifier. */ + PrintFilterLengthFlag(&p); +#endif + + /* Now we're ready to examine the format. */ + c = *++p; + { + if (1U == PrintIsdi(c)) + { +#if (defined(PRINTF_ADVANCED_ENABLE) && (PRINTF_ADVANCED_ENABLE > 0U)) + StrFormatExaminedi(&flags_used, &ival, &ap); +#else + StrFormatExaminedi(&ival, &ap); +#endif + + vlen = ConvertRadixNumToString((char *)vstr, (void *)&ival, 1, 10, use_caps); + vstrp = &vstr[vlen]; +#if (defined(PRINTF_ADVANCED_ENABLE) && (PRINTF_ADVANCED_ENABLE > 0U)) + vlen += (int)PrintGetSignChar(ival, flags_used, &schar); + PrintOutputdifFobpu(flags_used, field_width, (unsigned int)vlen, schar, vstrp, cb, buf, &count); +#else + PrintOutputdifFobpu(0U, field_width, (unsigned int)vlen, '\0', vstrp, cb, buf, &count); +#endif + } + else if (1U == PrintIsfF(c)) + { +#if (defined(PRINTF_FLOAT_ENABLE) && (PRINTF_FLOAT_ENABLE > 0U)) + fval = (double)va_arg(ap, double); + vlen = ConvertFloatRadixNumToString(vstr, &fval, 10, precision_width); + vstrp = &vstr[vlen]; + +#if (defined(PRINTF_ADVANCED_ENABLE) && (PRINTF_ADVANCED_ENABLE > 0U)) + vlen += (int32_t)PrintGetSignChar(((fval < 0.0) ? ((long long int)-1) : ((long long int)fval)), + flags_used, &schar); + PrintOutputdifFobpu(flags_used, field_width, (unsigned int)vlen, schar, vstrp, cb, buf, &count); +#else + PrintOutputdifFobpu(0, field_width, (unsigned int)vlen, '\0', vstrp, cb, buf, &count); +#endif + +#else + (void)va_arg(ap, double); +#endif /* PRINTF_FLOAT_ENABLE */ + } + else if (1U == PrintIsxX(c)) + { + if (c == 'x') + { + use_caps = false; + } +#if (defined(PRINTF_ADVANCED_ENABLE) && (PRINTF_ADVANCED_ENABLE > 0U)) + StrFormatExaminexX(&flags_used, &uval, &ap); +#else + StrFormatExaminexX(&uval, &ap); +#endif + + vlen = ConvertRadixNumToString((char *)vstr, (void *)&uval, 0, 16, use_caps); + vstrp = &vstr[vlen]; +#if (defined(PRINTF_ADVANCED_ENABLE) && (PRINTF_ADVANCED_ENABLE > 0U)) + PrintOutputxX(flags_used, field_width, (unsigned int)vlen, use_caps, vstrp, cb, buf, &count); +#else + PrintOutputxX(0U, field_width, (uint32_t)vlen, use_caps, vstrp, cb, buf, &count); +#endif + } + else if (1U == PrintIsobpu(c)) + { + if ('p' == c) + { + /* + * Fix MISRA issue: CID 17205581 (#15 of 15): MISRA C-2012 Pointer Type Conversions (MISRA C-2012 + * Rule 11.6) 1.misra_c_2012_rule_11_6_violation: The expression va_arg (ap, void *) of type void * + * is cast to type uint32_t. + * + * Orignal code: uval = (STR_FORMAT_PRINTF_UVAL_TYPE)(uint32_t)va_arg(ap, void *); + */ + void *pval; + pval = (void *)va_arg(ap, void *); + (void)memcpy((void *)&uval, (void *)&pval, sizeof(void *)); + } + else + { +#if (defined(PRINTF_ADVANCED_ENABLE) && (PRINTF_ADVANCED_ENABLE > 0U)) + StrFormatExamineobpu(&flags_used, &uval, &ap); +#else + StrFormatExamineobpu(&uval, &ap); +#endif + } + + radix = PrintGetRadixFromobpu(c); + + vlen = ConvertRadixNumToString((char *)vstr, (void *)&uval, 0, radix, use_caps); + vstrp = &vstr[vlen]; +#if (defined(PRINTF_ADVANCED_ENABLE) && (PRINTF_ADVANCED_ENABLE > 0U)) + PrintOutputdifFobpu(flags_used, field_width, (unsigned int)vlen, '\0', vstrp, cb, buf, &count); +#else + PrintOutputdifFobpu(0U, field_width, (uint32_t)vlen, '\0', vstrp, cb, buf, &count); +#endif + } + else if (c == 'c') + { + cval = (int32_t)va_arg(ap, int); + cb(buf, &count, cval, 1); + } + else if (c == 's') + { + sval = (char *)va_arg(ap, char *); + if (NULL != sval) + { +#if (defined(PRINTF_ADVANCED_ENABLE) && (PRINTF_ADVANCED_ENABLE > 0U)) + vlen = ConvertPrecisionWidthToLength(valid_precision_width, precision_width, sval); +#else + vlen = ConvertPrecisionWidthToLength(sval); +#endif +#if (defined(PRINTF_ADVANCED_ENABLE) && (PRINTF_ADVANCED_ENABLE > 0U)) + if (0U == (flags_used & (unsigned int)kPRINTF_Minus)) +#endif /* PRINTF_ADVANCED_ENABLE */ + { + cb(buf, &count, ' ', (int)field_width - (int)vlen); + } + +#if (defined(PRINTF_ADVANCED_ENABLE) && (PRINTF_ADVANCED_ENABLE > 0U)) + if (valid_precision_width) + { + while (('\0' != *sval) && (vlen > 0)) + { + cb(buf, &count, *sval++, 1); + vlen--; + } + /* In case that vlen sval is shorter than vlen */ + vlen = (int)precision_width - vlen; + } + else + { +#endif /* PRINTF_ADVANCED_ENABLE */ + while ('\0' != (*sval)) + { + cb(buf, &count, *sval++, 1); + } +#if (defined(PRINTF_ADVANCED_ENABLE) && (PRINTF_ADVANCED_ENABLE > 0U)) + } +#endif /* PRINTF_ADVANCED_ENABLE */ + +#if (defined(PRINTF_ADVANCED_ENABLE) && (PRINTF_ADVANCED_ENABLE > 0U)) + if (0U != (flags_used & (unsigned int)kPRINTF_Minus)) + { + cb(buf, &count, ' ', (int)field_width - vlen); + } +#endif /* PRINTF_ADVANCED_ENABLE */ + } + } + else + { + cb(buf, &count, c, 1); + } + } + p++; + } + + return (int)count; +} + +#if (defined(SCANF_FLOAT_ENABLE) && (SCANF_FLOAT_ENABLE > 0U)) +static uint8_t StrFormatScanIsFloat(char *c) +{ + uint8_t ret = 0U; + if (('a' == (*c)) || ('A' == (*c)) || ('e' == (*c)) || ('E' == (*c)) || ('f' == (*c)) || ('F' == (*c)) || + ('g' == (*c)) || ('G' == (*c))) + { + ret = 1U; + } + return ret; +} +#endif + +static uint8_t StrFormatScanIsFormatStarting(char *c) +{ + uint8_t ret = 1U; + if ((*c != '%')) + { + ret = 0U; + } + else if (*(c + 1) == '%') + { + ret = 0U; + } + else + { + /*MISRA rule 15.7*/ + } + + return ret; +} + +static uint8_t StrFormatScanGetBase(uint8_t base, const char *s) +{ + if (base == 0U) + { + if (s[0] == '0') + { + if ((s[1] == 'x') || (s[1] == 'X')) + { + base = 16; + } + else + { + base = 8; + } + } + else + { + base = 10; + } + } + return base; +} + +static uint8_t StrFormatScanCheckSymbol(const char *p, int8_t *neg) +{ + uint8_t len; + switch (*p) + { + case '-': + *neg = -1; + len = 1; + break; + case '+': + *neg = 1; + len = 1; + break; + default: + *neg = 1; + len = 0; + break; + } + return len; +} + +static uint8_t StrFormatScanFillInteger(uint32_t flag, va_list *args_ptr, int32_t val) +{ +#if (defined(SCANF_ADVANCED_ENABLE) && (SCANF_ADVANCED_ENABLE > 0U)) + if (0U != (flag & (uint32_t)kSCANF_Suppress)) + { + return 0u; + } + + switch (flag & (uint32_t)kSCANF_LengthMask) + { + case (uint32_t)kSCANF_LengthChar: + if (0U != (flag & (uint32_t)kSCANF_TypeSinged)) + { + *va_arg(*args_ptr, signed char *) = (signed char)val; + } + else + { + *va_arg(*args_ptr, unsigned char *) = (unsigned char)val; + } + break; + case (uint32_t)kSCANF_LengthShortInt: + if (0U != (flag & (uint32_t)kSCANF_TypeSinged)) + { + *va_arg(*args_ptr, signed short *) = (signed short)val; + } + else + { + *va_arg(*args_ptr, unsigned short *) = (unsigned short)val; + } + break; + case (uint32_t)kSCANF_LengthLongInt: + if (0U != (flag & (uint32_t)kSCANF_TypeSinged)) + { + *va_arg(*args_ptr, signed long int *) = (signed long int)val; + } + else + { + *va_arg(*args_ptr, unsigned long int *) = (unsigned long int)val; + } + break; + case (uint32_t)kSCANF_LengthLongLongInt: + if (0U != (flag & (uint32_t)kSCANF_TypeSinged)) + { + *va_arg(*args_ptr, signed long long int *) = (signed long long int)val; + } + else + { + *va_arg(*args_ptr, unsigned long long int *) = (unsigned long long int)val; + } + break; + default: + /* The default type is the type int. */ + if (0U != (flag & (uint32_t)kSCANF_TypeSinged)) + { + *va_arg(*args_ptr, signed int *) = (signed int)val; + } + else + { + *va_arg(*args_ptr, unsigned int *) = (unsigned int)val; + } + break; + } +#else + /* The default type is the type int. */ + if (0U != (flag & (uint32_t)kSCANF_TypeSinged)) + { + *va_arg(*args_ptr, signed int *) = (signed int)val; + } + else + { + *va_arg(*args_ptr, unsigned int *) = (unsigned int)val; + } +#endif /* SCANF_ADVANCED_ENABLE */ + + return 1U; +} + +#if (defined(SCANF_FLOAT_ENABLE) && (SCANF_FLOAT_ENABLE > 0U)) +static uint8_t StrFormatScanFillFloat(uint32_t flag, va_list *args_ptr, double fnum) +{ +#if (defined(SCANF_ADVANCED_ENABLE) && (SCANF_ADVANCED_ENABLE > 0U)) + if (0U != (flag & (uint32_t)kSCANF_Suppress)) + { + return 0U; + } + else +#endif /* SCANF_ADVANCED_ENABLE */ + { + if (0U != (flag & (uint32_t)kSCANF_LengthLongLongDouble)) + { + *va_arg(*args_ptr, double *) = fnum; + } + else + { + *va_arg(*args_ptr, float *) = (float)fnum; + } + return 1U; + } +} +#endif /* SCANF_FLOAT_ENABLE */ + +#if (defined(SCANF_ADVANCED_ENABLE) && (SCANF_ADVANCED_ENABLE > 0U)) +static uint8_t strFormatScanfHandleh(uint8_t exitPending, char **c, uint32_t *flag) +{ + if (0U != ((*flag) & (uint32_t)kSCANF_LengthMask)) + { + /* Match failure. */ + exitPending = 1U; + } + else + { + if ((*c)[1] == 'h') + { + (*flag) |= (uint32_t)kSCANF_LengthChar; + *c = *c + 1U; + } + else + { + (*flag) |= (uint32_t)kSCANF_LengthShortInt; + } + } + + return exitPending; +} + +static uint8_t strFormatScanfHandlel(uint8_t exitPending, char **c, uint32_t *flag) +{ + if (0U != ((*flag) & (uint32_t)kSCANF_LengthMask)) + { + /* Match failure. */ + exitPending = 1U; + } + else + { + if ((*c)[1] == 'l') + { + (*flag) |= (uint32_t)kSCANF_LengthLongLongInt; + *c = *c + 1U; + } + else + { + (*flag) |= (uint32_t)kSCANF_LengthLongInt; + } + } + + return exitPending; +} +#endif + +static uint8_t StrFormatScanfStringHandling(char **str, uint32_t *flag, uint32_t *field_width, uint8_t *base) +{ + uint8_t exitPending = 0U; + char *c = *str; + + /* Loop to get full conversion specification. */ + while (('\0' != (*c)) && (0U == (*flag & (uint32_t)kSCANF_DestMask))) + { +#if (defined(SCANF_ADVANCED_ENABLE) && (SCANF_ADVANCED_ENABLE > 0U)) + if ('*' == (*c)) + { + if (0U != ((*flag) & (uint32_t)kSCANF_Suppress)) + { + /* Match failure. */ + exitPending = 1U; + } + else + { + (*flag) |= (uint32_t)kSCANF_Suppress; + } + } + else if ('h' == (*c)) + { + exitPending = strFormatScanfHandleh(exitPending, &c, flag); + } + else if ('l' == (*c)) + { + exitPending = strFormatScanfHandlel(exitPending, &c, flag); + } + else +#endif /* SCANF_ADVANCED_ENABLE */ +#if (defined(SCANF_FLOAT_ENABLE) && (SCANF_FLOAT_ENABLE > 0U)) + if ('L' == (*c)) + { + if (0U != ((*flag) & (uint32_t)kSCANF_LengthMask)) + { + /* Match failure. */ + exitPending = 1U; + } + else + { + (*flag) |= (uint32_t)kSCANF_LengthLongLongDouble; + } + } + else +#endif /* SCANF_FLOAT_ENABLE */ + if (((*c) >= '0') && ((*c) <= '9')) + { + { + char *p; + errno = 0; + (*field_width) = strtoul(c, &p, 10); + if (0 != errno) + { + *field_width = 0U; + } + c = p - 1; + } + } + else if ('d' == (*c)) + { + (*base) = 10U; + (*flag) |= (uint32_t)kSCANF_TypeSinged; + (*flag) |= (uint32_t)kSCANF_DestInt; + } + else if ('u' == (*c)) + { + (*base) = 10U; + (*flag) |= (uint32_t)kSCANF_DestInt; + } + else if ('o' == (*c)) + { + (*base) = 8U; + (*flag) |= (uint32_t)kSCANF_DestInt; + } + else if (('x' == (*c))) + { + (*base) = 16U; + (*flag) |= (uint32_t)kSCANF_DestInt; + } + else if ('X' == (*c)) + { + (*base) = 16U; + (*flag) |= (uint32_t)kSCANF_DestInt; + } + else if ('i' == (*c)) + { + (*base) = 0U; + (*flag) |= (uint32_t)kSCANF_DestInt; + } +#if (defined(SCANF_FLOAT_ENABLE) && (SCANF_FLOAT_ENABLE > 0U)) + else if (1U == StrFormatScanIsFloat(c)) + { + (*flag) |= (uint32_t)kSCANF_DestFloat; + } +#endif /* SCANF_FLOAT_ENABLE */ + else if ('c' == (*c)) + { + (*flag) |= (uint32_t)kSCANF_DestChar; + if (MAX_FIELD_WIDTH == (*field_width)) + { + (*field_width) = 1; + } + } + else if ('s' == (*c)) + { + (*flag) |= (uint32_t)kSCANF_DestString; + } + else + { + exitPending = 1U; + } + + if (1U == exitPending) + { + break; + } + else + { + c++; + } + } + *str = c; + return exitPending; +} + +static void StrFormatScanfHandleChar( + const char **Cp, uint32_t *field_width, char **buf, uint32_t flag, uint32_t *n_decode, uint32_t *nassigned) +{ +#if (defined(SCANF_ADVANCED_ENABLE) && (SCANF_ADVANCED_ENABLE > 0U)) + uint8_t added = 0; +#endif + while ((0U != ((*field_width)--)) +#if (defined(SCANF_ADVANCED_ENABLE) && (SCANF_ADVANCED_ENABLE > 0U)) + && ('\0' != (**Cp)) +#endif + ) + { +#if (defined(SCANF_ADVANCED_ENABLE) && (SCANF_ADVANCED_ENABLE > 0U)) + if (0U != (flag & (uint32_t)kSCANF_Suppress)) + { + (*Cp) = (*Cp) + 1U; + } + else +#endif + { + **buf = **Cp; + (*Cp) = (*Cp) + 1U; + (*buf) = (*buf) + 1U; + +#if (defined(SCANF_ADVANCED_ENABLE) && (SCANF_ADVANCED_ENABLE > 0U)) + added = 1u; +#endif + } + *n_decode = *n_decode + 1U; + } + +#if (defined(SCANF_ADVANCED_ENABLE) && (SCANF_ADVANCED_ENABLE > 0U)) + if (1u == added) +#endif + { + *nassigned = *nassigned + 1U; + } +} + +static void StrFormatScanfHandleString( + const char **Sp, uint32_t *field_width, char **buf, uint32_t flag, uint32_t *n_decode, uint32_t *nassigned) +{ +#if (defined(SCANF_ADVANCED_ENABLE) && (SCANF_ADVANCED_ENABLE > 0U)) + uint8_t added = 0; +#endif + while ((0U != ((*field_width)--)) && (**Sp != '\0') && (0U == ScanIsWhiteSpace(**Sp))) + { +#if (defined(SCANF_ADVANCED_ENABLE) && (SCANF_ADVANCED_ENABLE > 0U)) + if (0U != (flag & (uint32_t)kSCANF_Suppress)) + { + (*Sp) = (*Sp) + 1U; + } + else +#endif + { + **buf = **Sp; + (*buf) = (*buf) + 1U; + (*Sp) = (*Sp) + 1U; +#if (defined(SCANF_ADVANCED_ENABLE) && (SCANF_ADVANCED_ENABLE > 0U)) + added = 1u; +#endif + } + *n_decode = *n_decode + 1U; + } + +#if (defined(SCANF_ADVANCED_ENABLE) && (SCANF_ADVANCED_ENABLE > 0U)) + if (1u == added) +#endif + { + /* Add NULL to end of string. */ + **buf = '\0'; + *nassigned = *nassigned + 1U; + } +} + +/*! + * brief Converts an input line of ASCII characters based upon a provided + * string format. + * + * param[in] line_ptr The input line of ASCII data. + * param[in] format Format first points to the format string. + * param[in] args_ptr The list of parameters. + * + * return Number of input items converted and assigned. + * retval IO_EOF When line_ptr is empty string "". + */ +int StrFormatScanf(const char *line_ptr, char *format, va_list args_ptr) +{ + uint8_t base; + int8_t neg; + /* Identifier for the format string. */ + char *c = format; + char *buf; + /* Flag telling the conversion specification. */ + uint32_t flag = 0; + /* Filed width for the matching input streams. */ + uint32_t field_width; + /* How many arguments are assigned except the suppress. */ + uint32_t nassigned = 0; + /* How many characters are read from the input streams. */ + uint32_t n_decode = 0; + + int32_t val; + + uint8_t added = 0U; + + uint8_t exitPending = 0; + + const char *s; +#if (defined(SCANF_FLOAT_ENABLE) && (SCANF_FLOAT_ENABLE > 0U)) + char *s_temp; /* MISRA C-2012 Rule 11.3 */ +#endif + + /* Identifier for the input string. */ + const char *p = line_ptr; + +#if (defined(SCANF_FLOAT_ENABLE) && (SCANF_FLOAT_ENABLE > 0U)) + double fnum = 0.0; +#endif /* SCANF_FLOAT_ENABLE */ + /* Return EOF error before any conversion. */ + if (*p == '\0') + { + return -1; + } + + /* Decode directives. */ + while (('\0' != (*c)) && ('\0' != (*p))) + { + /* Ignore all white-spaces in the format strings. */ + if (0U != ScanIgnoreWhiteSpace((const char **)((void *)&c))) + { + n_decode += ScanIgnoreWhiteSpace(&p); + } + else if (0U == StrFormatScanIsFormatStarting(c)) + { + /* Ordinary characters. */ + c++; + if (*p == *c) + { + n_decode++; + p++; + c++; + } + else + { + /* Match failure. Misalignment with C99, the unmatched characters need to be pushed back to stream. + * However, it is deserted now. */ + break; + } + } + else + { + /* convernsion specification */ + c++; + /* Reset. */ + flag = 0; + field_width = MAX_FIELD_WIDTH; + base = 0; + + exitPending = StrFormatScanfStringHandling(&c, &flag, &field_width, &base); + + if (1U == exitPending) + { + /* Format strings are exhausted. */ + break; + } + + /* Matching strings in input streams and assign to argument. */ + if ((flag & (uint32_t)kSCANF_DestMask) == (uint32_t)kSCANF_DestChar) + { + s = (const char *)p; + buf = va_arg(args_ptr, char *); + StrFormatScanfHandleChar(&p, &field_width, &buf, flag, &n_decode, &nassigned); + } + else if ((flag & (uint32_t)kSCANF_DestMask) == (uint32_t)kSCANF_DestString) + { + n_decode += ScanIgnoreWhiteSpace(&p); + buf = va_arg(args_ptr, char *); + StrFormatScanfHandleString(&p, &field_width, &buf, flag, &n_decode, &nassigned); + } + else if ((flag & (uint32_t)kSCANF_DestMask) == (uint32_t)kSCANF_DestInt) + { + n_decode += ScanIgnoreWhiteSpace(&p); + s = p; + val = 0; + base = StrFormatScanGetBase(base, s); + + added = StrFormatScanCheckSymbol(p, &neg); + n_decode += added; + p += added; + field_width -= added; + + s = p; + if (strlen(p) > field_width) + { + char temp[12]; + char *tempEnd; + (void)memcpy(temp, p, sizeof(temp) - 1U); + temp[sizeof(temp) - 1U] = '\0'; + errno = 0; + val = (int32_t)strtoul(temp, &tempEnd, (int)base); + if (0 != errno) + { + break; + } + p = p + (tempEnd - temp); + } + else + { + char *tempEnd; + errno = 0; + val = (int32_t)strtoul(p, &tempEnd, (int)base); + if (0 != errno) + { + break; + } + p = tempEnd; + } + n_decode += (uintptr_t)p - (uintptr_t)s; + + val *= neg; + + nassigned += StrFormatScanFillInteger(flag, &args_ptr, val); + } +#if (defined(SCANF_FLOAT_ENABLE) && (SCANF_FLOAT_ENABLE > 0U)) + else if ((flag & (uint32_t)kSCANF_DestMask) == (uint32_t)kSCANF_DestFloat) + { + n_decode += ScanIgnoreWhiteSpace(&p); + errno = 0; + + fnum = strtod(p, (char **)&s_temp); + s = s_temp; /* MISRA C-2012 Rule 11.3 */ + + /* MISRA C-2012 Rule 22.9 */ + if (0 != errno) + { + break; + } + + if ((fnum < HUGE_VAL) && (fnum > -HUGE_VAL)) + { + n_decode = (uint32_t)n_decode + (uint32_t)s - (uint32_t)p; + p = s; + nassigned += StrFormatScanFillFloat(flag, &args_ptr, fnum); + } + } +#endif /* SCANF_FLOAT_ENABLE */ + else + { + break; + } + } + } + return (int)nassigned; +} diff --git a/drivers/Src/fsl_usart.c b/drivers/Src/fsl_usart.c new file mode 100644 index 0000000..12c23e8 --- /dev/null +++ b/drivers/Src/fsl_usart.c @@ -0,0 +1,1314 @@ +/* + * Copyright (c) 2016, Freescale Semiconductor, Inc. + * Copyright 2016-2023 NXP + * All rights reserved. + * + * SPDX-License-Identifier: BSD-3-Clause + */ + +#include "fsl_usart.h" +#include "fsl_device_registers.h" +#include "fsl_flexcomm.h" + +/******************************************************************************* + * Definitions + ******************************************************************************/ + +/* Component ID definition, used by tools. */ +#ifndef FSL_COMPONENT_ID +#define FSL_COMPONENT_ID "platform.drivers.flexcomm_usart" +#endif + +/*! + * @brief Used for conversion from `flexcomm_usart_irq_handler_t` to `flexcomm_irq_handler_t` + */ +typedef union usart_to_flexcomm +{ + flexcomm_usart_irq_handler_t usart_master_handler; + flexcomm_irq_handler_t flexcomm_handler; +} usart_to_flexcomm_t; + +enum +{ + kUSART_TxIdle, /* TX idle. */ + kUSART_TxBusy, /* TX busy. */ + kUSART_RxIdle, /* RX idle. */ + kUSART_RxBusy /* RX busy. */ +}; + +/******************************************************************************* + * Variables + ******************************************************************************/ + +/*! @brief IRQ name array */ +static const IRQn_Type s_usartIRQ[] = USART_IRQS; + +/*! @brief Array to map USART instance number to base address. */ +static const uint32_t s_usartBaseAddrs[FSL_FEATURE_SOC_USART_COUNT] = USART_BASE_ADDRS; + +/******************************************************************************* + * Code + ******************************************************************************/ + +/* Get the index corresponding to the USART */ +/*! brief Returns instance number for USART peripheral base address. */ +uint32_t USART_GetInstance(USART_Type *base) +{ + uint32_t i; + + for (i = 0; i < (uint32_t)FSL_FEATURE_SOC_USART_COUNT; i++) + { + if ((uint32_t)base == s_usartBaseAddrs[i]) + { + break; + } + } + + assert(i < (uint32_t)FSL_FEATURE_SOC_USART_COUNT); + return i; +} + +/*! + * brief Get the length of received data in RX ring buffer. + * + * param handle USART handle pointer. + * return Length of received data in RX ring buffer. + */ +size_t USART_TransferGetRxRingBufferLength(usart_handle_t *handle) +{ + size_t size; + + /* Check arguments */ + assert(NULL != handle); + uint16_t rxRingBufferHead = handle->rxRingBufferHead; + uint16_t rxRingBufferTail = handle->rxRingBufferTail; + + if (rxRingBufferTail > rxRingBufferHead) + { + size = (size_t)rxRingBufferHead + handle->rxRingBufferSize - (size_t)rxRingBufferTail; + } + else + { + size = (size_t)rxRingBufferHead - (size_t)rxRingBufferTail; + } + return size; +} + +static bool USART_TransferIsRxRingBufferFull(usart_handle_t *handle) +{ + bool full; + + /* Check arguments */ + assert(NULL != handle); + + if (USART_TransferGetRxRingBufferLength(handle) == (handle->rxRingBufferSize - 1U)) + { + full = true; + } + else + { + full = false; + } + return full; +} + +/*! + * brief Sets up the RX ring buffer. + * + * This function sets up the RX ring buffer to a specific USART handle. + * + * When the RX ring buffer is used, data received are stored into the ring buffer even when the + * user doesn't call the USART_TransferReceiveNonBlocking() API. If there is already data received + * in the ring buffer, the user can get the received data from the ring buffer directly. + * + * note When using the RX ring buffer, one byte is reserved for internal use. In other + * words, if p ringBufferSize is 32, then only 31 bytes are used for saving data. + * + * param base USART peripheral base address. + * param handle USART handle pointer. + * param ringBuffer Start address of the ring buffer for background receiving. Pass NULL to disable the ring buffer. + * param ringBufferSize size of the ring buffer. + */ +void USART_TransferStartRingBuffer(USART_Type *base, usart_handle_t *handle, uint8_t *ringBuffer, size_t ringBufferSize) +{ + /* Check arguments */ + assert(NULL != base); + assert(NULL != handle); + assert(NULL != ringBuffer); + + /* Setup the ringbuffer address */ + handle->rxRingBuffer = ringBuffer; + handle->rxRingBufferSize = ringBufferSize; + handle->rxRingBufferHead = 0U; + handle->rxRingBufferTail = 0U; + /* ring buffer is ready we can start receiving data */ + base->FIFOINTENSET = USART_FIFOINTENSET_RXLVL_MASK | USART_FIFOINTENSET_RXERR_MASK; +} + +/*! + * brief Aborts the background transfer and uninstalls the ring buffer. + * + * This function aborts the background transfer and uninstalls the ring buffer. + * + * param base USART peripheral base address. + * param handle USART handle pointer. + */ +void USART_TransferStopRingBuffer(USART_Type *base, usart_handle_t *handle) +{ + /* Check arguments */ + assert(NULL != base); + assert(NULL != handle); + + if (handle->rxState == (uint8_t)kUSART_RxIdle) + { + base->FIFOINTENCLR = USART_FIFOINTENCLR_RXLVL_MASK | USART_FIFOINTENCLR_RXERR_MASK; + } + handle->rxRingBuffer = NULL; + handle->rxRingBufferSize = 0U; + handle->rxRingBufferHead = 0U; + handle->rxRingBufferTail = 0U; +} + +/*! + * brief Initializes a USART instance with user configuration structure and peripheral clock. + * + * This function configures the USART module with the user-defined settings. The user can configure the configuration + * structure and also get the default configuration by using the USART_GetDefaultConfig() function. + * Example below shows how to use this API to configure USART. + * code + * usart_config_t usartConfig; + * usartConfig.baudRate_Bps = 115200U; + * usartConfig.parityMode = kUSART_ParityDisabled; + * usartConfig.stopBitCount = kUSART_OneStopBit; + * USART_Init(USART1, &usartConfig, 20000000U); + * endcode + * + * param base USART peripheral base address. + * param config Pointer to user-defined configuration structure. + * param srcClock_Hz USART clock source frequency in HZ. + * retval kStatus_USART_BaudrateNotSupport Baudrate is not support in current clock source. + * retval kStatus_InvalidArgument USART base address is not valid + * retval kStatus_Success Status USART initialize succeed + */ +status_t USART_Init(USART_Type *base, const usart_config_t *config, uint32_t srcClock_Hz) +{ + int result; + + /* check arguments */ + assert(!((NULL == base) || (NULL == config) || (0U == srcClock_Hz))); + if ((NULL == base) || (NULL == config) || (0U == srcClock_Hz)) + { + return kStatus_InvalidArgument; + } + + /* initialize flexcomm to USART mode */ + result = FLEXCOMM_Init(base, FLEXCOMM_PERIPH_USART); + if (kStatus_Success != result) + { + return result; + } + + if (config->enableTx) + { + /* empty and enable txFIFO */ + base->FIFOCFG |= USART_FIFOCFG_EMPTYTX_MASK | USART_FIFOCFG_ENABLETX_MASK; + /* setup trigger level */ + base->FIFOTRIG &= ~(USART_FIFOTRIG_TXLVL_MASK); + base->FIFOTRIG |= USART_FIFOTRIG_TXLVL(config->txWatermark); + /* enable trigger interrupt */ + base->FIFOTRIG |= USART_FIFOTRIG_TXLVLENA_MASK; + } + + /* empty and enable rxFIFO */ + if (config->enableRx) + { + base->FIFOCFG |= USART_FIFOCFG_EMPTYRX_MASK | USART_FIFOCFG_ENABLERX_MASK; + /* setup trigger level */ + base->FIFOTRIG &= ~(USART_FIFOTRIG_RXLVL_MASK); + base->FIFOTRIG |= USART_FIFOTRIG_RXLVL(config->rxWatermark); + /* enable trigger interrupt */ + base->FIFOTRIG |= USART_FIFOTRIG_RXLVLENA_MASK; + } +#if defined(FSL_FEATURE_USART_HAS_FIFORXTIMEOUTCFG) && FSL_FEATURE_USART_HAS_FIFORXTIMEOUTCFG + USART_SetRxTimeoutConfig(base, &(config->rxTimeout)); +#endif + /* setup configuration and enable USART */ + base->CFG = USART_CFG_PARITYSEL(config->parityMode) | USART_CFG_STOPLEN(config->stopBitCount) | + USART_CFG_DATALEN(config->bitCountPerChar) | USART_CFG_LOOP(config->loopback) | + USART_CFG_SYNCEN((uint32_t)config->syncMode >> 1) | USART_CFG_SYNCMST((uint8_t)config->syncMode) | + USART_CFG_CLKPOL(config->clockPolarity) | USART_CFG_MODE32K(config->enableMode32k) | + USART_CFG_CTSEN(config->enableHardwareFlowControl) | USART_CFG_ENABLE_MASK; + + /* Setup baudrate */ + if (config->enableMode32k) + { + if ((9600U % config->baudRate_Bps) == 0U) + { + base->BRG = 9600U / config->baudRate_Bps - 1U; + } + else + { + return kStatus_USART_BaudrateNotSupport; + } + } + else + { + result = USART_SetBaudRate(base, config->baudRate_Bps, srcClock_Hz); + if (kStatus_Success != result) + { + return result; + } + } + /* Setting continuous Clock configuration. used for synchronous mode. */ + USART_EnableContinuousSCLK(base, config->enableContinuousSCLK); + + return kStatus_Success; +} + +/*! + * brief Deinitializes a USART instance. + * + * This function waits for TX complete, disables TX and RX, and disables the USART clock. + * + * param base USART peripheral base address. + */ +void USART_Deinit(USART_Type *base) +{ + /* Check arguments */ + assert(NULL != base); + + /* Don't wait for TX idle when peripheral is disabled. */ + if ((base->CFG & (USART_CFG_ENABLE_MASK)) != 0U) + { +#if UART_RETRY_TIMES + uint32_t waitTimes = UART_RETRY_TIMES; + while ((0U == (base->STAT & USART_STAT_TXIDLE_MASK)) && (--waitTimes != 0U)) +#else + while (0U == (base->STAT & USART_STAT_TXIDLE_MASK)) +#endif + { + } + } + /* Disable interrupts, disable dma requests, disable peripheral */ + base->FIFOINTENCLR = USART_FIFOINTENCLR_TXERR_MASK | USART_FIFOINTENCLR_RXERR_MASK | USART_FIFOINTENCLR_TXLVL_MASK | + USART_FIFOINTENCLR_RXLVL_MASK; + base->FIFOCFG &= ~(USART_FIFOCFG_DMATX_MASK | USART_FIFOCFG_DMARX_MASK); + base->CFG &= ~(USART_CFG_ENABLE_MASK); +#if defined(FSL_FEATURE_USART_HAS_FIFORXTIMEOUTCFG) && FSL_FEATURE_USART_HAS_FIFORXTIMEOUTCFG + base->FIFORXTIMEOUTCFG = 0U; +#endif +} + +/*! + * brief Gets the default configuration structure. + * + * This function initializes the USART configuration structure to a default value. The default + * values are: + * usartConfig->baudRate_Bps = 115200U; + * usartConfig->parityMode = kUSART_ParityDisabled; + * usartConfig->stopBitCount = kUSART_OneStopBit; + * usartConfig->bitCountPerChar = kUSART_8BitsPerChar; + * usartConfig->loopback = false; + * usartConfig->enableTx = false; + * usartConfig->enableRx = false; + * + * param config Pointer to configuration structure. + */ +void USART_GetDefaultConfig(usart_config_t *config) +{ + /* Check arguments */ + assert(NULL != config); + + /* Initializes the configure structure to zero. */ + (void)memset(config, 0, sizeof(*config)); + + /* Set always all members ! */ + config->baudRate_Bps = 115200U; + config->parityMode = kUSART_ParityDisabled; + config->stopBitCount = kUSART_OneStopBit; + config->bitCountPerChar = kUSART_8BitsPerChar; + config->loopback = false; + config->enableRx = false; + config->enableTx = false; + config->enableMode32k = false; + config->txWatermark = kUSART_TxFifo0; + config->rxWatermark = kUSART_RxFifo1; + config->syncMode = kUSART_SyncModeDisabled; + config->enableContinuousSCLK = false; + config->clockPolarity = kUSART_RxSampleOnFallingEdge; + config->enableHardwareFlowControl = false; +#if defined(FSL_FEATURE_USART_HAS_FIFORXTIMEOUTCFG) && FSL_FEATURE_USART_HAS_FIFORXTIMEOUTCFG + config->rxTimeout.enable = false; + config->rxTimeout.resetCounterOnEmpty = true; + config->rxTimeout.resetCounterOnReceive = true; + config->rxTimeout.counter = 0U; + config->rxTimeout.prescaler = 0U; +#endif +} +#if defined(FSL_FEATURE_USART_HAS_FIFORXTIMEOUTCFG) && FSL_FEATURE_USART_HAS_FIFORXTIMEOUTCFG +/*! + * brief Calculate the USART instance RX timeout prescaler and counter. + * + * This function for calculate the USART RXFIFO timeout config. This function is used to calculate + * suitable prescaler and counter for target_us. + * Example below shows how to use this API to configure USART. + * code + * usart_config_t config; + * config.rxWatermark = kUSART_RxFifo2; + * config.rxTimeout.enable = true; + * config.rxTimeout.resetCounterOnEmpty = true; + * config.rxTimeout.resetCounterOnReceive = true; + * USART_CalcTimeoutConfig(200, &config.rxTimeout.prescaler, &config.rxTimeout.counter, + * CLOCK_GetFreq(kCLOCK_BusClk)); + * endcode + * param target_us Time for rx timeout unit us. + * param rxTimeoutPrescaler The prescaler to be setted after function. + * param rxTimeoutcounter The counter to be setted after function. + * param srcClock_Hz The clockSrc for rx timeout. + */ +void USART_CalcTimeoutConfig(uint32_t target_us, + uint8_t *rxTimeoutPrescaler, + uint32_t *rxTimeoutcounter, + uint32_t srcClock_Hz) +{ + uint32_t counter = 0U; + uint32_t perscalar = 0U, calculate_us = 0U, us_diff = 0U, min_diff = 0xffffffffUL; + /* find the suitable value */ + for (perscalar = 0U; perscalar < 256U; perscalar++) + { + counter = target_us * (srcClock_Hz / 1000000UL) / (16U * (perscalar + 1U)); + calculate_us = 16U * (perscalar + 1U) * counter / (srcClock_Hz / 1000000UL); + us_diff = (calculate_us > target_us) ? (calculate_us - target_us) : (target_us - calculate_us); + if (us_diff == 0U) + { + *rxTimeoutPrescaler = (uint8_t)perscalar; + *rxTimeoutcounter = counter; + break; + } + else + { + if (min_diff > us_diff) + { + min_diff = us_diff; + *rxTimeoutPrescaler = (uint8_t)perscalar; + *rxTimeoutcounter = counter; + } + } + } +} +/*! + * brief Sets the USART instance RX timeout config. + * + * This function configures the USART RXFIFO timeout config. This function is used to config + * the USART RXFIFO timeout config after the USART module is initialized by the USART_Init. + * + * param base USART peripheral base address. + * param config pointer to receive timeout configuration structure. + */ +void USART_SetRxTimeoutConfig(USART_Type *base, const usart_rx_timeout_config *config) +{ + base->FIFORXTIMEOUTCFG = 0U; + base->FIFORXTIMEOUTCFG = USART_FIFORXTIMEOUTCFG_RXTIMEOUT_COW((config->resetCounterOnReceive) ? 0U : 1U) | + USART_FIFORXTIMEOUTCFG_RXTIMEOUT_COE((config->resetCounterOnEmpty) ? 0U : 1U) | + USART_FIFORXTIMEOUTCFG_RXTIMEOUT_EN(config->enable) | + USART_FIFORXTIMEOUTCFG_RXTIMEOUT_VALUE(config->counter) | + USART_FIFORXTIMEOUTCFG_RXTIMEOUT_PRESCALER(config->prescaler); +} +#endif + +/*! + * brief Sets the USART instance baud rate. + * + * This function configures the USART module baud rate. This function is used to update + * the USART module baud rate after the USART module is initialized by the USART_Init. + * code + * USART_SetBaudRate(USART1, 115200U, 20000000U); + * endcode + * + * param base USART peripheral base address. + * param baudrate_Bps USART baudrate to be set. + * param srcClock_Hz USART clock source frequency in HZ. + * retval kStatus_USART_BaudrateNotSupport Baudrate is not support in current clock source. + * retval kStatus_Success Set baudrate succeed. + * retval kStatus_InvalidArgument One or more arguments are invalid. + */ +status_t USART_SetBaudRate(USART_Type *base, uint32_t baudrate_Bps, uint32_t srcClock_Hz) +{ + uint32_t best_diff = (uint32_t)-1, best_osrval = 0xf, best_brgval = (uint32_t)-1; + uint32_t osrval, brgval, diff, baudrate, allowed_error; + + /* check arguments */ + assert(!((NULL == base) || (0U == baudrate_Bps) || (0U == srcClock_Hz))); + if ((NULL == base) || (0U == baudrate_Bps) || (0U == srcClock_Hz)) + { + return kStatus_InvalidArgument; + } + + /* If synchronous master mode is enabled, only configure the BRG value. */ + if ((base->CFG & USART_CFG_SYNCEN_MASK) != 0U) + { + if ((base->CFG & USART_CFG_SYNCMST_MASK) != 0U) + { + brgval = srcClock_Hz / baudrate_Bps; + base->BRG = brgval - 1U; + } + } + else + { + /* Actual baud rate must be within 3% of desired baud rate based on the calculated OSR and BRG value */ + allowed_error = ((baudrate_Bps / 100U) * 3U); + + for (osrval = best_osrval; osrval >= 4U; osrval--) + { + /* + * Smaller values of OSR can make the sampling position within a data bit less accurate and may + * potentially cause more noise errors or incorrect data. + * Break if the best baudrate's diff is in the allowed error range and the osrval is below 8, + * only use lower osrval if the baudrate cannot be obtained with an osrval of 8 or above. */ + if ((osrval <= 8U) && (best_diff <= allowed_error)) + { + break; + } + + brgval = (((srcClock_Hz * 10U) / ((osrval + 1U) * baudrate_Bps)) - 5U) / 10U; + if (brgval > 0xFFFFU) + { + continue; + } + baudrate = srcClock_Hz / ((osrval + 1U) * (brgval + 1U)); + diff = (baudrate_Bps < baudrate) ? (baudrate - baudrate_Bps) : (baudrate_Bps - baudrate); + if (diff < best_diff) + { + best_diff = diff; + best_osrval = osrval; + best_brgval = brgval; + } + } + + /* Check to see if actual baud rate is within 3% of desired baud rate + * based on the best calculated OSR and BRG value */ + baudrate = srcClock_Hz / ((best_osrval + 1U) * (best_brgval + 1U)); + diff = (baudrate_Bps < baudrate) ? (baudrate - baudrate_Bps) : (baudrate_Bps - baudrate); + if (diff > allowed_error) + { + return kStatus_USART_BaudrateNotSupport; + } + + /* value over range */ + if (best_brgval > 0xFFFFU) + { + return kStatus_USART_BaudrateNotSupport; + } + + base->OSR = best_osrval; + base->BRG = best_brgval; + } + + return kStatus_Success; +} + +/*! + * brief Enable 32 kHz mode which USART uses clock from the RTC oscillator as the clock source. + * + * Please note that in order to use a 32 kHz clock to operate USART properly, the RTC oscillator + * and its 32 kHz output must be manully enabled by user, by calling RTC_Init and setting + * SYSCON_RTCOSCCTRL_EN bit to 1. + * And in 32kHz clocking mode the USART can only work at 9600 baudrate or at the baudrate that + * 9600 can evenly divide, eg: 4800, 3200. + * + * param base USART peripheral base address. + * param baudRate_Bps USART baudrate to be set.. + * param enableMode32k true is 32k mode, false is normal mode. + * param srcClock_Hz USART clock source frequency in HZ. + * retval kStatus_USART_BaudrateNotSupport Baudrate is not support in current clock source. + * retval kStatus_Success Set baudrate succeed. + * retval kStatus_InvalidArgument One or more arguments are invalid. + */ +status_t USART_Enable32kMode(USART_Type *base, uint32_t baudRate_Bps, bool enableMode32k, uint32_t srcClock_Hz) +{ + status_t result = kStatus_Success; + base->CFG &= ~(USART_CFG_ENABLE_MASK); + if (enableMode32k) + { + base->CFG |= USART_CFG_MODE32K_MASK; + if ((9600U % baudRate_Bps) == 0U) + { + base->BRG = 9600U / baudRate_Bps - 1U; + } + else + { + return kStatus_USART_BaudrateNotSupport; + } + } + else + { + base->CFG &= ~(USART_CFG_MODE32K_MASK); + result = USART_SetBaudRate(base, baudRate_Bps, srcClock_Hz); + if (kStatus_Success != result) + { + return result; + } + } + base->CFG |= USART_CFG_ENABLE_MASK; + return result; +} + +/*! + * brief Enable 9-bit data mode for USART. + * + * This function set the 9-bit mode for USART module. The 9th bit is not used for parity thus can be modified by user. + * + * param base USART peripheral base address. + * param enable true to enable, false to disable. + */ +void USART_Enable9bitMode(USART_Type *base, bool enable) +{ + assert(base != NULL); + + uint32_t temp = 0U; + + if (enable) + { + /* Set USART 9-bit mode, disable parity. */ + temp = base->CFG & ~((uint32_t)USART_CFG_DATALEN_MASK | (uint32_t)USART_CFG_PARITYSEL_MASK); + temp |= (uint32_t)USART_CFG_DATALEN(0x2U); + base->CFG = temp; + } + else + { + /* Set USART to 8-bit mode. */ + base->CFG &= ~((uint32_t)USART_CFG_DATALEN_MASK); + base->CFG |= (uint32_t)USART_CFG_DATALEN(0x1U); + } +} + +/*! + * brief Transmit an address frame in 9-bit data mode. + * + * param base USART peripheral base address. + * param address USART slave address. + */ +void USART_SendAddress(USART_Type *base, uint8_t address) +{ + assert(base != NULL); + base->FIFOWR = ((uint32_t)address | 0x100UL); +} + +/*! + * brief Writes to the TX register using a blocking method. + * + * This function polls the TX register, waits for the TX register to be empty or for the TX FIFO + * to have room and writes data to the TX buffer. + * + * param base USART peripheral base address. + * param data Start address of the data to write. + * param length Size of the data to write. + * retval kStatus_USART_Timeout Transmission timed out and was aborted. + * retval kStatus_InvalidArgument Invalid argument. + * retval kStatus_Success Successfully wrote all data. + */ +status_t USART_WriteBlocking(USART_Type *base, const uint8_t *data, size_t length) +{ + /* Check arguments */ + assert(!((NULL == base) || (NULL == data))); +#if UART_RETRY_TIMES + uint32_t waitTimes; +#endif + if ((NULL == base) || (NULL == data)) + { + return kStatus_InvalidArgument; + } + /* Check whether txFIFO is enabled */ + if (0U == (base->FIFOCFG & USART_FIFOCFG_ENABLETX_MASK)) + { + return kStatus_InvalidArgument; + } + for (; length > 0U; length--) + { + /* Loop until txFIFO get some space for new data */ +#if UART_RETRY_TIMES + waitTimes = UART_RETRY_TIMES; + while ((0U == (base->FIFOSTAT & USART_FIFOSTAT_TXNOTFULL_MASK)) && (--waitTimes != 0U)) +#else + while (0U == (base->FIFOSTAT & USART_FIFOSTAT_TXNOTFULL_MASK)) +#endif + { + } +#if UART_RETRY_TIMES + if (0U == waitTimes) + { + return kStatus_USART_Timeout; + } +#endif + base->FIFOWR = *data; + data++; + } + /* Wait to finish transfer */ +#if UART_RETRY_TIMES + waitTimes = UART_RETRY_TIMES; + while ((0U == (base->STAT & USART_STAT_TXIDLE_MASK)) && (--waitTimes != 0U)) +#else + while (0U == (base->STAT & USART_STAT_TXIDLE_MASK)) +#endif + { + } +#if UART_RETRY_TIMES + if (0U == waitTimes) + { + return kStatus_USART_Timeout; + } +#endif + return kStatus_Success; +} + +/*! + * brief Read RX data register using a blocking method. + * + * This function polls the RX register, waits for the RX register to be full or for RX FIFO to + * have data and read data from the TX register. + * + * param base USART peripheral base address. + * param data Start address of the buffer to store the received data. + * param length Size of the buffer. + * retval kStatus_USART_FramingError Receiver overrun happened while receiving data. + * retval kStatus_USART_ParityError Noise error happened while receiving data. + * retval kStatus_USART_NoiseError Framing error happened while receiving data. + * retval kStatus_USART_RxError Overflow or underflow rxFIFO happened. + * retval kStatus_USART_Timeout Transmission timed out and was aborted. + * retval kStatus_Success Successfully received all data. + */ +status_t USART_ReadBlocking(USART_Type *base, uint8_t *data, size_t length) +{ + uint32_t statusFlag; + status_t status = kStatus_Success; +#if UART_RETRY_TIMES + uint32_t waitTimes; +#endif + + /* check arguments */ + assert(!((NULL == base) || (NULL == data))); + if ((NULL == base) || (NULL == data)) + { + return kStatus_InvalidArgument; + } + + /* Check whether rxFIFO is enabled */ + if ((base->FIFOCFG & USART_FIFOCFG_ENABLERX_MASK) == 0U) + { + return kStatus_Fail; + } + for (; length > 0U; length--) + { + /* loop until rxFIFO have some data to read */ +#if UART_RETRY_TIMES + waitTimes = UART_RETRY_TIMES; + while (((base->FIFOSTAT & USART_FIFOSTAT_RXNOTEMPTY_MASK) == 0U) && (--waitTimes != 0U)) +#else + while ((base->FIFOSTAT & USART_FIFOSTAT_RXNOTEMPTY_MASK) == 0U) +#endif + { + } +#if UART_RETRY_TIMES + if (waitTimes == 0U) + { + status = kStatus_USART_Timeout; + break; + } +#endif + /* check rxFIFO statusFlag */ + if ((base->FIFOSTAT & USART_FIFOSTAT_RXERR_MASK) != 0U) + { + base->FIFOCFG |= USART_FIFOCFG_EMPTYRX_MASK; + base->FIFOSTAT |= USART_FIFOSTAT_RXERR_MASK; + status = kStatus_USART_RxError; + break; + } + /* check receive statusFlag */ + statusFlag = base->STAT; + /* Clear all status flags */ + base->STAT |= statusFlag; + if ((statusFlag & USART_STAT_PARITYERRINT_MASK) != 0U) + { + status = kStatus_USART_ParityError; + } + if ((statusFlag & USART_STAT_FRAMERRINT_MASK) != 0U) + { + status = kStatus_USART_FramingError; + } + if ((statusFlag & USART_STAT_RXNOISEINT_MASK) != 0U) + { + status = kStatus_USART_NoiseError; + } + + if (kStatus_Success == status) + { + *data = (uint8_t)base->FIFORD; + data++; + } + else + { + break; + } + } + return status; +} + +/*! + * brief Initializes the USART handle. + * + * This function initializes the USART handle which can be used for other USART + * transactional APIs. Usually, for a specified USART instance, + * call this API once to get the initialized handle. + * + * param base USART peripheral base address. + * param handle USART handle pointer. + * param callback The callback function. + * param userData The parameter of the callback function. + */ +status_t USART_TransferCreateHandle(USART_Type *base, + usart_handle_t *handle, + usart_transfer_callback_t callback, + void *userData) +{ + /* Check 'base' */ + assert(!((NULL == base) || (NULL == handle))); + + uint32_t instance = 0; + usart_to_flexcomm_t handler; + handler.usart_master_handler = USART_TransferHandleIRQ; + + if ((NULL == base) || (NULL == handle)) + { + return kStatus_InvalidArgument; + } + + instance = USART_GetInstance(base); + + (void)memset(handle, 0, sizeof(*handle)); + /* Set the TX/RX state. */ + handle->rxState = (uint8_t)kUSART_RxIdle; + handle->txState = (uint8_t)kUSART_TxIdle; + /* Set the callback and user data. */ + handle->callback = callback; + handle->userData = userData; + handle->rxWatermark = (uint8_t)USART_FIFOTRIG_RXLVL_GET(base); + handle->txWatermark = (uint8_t)USART_FIFOTRIG_TXLVL_GET(base); + + FLEXCOMM_SetIRQHandler(base, handler.flexcomm_handler, handle); + + /* Enable interrupt in NVIC. */ + (void)EnableIRQ(s_usartIRQ[instance]); + + return kStatus_Success; +} + +/*! + * brief Transmits a buffer of data using the interrupt method. + * + * This function sends data using an interrupt method. This is a non-blocking function, which + * returns directly without waiting for all data to be written to the TX register. When + * all data is written to the TX register in the IRQ handler, the USART driver calls the callback + * function and passes the ref kStatus_USART_TxIdle as status parameter. + * + * param base USART peripheral base address. + * param handle USART handle pointer. + * param xfer USART transfer structure. See #usart_transfer_t. + * retval kStatus_Success Successfully start the data transmission. + * retval kStatus_USART_TxBusy Previous transmission still not finished, data not all written to TX register yet. + * retval kStatus_InvalidArgument Invalid argument. + */ +status_t USART_TransferSendNonBlocking(USART_Type *base, usart_handle_t *handle, usart_transfer_t *xfer) +{ + /* Check arguments */ + assert(!((NULL == base) || (NULL == handle) || (NULL == xfer))); + if ((NULL == base) || (NULL == handle) || (NULL == xfer)) + { + return kStatus_InvalidArgument; + } + /* Check xfer members */ + assert(!((0U == xfer->dataSize) || (NULL == xfer->txData))); + if ((0U == xfer->dataSize) || (NULL == xfer->txData)) + { + return kStatus_InvalidArgument; + } + + uint32_t globalMask = DisableGlobalIRQ(); + + /* Return error if current TX busy. */ + if ((uint8_t)kUSART_TxBusy == handle->txState) + { + EnableGlobalIRQ(globalMask); + return kStatus_USART_TxBusy; + } + else + { + handle->txState = (uint8_t)kUSART_TxBusy; + uint32_t usartMask = USART_GetEnabledInterrupts(base); + USART_DisableInterrupts(base, usartMask); + EnableGlobalIRQ(globalMask); + + handle->txData = xfer->txData; + handle->txDataSize = xfer->dataSize; + handle->txDataSizeAll = xfer->dataSize; + USART_EnableInterrupts(base, usartMask | (uint32_t)kUSART_TxLevelInterruptEnable); + } + + return kStatus_Success; +} + +/*! + * brief Aborts the interrupt-driven data transmit. + * + * This function aborts the interrupt driven data sending. The user can get the remainBtyes to find out + * how many bytes are still not sent out. + * + * param base USART peripheral base address. + * param handle USART handle pointer. + */ +void USART_TransferAbortSend(USART_Type *base, usart_handle_t *handle) +{ + assert(NULL != handle); + + /* Disable interrupts */ + USART_DisableInterrupts(base, (uint32_t)kUSART_TxLevelInterruptEnable); + /* Empty txFIFO */ + base->FIFOCFG |= USART_FIFOCFG_EMPTYTX_MASK; + + handle->txDataSize = 0U; + handle->txState = (uint8_t)kUSART_TxIdle; +} + +/*! + * brief Get the number of bytes that have been sent out to bus. + * + * This function gets the number of bytes that have been sent out to bus by interrupt method. + * + * param base USART peripheral base address. + * param handle USART handle pointer. + * param count Send bytes count. + * retval kStatus_NoTransferInProgress No send in progress. + * retval kStatus_InvalidArgument Parameter is invalid. + * retval kStatus_Success Get successfully through the parameter \p count; + */ +status_t USART_TransferGetSendCount(USART_Type *base, usart_handle_t *handle, uint32_t *count) +{ + assert(NULL != handle); + assert(NULL != count); + + if ((uint8_t)kUSART_TxIdle == handle->txState) + { + return kStatus_NoTransferInProgress; + } + + *count = handle->txDataSizeAll - handle->txDataSize - + ((base->FIFOSTAT & USART_FIFOSTAT_TXLVL_MASK) >> USART_FIFOSTAT_TXLVL_SHIFT); + + return kStatus_Success; +} + +/*! + * brief Receives a buffer of data using an interrupt method. + * + * This function receives data using an interrupt method. This is a non-blocking function, which + * returns without waiting for all data to be received. + * If the RX ring buffer is used and not empty, the data in the ring buffer is copied and + * the parameter p receivedBytes shows how many bytes are copied from the ring buffer. + * After copying, if the data in the ring buffer is not enough to read, the receive + * request is saved by the USART driver. When the new data arrives, the receive request + * is serviced first. When all data is received, the USART driver notifies the upper layer + * through a callback function and passes the status parameter ref kStatus_USART_RxIdle. + * For example, the upper layer needs 10 bytes but there are only 5 bytes in the ring buffer. + * The 5 bytes are copied to the xfer->data and this function returns with the + * parameter p receivedBytes set to 5. For the left 5 bytes, newly arrived data is + * saved from the xfer->data[5]. When 5 bytes are received, the USART driver notifies the upper layer. + * If the RX ring buffer is not enabled, this function enables the RX and RX interrupt + * to receive data to the xfer->data. When all data is received, the upper layer is notified. + * + * param base USART peripheral base address. + * param handle USART handle pointer. + * param xfer USART transfer structure, see #usart_transfer_t. + * param receivedBytes Bytes received from the ring buffer directly. + * retval kStatus_Success Successfully queue the transfer into transmit queue. + * retval kStatus_USART_RxBusy Previous receive request is not finished. + * retval kStatus_InvalidArgument Invalid argument. + */ +status_t USART_TransferReceiveNonBlocking(USART_Type *base, + usart_handle_t *handle, + usart_transfer_t *xfer, + size_t *receivedBytes) +{ + uint32_t i; + /* How many bytes to copy from ring buffer to user memory. */ + size_t bytesToCopy = 0U; + /* How many bytes to receive. */ + size_t bytesToReceive; + /* How many bytes currently have received. */ + size_t bytesCurrentReceived; + + /* Check arguments */ + assert(!((NULL == base) || (NULL == handle) || (NULL == xfer))); + if ((NULL == base) || (NULL == handle) || (NULL == xfer)) + { + return kStatus_InvalidArgument; + } + /* Check xfer members */ + assert(!((0U == xfer->dataSize) || (NULL == xfer->rxData))); + if ((0U == xfer->dataSize) || (NULL == xfer->rxData)) + { + return kStatus_InvalidArgument; + } + + /* Enable address detect when address match is enabled. */ + if ((base->CFG & (uint32_t)USART_CFG_AUTOADDR_MASK) != 0U) + { + base->CTL |= (uint32_t)USART_CTL_ADDRDET_MASK; + } + + uint32_t globalMask = DisableGlobalIRQ(); + + /* How to get data: + 1. If RX ring buffer is not enabled, then save xfer->data and xfer->dataSize + to uart handle, enable interrupt to store received data to xfer->data. When + all data received, trigger callback. + 2. If RX ring buffer is enabled and not empty, get data from ring buffer first. + If there are enough data in ring buffer, copy them to xfer->data and return. + If there are not enough data in ring buffer, copy all of them to xfer->data, + save the xfer->data remained empty space to uart handle, receive data + to this empty space and trigger callback when finished. */ + if ((uint8_t)kUSART_RxBusy == handle->rxState) + { + EnableGlobalIRQ(globalMask); + return kStatus_USART_RxBusy; + } + else + { + handle->rxState = (uint8_t)kUSART_RxBusy; + uint32_t usartMask = USART_GetEnabledInterrupts(base); + USART_DisableInterrupts(base, usartMask); + EnableGlobalIRQ(globalMask); + + bytesToReceive = xfer->dataSize; + bytesCurrentReceived = 0U; + /* If RX ring buffer is used. */ + if (handle->rxRingBuffer != NULL) + { + /* How many bytes in RX ring buffer currently. */ + bytesToCopy = USART_TransferGetRxRingBufferLength(handle); + if (bytesToCopy != 0U) + { + bytesToCopy = MIN(bytesToReceive, bytesToCopy); + bytesToReceive -= bytesToCopy; + /* Copy data from ring buffer to user memory. */ + for (i = 0U; i < bytesToCopy; i++) + { + xfer->rxData[bytesCurrentReceived++] = handle->rxRingBuffer[handle->rxRingBufferTail]; + /* Wrap to 0. Not use modulo (%) because it might be large and slow. */ + if ((size_t)handle->rxRingBufferTail + 1U == handle->rxRingBufferSize) + { + handle->rxRingBufferTail = 0U; + } + else + { + handle->rxRingBufferTail++; + } + } + } + /* If ring buffer does not have enough data, still need to read more data. */ + if (bytesToReceive != 0U) + { + /* No data in ring buffer, save the request to UART handle. */ + handle->rxData = xfer->rxData + bytesCurrentReceived; + handle->rxDataSize = bytesToReceive; + handle->rxDataSizeAll = xfer->dataSize; + } + else + { + handle->rxState = (uint8_t)kUSART_RxIdle; + } + } + /* Ring buffer not used. */ + else + { + handle->rxData = xfer->rxData + bytesCurrentReceived; + handle->rxDataSize = bytesToReceive; + handle->rxDataSizeAll = bytesToReceive; + + /* Enable RX interrupt. */ + base->FIFOINTENSET = USART_FIFOINTENSET_RXLVL_MASK; + } + + /* Re-enable USART IRQ. */ + USART_EnableInterrupts(base, usartMask); + + /* Return the how many bytes have read. */ + if (receivedBytes != NULL) + { + *receivedBytes = bytesCurrentReceived; + } + + /* When using ring buffer and we received everything, call user callback. */ + if (handle->rxRingBuffer != NULL && bytesToReceive == 0U) + { + if (handle->callback != NULL) + { + handle->callback(base, handle, kStatus_USART_RxIdle, handle->userData); + } + } + } + + return kStatus_Success; +} + +/*! + * brief Aborts the interrupt-driven data receiving. + * + * This function aborts the interrupt-driven data receiving. The user can get the remainBytes to find out + * how many bytes not received yet. + * + * param base USART peripheral base address. + * param handle USART handle pointer. + */ +void USART_TransferAbortReceive(USART_Type *base, usart_handle_t *handle) +{ + assert(NULL != handle); + + /* Only abort the receive to handle->rxData, the RX ring buffer is still working. */ + if (NULL == handle->rxRingBuffer) + { + /* Disable interrupts */ + USART_DisableInterrupts(base, (uint32_t)kUSART_RxLevelInterruptEnable); + /* Empty rxFIFO */ + base->FIFOCFG |= USART_FIFOCFG_EMPTYRX_MASK; + } + + handle->rxDataSize = 0U; + handle->rxState = (uint8_t)kUSART_RxIdle; +} + +/*! + * brief Get the number of bytes that have been received. + * + * This function gets the number of bytes that have been received. + * + * param base USART peripheral base address. + * param handle USART handle pointer. + * param count Receive bytes count. + * retval kStatus_NoTransferInProgress No receive in progress. + * retval kStatus_InvalidArgument Parameter is invalid. + * retval kStatus_Success Get successfully through the parameter \p count; + */ +status_t USART_TransferGetReceiveCount(USART_Type *base, usart_handle_t *handle, uint32_t *count) +{ + assert(NULL != handle); + assert(NULL != count); + + if ((uint8_t)kUSART_RxIdle == handle->rxState) + { + return kStatus_NoTransferInProgress; + } + + *count = handle->rxDataSizeAll - handle->rxDataSize; + + return kStatus_Success; +} + +/*! + * brief USART IRQ handle function. + * + * This function handles the USART transmit and receive IRQ request. + * + * param base USART peripheral base address. + * param handle USART handle pointer. + */ +void USART_TransferHandleIRQ(USART_Type *base, usart_handle_t *handle) +{ + /* Check arguments */ + assert((NULL != base) && (NULL != handle)); + + bool receiveEnabled = ((handle->rxDataSize != 0U) || (handle->rxRingBuffer != NULL)); + bool sendEnabled = (handle->txDataSize != 0U); + uint8_t rxdata; + size_t tmpsize; + + /* If RX overrun. */ + if ((base->FIFOSTAT & USART_FIFOSTAT_RXERR_MASK) != 0U) + { + /* Clear rx error state. */ + base->FIFOSTAT |= USART_FIFOSTAT_RXERR_MASK; + /* clear rxFIFO */ + base->FIFOCFG |= USART_FIFOCFG_EMPTYRX_MASK; + /* Trigger callback. */ + if (handle->callback != NULL) + { + handle->callback(base, handle, kStatus_USART_RxError, handle->userData); + } + } + /* TX under run, happens when slave is in synchronous mode and the data is not written in tx register in time. */ + if ((base->FIFOSTAT & USART_FIFOSTAT_TXERR_MASK) != 0U) + { + /* Clear tx error state. */ + base->FIFOSTAT |= USART_FIFOSTAT_TXERR_MASK; + /* Trigger callback. */ + if (handle->callback != NULL) + { + handle->callback(base, handle, kStatus_USART_TxError, handle->userData); + } + } + /* If noise error. */ + if ((base->STAT & USART_STAT_RXNOISEINT_MASK) != 0U) + { + /* Clear rx error state. */ + base->STAT |= USART_STAT_RXNOISEINT_MASK; + /* clear rxFIFO */ + base->FIFOCFG |= USART_FIFOCFG_EMPTYRX_MASK; + /* Trigger callback. */ + if (handle->callback != NULL) + { + handle->callback(base, handle, kStatus_USART_NoiseError, handle->userData); + } + } + /* If framing error. */ + if ((base->STAT & USART_STAT_FRAMERRINT_MASK) != 0U) + { + /* Clear rx error state. */ + base->STAT |= USART_STAT_FRAMERRINT_MASK; + /* clear rxFIFO */ + base->FIFOCFG |= USART_FIFOCFG_EMPTYRX_MASK; + /* Trigger callback. */ + if (handle->callback != NULL) + { + handle->callback(base, handle, kStatus_USART_FramingError, handle->userData); + } + } + /* If parity error. */ + if ((base->STAT & USART_STAT_PARITYERRINT_MASK) != 0U) + { + /* Clear rx error state. */ + base->STAT |= USART_STAT_PARITYERRINT_MASK; + /* clear rxFIFO */ + base->FIFOCFG |= USART_FIFOCFG_EMPTYRX_MASK; + /* Trigger callback. */ + if (handle->callback != NULL) + { + handle->callback(base, handle, kStatus_USART_ParityError, handle->userData); + } + } + while ((receiveEnabled && ((base->FIFOSTAT & USART_FIFOSTAT_RXNOTEMPTY_MASK) != 0U)) || + (sendEnabled && ((base->FIFOSTAT & USART_FIFOSTAT_TXNOTFULL_MASK) != 0U))) + { + /* Receive data */ + if (receiveEnabled && ((base->FIFOSTAT & USART_FIFOSTAT_RXNOTEMPTY_MASK) != 0U)) + { + /* Clear address detect when RXFIFO has data. */ + base->CTL &= ~(uint32_t)USART_CTL_ADDRDET_MASK; + /* Receive to app bufffer if app buffer is present */ + if (handle->rxDataSize != 0U) + { + rxdata = (uint8_t)base->FIFORD; + *handle->rxData = rxdata; + handle->rxDataSize--; + handle->rxData++; + receiveEnabled = ((handle->rxDataSize != 0U) || (handle->rxRingBuffer != NULL)); + if (0U == handle->rxDataSize) + { + if (NULL == handle->rxRingBuffer) + { + base->FIFOINTENCLR = USART_FIFOINTENCLR_RXLVL_MASK | USART_FIFOINTENSET_RXERR_MASK; + } + handle->rxState = (uint8_t)kUSART_RxIdle; + if (handle->callback != NULL) + { + handle->callback(base, handle, kStatus_USART_RxIdle, handle->userData); + } + } + } + /* Otherwise receive to ring buffer if ring buffer is present */ + else + { + if (handle->rxRingBuffer != NULL) + { + /* If RX ring buffer is full, trigger callback to notify over run. */ + if (USART_TransferIsRxRingBufferFull(handle)) + { + if (handle->callback != NULL) + { + handle->callback(base, handle, kStatus_USART_RxRingBufferOverrun, handle->userData); + } + } + /* If ring buffer is still full after callback function, the oldest data is overridden. */ + if (USART_TransferIsRxRingBufferFull(handle)) + { + /* Increase handle->rxRingBufferTail to make room for new data. */ + if ((size_t)handle->rxRingBufferTail + 1U == handle->rxRingBufferSize) + { + handle->rxRingBufferTail = 0U; + } + else + { + handle->rxRingBufferTail++; + } + } + /* Read data. */ + rxdata = (uint8_t)base->FIFORD; + handle->rxRingBuffer[handle->rxRingBufferHead] = rxdata; + /* Increase handle->rxRingBufferHead. */ + if ((size_t)handle->rxRingBufferHead + 1U == handle->rxRingBufferSize) + { + handle->rxRingBufferHead = 0U; + } + else + { + handle->rxRingBufferHead++; + } + } + } + } + /* Send data */ + if (sendEnabled && ((base->FIFOSTAT & USART_FIFOSTAT_TXNOTFULL_MASK) != 0U)) + { + base->FIFOWR = *handle->txData; + handle->txDataSize--; + handle->txData++; + sendEnabled = handle->txDataSize != 0U; + if (!sendEnabled) + { + base->FIFOINTENCLR = USART_FIFOINTENCLR_TXLVL_MASK; + + base->INTENSET = USART_INTENSET_TXIDLEEN_MASK; + } + } + } + + /* Tx idle and the interrupt is enabled. */ + if ((0U != (base->INTENSET & USART_INTENSET_TXIDLEEN_MASK)) && (0U != (base->INTSTAT & USART_INTSTAT_TXIDLE_MASK))) + { + /* Set txState to idle only when all data has been sent out to bus. */ + handle->txState = (uint8_t)kUSART_TxIdle; + /* Disable tx idle interrupt */ + base->INTENCLR = USART_INTENCLR_TXIDLECLR_MASK; + + /* Trigger callback. */ + if (handle->callback != NULL) + { + handle->callback(base, handle, kStatus_USART_TxIdle, handle->userData); + } + } + + /* ring buffer is not used */ + if (NULL == handle->rxRingBuffer) + { + tmpsize = handle->rxDataSize; + + /* restore if rx transfer ends and rxLevel is different from default value */ + if ((tmpsize == 0U) && (USART_FIFOTRIG_RXLVL_GET(base) != handle->rxWatermark)) + { + base->FIFOTRIG = + (base->FIFOTRIG & (~USART_FIFOTRIG_RXLVL_MASK)) | USART_FIFOTRIG_RXLVL(handle->rxWatermark); + } + /* decrease level if rx transfer is bellow */ + if ((tmpsize != 0U) && (tmpsize < (USART_FIFOTRIG_RXLVL_GET(base) + 1U))) + { + base->FIFOTRIG = (base->FIFOTRIG & (~USART_FIFOTRIG_RXLVL_MASK)) | (USART_FIFOTRIG_RXLVL(tmpsize - 1U)); + } + } +} diff --git a/drivers/Src/led.c b/drivers/Src/led.c new file mode 100644 index 0000000..7e18f8c --- /dev/null +++ b/drivers/Src/led.c @@ -0,0 +1,23 @@ +#include "led.h" + + +#define PORT1 (1U<<15) +#define GPIO1_4 (1U<<4) + +void led_init(void){ + /* ENable Clock access to led port (PORT1) */ + SYSCON->AHBCLKCTRLX[0] |= PORT1; + /* Set led pin as output pin */ + GPIO->W[1][4] = 1; + GPIO->DIRSET[1] = GPIO1_4; +} + +void led_on(void){ + /* Set Led pin HIGH (P1-4) */ + GPIO->W[1][4] = 0; +} + +void led_off(void){ + /* Set Led pin LOW (P1-4) */ + GPIO->W[1][4] = 1; +} diff --git a/drivers/Src/uart.c b/drivers/Src/uart.c new file mode 100644 index 0000000..daa7cf3 --- /dev/null +++ b/drivers/Src/uart.c @@ -0,0 +1,60 @@ +#include "uart.h" +#include "fsl_common.h" +#include "fsl_debug_console.h" + +void uart_tx_pin(void) +{ + /* Enable IOCON Clock */ + CLOCK_EnableClock(kCLOCK_Iocon); + + /* Enable Uart Clock IP */ + const uint32_t port0_pin30_config = (/* Pin is configured as FC0_TXD_SCL_MISO_WS */ + 0x01u | + /* No addition pin function */ + 0x00u | + /* Standard mode, output slew rate control is enabled */ + 0x00u | + /* Input function is not inverted */ + 0x00u | + /* Enables digital function */ + 0x0100u | + /* Open drain is disabled */ + 0x00u); + /* PORT0 PIN30 (coords: 94) is configured as FC0_TXD_SCL_MISO_WS */ + IOCON->PIO[0U][30U] = port0_pin30_config; + +} + +void uart_rx_pin(void) +{ + /* Enable IOCON Clock */ + CLOCK_EnableClock(kCLOCK_Iocon); + + /* Enable Uart Clock IP */ + const uint32_t port0_pin29_config = (/* Pin is configured as FC0_TXD_SCL_MISO_WS */ + 0x01u | + /* No addition pin function */ + 0x00u | + /* Standard mode, output slew rate control is enabled */ + 0x00u | + /* Input function is not inverted */ + 0x00u | + /* Enables digital function */ + 0x0100u | + /* Open drain is disabled */ + 0x00u); + /* PORT0 PIN30 (coords: 94) is configured as FC0_TXD_SCL_MISO_WS */ + IOCON->PIO[0U][29U] = port0_pin29_config; + +} + +void uart_init(void){ + uart_tx_pin(); + uart_rx_pin(); + CLOCK_AttachClk(kFRO12M_to_FLEXCOMM0); + RESET_ClearPeripheralReset(kFC0_RST_SHIFT_RSTn); + uint32_t uartClkSrcFreq = 12000000U; + DbgConsole_Init(0, 115200U, kSerialPort_Uart, uartClkSrcFreq); + +} + diff --git a/main.c b/main.c new file mode 100644 index 0000000..92aa24f --- /dev/null +++ b/main.c @@ -0,0 +1,24 @@ +#include "led.h" +#include "uart.h" +#include "fsl_debug_console.h" +#include "timebase.h" +#include "fsl_power.h" + + +int main(){ + SystemCoreClockUpdate(); + uart_init(); + led_init(); + timebase_init(); + + PRINTF("LPC55S69 ..............\n\r"); + + while (1) + { + delay_s(1); + PRINTF("A second just occured!!\n\r"); + + + } +} +