feat support nuvoton-m2354 bsp for Ubiquitous/XiZi kernel

This commit is contained in:
Liu_Weichao 2022-03-08 15:32:51 +08:00
parent a35e73e7dd
commit 2db01c89dd
152 changed files with 80100 additions and 21 deletions

View File

@ -3,6 +3,8 @@ config ADAPTER_ETHERCAT_HFA21
default "hfa21_ethercat"
config ADAPTER_ETHERCAT_HFA21_ROLE
bool "support ethercat role configure"
default y
choice
prompt "EtherCAT adapter select net role type "
default AS_ETHERCAT_SLAVE_ROLE

View File

@ -5,7 +5,7 @@ MAKEFLAGS += --no-print-directory
.PHONY:COMPILE_APP COMPILE_KERNEL
support :=kd233 stm32f407-st-discovery maix-go stm32f407zgt6 aiit-riscv64-board aiit-arm32-board hifive1-rev-B hifive1-emulator k210-emulator cortex-m3-emulator cortex-m4-emulator ok1052-c gapuino stm32f103-nano gd32vf103_rvstar cortex-m0-emulator rv32m1_vega
support :=kd233 stm32f407-st-discovery maix-go stm32f407zgt6 aiit-riscv64-board aiit-arm32-board hifive1-rev-B hifive1-emulator k210-emulator cortex-m3-emulator cortex-m4-emulator ok1052-c gapuino stm32f103-nano gd32vf103_rvstar cortex-m0-emulator rv32m1_vega nuvoton-m2354
SRC_DIR:=
export BOARD ?=kd233

View File

@ -26,4 +26,8 @@ ifeq ($(CONFIG_BOARD_CORTEX_M0_EVB),y)
SRC_DIR += cortex-m0
endif
ifeq ($(CONFIG_BOARD_NUVOTON_M2354),y)
SRC_DIR += cortex-m23
endif
include $(KERNEL_ROOT)/compiler.mk

View File

@ -12,7 +12,7 @@
/**
* @file interrupt.c
* @brief support arm cortex-m4 interrupt function
* @brief support arm cortex-m0 interrupt function
* @version 1.0
* @author AIIT XUOS Lab
* @date 2021-04-29

View File

@ -0,0 +1,3 @@
SRC_FILES := boot.S interrupt.c interrupt_vector.S pendsv.S prepare_ahwstack.c arm32_switch.c
include $(KERNEL_ROOT)/compiler.mk

View File

@ -0,0 +1,28 @@
/*
* Copyright (c) 2020 AIIT XUOS Lab
* XiUOS is licensed under Mulan PSL v2.
* You can use this software according to the terms and conditions of the Mulan PSL v2.
* You may obtain a copy of Mulan PSL v2 at:
* http://license.coscl.org.cn/MulanPSL2
* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND,
* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT,
* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE.
* See the Mulan PSL v2 for more details.
*/
#ifndef ARCH_INTERRUPT_H__
#define ARCH_INTERRUPT_H__
#include <xs_base.h>
#define ARCH_MAX_IRQ_NUM (256)
#define ARCH_IRQ_NUM_OFFSET 14
#define SYSTICK_IRQ_NUM -1
#define UART0_IRQ_NUM 36
int32 ArchEnableHwIrq(uint32 irq_num);
int32 ArchDisableHwIrq(uint32 irq_num);
#endif

View File

@ -0,0 +1,179 @@
/*
* Copyright (c) 2020 AIIT XUOS Lab
* XiUOS is licensed under Mulan PSL v2.
* You can use this software according to the terms and conditions of the Mulan PSL v2.
* You may obtain a copy of Mulan PSL v2 at:
* http://license.coscl.org.cn/MulanPSL2
* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND,
* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT,
* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE.
* See the Mulan PSL v2 for more details.
*/
#include <xs_base.h>
#include <xs_ktask.h>
#define SCB_VTOR "0xE000ED08"
#define NVIC_INT_CTRL "0xE000ED04"
#define NVIC_SYSPRI2 "0xE000ED20"
#define NVIC_PENDSV_PRI "0xFFFF0000"
#define NVIC_PENDSVSET "0x10000000"
void __attribute__((naked)) HwInterruptcontextSwitch(x_ubase from, x_ubase to, struct TaskDescriptor *to_task, void *context)
{
asm volatile ("LDR r3, =InterruptFromKtask");
asm volatile ("STR r0, [r3]");
asm volatile ("LDR r3, =InterruptToKtask");
asm volatile ("STR r1, [r3]");
asm volatile ("LDR r3, =InterruptToKtaskDescriptor");
asm volatile ("STR r2, [r3]");
asm volatile ("LDR r2, =KtaskSwitchInterruptFlag");
asm volatile ("LDR r3, [r2]");
asm volatile ("CMP r3, #1");
asm volatile ("BEQ Arm32SwitchReswitch");
asm volatile ("MOVS r3, #1");
asm volatile ("STR r3, [r2]");
asm volatile ("B Arm32SwitchReswitch");
}
void __attribute__((naked)) Arm32SwitchReswitch()
{
asm volatile ("LDR r2, =InterruptToKtask");
asm volatile ("STR r1, [r2]");
asm volatile ("LDR r0, =" NVIC_INT_CTRL);/* trigger the PendSV exception (causes context switch) */
asm volatile ("LDR r1, =" NVIC_PENDSVSET);
asm volatile ("STR r1, [r0]");
asm volatile ("BX lr");
}
void __attribute__((naked)) SwitchKtaskContext(x_ubase from, x_ubase to, struct TaskDescriptor *to_task)
{
asm volatile("B HwInterruptcontextSwitch");
}
void SwitchKtaskContextTo(x_ubase to, struct TaskDescriptor *to_task)
{
asm volatile ("LDR r2, =InterruptToKtask");
asm volatile ("STR r0, [r2]");
asm volatile ("LDR r2, =InterruptToKtaskDescriptor");
asm volatile ("STR r1, [r2]");
asm volatile ("LDR r1, =InterruptFromKtask");
asm volatile ("MOV r0, #0x0");
asm volatile ("STR r0, [r1]");
asm volatile ("LDR r1, =KtaskSwitchInterruptFlag");
asm volatile ("MOV r0, #1");
asm volatile ("STR r0, [r1]");
asm volatile ("LDR r0, =" NVIC_SYSPRI2);
asm volatile ("LDR r1, =" NVIC_PENDSV_PRI);
asm volatile ("LDR r2, [r0,#0x00]");
asm volatile ("ORR r1,r1,r2");
asm volatile ("STR r1, [r0]");
asm volatile ("LDR r0, =" NVIC_INT_CTRL);
asm volatile ("LDR r1, =" NVIC_PENDSVSET);
asm volatile ("STR r1, [r0]");
asm volatile ("LDR r0, =" SCB_VTOR);
asm volatile ("LDR r0, [r0]");
asm volatile ("LDR r0, [r0]");
asm volatile ("NOP");
asm volatile ("MSR msp, r0");
asm volatile ("CPSIE I");
//asm volatile ("BX lr");
}
void __attribute__((naked)) Arm32SwitchGetSpDone()
{
asm volatile ("MRS r3, primask");
asm volatile ("SUB r0, r0, #0x24");
asm volatile ("STMIA r0!, {r3 - r7}");
asm volatile ("MOV r3, r8");
asm volatile ("MOV r4, r9");
asm volatile ("MOV r5, r10");
asm volatile ("MOV r6, r11");
asm volatile ("STMIA r0!, {r3 - r6}");
asm volatile ("SUB r0, r0, #0x24");
asm volatile ("SUB r0, r0, #0x4");
asm volatile ("MOV r0, lr");
asm volatile ("MOV r1, lr");
asm volatile ("MOV r2, #0x04");
asm volatile ("TST r1, r2");
asm volatile ("BEQ Arm32SwitchUpdateMsp");
asm volatile ("MSR psp, r0");
asm volatile ("B Arm32SwitchUpdateDone");
asm volatile ("B Arm32SwitchUpdateMsp");
}
void __attribute__((naked)) Arm32SwitchUpdateMsp()
{
asm volatile ("MSR msp, r0");
asm volatile ("B Arm32SwitchUpdateDone");
}
void __attribute__((naked)) Arm32SwitchUpdateDone()
{
asm volatile ("PUSH {LR}");
asm volatile ("BL HwHardFaultException");
asm volatile ("POP {R1}");
asm volatile ("MOV lr, r1");
asm volatile ("MOV r1, lr");
asm volatile ("MOV r2, #0x04");
asm volatile ("ORR r1, r2");
asm volatile ("MOV lr, r1");
asm volatile ("BX lr");
}
void __attribute__((naked)) MemFaultHandler()
{
asm volatile ("MRS r0, msp");
// asm volatile ("TST lr, #0x04");
asm volatile ("MOV r1, lr");
asm volatile ("MOV r2, #0x04");
asm volatile ("TST r1, r2");
asm volatile ("BEQ Arm32Switch1");
asm volatile ("MRS r0, psp");
asm volatile ("B Arm32Switch1");
}
void __attribute__((naked)) Arm32Switch1()
{
asm volatile ("MRS r3, primask");
asm volatile ("SUB r0, r0, #0x24");
asm volatile ("STMIA r0!, {r3 - r7}");
asm volatile ("MOV r3, r8");
asm volatile ("MOV r4, r9");
asm volatile ("MOV r5, r10");
asm volatile ("MOV r6, r11");
asm volatile ("STMIA r0!, {r3 - r6}");
asm volatile ("SUB r0, r0, #0x24");
asm volatile ("SUB r0, r0, #0x4");
asm volatile ("MOV r0, lr");
asm volatile ("PUSH {LR}");
asm volatile ("BL MemFaultHandle");
asm volatile ("POP {R5}");
asm volatile ("MOV lr, r5");
asm volatile ("MOV r5, lr");
asm volatile ("MOV r6, #0x04");
asm volatile ("ORR r5, r6");
asm volatile ("MOV lr, r5");
asm volatile ("BX lr");
}

View File

@ -0,0 +1,131 @@
/****************************************************************************//**
* @file startup_M2354.S
* @version V1.00
* @brief CMSIS Device Startup File
*
* SPDX-License-Identifier: Apache-2.0
* @copyright (C) 2018-2020 Nuvoton Technology Corp. All rights reserved.
*****************************************************************************/
/**
* @file boot.S
* @brief derived from M2354_SERIES_BSP_CMSIS_V3.00.002
* @version 1.1
* @author AIIT XUOS Lab
* @date 2022-02-23
*/
/*************************************************
File name: boot.S
Description: Reset and init function
Others:
History:
1. Date: 2022-02-23
Author: AIIT XUOS Lab
Modification:
1. take startup_M2354.S for XiUOS
*************************************************/
.syntax unified
.arch armv8 - m.base
.fpu softvfp
.thumb
/* start address for the initialization values of the .data section.
defined in linker script */
.word _sidata
/* start address for the .data section. defined in linker script */
.word _sdata
/* end address for the .data section. defined in linker script */
.word _edata
/* start address for the .bss section. defined in linker script */
.word _sbss
/* end address for the .bss section. defined in linker script */
.word _ebss
.section .text.Reset_Handler
.weak Reset_Handler
.type Reset_Handler, %function
Reset_Handler:
/* Check SecureWorld */
MOV R0, R15
LSLS R0, R0, #3
BMI.N GotoSystemInit
/* Unlock Register */
LDR R0, =0x40000100
LDR R1, =0x59
STR R1, [R0]
LDR R1, =0x16
STR R1, [R0]
LDR R1, =0x88
STR R1, [R0]
/* power gating */
/* M32(0x400001f4) = 0xfffffffful; */
LDR R0, =0x400001f4
LDR R1, =0xffffffff
STR R1, [R0]
/* M32(0x400000dC) = 0ul; */
LDR R0, =0x400000dC
LDR R1, =0x0
STR R1, [R0]
/* Enable GPIO clks, SRAM clks, Trace clk */
/* CLK->AHBCLK |= (0xffful << 20) | (1ul << 14); */
LDR R0, =0x40000200
LDR R1, [R0,#0x4]
LDR R2, =0xfff02000
ORRS R1, R1, R2
STR R1, [R0,#0x4]
GotoSystemInit:
/* Lock register */
LDR R0, =0x40000100
MOVS R1, #0
STR R1, [R0]
/* Copy the data segment initializers from flash to SRAM */
movs r1, #0
b LoopCopyDataInit
CopyDataInit:
ldr r3, =_sidata
ldr r3, [r3, r1]
str r3, [r0, r1]
adds r1, r1, #4
LoopCopyDataInit:
ldr r0, =_sdata
ldr r3, =_edata
adds r2, r0, r1
cmp r2, r3
bcc CopyDataInit
ldr r2, =_sbss
b LoopFillZerobss
/* Zero fill the bss segment. */
FillZerobss:
movs r3, #0
str r3, [r2, #4]
adds r2, r2, #4
LoopFillZerobss:
ldr r3, = _ebss
cmp r2, r3
bcc FillZerobss
/* Call the clock system intitialization function.*/
bl SystemInit
/* Call the application's entry point.*/
bl entry
bx lr
.size Reset_Handler, .-Reset_Handler

View File

@ -0,0 +1,83 @@
/*
* Copyright (c) 2020 AIIT XUOS Lab
* XiUOS is licensed under Mulan PSL v2.
* You can use this software according to the terms and conditions of the Mulan PSL v2.
* You may obtain a copy of Mulan PSL v2 at:
* http://license.coscl.org.cn/MulanPSL2
* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND,
* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT,
* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE.
* See the Mulan PSL v2 for more details.
*/
/**
* @file interrupt.c
* @brief support arm cortex-m23 interrupt function
* @version 1.1
* @author AIIT XUOS Lab
* @date 2022-02-24
*/
#include <xs_base.h>
#include <xs_isr.h>
x_base __attribute__((naked)) DisableLocalInterrupt()
{
asm volatile ("MRS r0, PRIMASK");
asm volatile ("CPSID I");
asm volatile ("BX LR ");
}
void __attribute__((naked)) EnableLocalInterrupt(x_base level)
{
asm volatile ("MSR PRIMASK, r0");
asm volatile ("BX LR");
}
int32 ArchEnableHwIrq(uint32 irq_num)
{
return EOK;
}
int32 ArchDisableHwIrq(uint32 irq_num)
{
return EOK;
}
extern void KTaskOsAssignAfterIrq(void *context);
void IsrEntry()
{
uint32 ipsr;
__asm__ volatile("MRS %0, IPSR" : "=r"(ipsr));
isrManager.done->incCounter();
isrManager.done->handleIrq(ipsr);
KTaskOsAssignAfterIrq(NONE);
isrManager.done->decCounter();
}
void UsageFault_Handler()
{
/* Go to infinite loop when Usage Fault exception occurs */
while (1)
{
}
}
void BusFault_Handler()
{
/* Go to infinite loop when Bus Fault exception occurs */
while (1)
{
}
}
void NMI_Handler()
{
while (1)
{
}
}

View File

@ -0,0 +1,197 @@
/****************************************************************************//**
* @file startup_M2354.S
* @version V1.00
* @brief CMSIS Device Startup File
*
* SPDX-License-Identifier: Apache-2.0
* @copyright (C) 2018-2020 Nuvoton Technology Corp. All rights reserved.
*****************************************************************************/
/**
* @file interrupt_vector.S
* @brief derived from M2354_SERIES_BSP_CMSIS_V3.00.002
* @version 1.1
* @author AIIT XUOS Lab
* @date 2022-02-23
*/
/*************************************************
File name: interrupt_vector.S
Description: vector table for a M2354KJFAE
Others:
History:
1. Date: 2022-02-23
Author: AIIT XUOS Lab
Modification:
1. take startup_M2354.S for XiUOS
*************************************************/
.align 2
.thumb_func
.global __PC
.type __PC, % function
__PC:
MOV r0, lr
BLX lr
.size __PC, . - __PC
.global HardFaultHandler
.type HardFaultHandler, %function
HardFaultHandler:
/* get current context */
MRS R0, PSP /* get fault thread stack pointer */
PUSH {LR}
BL HwHardFaultException
POP {PC}
/*******************************************************************************
*
* The minimal vector table for a Cortex M23. Note that the proper constructs
* must be placed on this to ensure that it ends up at physical address
* 0x0000.0000.
*******************************************************************************/
.globl InterruptVectors
.section .isr_vector,"a",%progbits
.type InterruptVectors, %object
.size InterruptVectors, . - InterruptVectors
InterruptVectors:
.long _sp /* Top of Stack */
.long Reset_Handler /* Reset Handler */
.long NMI_Handler /* NMI Handler */
.long HardFaultHandler /* Hard Fault Handler */
.long 0 /* Reserved */
.long 0 /* Reserved */
.long 0 /* Reserved */
.long 0 /* Reserved */
.long 0 /* Reserved */
.long 0 /* Reserved */
.long 0 /* Reserved */
.long IsrEntry /* SVCall Handler */
.long 0 /* Reserved */
.long 0 /* Reserved */
.long PendSV_Handler /* PendSV Handler */
.long SysTick_Handler /* SysTick Handler */
/* External interrupts */
.long IsrEntry /*BOD_IRQHandler 0 */
.long IsrEntry /*IRC_IRQHandler 1 */
.long IsrEntry /*PWRWU_IRQHandler 2 */
.long IsrEntry /*SRAM_IRQHandler 3 */
.long IsrEntry /*CLKFAIL_IRQHandler 4 */
.long IsrEntry /*Default_Handler 5 */
.long IsrEntry /*RTC_IRQHandler 6 */
.long IsrEntry /*RTC_TAMPER_IRQHandler 7 */
.long IsrEntry /*WDT_IRQHandler 8 */
.long IsrEntry /*WWDT_IRQHandler 9 */
.long IsrEntry /*EINT0_IRQHandler 10 */
.long IsrEntry /*EINT1_IRQHandler 11 */
.long IsrEntry /*EINT2_IRQHandler 12 */
.long IsrEntry /*EINT3_IRQHandler 13 */
.long IsrEntry /*EINT4_IRQHandler 14 */
.long IsrEntry /*EINT5_IRQHandler 15 */
.long IsrEntry /*GPA_IRQHandler 16 */
.long IsrEntry /*GPB_IRQHandler 17 */
.long IsrEntry /*GPC_IRQHandler 18 */
.long IsrEntry /*GPD_IRQHandler 19 */
.long IsrEntry /*GPE_IRQHandler 20 */
.long IsrEntry /*GPF_IRQHandler 21 */
.long IsrEntry /*QSPI0_IRQHandler 22 */
.long IsrEntry /*SPI0_IRQHandler 23 */
.long IsrEntry /*BRAKE0_IRQHandler 24 */
.long IsrEntry /*EPWM0_P0_IRQHandler 25 */
.long IsrEntry /*EPWM0_P1_IRQHandler 26 */
.long IsrEntry /*EPWM0_P2_IRQHandler 27 */
.long IsrEntry /*BRAKE1_IRQHandler 28 */
.long IsrEntry /*EPWM1_P0_IRQHandler 29 */
.long IsrEntry /*EPWM1_P1_IRQHandler 30 */
.long IsrEntry /*EPWM1_P2_IRQHandler 31 */
.long IsrEntry /*TMR0_IRQHandler 32 */
.long IsrEntry /*TMR1_IRQHandler 33 */
.long IsrEntry /*TMR2_IRQHandler 34 */
.long IsrEntry /*TMR3_IRQHandler 35 */
.long UART0_IRQHandler /*UART0_IRQHandler 36 */
.long IsrEntry /*UART1_IRQHandler 37 */
.long IsrEntry /*I2C0_IRQHandler 38 */
.long IsrEntry /*I2C1_IRQHandler 39 */
.long IsrEntry /*PDMA0_IRQHandler 40 */
.long IsrEntry /*DAC_IRQHandler 41 */
.long IsrEntry /*EADC0_IRQHandler 42 */
.long IsrEntry /*EADC1_IRQHandler 43 */
.long IsrEntry /*ACMP01_IRQHandler 44 */
.long IsrEntry /*Default_Handler 45 */
.long IsrEntry /*EADC2_IRQHandler 46 */
.long IsrEntry /*EADC3_IRQHandler 47 */
.long IsrEntry /*UART2_IRQHandler 48 */
.long IsrEntry /*UART3_IRQHandler 49 */
.long IsrEntry /*Default_Handler 50 */
.long IsrEntry /*SPI1_IRQHandler 51 */
.long IsrEntry /*SPI2_IRQHandler 52 */
.long IsrEntry /*USBD_IRQHandler 53 */
.long IsrEntry /*USBH_IRQHandler 54 */
.long IsrEntry /*USBOTG_IRQHandler 55 */
.long IsrEntry /*CAN0_IRQHandler 56 */
.long IsrEntry /*Default_Handler 57 */
.long IsrEntry /*SC0_IRQHandler 58 */
.long IsrEntry /*SC1_IRQHandler 59 */
.long IsrEntry /*SC2_IRQHandler 60 */
.long IsrEntry /*Default_Handler 61 */
.long IsrEntry /*SPI3_IRQHandler 62 */
.long IsrEntry /*Default_Handler 63 */
.long IsrEntry /*SDH0_IRQHandler 64 */
.long IsrEntry /*Default_Handler 65 */
.long IsrEntry /*Default_Handler 66 */
.long IsrEntry /*Default_Handler 67 */
.long IsrEntry /*I2S0_IRQHandler 68 */
.long IsrEntry /*Default_Handler 69 */
.long IsrEntry /*OPA0_IRQHandler 70 */
.long IsrEntry /*CRPT_IRQHandler 71 */
.long IsrEntry /*GPG_IRQHandler 72 */
.long IsrEntry /*EINT6_IRQHandler 73 */
.long IsrEntry /*UART4_IRQHandler 74 */
.long IsrEntry /*UART5_IRQHandler 75 */
.long IsrEntry /*USCI0_IRQHandler 76 */
.long IsrEntry /*USCI1_IRQHandler 77 */
.long IsrEntry /*BPWM0_IRQHandler 78 */
.long IsrEntry /*BPWM1_IRQHandler 79 */
.long IsrEntry /*Default_Handler 80 */
.long IsrEntry /*Default_Handler 81 */
.long IsrEntry /*I2C2_IRQHandler 82 */
.long IsrEntry /*Default_Handler 83 */
.long IsrEntry /*QEI0_IRQHandler 84 */
.long IsrEntry /*QEI1_IRQHandler 85 */
.long IsrEntry /*ECAP0_IRQHandler 86 */
.long IsrEntry /*ECAP1_IRQHandler 87 */
.long IsrEntry /*GPH_IRQHandler 88 */
.long IsrEntry /*EINT7_IRQHandler 89 */
.long IsrEntry /*Default_Handler 90 */
.long IsrEntry /*Default_Handler 91 */
.long IsrEntry /*Default_Handler 92 */
.long IsrEntry /*Default_Handler 93 */
.long IsrEntry /*Default_Handler 94 */
.long IsrEntry /*Default_Handler 95 */
.long IsrEntry /*Default_Handler 96 */
.long IsrEntry /*Default_Handler 97 */
.long IsrEntry /*PDMA1_IRQHandler 98 */
.long IsrEntry /*SCU_IRQHandler 99 */
.long IsrEntry /*LCD_IRQHandler 100 */
.long IsrEntry /*TRNG_IRQHandler 101 */
.long IsrEntry /*Default_Handler 102 */
.long IsrEntry /*Default_Handler 103 */
.long IsrEntry /*Default_Handler 104 */
.long IsrEntry /*Default_Handler 105 */
.long IsrEntry /*Default_Handler 106 */
.long IsrEntry /*Default_Handler 107 */
.long IsrEntry /*Default_Handler 108 */
.long IsrEntry /*KS_IRQHandler 109 */
.long IsrEntry /*TAMPER_IRQHandler 110 */
.long IsrEntry /*EWDT_IRQHandler 111 */
.long IsrEntry /*EWWDT_IRQHandler 112 */
.long IsrEntry /*NS_ISP_IRQHandler 113 */
.long IsrEntry /*TMR4_IRQHandler 114 */
.long IsrEntry /*TMR5_IRQHandler 115 */
.end

View File

@ -0,0 +1,105 @@
/*
* Copyright (c) 2006-2022, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2010-01-25 Bernard first version
* 2012-06-01 aozima set pendsv priority to 0xFF.
* 2012-08-17 aozima fixed bug: store r8 - r11.
* 2013-02-20 aozima port to gcc.
* 2013-06-18 aozima add restore MSP feature.
* 2013-11-04 bright fixed hardfault bug for gcc.
* 2019-03-31 xuzhuoyi port to Cortex-M23.
*/
/*************************************************
File name: pendsv.S
Description: PendSV interrupt handler
Others: take RT-Thread v4.0.2/libcpu/arm/cortex-m23/context_gcc.S for references
https://github.com/RT-Thread/rt-thread/tree/v4.0.2
History:
1. Date: 2022-02-28
Author: AIIT XUOS Lab
*************************************************/
#include <xsconfig.h>
.cpu cortex-m23
.syntax unified
.thumb
.text
.equ SCB_VTOR, 0xE000ED08
.equ NVIC_INT_CTRL, 0xE000ED04
.equ NVIC_SYSPRI2, 0xE000ED20
.equ NVIC_PENDSV_PRI, 0xFFFF0000
.equ NVIC_PENDSVSET, 0x10000000
/* R0 --> switch from thread stack
* R1 --> switch to thread stack
* psr, pc, LR, R12, R3, R2, R1, R0 are pushed into [from] stack
*/
.global PendSV_Handler
.type PendSV_Handler, %function
PendSV_Handler:
/* disable interrupt to protect context switch */
MRS R2, PRIMASK
CPSID I
LDR R0, =KtaskSwitchInterruptFlag
LDR R1, [R0]
CMP R1, #0x00
BEQ pendsv_exit /* pendsv aLReady handled */
/* clear KtaskSwitchInterruptFlag to 0 */
MOVS R1, #0
STR R1, [R0]
LDR R0, =InterruptFromKtask
LDR R1, [R0]
CMP R1, #0x00
BEQ switch_to_task /* skip register save at the first time */
MRS R1, PSP /* get from thread stack pointer */
SUBS R1, R1, #0x20 /* space for {R4 - R7} and {R8 - R11} */
LDR R0, [R0]
STR R1, [R0] /* update from thread stack pointer */
STMIA R1!, {R4 - R7} /* push thread {R4 - R7} register to thread stack */
MOV R4, R8 /* mov thread {R8 - R11} to {R4 - R7} */
MOV R5, R9
MOV R6, R10
MOV R7, R11
STMIA R1!, {R4 - R7} /* push thread {R8 - R11} high register to thread stack */
switch_to_task:
BL UpdateRunningTask
LDR R1, =InterruptToKtask
LDR R1, [R1]
LDR R1, [R1] /* load thread stack pointer */
LDMIA R1!, {R4 - R7} /* pop thread {R4 - R7} register from thread stack */
PUSH {R4 - R7} /* push {R4 - R7} to MSP for copy {R8 - R11} */
LDMIA R1!, {R4 - R7} /* pop thread {R8 - R11} high register from thread stack to {R4 - R7} */
MOV R8, R4 /* mov {R4 - R7} to {R8 - R11} */
MOV R9, R5
MOV R10, R6
MOV R11, R7
POP {R4 - R7} /* pop {R4 - R7} from MSP */
MSR PSP, R1 /* update stack pointer */
pendsv_exit:
/* restore interrupt */
MSR PRIMASK, R2
MOVS R0, #0x03
RSBS R0, R0, #0x00
BX R0

View File

@ -0,0 +1,411 @@
/*
* Copyright (c) 2020 AIIT XUOS Lab
* XiUOS is licensed under Mulan PSL v2.
* You can use this software according to the terms and conditions of the Mulan PSL v2.
* You may obtain a copy of Mulan PSL v2 at:
* http://license.coscl.org.cn/MulanPSL2
* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND,
* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT,
* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE.
* See the Mulan PSL v2 for more details.
*/
#include <xs_base.h>
#include <xs_ktask.h>
#include <xs_assign.h>
#include "svc_handle.h"
#include <board.h>
#include <shell.h>
#if (defined ( __GNUC__ ) && defined ( __VFP_FP__ ) && !defined(__SOFTFP__))
#define USE_FPU 1
#else
#define USE_FPU 0
#endif
uint32 InterruptFromKtask;
uint32 InterruptToKtask;
uint32 KtaskSwitchInterruptFlag;
uint32 InterruptToKtaskDescriptor;
#define RunningKTask Assign.os_running_task
static x_err_t (*ExceptionHook)(void *context) = NONE;
struct ExceptionStackRegister
{
uint32 r0;
uint32 r1;
uint32 r2;
uint32 r3;
uint32 r12;
uint32 lr;
uint32 pc;
uint32 psr;
};
struct StackRegisterContent
{
#if defined ( __VFP_FP__ ) && !defined(__SOFTFP__)
uint32 flag;
#endif
//uint32 primask;
uint32 r4;
uint32 r5;
uint32 r6;
uint32 r7;
uint32 r8;
uint32 r9;
uint32 r10;
uint32 r11;
// uint32 exc_ret;
struct ExceptionStackRegister ExErrorStackContex;
};
struct ExceptionStackFrameFpu
{
uint32 r0;
uint32 r1;
uint32 r2;
uint32 r3;
uint32 r12;
uint32 lr;
uint32 pc;
uint32 psr;
#if USE_FPU
uint32 S0;
uint32 S1;
uint32 S2;
uint32 S3;
uint32 S4;
uint32 S5;
uint32 S6;
uint32 S7;
uint32 S8;
uint32 S9;
uint32 S10;
uint32 S11;
uint32 S12;
uint32 S13;
uint32 S14;
uint32 S15;
uint32 FPSCR;
uint32 NO_NAME;
#endif
};
struct StackFrameFpu
{
uint32 flag;
uint32 r4;
uint32 r5;
uint32 r6;
uint32 r7;
uint32 r8;
uint32 r9;
uint32 r10;
uint32 r11;
#if USE_FPU
uint32 s16;
uint32 s17;
uint32 s18;
uint32 s19;
uint32 s20;
uint32 s21;
uint32 s22;
uint32 s23;
uint32 s24;
uint32 s25;
uint32 s26;
uint32 s27;
uint32 s28;
uint32 s29;
uint32 s30;
uint32 s31;
#endif
struct ExceptionStackFrameFpu ExErrorStackContex;
};
uint8 KTaskStackSetup(struct TaskDescriptor *task)
{
struct StackRegisterContent* StackContex;
int i = 0;
task->stack_point = (uint8 *)ALIGN_MEN_DOWN((x_ubase)(task->task_base_info.stack_start + task->task_base_info.stack_depth), 8);
task->stack_point -= sizeof(struct StackRegisterContent);
StackContex = (struct StackRegisterContent*)task->stack_point;
for (i = 0; i < sizeof(struct StackRegisterContent) / sizeof(uint32); i++)
((uint32 *)StackContex)[i] = 0xfadeface;
StackContex->ExErrorStackContex.r0 = (unsigned long)task->task_base_info.func_param;
StackContex->ExErrorStackContex.pc = (unsigned long)task->task_base_info.func_entry ;
StackContex->ExErrorStackContex.psr = 0x01000000L;
//StackContex->primask = 0x00000000L;
#ifdef SEPARATE_COMPILE
if(task->task_dync_sched_member.isolation_flag == 1 ) {
StackContex->ExErrorStackContex.lr = (unsigned long)USERSPACE->us_taskquit;
} else {
StackContex->ExErrorStackContex.lr = (unsigned long)KTaskQuit;
}
#else
StackContex->ExErrorStackContex.lr = (unsigned long)KTaskQuit;
#endif
#if USE_FPU
StackContex->flag = 0;
#endif
return EOK;
}
void HwExceptionInstall(x_err_t (*exception_handle)(void *context))
{
ExceptionHook = exception_handle;
}
#define SCB_CFSR (*(volatile const unsigned *)0xE000ED28)
#define SCB_HFSR (*(volatile const unsigned *)0xE000ED2C)
#define SCB_MMAR (*(volatile const unsigned *)0xE000ED34)
#define SCB_BFAR (*(volatile const unsigned *)0xE000ED38)
#define SCB_AIRCR (*(volatile unsigned long *)0xE000ED0C)
#define SCB_RESET_VALUE 0x05FA0004
#define SCB_CFSR_MFSR (*(volatile const unsigned char*)0xE000ED28)
#define SCB_CFSR_BFSR (*(volatile const unsigned char*)0xE000ED29)
#define SCB_CFSR_UFSR (*(volatile const unsigned short*)0xE000ED2A)
#ifdef TOOL_SHELL
static void UsageFaultTrack(void)
{
KPrintf("usage fault:\n");
KPrintf("SCB_CFSR_UFSR:0x%02X ", SCB_CFSR_UFSR);
if(SCB_CFSR_UFSR & (1<<0))
KPrintf("UNDEFINSTR ");
if(SCB_CFSR_UFSR & (1<<1))
KPrintf("INVSTATE ");
if(SCB_CFSR_UFSR & (1<<2))
KPrintf("INVPC ");
if(SCB_CFSR_UFSR & (1<<3))
KPrintf("NOCP ");
if(SCB_CFSR_UFSR & (1<<8))
KPrintf("UNALIGNED ");
if(SCB_CFSR_UFSR & (1<<9))
KPrintf("DIVBYZERO ");
KPrintf("\n");
}
static void BusFaultTrack(void)
{
KPrintf("bus fault:\n");
KPrintf("SCB_CFSR_BFSR:0x%02X ", SCB_CFSR_BFSR);
if(SCB_CFSR_BFSR & (1<<0))
KPrintf("IBUSERR ");
if(SCB_CFSR_BFSR & (1<<1))
KPrintf("PRECISERR ");
if(SCB_CFSR_BFSR & (1<<2))
KPrintf("IMPRECISERR ");
if(SCB_CFSR_BFSR & (1<<3))
KPrintf("UNSTKERR ");
if(SCB_CFSR_BFSR & (1<<4))
KPrintf("STKERR ");
if(SCB_CFSR_BFSR & (1<<7))
KPrintf("SCB->BFAR:%08X\n", SCB_BFAR);
else
KPrintf("\n");
}
static void MemManageFaultTrack(void)
{
KPrintf("mem manage fault:\n");
KPrintf("SCB_CFSR_MFSR:0x%02X ", SCB_CFSR_MFSR);
if(SCB_CFSR_MFSR & (1<<0))
KPrintf("IACCVIOL ");
if(SCB_CFSR_MFSR & (1<<1))
KPrintf("DACCVIOL ");
if(SCB_CFSR_MFSR & (1<<3))
KPrintf("MUNSTKERR ");
if(SCB_CFSR_MFSR & (1<<4))
KPrintf("MSTKERR ");
if(SCB_CFSR_MFSR & (1<<7))
KPrintf("SCB->MMAR:%08X\n", SCB_MMAR);
else
KPrintf("\n");
}
static void HardFaultTrack(void)
{
if(SCB_HFSR & (1UL<<1))
KPrintf("failed vector fetch\n");
if(SCB_HFSR & (1UL<<30)) {
if(SCB_CFSR_BFSR)
BusFaultTrack();
if(SCB_CFSR_MFSR)
MemManageFaultTrack();
if(SCB_CFSR_UFSR)
UsageFaultTrack();
}
if(SCB_HFSR & (1UL<<31))
KPrintf("debug event\n");
}
#endif
struct ExceptionInfo
{
uint32 ExcReturn;
struct StackRegisterContent stackframe;
};
void HwHardFaultException(struct ExceptionInfo *ExceptionInfo)
{
extern long ShowTask(void);
struct ExErrorStackContex* ExceptionStack = (struct ExErrorStackContex*)&ExceptionInfo->stackframe.ExErrorStackContex;
struct StackRegisterContent* context = (struct StackRegisterContent*)&ExceptionInfo->stackframe;
if (ExceptionHook != NONE) {
x_err_t result = ExceptionHook(ExceptionStack);
if (result == EOK) return;
}
KPrintf("psr: 0x%08x\n", context->ExErrorStackContex.psr);
KPrintf("r00: 0x%08x\n", context->ExErrorStackContex.r0);
KPrintf("r01: 0x%08x\n", context->ExErrorStackContex.r1);
KPrintf("r02: 0x%08x\n", context->ExErrorStackContex.r2);
KPrintf("r03: 0x%08x\n", context->ExErrorStackContex.r3);
KPrintf("r04: 0x%08x\n", context->r4);
KPrintf("r05: 0x%08x\n", context->r5);
KPrintf("r06: 0x%08x\n", context->r6);
KPrintf("r07: 0x%08x\n", context->r7);
KPrintf("r08: 0x%08x\n", context->r8);
KPrintf("r09: 0x%08x\n", context->r9);
KPrintf("r10: 0x%08x\n", context->r10);
KPrintf("r11: 0x%08x\n", context->r11);
//KPrintf("exc_ret: 0x%08x\n", context->exc_ret);
KPrintf("r12: 0x%08x\n", context->ExErrorStackContex.r12);
KPrintf(" lr: 0x%08x\n", context->ExErrorStackContex.lr);
KPrintf(" pc: 0x%08x\n", context->ExErrorStackContex.pc);
if (ExceptionInfo->ExcReturn & (1 << 2)) {
KPrintf("hard fault on task: %s\r\n\r\n", GetKTaskDescriptor()->task_base_info.name);
#ifdef TOOL_SHELL
ShowTask();
#endif
} else {
KPrintf("hard fault on handler\r\n\r\n");
}
if ( (ExceptionInfo->ExcReturn & 0x10) == 0)
KPrintf("FPU active!\r\n");
#ifdef TOOL_SHELL
HardFaultTrack();
#endif
while (1);
}
void UpdateRunningTask(void)
{
RunningKTask = (struct TaskDescriptor *)InterruptToKtaskDescriptor;
}
void MemFaultExceptionPrint(struct ExceptionInfo *ExceptionInfo)
{
extern long ShowTask(void);
struct ExErrorStackContex* ExceptionStack = (struct ExErrorStackContex*)&ExceptionInfo->stackframe.ExErrorStackContex;
struct StackRegisterContent* context = (struct StackRegisterContent*)&ExceptionInfo->stackframe;
if (ExceptionHook != NONE) {
x_err_t result = ExceptionHook(ExceptionStack);
if (result == EOK) return;
}
KPrintf("psr: 0x%08x\n", context->ExErrorStackContex.psr);
KPrintf("r00: 0x%08x\n", context->ExErrorStackContex.r0);
KPrintf("r01: 0x%08x\n", context->ExErrorStackContex.r1);
KPrintf("r02: 0x%08x\n", context->ExErrorStackContex.r2);
KPrintf("r03: 0x%08x\n", context->ExErrorStackContex.r3);
KPrintf("r04: 0x%08x\n", context->r4);
KPrintf("r05: 0x%08x\n", context->r5);
KPrintf("r06: 0x%08x\n", context->r6);
KPrintf("r07: 0x%08x\n", context->r7);
KPrintf("r08: 0x%08x\n", context->r8);
KPrintf("r09: 0x%08x\n", context->r9);
KPrintf("r10: 0x%08x\n", context->r10);
KPrintf("r11: 0x%08x\n", context->r11);
KPrintf("exc_ret: 0x%08x\n", ExceptionInfo->ExcReturn);
KPrintf("r12: 0x%08x\n", context->ExErrorStackContex.r12);
KPrintf(" lr: 0x%08x\n", context->ExErrorStackContex.lr);
KPrintf(" pc: 0x%08x\n", context->ExErrorStackContex.pc);
if (ExceptionInfo->ExcReturn & (1 << 2)) {
KPrintf("hard fault on task: %s\r\n\r\n", GetKTaskDescriptor()->task_base_info.name);
#ifdef TOOL_SHELL
ShowTask();
#endif
} else {
KPrintf("hard fault on handler\r\n\r\n");
}
if ((ExceptionInfo->ExcReturn & 0x10) == 0)
KPrintf("FPU active!\r\n");
#ifdef TOOL_SHELL
HardFaultTrack();
#endif
while (1);
}
void MemFaultHandle(uintptr_t *sp)
{
#ifdef TASK_ISOLATION
struct TaskDescriptor *task;
task = GetKTaskDescriptor();
if( task->task_dync_sched_member.isolation_flag == 1){
KPrintf("\nSegmentation fault, task: %s\n", task->task_base_info.name);
KTaskQuit();
}
else
#endif
{
MemFaultExceptionPrint((struct ExceptionInfo *)sp);
}
}
__attribute__((weak)) void HwCpuReset(void)
{
SCB_AIRCR = SCB_RESET_VALUE;
}
SHELL_EXPORT_CMD(SHELL_CMD_PERMISSION(0)|SHELL_CMD_TYPE(SHELL_TYPE_CMD_FUNC)|SHELL_CMD_PARAM_NUM(0), Reboot, HwCpuReset, reset machine );

View File

@ -0,0 +1,58 @@
/*
* Copyright (c) 2020 AIIT XUOS Lab
* XiUOS is licensed under Mulan PSL v2.
* You can use this software according to the terms and conditions of the Mulan PSL v2.
* You may obtain a copy of Mulan PSL v2 at:
* http://license.coscl.org.cn/MulanPSL2
* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND,
* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT,
* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE.
* See the Mulan PSL v2 for more details.
*/
#ifndef __INC_SVC_HANDLE_H__
#define __INC_SVC_HANDLE_H__
#if defined ( __VFP_FP__ ) && !defined(__SOFTFP__)
#define INT_FPU_REGS (1)
#else
#define INT_FPU_REGS (0)
#endif
#define HW_INT_REGS (8)
#define SW_INT_REGS (9 + INT_FPU_REGS)
#define REG_INT_R0 (SW_INT_REGS + 0) /* R0 */
#define REG_INT_R1 (SW_INT_REGS + 1) /* R1 */
#define REG_INT_R2 (SW_INT_REGS + 2) /* R2 */
#define REG_INT_R3 (SW_INT_REGS + 3) /* R3 */
#define REG_INT_R12 (SW_INT_REGS + 4) /* R12 */
#define REG_INT_R14 (SW_INT_REGS + 5) /* R14 = LR */
#define REG_INT_PC (SW_INT_REGS + 6) /* R15 = PC */
#define REG_INT_XPSR (SW_INT_REGS + 7) /* xPSR */
#if defined ( __VFP_FP__ ) && !defined(__SOFTFP__)
#define REG_INT_FPU_FLAG (0) /* fpu flag */
#define REG_INT_PRIMASK (1) /* PRIMASK */
#define REG_INT_R4 (2) /* R4 */
#define REG_INT_R5 (3) /* R5 */
#define REG_INT_R6 (4) /* R6 */
#define REG_INT_R7 (5) /* R7 */
#define REG_INT_R8 (6) /* R8 */
#define REG_INT_R9 (7) /* R9 */
#define REG_INT_R10 (8) /* R10 */
#define REG_INT_R11 (9) /* R11 */
#else
#define REG_INT_PRIMASK (0) /* PRIMASK */
#define REG_INT_R4 (1) /* R4 */
#define REG_INT_R5 (2) /* R5 */
#define REG_INT_R6 (3) /* R6 */
#define REG_INT_R7 (4) /* R7 */
#define REG_INT_R8 (5) /* R8 */
#define REG_INT_R9 (6) /* R9 */
#define REG_INT_R10 (7) /* R10 */
#define REG_INT_R11 (8) /* R11 */
#endif
#endif

View File

@ -82,6 +82,7 @@ Modification:
void SystemInit(void)
{
//cortex-m4 FPU register support
SCB->CPACR |= ((3UL << 10*2)|(3UL << 11*2));
RCC->CR |= (uint32_t)0x00000001;

View File

@ -19,7 +19,7 @@
/**
* @file boot.S
* @brief Contex-M7 start function
* @brief Cortex-M7 start function
* @version 1.0
* @author AIIT XUOS Lab
* @date 2021-05-28

View File

@ -12,7 +12,7 @@
/**
* @file interrupt.c
* @brief support arm cortex-m4 interrupt function
* @brief support arm cortex-m7 interrupt function
* @version 1.0
* @author AIIT XUOS Lab
* @date 2021-05-28

View File

@ -0,0 +1,218 @@
#
# Automatically generated file; DO NOT EDIT.
# XiUOS Project Configuration
#
CONFIG_BOARD_NUVOTON_M2354=y
CONFIG_KERNEL_CONSOLE_DEVICE_NAME="uart1"
CONFIG_ARCH_ARM=y
#
# nuvoton-m2354 feature
#
# CONFIG_BSP_USING_DMA is not set
# CONFIG_BSP_USING_GPIO is not set
# CONFIG_BSP_USING_I2C is not set
# CONFIG_BSP_USING_LCD is not set
# CONFIG_BSP_USING_EXTMEM is not set
# CONFIG_BSP_USING_SDIO is not set
# CONFIG_BSP_USING_RTC is not set
# CONFIG_BSP_USING_SPI is not set
# CONFIG_BSP_USING_HWTIMER is not set
# CONFIG_BSP_USING_WDT is not set
CONFIG_BSP_USING_UART=y
CONFIG_BSP_USING_UART1=y
# CONFIG_BSP_USING_UART2 is not set
# CONFIG_BSP_USING_UART3 is not set
# CONFIG_BSP_USING_UART4 is not set
# CONFIG_BSP_USING_UART5 is not set
# CONFIG_BSP_USING_USB is not set
# CONFIG_BSP_USING_STM32_USBH is not set
#
# Hardware feature
#
CONFIG_RESOURCES_SERIAL=y
# CONFIG_SERIAL_USING_DMA is not set
# CONFIG_SERIAL_RB_BUFSZ is not set
# CONFIG_RESOURCES_CAN is not set
# CONFIG_RESOURCES_HWTIMER is not set
# CONFIG_RESOURCES_I2C is not set
# CONFIG_RESOURCES_LCD is not set
# CONFIG_RESOURCES_SDIO is not set
# CONFIG_RESOURCES_TOUCH is not set
CONFIG_RESOURCES_PIN=y
# CONFIG_RESOURCES_RTC is not set
# CONFIG_RESOURCES_SPI is not set
# CONFIG_RESOURCES_SPI_SD is not set
# CONFIG_RESOURCES_SPI_SFUD is not set
# SFUD_USING_SFDP is not set
# SFUD_USING_FLASH_INFO_TABLE is not set
# SFUD_DEBUG_LOG is not set
# CONFIG_RESOURCES_WDT is not set
# CONFIG_RESOURCES_USB is not set
# CONFIG_RESOURCES_USB_HOST is not set
# CONFIG_UDISK_MOUNTPOINT is not set
# CONFIG_USBH_MSTORAGE is not set
# CONFIG_RESOURCES_USB_DEVICE is not set
# CONFIG_USBD_THREAD_STACK_SZ is not set
#
# Kernel feature
#
# CONFIG_SEPARATE_COMPILE is not set
# CONFIG_COMPILER_APP is not set
# CONFIG_COMPILER_KERNEL is not set
#
# Kernel Device Object
#
CONFIG_KERNEL_DEVICE=y
CONFIG_KERNEL_CONSOLE=y
CONFIG_KERNEL_CONSOLEBUF_SIZE=128
#
# Task feature
#
CONFIG_SCHED_POLICY_RR_REMAINSLICE=y
# CONFIG_SCHED_POLICY_RR is not set
# CONFIG_SCHED_POLICY_FIFO is not set
#
# Inter-Task communication
#
CONFIG_KERNEL_SEMAPHORE=y
CONFIG_KERNEL_MUTEX=y
CONFIG_KERNEL_EVENT=y
CONFIG_KERNEL_MESSAGEQUEUE=y
# CONFIG_KTASK_PRIORITY_8 is not set
CONFIG_KTASK_PRIORITY_32=y
# CONFIG_KTASK_PRIORITY_256 is not set
CONFIG_KTASK_PRIORITY_MAX=32
CONFIG_TICK_PER_SECOND=1000
CONFIG_KERNEL_STACK_OVERFLOW_CHECK=y
CONFIG_KERNEL_BANNER=y
# CONFIG_KERNEL_HOOK is not set
CONFIG_KERNEL_SOFTTIMER=y
CONFIG_KERNEL_IDLE_HOOK=y
CONFIG_IDEL_HOOK_LIST_SIZE=4
CONFIG_IDLE_KTASK_STACKSIZE=256
CONFIG_USER_APPLICATION=y
# CONFIG_TASK_ISOLATION is not set
#
# Memory Management
#
# CONFIG_KERNEL_MEMBLOCK is not set
#
# Command shell
#
CONFIG_TOOL_SHELL=y
CONFIG_SHELL_ENTER_CR=y
CONFIG_SHELL_ENTER_LF=y
CONFIG_SHELL_ENTER_CR_AND_LF=y
# CONFIG_SHELL_ENTER_CRLF is not set
#
# User Control
#
CONFIG_SHELL_DEFAULT_USER="letter"
CONFIG_SHELL_DEFAULT_USER_PASSWORD=""
CONFIG_SHELL_LOCK_TIMEOUT=10000
CONFIG_SHELL_TASK_STACK_SIZE=4096
CONFIG_SHELL_TASK_PRIORITY=20
CONFIG_SHELL_MAX_NUMBER=5
CONFIG_SHELL_PARAMETER_MAX_NUMBER=8
CONFIG_SHELL_HISTORY_MAX_NUMBER=5
CONFIG_SHELL_PRINT_BUFFER=128
CONFIG_SHELL_USING_CMD_EXPORT=y
CONFIG_SHELL_HELP_SHOW_PERMISSION=y
# CONFIG_SHELL_HELP_LIST_USER is not set
# CONFIG_SHELL_HELP_LIST_VAR is not set
# CONFIG_SHELL_HELP_LIST_KEY is not set
CONFIG_KERNEL_QUEUEMANAGE=y
CONFIG_KERNEL_WORKQUEUE=y
# CONFIG_WORKQUEUE_KTASK_STACKSIZE is not set
# CONFIG_WORKQUEUE_KTASK_PRIORITY is not set
CONFIG_KERNEL_WAITQUEUE=y
CONFIG_KERNEL_DATAQUEUE=y
# CONFIG_KERNEL_CIRCULAR_AREA is not set
# CONFIG_KERNEL_AVL_TREE is not set
CONFIG_NAME_MAX=8
CONFIG_ALIGN_SIZE=4
CONFIG_KERNEL_COMPONENTS_INIT=y
CONFIG_KERNEL_USER_MAIN=y
CONFIG_MAIN_KTASK_STACK_SIZE=2048
CONFIG_ENV_INIT_KTASK_STACK_SIZE=2048
CONFIG_MAIN_KTASK_PRIORITY=10
# CONFIG_USER_TEST is not set
# CONFIG_TOOL_TEST_SEM is not set
# CONFIG_TOOL_TEST_MUTEX is not set
# CONFIG_TOOL_TEST_EVENT is not set
# CONFIG_TOOL_TEST_MSG is not set
# CONFIG_TOOL_TEST_AVLTREE is not set
# CONFIG_TEST_CRICULAR_AREA is not set
# CONFIG_TOOL_TEST_MEM is not set
# CONFIG_TOOL_TEST_TIMER is not set
# CONFIG_TOOL_TEST_IWG is not set
# CONFIG_TOOL_TEST_REALTIME is not set
# CONFIG_TOOL_TEST_DBG is not set
# CONFIG_TOOL_TEST_SCHED is not set
# CONFIG_KERNEL_DEBUG is not set
CONFIG_DEBUG_INIT_CONFIG=y
CONFIG_DBG_INIT=1
# CONFIG_ARCH_SMP is not set
#
# File system
#
CONFIG_FS_VFS=y
CONFIG_VFS_USING_WORKDIR=y
CONFIG_FS_VFS_DEVFS=y
#
# Fat filesystem
#
#
# IOT-Device File system
#
#
# Lwext4 filesystem
#
#
# APP Framework
#
#
# connection
#
# CONFIG_CONNECTION_AT is not set
# CONFIG_CONNECTION_MQTT is not set
#
# medium communication
#
#
# Intelligence
#
#
# Control
#
#
# Lib
#
CONFIG_LIB=y
CONFIG_LIB_POSIX=y
CONFIG_LIB_NEWLIB=y
# CONFIG_LITTLEVGL2RTT_USING_DEMO is not set
#
# Security
#

View File

@ -0,0 +1,44 @@
mainmenu "XiUOS Project Configuration"
config BSP_DIR
string
option env="BSP_ROOT"
default "."
config KERNEL_DIR
string
option env="KERNEL_ROOT"
default "../.."
config BOARD_NUVOTON_M2354
bool
select ARCH_ARM
default y
source "$KERNEL_DIR/arch/Kconfig"
menu "nuvoton-m2354 feature"
source "$BSP_DIR/third_party_driver/Kconfig"
menu "config default board resources"
menu "config board app name"
config BOARD_APP_NAME
string "config board app name"
default "/XiUOS_nuvoton_m2354_app.bin"
endmenu
menu "config board service table"
config SERVICE_TABLE_ADDRESS
hex "board service table address"
default 0x20000000
endmenu
endmenu
endmenu
menu "Hardware feature"
source "$KERNEL_DIR/resources/Kconfig"
endmenu
source "$KERNEL_DIR/Kconfig"

View File

@ -0,0 +1,5 @@
SRC_FILES := board.c
SRC_DIR := third_party_driver
include $(KERNEL_ROOT)/compiler.mk

View File

@ -0,0 +1,154 @@
# 从零开始构建矽璓工业物联操作系统使用ARM架构的nuvoton-m2354
# ok1052-c
[XiUOS](http://xuos.io/) (X Industrial Ubiquitous Operating System) 矽璓XiUOS是一款面向智慧车间的工业物联网操作系统主要由一个极简的微型实时操作系统内核和其上的工业物联框架构成通过高效管理工业物联网设备、支撑工业物联应用在生产车间内实现智能化的“感知环境、联网传输、知悉识别、控制调整”促进以工业设备和工业控制系统为核心的人、机、物深度互联帮助提升生产线的数字化和智能化水平。
## 1. 简介
| 硬件 | 描述 |
| -- | -- |
|芯片型号| M2354KJFA |
|架构| cortex-m23 |
|主频| 96MHz |
|片内SRAM| 256KB |
|Flash| 1MB Dual Bank Flash |
|外设支持| UART |
XiUOS板级当前支持使用UART0。
## 2. 开发环境搭建
### 推荐使用:
**操作系统:** ubuntu18.04 [https://ubuntu.com/download/desktop](https://ubuntu.com/download/desktop)
更新`ubuntu 18.04`源的方法:(根据自身情况而定,可以不更改)
第一步:打开sources.list文件
```c
sudo vim /etc/apt/sources.list
```
第二步:将以下内容复制到sources.list文件
```c
deb http://mirrors.aliyun.com/ubuntu/ bionic main restricted universe multiverse
deb http://mirrors.aliyun.com/ubuntu/ bionic-security main restricted universe multiverse
deb http://mirrors.aliyun.com/ubuntu/ bionic-updates main restricted universe multiverse
deb http://mirrors.aliyun.com/ubuntu/ bionic-proposed main restricted universe multiverse
deb http://mirrors.aliyun.com/ubuntu/ bionic-backports main restricted universe multiverse
deb-src http://mirrors.aliyun.com/ubuntu/ bionic main restricted universe multiverse
deb-src http://mirrors.aliyun.com/ubuntu/ bionic-security main restricted universe multiverse
deb-src http://mirrors.aliyun.com/ubuntu/ bionic-updates main restricted universe multiverse
deb-src http://mirrors.aliyun.com/ubuntu/ bionic-proposed main restricted universe multiverse
deb-src http://mirrors.aliyun.com/ubuntu/ bionic-backports main restricted universe multiverse
```
第三步:更新源和系统软件
```c
sudo apt-get update
sudo apt-get upgrade
```
**开发工具推荐使用 VSCode VScode下载地址为** VSCode [https://code.visualstudio.com/](https://code.visualstudio.com/),推荐下载地址为 [http://vscode.cdn.azure.cn/stable/3c4e3df9e89829dce27b7b5c24508306b151f30d/code_1.55.2-1618307277_amd64.deb](http://vscode.cdn.azure.cn/stable/3c4e3df9e89829dce27b7b5c24508306b151f30d/code_1.55.2-1618307277_amd64.deb)
### 依赖包安装:
```
$ sudo apt install build-essential pkg-config git
$ sudo apt install gcc make libncurses5-dev openssl libssl-dev bison flex libelf-dev autoconf libtool gperf libc6-dev
```
**XiUOS操作系统源码下载** XiUOS [https://www.gitlink.org.cn/xuos/xiuos](https://www.gitlink.org.cn/xuos/xiuos)
新建一个空文件夹并进入文件夹中,并下载源码,具体命令如下:
```c
mkdir test && cd test
git clone https://gitlink.org.cn/xuos/xiuos.git
```
打开源码文件包可以看到以下目录:
| 名称 | 说明 |
| -- | -- |
| APP_Framework | 应用代码 |
| Ubiquitous | 板级支持包,支持NuttX、RT-Thread和XiZi内核 |
使用VScode打开代码具体操作步骤为在源码文件夹下打开系统终端输入`code .`即可打开VScode开发环境如下图所示
<div align= "center">
<img src = ./img/vscode.jpg width =1000>
</div>
### 裁减配置工具的下载
裁减配置工具:
**工具地址:** kconfig-frontends [https://forgeplus.trustie.net/projects/xuos/kconfig-frontends](https://forgeplus.trustie.net/projects/xuos/kconfig-frontends),下载与安装的具体命令如下:
```c
mkdir kfrontends && cd kfrontends
git clone https://gitlink.org.cn/xuos/kconfig-frontends.git
```
下载源码后按以下步骤执行软件安装:
```c
cd kconfig-frontends
./xs_build.sh
```
### 编译工具链:
ARM gcc-arm-none-eabi-6-2017-q1-update/bin/arm-none-eabi(`gcc 6.3.1 20170215 (release) [ARM/embedded-6-branch revision 245512]`)安装到Ubuntu的/opt/arm-none-eabi-,需要在新唐官网下载和安装。
**官网地址:** M2354 [https://www.nuvoton.com.cn/products/microcontrollers/arm-cortex-m23-mcus/m2354-series/?group=Software&tab=2
](https://www.nuvoton.com.cn/products/microcontrollers/arm-cortex-m23-mcus/m2354-series/?group=Software&tab=2
)
## 编译说明
### 编辑环境:`Ubuntu18.04`
### 编译工具链:`arm-none-eabi-gcc`
使用`VScode`打开工程的方法有多种,本文介绍一种快捷键,在项目目录下将`code .`输入linux系统命令终端即可打开目标项目
编译步骤:
1.在VScode命令终端中执行以下命令生成配置文件
```c
cd ./Ubiquitous/XiZi
make BOARD=nuvoton-m2354 distclean
make BOARD=nuvoton-m2354 menuconfig
```
2.在menuconfig界面配置需要关闭和开启的功能按回车键进入下级菜单按Y键选中需要开启的功能按N键选中需要关闭的功能配置结束后保存并退出本例旨在演示简单的输出例程所以没有需要配置的选项双击快捷键ESC退出配置
![menuconfig](./img/menuconfig.png)
退出时选择`yes`保存上面所配置的内容,如下图所示:
![menuconfig1](./img/menuconfig1.png)
3.继续执行以下命令,进行编译
```
make BOARD=nuvoton-m2354
```
4.如果编译正确无误会产生XiZi_nuvoton-m2354.elf、XiZi_nuvoton-m2354.bin文件。
## 3. 烧写及运行
### 3.1 烧写
1、nuvoton-m2354开发板使用片上Nu-Link2-Me v1.0烧写接口拨码开关1 on 2 on 3 on 4 on使用Micro USB与电脑连接(需提前安装Nu-Link_USB_Driver驱动)便可支持虚拟串口功能linux系统和windows系统均会提示接入新磁盘将编译生成的bin文件拷贝至虚拟磁盘中等待设备重启提示再次接入新磁盘后即可完成烧写下载功能。
### 3.2 运行结果
1、按照3.1烧写步骤执行后,若程序正常,则串口终端上会显示启动信息打印输出。如下图所示:
![terminal](./img/terminal.png)

View File

@ -0,0 +1,81 @@
/**************************************************************************//**
*
* @copyright (C) 2019 Nuvoton Technology Corp. All rights reserved.
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2020-1-16 Wayne First version
*
******************************************************************************/
/**
* @file board.c
* @brief define nuvoton-m2354 board init configure and start-up function
* @version 1.1
* @author AIIT XUOS Lab
* @date 2022-02-24
*/
/*************************************************
File name: board.c
Description: support nuvoton-m2354 board init function
Others: take rt-thread/bsp/nuvoton/libraries/m2354/rtt_port/drv_common.c for references
History:
1. Date: 2022-02-24
Author: AIIT XUOS Lab
Modification:
1. support nuvoton-m2354 clockmemory init
2. support nuvoton-m2354 uart driver init
*************************************************/
#include "board.h"
#include <NuMicro.h>
#include <nu_bitutil.h>
#include <nutool_pincfg.h>
#include <nutool_modclkcfg.h>
#include <connect_uart.h>
/* This is the timer interrupt service routine. */
void SysTick_Handler(int irqn, void *arg)
{
TickAndTaskTimesliceUpdate();
}
/**
* This function will initial nuvoton-m2354 board.
*/
void InitBoardHardware()
{
/* Init System/modules clock */
nutool_modclkcfg_init();
/* Unlock protected registers */
SYS_UnlockReg();
/* Init all pin function setting */
nutool_pincfg_init();
/* Configure SysTick */
SysTick_Config(SystemCoreClock / TICK_PER_SECOND);
/* Update System Core Clock */
/* User can use SystemCoreClockUpdate() to calculate SystemCoreClock. */
SystemCoreClockUpdate();
/* Lock protected registers */
SYS_LockReg();
/* Init Board Memory */
InitBoardMemory(HEAP_BEGIN, HEAP_END);
#ifdef BSP_USING_UART
M2354HwUartInit();
#endif
/* Install Console */
InstallConsole(KERNEL_CONSOLE_BUS_NAME, KERNEL_CONSOLE_DRV_NAME, KERNEL_CONSOLE_DEVICE_NAME);
}

View File

@ -0,0 +1,33 @@
/*
* Copyright (c) 2020 AIIT XUOS Lab
* XiUOS is licensed under Mulan PSL v2.
* You can use this software according to the terms and conditions of the Mulan PSL v2.
* You may obtain a copy of Mulan PSL v2 at:
* http://license.coscl.org.cn/MulanPSL2
* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND,
* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT,
* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE.
* See the Mulan PSL v2 for more details.
*/
/**
* @file board.h
* @brief define nuvoton-m2354 board init configure and start-up function
* @version 1.1
* @author AIIT XUOS Lab
* @date 2022-02-24
*/
#ifndef __BOARD_H__
#define __BOARD_H__
#define SRAM_SIZE (256)
#define SRAM_END (0x20000000 + SRAM_SIZE * 1024)
extern int __bss_end;
#define HEAP_BEGIN ((void *)&__bss_end)
#define HEAP_END (void *)SRAM_END
void InitBoardHardware(void);
#endif

View File

@ -0,0 +1,11 @@
export CROSS_COMPILE ?= /opt/gcc-arm-none-eabi-6-2017-q1-update/bin/arm-none-eabi-
export CFLAGS := -mcpu=cortex-m23 -mthumb -ffunction-sections -fdata-sections -Dgcc -O0 -gdwarf-2 -g -fgnu89-inline -Wa,-mimplicit-it=thumb
export AFLAGS := -c -mcpu=cortex-m23 -mthumb -ffunction-sections -fdata-sections -x assembler-with-cpp -Wa,-mimplicit-it=thumb -gdwarf-2
export LFLAGS := -mcpu=cortex-m23 -mthumb -ffunction-sections -fdata-sections -Wl,--gc-sections,-Map=XiZi_nuvoton_m2354.map,-cref,-u,Reset_Handler -T $(BSP_ROOT)/link.lds
export CXXFLAGS := -mcpu=cortex-m23 -mthumb -ffunction-sections -fdata-sections -Dgcc -O0 -gdwarf-2 -g
export DEFINES := -DHAVE_CCONFIG_H
export ARCH = arm
export MCU = cortex-m23

Binary file not shown.

After

Width:  |  Height:  |  Size: 131 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 37 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 19 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 58 KiB

View File

@ -0,0 +1,121 @@
/* ----------------------------------------------------------------------
* Project: CMSIS DSP Library
* Title: arm_common_tables.h
* Description: Extern declaration for common tables
*
* $Date: 27. January 2017
* $Revision: V.1.5.1
*
* Target Processor: Cortex-M cores
* -------------------------------------------------------------------- */
/*
* Copyright (C) 2010-2017 ARM Limited or its affiliates. All rights reserved.
*
* SPDX-License-Identifier: Apache-2.0
*
* Licensed under the Apache License, Version 2.0 (the License); you may
* not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an AS IS BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#ifndef _ARM_COMMON_TABLES_H
#define _ARM_COMMON_TABLES_H
#include "arm_math.h"
extern const uint16_t armBitRevTable[1024];
extern const q15_t armRecipTableQ15[64];
extern const q31_t armRecipTableQ31[64];
extern const float32_t twiddleCoef_16[32];
extern const float32_t twiddleCoef_32[64];
extern const float32_t twiddleCoef_64[128];
extern const float32_t twiddleCoef_128[256];
extern const float32_t twiddleCoef_256[512];
extern const float32_t twiddleCoef_512[1024];
extern const float32_t twiddleCoef_1024[2048];
extern const float32_t twiddleCoef_2048[4096];
extern const float32_t twiddleCoef_4096[8192];
#define twiddleCoef twiddleCoef_4096
extern const q31_t twiddleCoef_16_q31[24];
extern const q31_t twiddleCoef_32_q31[48];
extern const q31_t twiddleCoef_64_q31[96];
extern const q31_t twiddleCoef_128_q31[192];
extern const q31_t twiddleCoef_256_q31[384];
extern const q31_t twiddleCoef_512_q31[768];
extern const q31_t twiddleCoef_1024_q31[1536];
extern const q31_t twiddleCoef_2048_q31[3072];
extern const q31_t twiddleCoef_4096_q31[6144];
extern const q15_t twiddleCoef_16_q15[24];
extern const q15_t twiddleCoef_32_q15[48];
extern const q15_t twiddleCoef_64_q15[96];
extern const q15_t twiddleCoef_128_q15[192];
extern const q15_t twiddleCoef_256_q15[384];
extern const q15_t twiddleCoef_512_q15[768];
extern const q15_t twiddleCoef_1024_q15[1536];
extern const q15_t twiddleCoef_2048_q15[3072];
extern const q15_t twiddleCoef_4096_q15[6144];
extern const float32_t twiddleCoef_rfft_32[32];
extern const float32_t twiddleCoef_rfft_64[64];
extern const float32_t twiddleCoef_rfft_128[128];
extern const float32_t twiddleCoef_rfft_256[256];
extern const float32_t twiddleCoef_rfft_512[512];
extern const float32_t twiddleCoef_rfft_1024[1024];
extern const float32_t twiddleCoef_rfft_2048[2048];
extern const float32_t twiddleCoef_rfft_4096[4096];
/* floating-point bit reversal tables */
#define ARMBITREVINDEXTABLE_16_TABLE_LENGTH ((uint16_t)20)
#define ARMBITREVINDEXTABLE_32_TABLE_LENGTH ((uint16_t)48)
#define ARMBITREVINDEXTABLE_64_TABLE_LENGTH ((uint16_t)56)
#define ARMBITREVINDEXTABLE_128_TABLE_LENGTH ((uint16_t)208)
#define ARMBITREVINDEXTABLE_256_TABLE_LENGTH ((uint16_t)440)
#define ARMBITREVINDEXTABLE_512_TABLE_LENGTH ((uint16_t)448)
#define ARMBITREVINDEXTABLE_1024_TABLE_LENGTH ((uint16_t)1800)
#define ARMBITREVINDEXTABLE_2048_TABLE_LENGTH ((uint16_t)3808)
#define ARMBITREVINDEXTABLE_4096_TABLE_LENGTH ((uint16_t)4032)
extern const uint16_t armBitRevIndexTable16[ARMBITREVINDEXTABLE_16_TABLE_LENGTH];
extern const uint16_t armBitRevIndexTable32[ARMBITREVINDEXTABLE_32_TABLE_LENGTH];
extern const uint16_t armBitRevIndexTable64[ARMBITREVINDEXTABLE_64_TABLE_LENGTH];
extern const uint16_t armBitRevIndexTable128[ARMBITREVINDEXTABLE_128_TABLE_LENGTH];
extern const uint16_t armBitRevIndexTable256[ARMBITREVINDEXTABLE_256_TABLE_LENGTH];
extern const uint16_t armBitRevIndexTable512[ARMBITREVINDEXTABLE_512_TABLE_LENGTH];
extern const uint16_t armBitRevIndexTable1024[ARMBITREVINDEXTABLE_1024_TABLE_LENGTH];
extern const uint16_t armBitRevIndexTable2048[ARMBITREVINDEXTABLE_2048_TABLE_LENGTH];
extern const uint16_t armBitRevIndexTable4096[ARMBITREVINDEXTABLE_4096_TABLE_LENGTH];
/* fixed-point bit reversal tables */
#define ARMBITREVINDEXTABLE_FIXED_16_TABLE_LENGTH ((uint16_t)12)
#define ARMBITREVINDEXTABLE_FIXED_32_TABLE_LENGTH ((uint16_t)24)
#define ARMBITREVINDEXTABLE_FIXED_64_TABLE_LENGTH ((uint16_t)56)
#define ARMBITREVINDEXTABLE_FIXED_128_TABLE_LENGTH ((uint16_t)112)
#define ARMBITREVINDEXTABLE_FIXED_256_TABLE_LENGTH ((uint16_t)240)
#define ARMBITREVINDEXTABLE_FIXED_512_TABLE_LENGTH ((uint16_t)480)
#define ARMBITREVINDEXTABLE_FIXED_1024_TABLE_LENGTH ((uint16_t)992)
#define ARMBITREVINDEXTABLE_FIXED_2048_TABLE_LENGTH ((uint16_t)1984)
#define ARMBITREVINDEXTABLE_FIXED_4096_TABLE_LENGTH ((uint16_t)4032)
extern const uint16_t armBitRevIndexTable_fixed_16[ARMBITREVINDEXTABLE_FIXED_16_TABLE_LENGTH];
extern const uint16_t armBitRevIndexTable_fixed_32[ARMBITREVINDEXTABLE_FIXED_32_TABLE_LENGTH];
extern const uint16_t armBitRevIndexTable_fixed_64[ARMBITREVINDEXTABLE_FIXED_64_TABLE_LENGTH];
extern const uint16_t armBitRevIndexTable_fixed_128[ARMBITREVINDEXTABLE_FIXED_128_TABLE_LENGTH];
extern const uint16_t armBitRevIndexTable_fixed_256[ARMBITREVINDEXTABLE_FIXED_256_TABLE_LENGTH];
extern const uint16_t armBitRevIndexTable_fixed_512[ARMBITREVINDEXTABLE_FIXED_512_TABLE_LENGTH];
extern const uint16_t armBitRevIndexTable_fixed_1024[ARMBITREVINDEXTABLE_FIXED_1024_TABLE_LENGTH];
extern const uint16_t armBitRevIndexTable_fixed_2048[ARMBITREVINDEXTABLE_FIXED_2048_TABLE_LENGTH];
extern const uint16_t armBitRevIndexTable_fixed_4096[ARMBITREVINDEXTABLE_FIXED_4096_TABLE_LENGTH];
/* Tables for Fast Math Sine and Cosine */
extern const float32_t sinTable_f32[FAST_MATH_TABLE_SIZE + 1];
extern const q31_t sinTable_q31[FAST_MATH_TABLE_SIZE + 1];
extern const q15_t sinTable_q15[FAST_MATH_TABLE_SIZE + 1];
#endif /* ARM_COMMON_TABLES_H */

View File

@ -0,0 +1,66 @@
/* ----------------------------------------------------------------------
* Project: CMSIS DSP Library
* Title: arm_const_structs.h
* Description: Constant structs that are initialized for user convenience.
* For example, some can be given as arguments to the arm_cfft_f32() function.
*
* $Date: 27. January 2017
* $Revision: V.1.5.1
*
* Target Processor: Cortex-M cores
* -------------------------------------------------------------------- */
/*
* Copyright (C) 2010-2017 ARM Limited or its affiliates. All rights reserved.
*
* SPDX-License-Identifier: Apache-2.0
*
* Licensed under the Apache License, Version 2.0 (the License); you may
* not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an AS IS BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#ifndef _ARM_CONST_STRUCTS_H
#define _ARM_CONST_STRUCTS_H
#include "arm_math.h"
#include "arm_common_tables.h"
extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len16;
extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len32;
extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len64;
extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len128;
extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len256;
extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len512;
extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len1024;
extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len2048;
extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len4096;
extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len16;
extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len32;
extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len64;
extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len128;
extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len256;
extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len512;
extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len1024;
extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len2048;
extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len4096;
extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len16;
extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len32;
extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len64;
extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len128;
extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len256;
extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len512;
extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len1024;
extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len2048;
extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len4096;
#endif

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,368 @@
/**************************************************************************//**
* @file cmsis_compiler.h
* @brief CMSIS compiler generic header file
* @version V5.0.2
* @date 13. February 2017
******************************************************************************/
/*
* Copyright (c) 2009-2017 ARM Limited. All rights reserved.
*
* SPDX-License-Identifier: Apache-2.0
*
* Licensed under the Apache License, Version 2.0 (the License); you may
* not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an AS IS BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#ifndef __CMSIS_COMPILER_H
#define __CMSIS_COMPILER_H
#include <stdint.h>
/*
* ARM Compiler 4/5
*/
#if defined ( __CC_ARM )
#include "cmsis_armcc.h"
/*
* ARM Compiler 6 (armclang)
*/
#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
#include "cmsis_armclang.h"
/*
* GNU Compiler
*/
#elif defined ( __GNUC__ )
#include "cmsis_gcc.h"
/*
* IAR Compiler
*/
#elif defined ( __ICCARM__ )
#ifndef __ASM
#define __ASM __asm
#endif
#ifndef __INLINE
#define __INLINE inline
#endif
#ifndef __STATIC_INLINE
#define __STATIC_INLINE static inline
#endif
#include <cmsis_iar.h>
/* CMSIS compiler control architecture macros */
#if (__CORE__ == __ARM6M__) || (__CORE__ == __ARM6SM__)
#ifndef __ARM_ARCH_6M__
#define __ARM_ARCH_6M__ 1
#endif
#elif (__CORE__ == __ARM7M__)
#ifndef __ARM_ARCH_7M__
#define __ARM_ARCH_7M__ 1
#endif
#elif (__CORE__ == __ARM7EM__)
#ifndef __ARM_ARCH_7EM__
#define __ARM_ARCH_7EM__ 1
#endif
#endif
#ifndef __NO_RETURN
#define __NO_RETURN __noreturn
#endif
#ifndef __USED
#define __USED __root
#endif
#ifndef __WEAK
#define __WEAK __weak
#endif
#ifndef __PACKED
#define __PACKED __packed
#endif
#ifndef __PACKED_STRUCT
#define __PACKED_STRUCT __packed struct
#endif
#ifndef __PACKED_UNION
#define __PACKED_UNION __packed union
#endif
#ifndef __UNALIGNED_UINT32 /* deprecated */
__packed struct T_UINT32
{
uint32_t v;
};
#define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v)
#endif
#ifndef __UNALIGNED_UINT16_WRITE
__PACKED_STRUCT T_UINT16_WRITE { uint16_t v; };
#define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void *)(addr))->v) = (val))
#endif
#ifndef __UNALIGNED_UINT16_READ
__PACKED_STRUCT T_UINT16_READ { uint16_t v; };
#define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v)
#endif
#ifndef __UNALIGNED_UINT32_WRITE
__PACKED_STRUCT T_UINT32_WRITE { uint32_t v; };
#define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val))
#endif
#ifndef __UNALIGNED_UINT32_READ
__PACKED_STRUCT T_UINT32_READ { uint32_t v; };
#define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v)
#endif
#ifndef __ALIGNED
//#warning No compiler specific solution for __ALIGNED. __ALIGNED is ignored.
#define __ALIGNED(x)
#endif
#ifndef __RESTRICT
//#warning No compiler specific solution for __RESTRICT. __RESTRICT is ignored.
#define __RESTRICT
#endif
// Workaround for missing __CLZ intrinsic in
// various versions of the IAR compilers.
// __IAR_FEATURE_CLZ__ should be defined by
// the compiler that supports __CLZ internally.
#if (defined (__ARM_ARCH_6M__)) && (__ARM_ARCH_6M__ == 1) && (!defined (__IAR_FEATURE_CLZ__))
__STATIC_INLINE uint32_t __CLZ(uint32_t data)
{
if (data == 0u)
{
return 32u;
}
uint32_t count = 0;
uint32_t mask = 0x80000000;
while ((data & mask) == 0)
{
count += 1u;
mask = mask >> 1u;
}
return (count);
}
#endif
/*
* TI ARM Compiler
*/
#elif defined ( __TI_ARM__ )
#include <cmsis_ccs.h>
#ifndef __ASM
#define __ASM __asm
#endif
#ifndef __INLINE
#define __INLINE inline
#endif
#ifndef __STATIC_INLINE
#define __STATIC_INLINE static inline
#endif
#ifndef __NO_RETURN
#define __NO_RETURN __attribute__((noreturn))
#endif
#ifndef __USED
#define __USED __attribute__((used))
#endif
#ifndef __WEAK
#define __WEAK __attribute__((weak))
#endif
#ifndef __PACKED
#define __PACKED __attribute__((packed))
#endif
#ifndef __PACKED_STRUCT
#define __PACKED_STRUCT struct __attribute__((packed))
#endif
#ifndef __PACKED_UNION
#define __PACKED_UNION union __attribute__((packed))
#endif
#ifndef __UNALIGNED_UINT32 /* deprecated */
struct __attribute__((packed)) T_UINT32
{
uint32_t v;
};
#define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v)
#endif
#ifndef __UNALIGNED_UINT16_WRITE
__PACKED_STRUCT T_UINT16_WRITE { uint16_t v; };
#define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void*)(addr))->v) = (val))
#endif
#ifndef __UNALIGNED_UINT16_READ
__PACKED_STRUCT T_UINT16_READ { uint16_t v; };
#define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v)
#endif
#ifndef __UNALIGNED_UINT32_WRITE
__PACKED_STRUCT T_UINT32_WRITE { uint32_t v; };
#define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val))
#endif
#ifndef __UNALIGNED_UINT32_READ
__PACKED_STRUCT T_UINT32_READ { uint32_t v; };
#define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v)
#endif
#ifndef __ALIGNED
#define __ALIGNED(x) __attribute__((aligned(x)))
#endif
#ifndef __RESTRICT
#warning No compiler specific solution for __RESTRICT. __RESTRICT is ignored.
#define __RESTRICT
#endif
/*
* TASKING Compiler
*/
#elif defined ( __TASKING__ )
/*
* The CMSIS functions have been implemented as intrinsics in the compiler.
* Please use "carm -?i" to get an up to date list of all intrinsics,
* Including the CMSIS ones.
*/
#ifndef __ASM
#define __ASM __asm
#endif
#ifndef __INLINE
#define __INLINE inline
#endif
#ifndef __STATIC_INLINE
#define __STATIC_INLINE static inline
#endif
#ifndef __NO_RETURN
#define __NO_RETURN __attribute__((noreturn))
#endif
#ifndef __USED
#define __USED __attribute__((used))
#endif
#ifndef __WEAK
#define __WEAK __attribute__((weak))
#endif
#ifndef __PACKED
#define __PACKED __packed__
#endif
#ifndef __PACKED_STRUCT
#define __PACKED_STRUCT struct __packed__
#endif
#ifndef __PACKED_UNION
#define __PACKED_UNION union __packed__
#endif
#ifndef __UNALIGNED_UINT32 /* deprecated */
struct __packed__ T_UINT32
{
uint32_t v;
};
#define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v)
#endif
#ifndef __UNALIGNED_UINT16_WRITE
__PACKED_STRUCT T_UINT16_WRITE { uint16_t v; };
#define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void *)(addr))->v) = (val))
#endif
#ifndef __UNALIGNED_UINT16_READ
__PACKED_STRUCT T_UINT16_READ { uint16_t v; };
#define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v)
#endif
#ifndef __UNALIGNED_UINT32_WRITE
__PACKED_STRUCT T_UINT32_WRITE { uint32_t v; };
#define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val))
#endif
#ifndef __UNALIGNED_UINT32_READ
__PACKED_STRUCT T_UINT32_READ { uint32_t v; };
#define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v)
#endif
#ifndef __ALIGNED
#define __ALIGNED(x) __align(x)
#endif
#ifndef __RESTRICT
#warning No compiler specific solution for __RESTRICT. __RESTRICT is ignored.
#define __RESTRICT
#endif
/*
* COSMIC Compiler
*/
#elif defined ( __CSMC__ )
#include <cmsis_csm.h>
#ifndef __ASM
#define __ASM _asm
#endif
#ifndef __INLINE
#define __INLINE inline
#endif
#ifndef __STATIC_INLINE
#define __STATIC_INLINE static inline
#endif
#ifndef __NO_RETURN
// NO RETURN is automatically detected hence no warning here
#define __NO_RETURN
#endif
#ifndef __USED
#warning No compiler specific solution for __USED. __USED is ignored.
#define __USED
#endif
#ifndef __WEAK
#define __WEAK __weak
#endif
#ifndef __PACKED
#define __PACKED @packed
#endif
#ifndef __PACKED_STRUCT
#define __PACKED_STRUCT @packed struct
#endif
#ifndef __PACKED_UNION
#define __PACKED_UNION @packed union
#endif
#ifndef __UNALIGNED_UINT32 /* deprecated */
@packed struct T_UINT32
{
uint32_t v;
};
#define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v)
#endif
#ifndef __UNALIGNED_UINT16_WRITE
__PACKED_STRUCT T_UINT16_WRITE { uint16_t v; };
#define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void *)(addr))->v) = (val))
#endif
#ifndef __UNALIGNED_UINT16_READ
__PACKED_STRUCT T_UINT16_READ { uint16_t v; };
#define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v)
#endif
#ifndef __UNALIGNED_UINT32_WRITE
__PACKED_STRUCT T_UINT32_WRITE { uint32_t v; };
#define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val))
#endif
#ifndef __UNALIGNED_UINT32_READ
__PACKED_STRUCT T_UINT32_READ { uint32_t v; };
#define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v)
#endif
#ifndef __ALIGNED
#warning No compiler specific solution for __ALIGNED. __ALIGNED is ignored.
#define __ALIGNED(x)
#endif
#ifndef __RESTRICT
#warning No compiler specific solution for __RESTRICT. __RESTRICT is ignored.
#define __RESTRICT
#endif
#else
#error Unknown compiler.
#endif
#endif /* __CMSIS_COMPILER_H */

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,39 @@
/**************************************************************************//**
* @file cmsis_version.h
* @brief CMSIS Core(M) Version definitions
* @version V5.0.2
* @date 19. April 2017
******************************************************************************/
/*
* Copyright (c) 2009-2017 ARM Limited. All rights reserved.
*
* SPDX-License-Identifier: Apache-2.0
*
* Licensed under the Apache License, Version 2.0 (the License); you may
* not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an AS IS BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#if defined ( __ICCARM__ )
#pragma system_include /* treat file as system include file for MISRA check */
#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
#pragma clang system_header /* treat file as system include file */
#endif
#ifndef __CMSIS_VERSION_H
#define __CMSIS_VERSION_H
/* CMSIS Version definitions */
#define __CM_CMSIS_VERSION_MAIN ( 5U) /*!< [31:16] CMSIS Core(M) main version */
#define __CM_CMSIS_VERSION_SUB ( 0U) /*!< [15:0] CMSIS Core(M) sub version */
#define __CM_CMSIS_VERSION ((__CM_CMSIS_VERSION_MAIN << 16U) | \
__CM_CMSIS_VERSION_SUB ) /*!< CMSIS Core(M) version number */
#endif

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,105 @@
/*
* @copyright (C) 2020 Nuvoton Technology Corp. All rights reserved.
*
* SPDX-License-Identifier: Apache-2.0
*
*/
/* Linker script to configure memory regions. */
MEMORY
{
flash (rx) : ORIGIN = 0x00000000, LENGTH = 1024K /* 1024K flash */
sram (rw) : ORIGIN = 0x20000000, LENGTH = 256K /* 256K sram */
}
ENTRY(Reset_Handler)
_system_stack_size = 0x2000;
SECTIONS
{
.text :
{
. = ALIGN(4);
KEEP(*(.isr_vector)) /* Startup code */
. = ALIGN(4);
*(.text) /* remaining code */
*(.text.*) /* remaining code */
*(.rodata) /* read-only data (constants) */
*(.rodata*)
/* section information for shell */
. = ALIGN(4);
_shell_command_start = .;
KEEP (*(shellCommand))
_shell_command_end = .;
. = ALIGN(4);
__isrtbl_idx_start = .;
KEEP(*(.isrtbl.idx))
__isrtbl_start = .;
KEEP(*(.isrtbl))
__isrtbl_end = .;
. = ALIGN(4);
PROVIDE(g_service_table_start = ABSOLUTE(.));
KEEP(*(.g_service_table))
PROVIDE(g_service_table_end = ABSOLUTE(.));
PROVIDE(_etext = ABSOLUTE(.));
. = ALIGN(4);
_etext = .;
} > flash = 0
/* .ARM.exidx is sorted, so has to go in its own output section. */
__exidx_start = .;
.ARM.exidx :
{
*(.ARM.exidx* .gnu.linkonce.armexidx.*)
/* This is used by the startup in order to initialize the .data section */
_sidata = .;
} > flash
__exidx_end = .;
.stack :
{
. = . + _system_stack_size;
. = ALIGN(4);
_sp = .;
} > sram
/* .data section which is used for initialized data */
.data : AT (_sidata)
{
. = ALIGN(4);
/* This is used by the startup in order to initialize the .data section */
_sdata = . ;
*(.data)
*(.data.*)
. = ALIGN(4);
/* This is used by the startup in order to initialize the .data section */
_edata = . ;
} > sram
__bss_start = .;
.bss :
{
. = ALIGN(4);
/* This is used by the startup in order to initialize the .bss section */
_sbss = .;
*(.bss)
*(.bss.*)
*(COMMON)
. = ALIGN(4);
/* This is used by the startup in order to initialize the .bss section */
_ebss = . ;
} > sram
__bss_end = .;
_end = .;
}

View File

@ -0,0 +1,7 @@
menuconfig BSP_USING_UART
bool "Using UART device"
default y
select RESOURCES_SERIAL
if BSP_USING_UART
source "$BSP_DIR/third_party_driver/uart/Kconfig"
endif

View File

@ -0,0 +1,7 @@
SRC_DIR := common
ifeq ($(CONFIG_BSP_USING_UART),y)
SRC_DIR += uart
endif
include $(KERNEL_ROOT)/compiler.mk

View File

@ -0,0 +1,5 @@
SRC_DIR := NuClockConfig NuPinConfig
SRC_FILES := nu_clk.c nu_gpio.c nu_sys.c nu_uart.c system_M2354.c
include $(KERNEL_ROOT)/compiler.mk

View File

@ -0,0 +1,3 @@
SRC_FILES := nutool_modclkcfg.c
include $(KERNEL_ROOT)/compiler.mk

View File

@ -0,0 +1,27 @@
/****************************************************************************
* @file nutool_clkcfg.h
* @version V1.05
* @Date 2020/11/11-11:43:32
* @brief NuMicro generated code file
*
* SPDX-License-Identifier: Apache-2.0
*
* Copyright (C) 2013-2020 Nuvoton Technology Corp. All rights reserved.
*****************************************************************************/
#ifndef __NUTOOL_CLKCFG_H__
#define __NUTOOL_CLKCFG_H__
#ifdef __cplusplus
extern "C"
{
#endif
#undef __HXT
#define __HXT (12000000UL) /*!< High Speed External Crystal Clock Frequency */
#ifdef __cplusplus
}
#endif
#endif /*__NUTOOL_CLKCFG_H__*/
/*** (C) COPYRIGHT 2013-2020 Nuvoton Technology Corp. ***/

View File

@ -0,0 +1,35 @@
/****************************************************************************
* @file nutool_modclkcfg.cfg
* @version V1.05
* @Date 2020/11/11-11:43:32
* @brief NuMicro clock config file
*
* @note Please do not modify this file.
* Otherwise, it may not be loaded successfully.
*
* SPDX-License-Identifier: Apache-2.0
*
* Copyright (C) 2013-2020 Nuvoton Technology Corp. All rights reserved.
*****************************************************************************/
MCU:M2354KJFAE(LQFP128)
Reg:CLKDIV0 = 0x00000010
Reg:CLKDIV1 = 0x00000000
Reg:CLKDIV4 = 0x00000000
Reg:PCLKDIV = 0x00000000
Reg:CLKSEL0 = 0x0020011A
Reg:CLKSEL1 = 0xB000009D
Reg:CLKSEL2 = 0x00002BAB
Reg:CLKSEL3 = 0x00020000
Reg:PWRCTL = 0x00240007
Reg:AHBCLK = 0xFFFFFFFF
Reg:APBCLK0 = 0xFFFFFFFF
Reg:APBCLK1 = 0xFFFFFFFF
Reg:PLLCTL = 0x00000206
Reg:CLKOCTL = 0x00000000
Reg:SYST_CTRL = 0x00000005
Reg:RTC_LXTCTL = 0x0000000E
LXT:32768
HXT:12000000
PLL:96000000
Step:4
/*** (C) COPYRIGHT 2013-2020 Nuvoton Technology Corp. ***/

View File

@ -0,0 +1,172 @@
/****************************************************************************
* @file nutool_modclkcfg.h
* @version V1.05
* @Date 2020/11/11-11:43:32
* @brief NuMicro generated code file
*
* SPDX-License-Identifier: Apache-2.0
*
* Copyright (C) 2013-2020 Nuvoton Technology Corp. All rights reserved.
*****************************************************************************/
#ifndef __NUTOOL_MODCLKCFG_H__
#define __NUTOOL_MODCLKCFG_H__
#ifdef __cplusplus
extern "C"
{
#endif
void nutool_modclkcfg_init_acmp01(void);
void nutool_modclkcfg_deinit_acmp01(void);
void nutool_modclkcfg_init_bpwm0(void);
void nutool_modclkcfg_deinit_bpwm0(void);
void nutool_modclkcfg_init_bpwm1(void);
void nutool_modclkcfg_deinit_bpwm1(void);
void nutool_modclkcfg_init_can0(void);
void nutool_modclkcfg_deinit_can0(void);
void nutool_modclkcfg_init_crc(void);
void nutool_modclkcfg_deinit_crc(void);
void nutool_modclkcfg_init_crpt(void);
void nutool_modclkcfg_deinit_crpt(void);
void nutool_modclkcfg_init_dac(void);
void nutool_modclkcfg_deinit_dac(void);
void nutool_modclkcfg_init_eadc(void);
void nutool_modclkcfg_deinit_eadc(void);
void nutool_modclkcfg_init_ebi(void);
void nutool_modclkcfg_deinit_ebi(void);
void nutool_modclkcfg_init_ecap0(void);
void nutool_modclkcfg_deinit_ecap0(void);
void nutool_modclkcfg_init_ecap1(void);
void nutool_modclkcfg_deinit_ecap1(void);
void nutool_modclkcfg_init_epwm0(void);
void nutool_modclkcfg_deinit_epwm0(void);
void nutool_modclkcfg_init_epwm1(void);
void nutool_modclkcfg_deinit_epwm1(void);
void nutool_modclkcfg_init_ewdt(void);
void nutool_modclkcfg_deinit_ewdt(void);
void nutool_modclkcfg_init_ewwdt(void);
void nutool_modclkcfg_deinit_ewwdt(void);
void nutool_modclkcfg_init_exst(void);
void nutool_modclkcfg_deinit_exst(void);
void nutool_modclkcfg_init_fmcidle(void);
void nutool_modclkcfg_deinit_fmcidle(void);
void nutool_modclkcfg_init_gpa(void);
void nutool_modclkcfg_deinit_gpa(void);
void nutool_modclkcfg_init_gpb(void);
void nutool_modclkcfg_deinit_gpb(void);
void nutool_modclkcfg_init_gpc(void);
void nutool_modclkcfg_deinit_gpc(void);
void nutool_modclkcfg_init_gpd(void);
void nutool_modclkcfg_deinit_gpd(void);
void nutool_modclkcfg_init_gpe(void);
void nutool_modclkcfg_deinit_gpe(void);
void nutool_modclkcfg_init_gpf(void);
void nutool_modclkcfg_deinit_gpf(void);
void nutool_modclkcfg_init_gpg(void);
void nutool_modclkcfg_deinit_gpg(void);
void nutool_modclkcfg_init_gph(void);
void nutool_modclkcfg_deinit_gph(void);
void nutool_modclkcfg_init_i2c0(void);
void nutool_modclkcfg_deinit_i2c0(void);
void nutool_modclkcfg_init_i2c1(void);
void nutool_modclkcfg_deinit_i2c1(void);
void nutool_modclkcfg_init_i2c2(void);
void nutool_modclkcfg_deinit_i2c2(void);
void nutool_modclkcfg_init_i2s0(void);
void nutool_modclkcfg_deinit_i2s0(void);
void nutool_modclkcfg_init_isp(void);
void nutool_modclkcfg_deinit_isp(void);
void nutool_modclkcfg_init_ks(void);
void nutool_modclkcfg_deinit_ks(void);
void nutool_modclkcfg_init_lcd(void);
void nutool_modclkcfg_deinit_lcd(void);
void nutool_modclkcfg_init_lcdcp(void);
void nutool_modclkcfg_deinit_lcdcp(void);
void nutool_modclkcfg_init_otg(void);
void nutool_modclkcfg_deinit_otg(void);
void nutool_modclkcfg_init_pdma0(void);
void nutool_modclkcfg_deinit_pdma0(void);
void nutool_modclkcfg_init_pdma1(void);
void nutool_modclkcfg_deinit_pdma1(void);
void nutool_modclkcfg_init_qei0(void);
void nutool_modclkcfg_deinit_qei0(void);
void nutool_modclkcfg_init_qei1(void);
void nutool_modclkcfg_deinit_qei1(void);
void nutool_modclkcfg_init_qspi0(void);
void nutool_modclkcfg_deinit_qspi0(void);
void nutool_modclkcfg_init_rtc(void);
void nutool_modclkcfg_deinit_rtc(void);
void nutool_modclkcfg_init_sc0(void);
void nutool_modclkcfg_deinit_sc0(void);
void nutool_modclkcfg_init_sc1(void);
void nutool_modclkcfg_deinit_sc1(void);
void nutool_modclkcfg_init_sc2(void);
void nutool_modclkcfg_deinit_sc2(void);
void nutool_modclkcfg_init_sdh0(void);
void nutool_modclkcfg_deinit_sdh0(void);
void nutool_modclkcfg_init_spi0(void);
void nutool_modclkcfg_deinit_spi0(void);
void nutool_modclkcfg_init_spi1(void);
void nutool_modclkcfg_deinit_spi1(void);
void nutool_modclkcfg_init_spi2(void);
void nutool_modclkcfg_deinit_spi2(void);
void nutool_modclkcfg_init_spi3(void);
void nutool_modclkcfg_deinit_spi3(void);
void nutool_modclkcfg_init_sram0(void);
void nutool_modclkcfg_deinit_sram0(void);
void nutool_modclkcfg_init_sram1(void);
void nutool_modclkcfg_deinit_sram1(void);
void nutool_modclkcfg_init_sram2(void);
void nutool_modclkcfg_deinit_sram2(void);
void nutool_modclkcfg_init_systick(void);
void nutool_modclkcfg_deinit_systick(void);
void nutool_modclkcfg_init_tamper(void);
void nutool_modclkcfg_deinit_tamper(void);
void nutool_modclkcfg_init_tmr0(void);
void nutool_modclkcfg_deinit_tmr0(void);
void nutool_modclkcfg_init_tmr1(void);
void nutool_modclkcfg_deinit_tmr1(void);
void nutool_modclkcfg_init_tmr2(void);
void nutool_modclkcfg_deinit_tmr2(void);
void nutool_modclkcfg_init_tmr3(void);
void nutool_modclkcfg_deinit_tmr3(void);
void nutool_modclkcfg_init_tmr4(void);
void nutool_modclkcfg_deinit_tmr4(void);
void nutool_modclkcfg_init_tmr5(void);
void nutool_modclkcfg_deinit_tmr5(void);
void nutool_modclkcfg_init_trace(void);
void nutool_modclkcfg_deinit_trace(void);
void nutool_modclkcfg_init_trng(void);
void nutool_modclkcfg_deinit_trng(void);
void nutool_modclkcfg_init_uart0(void);
void nutool_modclkcfg_deinit_uart0(void);
void nutool_modclkcfg_init_uart1(void);
void nutool_modclkcfg_deinit_uart1(void);
void nutool_modclkcfg_init_uart2(void);
void nutool_modclkcfg_deinit_uart2(void);
void nutool_modclkcfg_init_uart3(void);
void nutool_modclkcfg_deinit_uart3(void);
void nutool_modclkcfg_init_uart4(void);
void nutool_modclkcfg_deinit_uart4(void);
void nutool_modclkcfg_init_uart5(void);
void nutool_modclkcfg_deinit_uart5(void);
void nutool_modclkcfg_init_usbd(void);
void nutool_modclkcfg_deinit_usbd(void);
void nutool_modclkcfg_init_usbh(void);
void nutool_modclkcfg_deinit_usbh(void);
void nutool_modclkcfg_init_usci0(void);
void nutool_modclkcfg_deinit_usci0(void);
void nutool_modclkcfg_init_usci1(void);
void nutool_modclkcfg_deinit_usci1(void);
void nutool_modclkcfg_init_wdt(void);
void nutool_modclkcfg_deinit_wdt(void);
void nutool_modclkcfg_init_wwdt(void);
void nutool_modclkcfg_deinit_wwdt(void);
void nutool_modclkcfg_init_base(void);
void nutool_modclkcfg_init(void);
#ifdef __cplusplus
}
#endif
#endif /*__NUTOOL_MODCLKCFG_H__*/
/*** (C) COPYRIGHT 2013-2020 Nuvoton Technology Corp. ***/

View File

@ -0,0 +1,3 @@
SRC_FILES := nutool_pincfg.c
include $(KERNEL_ROOT)/compiler.mk

View File

@ -0,0 +1,434 @@
/****************************************************************************
* @file nutool_pincfg.c
* @version V1.21
* @Date 2020/11/11-12:06:36
* @brief NuMicro generated code file
*
* Copyright (C) 2013-2020 Nuvoton Technology Corp. All rights reserved.
*****************************************************************************/
/********************
MCU:M2354KJFAE(LQFP128)
Pin Configuration:
Pin1:SD0_DAT3
Pin2:SD0_DAT2
Pin3:SD0_DAT1
Pin4:SD0_DAT0
Pin5:EPWM1_CH0
Pin6:EPWM1_CH1
Pin7:EPWM1_CH2
Pin8:EPWM1_CH3
Pin9:SD0_CLK
Pin10:SD0_CMD
Pin15:UART1_TXD
Pin16:UART1_RXD
Pin21:I2C1_SCL
Pin22:I2C1_SDA
Pin25:I2S0_BCLK
Pin26:I2S0_MCLK
Pin27:I2S0_DI
Pin28:I2S0_DO
Pin29:I2S0_LRCK
Pin48:UART4_TXD
Pin49:UART4_RXD
Pin50:UART0_TXD
Pin51:UART0_RXD
Pin57:SPI0_SS
Pin58:SPI0_CLK
Pin59:SPI0_MISO
Pin60:SPI0_MOSI
Pin65:ICE_DAT
Pin66:ICE_CLK
Pin73:EPWM1_CH4
Pin74:EPWM1_CH5
Pin93:USB_VBUS
Pin94:USB_D-
Pin95:USB_D+
Pin96:USB_OTG_ID
Pin97:EPWM0_CH0
Pin98:EPWM0_CH1
Pin105:SPI1_MISO
Pin106:SPI1_MOSI
Pin107:SPI1_CLK
Pin108:SPI1_SS
Pin109:PH.10
Pin116:USB_VBUS_EN
Pin117:USB_VBUS_ST
Pin119:SD0_nCD
Pin123:EADC0_CH11
Pin124:EADC0_CH10
Pin125:EADC0_CH9
Pin126:EADC0_CH8
Pin127:EADC0_CH7
Pin128:EADC0_CH6
********************/
#include "M2354.h"
void nutool_pincfg_init_eadc0(void)
{
SYS->GPB_MFPH &= ~(SYS_GPB_MFPH_PB11MFP_Msk | SYS_GPB_MFPH_PB10MFP_Msk | SYS_GPB_MFPH_PB9MFP_Msk | SYS_GPB_MFPH_PB8MFP_Msk);
SYS->GPB_MFPH |= (SYS_GPB_MFPH_PB11MFP_EADC0_CH11 | SYS_GPB_MFPH_PB10MFP_EADC0_CH10 | SYS_GPB_MFPH_PB9MFP_EADC0_CH9 | SYS_GPB_MFPH_PB8MFP_EADC0_CH8);
SYS->GPB_MFPL &= ~(SYS_GPB_MFPL_PB7MFP_Msk | SYS_GPB_MFPL_PB6MFP_Msk);
SYS->GPB_MFPL |= (SYS_GPB_MFPL_PB7MFP_EADC0_CH7 | SYS_GPB_MFPL_PB6MFP_EADC0_CH6);
/* Disable digital path on these EADC pins */
GPIO_DISABLE_DIGITAL_PATH(PB, BIT6 | BIT7 | BIT8 | BIT9 | BIT10 | BIT11);
return;
}
void nutool_pincfg_deinit_eadc0(void)
{
SYS->GPB_MFPH &= ~(SYS_GPB_MFPH_PB11MFP_Msk | SYS_GPB_MFPH_PB10MFP_Msk | SYS_GPB_MFPH_PB9MFP_Msk | SYS_GPB_MFPH_PB8MFP_Msk);
SYS->GPB_MFPL &= ~(SYS_GPB_MFPL_PB7MFP_Msk | SYS_GPB_MFPL_PB6MFP_Msk);
/* Enable digital path on these EADC pins */
GPIO_ENABLE_DIGITAL_PATH(PB, BIT6 | BIT7 | BIT8 | BIT9 | BIT10 | BIT11);
return;
}
void nutool_pincfg_init_epwm0(void)
{
SYS->GPE_MFPL &= ~(SYS_GPE_MFPL_PE7MFP_Msk | SYS_GPE_MFPL_PE6MFP_Msk);
SYS->GPE_MFPL |= (SYS_GPE_MFPL_PE7MFP_EPWM0_CH0 | SYS_GPE_MFPL_PE6MFP_EPWM0_CH1);
return;
}
void nutool_pincfg_deinit_epwm0(void)
{
SYS->GPE_MFPL &= ~(SYS_GPE_MFPL_PE7MFP_Msk | SYS_GPE_MFPL_PE6MFP_Msk);
return;
}
void nutool_pincfg_init_epwm1(void)
{
SYS->GPC_MFPH &= ~(SYS_GPC_MFPH_PC12MFP_Msk | SYS_GPC_MFPH_PC11MFP_Msk | SYS_GPC_MFPH_PC10MFP_Msk | SYS_GPC_MFPH_PC9MFP_Msk);
#if !defined(BOARD_USING_LCD_ILI9341)
SYS->GPC_MFPH |= (SYS_GPC_MFPH_PC12MFP_EPWM1_CH0 | SYS_GPC_MFPH_PC11MFP_EPWM1_CH1 | SYS_GPC_MFPH_PC10MFP_EPWM1_CH2 | SYS_GPC_MFPH_PC9MFP_EPWM1_CH3);
#else
SYS->GPC_MFPH |= (SYS_GPC_MFPH_PC12MFP_EPWM1_CH0 | SYS_GPC_MFPH_PC10MFP_EPWM1_CH2 | SYS_GPC_MFPH_PC9MFP_EPWM1_CH3);
#endif
SYS->GPC_MFPL &= ~(SYS_GPC_MFPL_PC1MFP_Msk | SYS_GPC_MFPL_PC0MFP_Msk);
SYS->GPC_MFPL |= (SYS_GPC_MFPL_PC1MFP_EPWM1_CH4 | SYS_GPC_MFPL_PC0MFP_EPWM1_CH5);
return;
}
void nutool_pincfg_deinit_epwm1(void)
{
SYS->GPC_MFPH &= ~(SYS_GPC_MFPH_PC12MFP_Msk | SYS_GPC_MFPH_PC11MFP_Msk | SYS_GPC_MFPH_PC10MFP_Msk | SYS_GPC_MFPH_PC9MFP_Msk);
SYS->GPC_MFPL &= ~(SYS_GPC_MFPL_PC1MFP_Msk | SYS_GPC_MFPL_PC0MFP_Msk);
return;
}
void nutool_pincfg_init_i2c1(void)
{
SYS->GPG_MFPL &= ~(SYS_GPG_MFPL_PG3MFP_Msk | SYS_GPG_MFPL_PG2MFP_Msk);
SYS->GPG_MFPL |= (SYS_GPG_MFPL_PG3MFP_I2C1_SDA | SYS_GPG_MFPL_PG2MFP_I2C1_SCL);
return;
}
void nutool_pincfg_deinit_i2c1(void)
{
SYS->GPG_MFPL &= ~(SYS_GPG_MFPL_PG3MFP_Msk | SYS_GPG_MFPL_PG2MFP_Msk);
return;
}
void nutool_pincfg_init_i2s0(void)
{
SYS->GPF_MFPH &= ~(SYS_GPF_MFPH_PF10MFP_Msk | SYS_GPF_MFPH_PF9MFP_Msk | SYS_GPF_MFPH_PF8MFP_Msk);
SYS->GPF_MFPH |= (SYS_GPF_MFPH_PF10MFP_I2S0_BCLK | SYS_GPF_MFPH_PF9MFP_I2S0_MCLK | SYS_GPF_MFPH_PF8MFP_I2S0_DI);
SYS->GPF_MFPL &= ~(SYS_GPF_MFPL_PF7MFP_Msk | SYS_GPF_MFPL_PF6MFP_Msk);
SYS->GPF_MFPL |= (SYS_GPF_MFPL_PF7MFP_I2S0_DO | SYS_GPF_MFPL_PF6MFP_I2S0_LRCK);
return;
}
void nutool_pincfg_deinit_i2s0(void)
{
SYS->GPF_MFPH &= ~(SYS_GPF_MFPH_PF10MFP_Msk | SYS_GPF_MFPH_PF9MFP_Msk | SYS_GPF_MFPH_PF8MFP_Msk);
SYS->GPF_MFPL &= ~(SYS_GPF_MFPL_PF7MFP_Msk | SYS_GPF_MFPL_PF6MFP_Msk);
return;
}
void nutool_pincfg_init_ice(void)
{
SYS->GPF_MFPL &= ~(SYS_GPF_MFPL_PF1MFP_Msk | SYS_GPF_MFPL_PF0MFP_Msk);
SYS->GPF_MFPL |= (SYS_GPF_MFPL_PF1MFP_ICE_CLK | SYS_GPF_MFPL_PF0MFP_ICE_DAT);
return;
}
void nutool_pincfg_deinit_ice(void)
{
SYS->GPF_MFPL &= ~(SYS_GPF_MFPL_PF1MFP_Msk | SYS_GPF_MFPL_PF0MFP_Msk);
return;
}
void nutool_pincfg_init_ph(void)
{
SYS->GPH_MFPH &= ~(SYS_GPH_MFPH_PH10MFP_Msk);
SYS->GPH_MFPH |= (SYS_GPH_MFPH_PH10MFP_GPIO);
return;
}
void nutool_pincfg_deinit_ph(void)
{
SYS->GPH_MFPH &= ~(SYS_GPH_MFPH_PH10MFP_Msk);
return;
}
void nutool_pincfg_init_sd0(void)
{
SYS->GPB_MFPH &= ~(SYS_GPB_MFPH_PB12MFP_Msk);
SYS->GPB_MFPH |= (SYS_GPB_MFPH_PB12MFP_SD0_nCD);
SYS->GPB_MFPL &= ~(SYS_GPB_MFPL_PB5MFP_Msk | SYS_GPB_MFPL_PB4MFP_Msk | SYS_GPB_MFPL_PB3MFP_Msk | SYS_GPB_MFPL_PB2MFP_Msk | SYS_GPB_MFPL_PB1MFP_Msk | SYS_GPB_MFPL_PB0MFP_Msk);
SYS->GPB_MFPL |= (SYS_GPB_MFPL_PB5MFP_SD0_DAT3 | SYS_GPB_MFPL_PB4MFP_SD0_DAT2 | SYS_GPB_MFPL_PB3MFP_SD0_DAT1 | SYS_GPB_MFPL_PB2MFP_SD0_DAT0 | SYS_GPB_MFPL_PB1MFP_SD0_CLK | SYS_GPB_MFPL_PB0MFP_SD0_CMD);
return;
}
void nutool_pincfg_deinit_sd0(void)
{
SYS->GPB_MFPH &= ~(SYS_GPB_MFPH_PB12MFP_Msk);
SYS->GPB_MFPL &= ~(SYS_GPB_MFPL_PB5MFP_Msk | SYS_GPB_MFPL_PB4MFP_Msk | SYS_GPB_MFPL_PB3MFP_Msk | SYS_GPB_MFPL_PB2MFP_Msk | SYS_GPB_MFPL_PB1MFP_Msk | SYS_GPB_MFPL_PB0MFP_Msk);
return;
}
void nutool_pincfg_init_spi0(void)
{
SYS->GPA_MFPL &= ~(SYS_GPA_MFPL_PA3MFP_Msk | SYS_GPA_MFPL_PA2MFP_Msk | SYS_GPA_MFPL_PA1MFP_Msk | SYS_GPA_MFPL_PA0MFP_Msk);
SYS->GPA_MFPL |= (SYS_GPA_MFPL_PA3MFP_SPI0_SS | SYS_GPA_MFPL_PA2MFP_SPI0_CLK | SYS_GPA_MFPL_PA1MFP_SPI0_MISO | SYS_GPA_MFPL_PA0MFP_SPI0_MOSI);
return;
}
void nutool_pincfg_deinit_spi0(void)
{
SYS->GPA_MFPL &= ~(SYS_GPA_MFPL_PA3MFP_Msk | SYS_GPA_MFPL_PA2MFP_Msk | SYS_GPA_MFPL_PA1MFP_Msk | SYS_GPA_MFPL_PA0MFP_Msk);
return;
}
void nutool_pincfg_init_spi1(void)
{
SYS->GPE_MFPL &= ~(SYS_GPE_MFPL_PE1MFP_Msk | SYS_GPE_MFPL_PE0MFP_Msk);
SYS->GPE_MFPL |= (SYS_GPE_MFPL_PE1MFP_SPI1_MISO | SYS_GPE_MFPL_PE0MFP_SPI1_MOSI);
SYS->GPH_MFPH &= ~(SYS_GPH_MFPH_PH9MFP_Msk | SYS_GPH_MFPH_PH8MFP_Msk);
SYS->GPH_MFPH |= (SYS_GPH_MFPH_PH9MFP_SPI1_SS | SYS_GPH_MFPH_PH8MFP_SPI1_CLK);
return;
}
void nutool_pincfg_deinit_spi1(void)
{
SYS->GPE_MFPL &= ~(SYS_GPE_MFPL_PE1MFP_Msk | SYS_GPE_MFPL_PE0MFP_Msk);
SYS->GPH_MFPH &= ~(SYS_GPH_MFPH_PH9MFP_Msk | SYS_GPH_MFPH_PH8MFP_Msk);
return;
}
void nutool_pincfg_init_uart0(void)
{
SYS->GPA_MFPL &= ~(SYS_GPA_MFPL_PA7MFP_Msk | SYS_GPA_MFPL_PA6MFP_Msk);
SYS->GPA_MFPL |= (SYS_GPA_MFPL_PA7MFP_UART0_TXD | SYS_GPA_MFPL_PA6MFP_UART0_RXD);
return;
}
void nutool_pincfg_deinit_uart0(void)
{
SYS->GPA_MFPL &= ~(SYS_GPA_MFPL_PA7MFP_Msk | SYS_GPA_MFPL_PA6MFP_Msk);
return;
}
void nutool_pincfg_init_uart1(void)
{
SYS->GPA_MFPH &= ~(SYS_GPA_MFPH_PA9MFP_Msk | SYS_GPA_MFPH_PA8MFP_Msk);
SYS->GPA_MFPH |= (SYS_GPA_MFPH_PA9MFP_UART1_TXD | SYS_GPA_MFPH_PA8MFP_UART1_RXD);
return;
}
void nutool_pincfg_deinit_uart1(void)
{
SYS->GPA_MFPH &= ~(SYS_GPA_MFPH_PA9MFP_Msk | SYS_GPA_MFPH_PA8MFP_Msk);
return;
}
void nutool_pincfg_init_uart4(void)
{
SYS->GPC_MFPL &= ~(SYS_GPC_MFPL_PC7MFP_Msk | SYS_GPC_MFPL_PC6MFP_Msk);
SYS->GPC_MFPL |= (SYS_GPC_MFPL_PC7MFP_UART4_TXD | SYS_GPC_MFPL_PC6MFP_UART4_RXD);
return;
}
void nutool_pincfg_deinit_uart4(void)
{
SYS->GPC_MFPL &= ~(SYS_GPC_MFPL_PC7MFP_Msk | SYS_GPC_MFPL_PC6MFP_Msk);
return;
}
void nutool_pincfg_init_usb(void)
{
SYS->GPA_MFPH &= ~(SYS_GPA_MFPH_PA15MFP_Msk | SYS_GPA_MFPH_PA14MFP_Msk | SYS_GPA_MFPH_PA13MFP_Msk | SYS_GPA_MFPH_PA12MFP_Msk);
SYS->GPA_MFPH |= (SYS_GPA_MFPH_PA15MFP_USB_OTG_ID | SYS_GPA_MFPH_PA14MFP_USB_D_P | SYS_GPA_MFPH_PA13MFP_USB_D_N | SYS_GPA_MFPH_PA12MFP_USB_VBUS);
SYS->GPB_MFPH &= ~(SYS_GPB_MFPH_PB15MFP_Msk | SYS_GPB_MFPH_PB14MFP_Msk);
SYS->GPB_MFPH |= (SYS_GPB_MFPH_PB15MFP_USB_VBUS_EN | SYS_GPB_MFPH_PB14MFP_USB_VBUS_ST);
return;
}
void nutool_pincfg_deinit_usb(void)
{
SYS->GPA_MFPH &= ~(SYS_GPA_MFPH_PA15MFP_Msk | SYS_GPA_MFPH_PA14MFP_Msk | SYS_GPA_MFPH_PA13MFP_Msk | SYS_GPA_MFPH_PA12MFP_Msk);
SYS->GPB_MFPH &= ~(SYS_GPB_MFPH_PB15MFP_Msk | SYS_GPB_MFPH_PB14MFP_Msk);
return;
}
void pincfg_init_slcd(void)
{
/*
Summary of LCD pin usage:
COM 0~5 : PC.0, PC.1, PC.2, PC.3, PC.4, PC.5
COM 6~7 : PD.8, PD.9
SEG 0 : PD.14
SEG 1~4 : PH.11, PH.10, PH.9, PH.8
SEG 5~12 : PE.0, PE.1, PE.2, PE.3, PE.4, PE.5, PE.6, PE.7
SEG 13~14 : PD.6, PD.7
SEG 15~21 : PG.15, PG.14, PG.13, PG.12, PG.11, PG.10, PG.9
SEG 22~23 : PE.15, PE.14
SEG 24~29 : PA.0, PA.1, PA.2, PA.3, PA.4, PA.5
SEG 30~32 : PE.10, PE.9, PE.8
SEG 33~36 : PH.7, PH.6, PH.5, PH.4
SEG 37~39 : PG.4, PG.3, PG.2
*/
/* COM 0~5 */
SYS->GPC_MFPL = (SYS->GPC_MFPL &
~(SYS_GPC_MFPL_PC0MFP_Msk | SYS_GPC_MFPL_PC1MFP_Msk | SYS_GPC_MFPL_PC2MFP_Msk | SYS_GPC_MFPL_PC3MFP_Msk |
SYS_GPC_MFPL_PC4MFP_Msk | SYS_GPC_MFPL_PC5MFP_Msk)) |
(LCD_COM0_PC0 | LCD_COM1_PC1 | LCD_COM2_PC2 | LCD_COM3_PC3 | LCD_COM4_PC4 | LCD_COM5_PC5);
/* COM 6~7 */
SYS->GPD_MFPH = (SYS->GPD_MFPH & ~(SYS_GPD_MFPH_PD8MFP_Msk | SYS_GPD_MFPH_PD9MFP_Msk)) |
(LCD_COM6_PD8 | LCD_COM7_PD9);
/* SEG 0 */
SYS->GPD_MFPH = (SYS->GPD_MFPH & ~SYS_GPD_MFPH_PD14MFP_Msk) | LCD_SEG0_PD14;
/* SEG 1~4 */
SYS->GPH_MFPH = (SYS->GPH_MFPH & ~(SYS_GPH_MFPH_PH11MFP_Msk | SYS_GPH_MFPH_PH10MFP_Msk | SYS_GPH_MFPH_PH9MFP_Msk | SYS_GPH_MFPH_PH8MFP_Msk)) |
(LCD_SEG1_PH11 | LCD_SEG2_PH10 | LCD_SEG3_PH9 | LCD_SEG4_PH8);
/* SEG 5~12 */
SYS->GPE_MFPL = (SYS->GPE_MFPL &
~(SYS_GPE_MFPL_PE0MFP_Msk | SYS_GPE_MFPL_PE1MFP_Msk | SYS_GPE_MFPL_PE2MFP_Msk | SYS_GPE_MFPL_PE3MFP_Msk |
SYS_GPE_MFPL_PE4MFP_Msk | SYS_GPE_MFPL_PE5MFP_Msk | SYS_GPE_MFPL_PE6MFP_Msk | SYS_GPE_MFPL_PE7MFP_Msk)) |
(LCD_SEG5_PE0 | LCD_SEG6_PE1 | LCD_SEG7_PE2 | LCD_SEG8_PE3 |
LCD_SEG9_PE4 | LCD_SEG10_PE5 | LCD_SEG11_PE6 | LCD_SEG12_PE7);
/* SEG 13~14 */
SYS->GPD_MFPL = (SYS->GPD_MFPL & ~(SYS_GPD_MFPL_PD6MFP_Msk | SYS_GPD_MFPL_PD7MFP_Msk)) | (LCD_SEG13_PD6 | LCD_SEG14_PD7);
/* SEG 15~21 */
SYS->GPG_MFPH = (SYS->GPG_MFPH &
~(SYS_GPG_MFPH_PG15MFP_Msk | SYS_GPG_MFPH_PG14MFP_Msk | SYS_GPG_MFPH_PG13MFP_Msk | SYS_GPG_MFPH_PG12MFP_Msk |
SYS_GPG_MFPH_PG11MFP_Msk | SYS_GPG_MFPH_PG10MFP_Msk | SYS_GPG_MFPH_PG9MFP_Msk)) |
(LCD_SEG15_PG15 | LCD_SEG16_PG14 | LCD_SEG17_PG13 | LCD_SEG18_PG12 |
LCD_SEG19_PG11 | LCD_SEG20_PG10 | LCD_SEG21_PG9);
/* SEG 22~23 */
SYS->GPE_MFPH = (SYS->GPE_MFPH & ~(SYS_GPE_MFPH_PE15MFP_Msk | SYS_GPE_MFPH_PE14MFP_Msk)) | (LCD_SEG22_PE15 | LCD_SEG23_PE14);
/* SEG 24~29 */
SYS->GPA_MFPL = (SYS->GPA_MFPL &
~(SYS_GPA_MFPL_PA0MFP_Msk | SYS_GPA_MFPL_PA1MFP_Msk | SYS_GPA_MFPL_PA2MFP_Msk | SYS_GPA_MFPL_PA3MFP_Msk |
SYS_GPA_MFPL_PA4MFP_Msk | SYS_GPA_MFPL_PA5MFP_Msk)) |
(LCD_SEG24_PA0 | LCD_SEG25_PA1 | LCD_SEG26_PA2 | LCD_SEG27_PA3 | LCD_SEG28_PA4 | LCD_SEG29_PA5);
/* SEG 30~32 */
SYS->GPE_MFPH = (SYS->GPE_MFPH & ~(SYS_GPE_MFPH_PE10MFP_Msk | SYS_GPE_MFPH_PE9MFP_Msk | SYS_GPE_MFPH_PE8MFP_Msk)) |
(LCD_SEG30_PE10 | LCD_SEG31_PE9 | LCD_SEG32_PE8);
/* SEG 33~36 */
SYS->GPH_MFPL = (SYS->GPH_MFPL & ~(SYS_GPH_MFPL_PH7MFP_Msk | SYS_GPH_MFPL_PH6MFP_Msk | SYS_GPH_MFPL_PH5MFP_Msk | SYS_GPH_MFPL_PH4MFP_Msk)) |
(LCD_SEG33_PH7 | LCD_SEG34_PH6 | LCD_SEG35_PH5 | LCD_SEG36_PH4);
/* SEG 37~39 */
SYS->GPG_MFPL = (SYS->GPG_MFPL & ~(SYS_GPG_MFPL_PG4MFP_Msk | SYS_GPG_MFPL_PG3MFP_Msk | SYS_GPG_MFPL_PG2MFP_Msk)) |
(LCD_SEG37_PG4 | LCD_SEG38_PG3 | LCD_SEG39_PG2);
}
void nutool_pincfg_init(void)
{
//SYS->GPA_MFPH = 0xEEEE0077;
//SYS->GPA_MFPL = 0x77004444;
//SYS->GPB_MFPH = 0xEF091111;
//SYS->GPB_MFPL = 0x11333333;
//SYS->GPC_MFPH = 0x000CCCC0;
//SYS->GPC_MFPL = 0x550000CC;
//SYS->GPD_MFPH = 0x00000000;
//SYS->GPD_MFPL = 0x00000000;
//SYS->GPE_MFPH = 0x00000000;
//SYS->GPE_MFPL = 0xCC000066;
//SYS->GPF_MFPH = 0x00000444;
//SYS->GPF_MFPL = 0x440000EE;
//SYS->GPG_MFPH = 0x00000000;
//SYS->GPG_MFPL = 0x00005500;
//SYS->GPH_MFPH = 0x00000066;
//SYS->GPH_MFPL = 0x00000000;
nutool_pincfg_init_eadc0();
nutool_pincfg_init_epwm0();
nutool_pincfg_init_epwm1();
nutool_pincfg_init_i2c1();
nutool_pincfg_init_i2s0();
nutool_pincfg_init_ice();
nutool_pincfg_init_ph();
nutool_pincfg_init_sd0();
nutool_pincfg_init_spi0();
nutool_pincfg_init_spi1();
nutool_pincfg_init_uart0();
#if !defined(BOARD_USING_LCD_ILI9341)
nutool_pincfg_init_uart1();
#endif
nutool_pincfg_init_uart4();
nutool_pincfg_init_usb();
#if defined(BSP_USING_SLCD)
pincfg_init_slcd();
#endif
return;
}
void nutool_pincfg_deinit(void)
{
nutool_pincfg_deinit_eadc0();
nutool_pincfg_deinit_epwm0();
nutool_pincfg_deinit_epwm1();
nutool_pincfg_deinit_i2c1();
nutool_pincfg_deinit_i2s0();
nutool_pincfg_deinit_ice();
nutool_pincfg_deinit_ph();
nutool_pincfg_deinit_sd0();
nutool_pincfg_deinit_spi0();
nutool_pincfg_deinit_spi1();
nutool_pincfg_deinit_uart0();
nutool_pincfg_deinit_uart1();
nutool_pincfg_deinit_uart4();
nutool_pincfg_deinit_usb();
return;
}
/*** (C) COPYRIGHT 2013-2020 Nuvoton Technology Corp. ***/

View File

@ -0,0 +1,157 @@
/****************************************************************************
* @file nutool_pincfg.cfg
* @version V1.21
* @Date 2020/11/11-12:06:37
* @brief NuMicro config file
*
* @note Please do not modify this file.
* Otherwise, it may not be loaded successfully.
* Copyright (C) 2013-2020 Nuvoton Technology Corp. All rights reserved.
*****************************************************************************/
MCU:M2354KJFAE(LQFP128)
Pin1:SD0_DAT3
Pin2:SD0_DAT2
Pin3:SD0_DAT1
Pin4:SD0_DAT0
Pin5:EPWM1_CH0
Pin6:EPWM1_CH1
Pin7:EPWM1_CH2
Pin8:EPWM1_CH3
Pin9:SD0_CLK
Pin10:SD0_CMD
Pin11:VSS
Pin12:VDD
Pin13:PA.11
Pin14:PA.10
Pin15:UART1_TXD
Pin16:UART1_RXD
Pin17:PC.13
Pin18:PD.12
Pin19:PD.11
Pin20:PD.10
Pin21:I2C1_SCL
Pin22:I2C1_SDA
Pin23:PG.4
Pin24:PF.11
Pin25:I2S0_BCLK
Pin26:I2S0_MCLK
Pin27:I2S0_DI
Pin28:I2S0_DO
Pin29:I2S0_LRCK
Pin30:VBAT
Pin31:PF.5
Pin32:PF.4
Pin33:PH.4
Pin34:PH.5
Pin35:PH.6
Pin36:PH.7
Pin37:PF.3
Pin38:PF.2
Pin39:VSS
Pin40:VDD
Pin41:PE.8
Pin42:PE.9
Pin43:PE.10
Pin44:PE.11
Pin45:PE.12
Pin46:PE.13
Pin47:PC.8
Pin48:UART4_TXD
Pin49:UART4_RXD
Pin50:UART0_TXD
Pin51:UART0_RXD
Pin52:VSS
Pin53:VDD
Pin54:LDO_CAP
Pin55:PA.5
Pin56:PA.4
Pin57:SPI0_SS
Pin58:SPI0_CLK
Pin59:SPI0_MISO
Pin60:SPI0_MOSI
Pin61:VDDIO
Pin62:PE.14
Pin63:PE.15
Pin64:nRESET
Pin65:ICE_DAT
Pin66:ICE_CLK
Pin67:PD.9
Pin68:PD.8
Pin69:PC.5
Pin70:PC.4
Pin71:PC.3
Pin72:PC.2
Pin73:EPWM1_CH4
Pin74:EPWM1_CH5
Pin75:VSS
Pin76:VDD
Pin77:PG.9
Pin78:PG.10
Pin79:PG.11
Pin80:PG.12
Pin81:PG.13
Pin82:PG.14
Pin83:PG.15
Pin84:PD.7
Pin85:PD.6
Pin86:PD.5
Pin87:PD.4
Pin88:PD.3
Pin89:PD.2
Pin90:PD.1
Pin91:PD.0
Pin92:VLCD
Pin93:USB_VBUS
Pin94:USB_D-
Pin95:USB_D+
Pin96:USB_OTG_ID
Pin97:EPWM0_CH0
Pin98:EPWM0_CH1
Pin99:PE.5
Pin100:PE.4
Pin101:PE.3
Pin102:PE.2
Pin103:VSS
Pin104:VDD
Pin105:SPI1_MISO
Pin106:SPI1_MOSI
Pin107:SPI1_CLK
Pin108:SPI1_SS
Pin109:PH.10
Pin110:PH.11
Pin111:PD.14
Pin112:VSS
Pin113:Vsw
Pin114:VDD
Pin115:LDO_CAP
Pin116:USB_VBUS_EN
Pin117:USB_VBUS_ST
Pin118:PB.13
Pin119:SD0_nCD
Pin120:AVDD
Pin121:VREF
Pin122:AVSS
Pin123:EADC0_CH11
Pin124:EADC0_CH10
Pin125:EADC0_CH9
Pin126:EADC0_CH8
Pin127:EADC0_CH7
Pin128:EADC0_CH6
GPIOpin:108
SYS->GPA_MFPH = 0xEEEE0077
SYS->GPA_MFPL = 0x77004444
SYS->GPB_MFPH = 0xEF091111
SYS->GPB_MFPL = 0x11333333
SYS->GPC_MFPH = 0x000CCCC0
SYS->GPC_MFPL = 0x550000CC
SYS->GPD_MFPH = 0x00000000
SYS->GPD_MFPL = 0x00000000
SYS->GPE_MFPH = 0x00000000
SYS->GPE_MFPL = 0xCC000066
SYS->GPF_MFPH = 0x00000444
SYS->GPF_MFPL = 0x440000EE
SYS->GPG_MFPH = 0x00000000
SYS->GPG_MFPL = 0x00005500
SYS->GPH_MFPH = 0x00000066
SYS->GPH_MFPL = 0x00000000
/*** (C) COPYRIGHT 2013-2020 Nuvoton Technology Corp. ***/

View File

@ -0,0 +1,52 @@
/****************************************************************************
* @file nutool_pincfg.h
* @version V1.21
* @Date 2020/11/11-12:06:36
* @brief NuMicro generated code file
*
* Copyright (C) 2013-2020 Nuvoton Technology Corp. All rights reserved.
*****************************************************************************/
#ifndef __NUTOOL_PINCFG_H__
#define __NUTOOL_PINCFG_H__
#ifdef __cplusplus
extern "C"
{
#endif
void nutool_pincfg_init_eadc0(void);
void nutool_pincfg_deinit_eadc0(void);
void nutool_pincfg_init_epwm0(void);
void nutool_pincfg_deinit_epwm0(void);
void nutool_pincfg_init_epwm1(void);
void nutool_pincfg_deinit_epwm1(void);
void nutool_pincfg_init_i2c1(void);
void nutool_pincfg_deinit_i2c1(void);
void nutool_pincfg_init_i2s0(void);
void nutool_pincfg_deinit_i2s0(void);
void nutool_pincfg_init_ice(void);
void nutool_pincfg_deinit_ice(void);
void nutool_pincfg_init_ph(void);
void nutool_pincfg_deinit_ph(void);
void nutool_pincfg_init_sd0(void);
void nutool_pincfg_deinit_sd0(void);
void nutool_pincfg_init_spi0(void);
void nutool_pincfg_deinit_spi0(void);
void nutool_pincfg_init_spi1(void);
void nutool_pincfg_deinit_spi1(void);
void nutool_pincfg_init_uart0(void);
void nutool_pincfg_deinit_uart0(void);
void nutool_pincfg_init_uart1(void);
void nutool_pincfg_deinit_uart1(void);
void nutool_pincfg_init_uart4(void);
void nutool_pincfg_deinit_uart4(void);
void nutool_pincfg_init_usb(void);
void nutool_pincfg_deinit_usb(void);
void nutool_pincfg_init(void);
void nutool_pincfg_deinit(void);
#ifdef __cplusplus
}
#endif
#endif /*__NUTOOL_PINCFG_H__*/
/*** (C) COPYRIGHT 2013-2020 Nuvoton Technology Corp. ***/

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,189 @@
/**************************************************************************//**
* @file gpio.c
* @version V3.00
* @brief M2354 series General Purpose I/O (GPIO) driver source file
*
* @copyright SPDX-License-Identifier: Apache-2.0
* @copyright Copyright (C) 2020 Nuvoton Technology Corp. All rights reserved.
*****************************************************************************/
#include "NuMicro.h"
/** @addtogroup Standard_Driver Standard Driver
@{
*/
/** @addtogroup GPIO_Driver GPIO Driver
@{
*/
/** @addtogroup GPIO_EXPORTED_FUNCTIONS GPIO Exported Functions
@{
*/
/**
* @brief Set GPIO operation mode
*
* @param[in] port GPIO port. It could be PA, PB, PC, PD, PE, PF, PG or PH.
* @param[in] u32PinMask The single or multiple pins of specified GPIO port. \n
* It could be BIT0 ~ BIT15 for PA, PB and PE. \n
* It could be BIT0 ~ BIT13 for PC. \n
* It could be BIT0 ~ BIT12, BIT14 for PD. \n
* It could be BIT0 ~ BIT11 for PF. \n
* It could be BIT2 ~ BIT3, BIT9 ~ BIT15 for PG. \n
* It could be BIT4 ~ BIT11 for PH.
* @param[in] u32Mode Operation mode. It could be
* - \ref GPIO_MODE_INPUT
* - \ref GPIO_MODE_OUTPUT
* - \ref GPIO_MODE_OPEN_DRAIN
* - \ref GPIO_MODE_QUASI
*
* @return None
*
* @details This function is used to set specified GPIO operation mode.
*/
void GPIO_SetMode(GPIO_T *port, uint32_t u32PinMask, uint32_t u32Mode)
{
uint32_t u32Idx;
for(u32Idx = 0ul; u32Idx < GPIO_PIN_MAX; u32Idx++)
{
if((u32PinMask & (1ul << u32Idx)) == (1ul << u32Idx))
{
port->MODE = (port->MODE & ~(0x3ul << (u32Idx << 1))) | (u32Mode << (u32Idx << 1));
}
}
}
/**
* @brief Enable GPIO interrupt
*
* @param[in] port GPIO port. It could be PA, PB, PC, PD, PE, PF, PG or PH.
* @param[in] u32Pin The pin of specified GPIO port. \n
* It could be 0 ~ 15 for PA, PB and PE. \n
* It could be 0 ~ 13 for PC GPIO port. \n
* It could be 0 ~ 12, 14 for PD GPIO port. \n
* It could be 0 ~ 11 for PF GPIO port. \n
* It could be 2 ~ 4, 9 ~ 15 for PG GPIO port. \n
* It could be 4 ~ 11 for PH GPIO port.
* @param[in] u32IntAttribs The interrupt attribute of specified GPIO pin. It could be
* - \ref GPIO_INT_RISING
* - \ref GPIO_INT_FALLING
* - \ref GPIO_INT_BOTH_EDGE
* - \ref GPIO_INT_HIGH
* - \ref GPIO_INT_LOW
*
* @return None
*
* @details This function is used to enable specified GPIO pin interrupt.
*/
void GPIO_EnableInt(GPIO_T *port, uint32_t u32Pin, uint32_t u32IntAttribs)
{
/* Configure interrupt mode of specified pin */
port->INTTYPE = (port->INTTYPE & ~(1ul << u32Pin)) | (((u32IntAttribs >> 24) & 0xFFUL) << u32Pin);
/* Enable interrupt function of specified pin */
port->INTEN = (port->INTEN & ~(0x00010001ul << u32Pin)) | ((u32IntAttribs & 0xFFFFFFUL) << u32Pin);
}
/**
* @brief Disable GPIO interrupt
*
* @param[in] port GPIO port. It could be PA, PB, PC, PD, PE, PF, PG or PH.
* @param[in] u32Pin The pin of specified GPIO port. \n
* It could be 0 ~ 15 for PA, PB and PE. \n
* It could be 0 ~ 13 for PC GPIO port. \n
* It could be 0 ~ 12, 14 for PD GPIO port. \n
* It could be 0 ~ 11 for PF GPIO port. \n
* It could be 2 ~ 4, 9 ~ 15 for PG GPIO port. \n
* It could be 4 ~ 11 for PH GPIO port.
*
* @return None
*
* @details This function is used to enable specified GPIO pin interrupt.
*/
void GPIO_DisableInt(GPIO_T *port, uint32_t u32Pin)
{
/* Configure interrupt mode of specified pin */
port->INTTYPE &= ~(1UL << u32Pin);
/* Disable interrupt function of specified pin */
port->INTEN &= ~((0x00010001UL) << u32Pin);
}
/**
* @brief Set GPIO slew rate control
*
* @param[in] port GPIO port. It could be PA, PB, PC, PD, PE, PF, PG or PH.
* @param[in] u32PinMask The single or multiple pins of specified GPIO port. \n
* It could be BIT0 ~ BIT15 for PA, PB and PE. \n
* It could be BIT0 ~ BIT13 for PC. \n
* It could be BIT0 ~ BIT12, BIT14. \n
* It could be BIT0 ~ BIT11 for PF. \n
* It could be BIT2 ~ BIT3, BIT9 ~ BIT15 for PG. \n
* It could be BIT4 ~ BIT11 for PH.
* @param[in] u32Mode Slew rate mode. It could be
* - \ref GPIO_SLEWCTL_NORMAL (maximum 40 MHz at 2.7V)
* - \ref GPIO_SLEWCTL_HIGH (maximum 80 MHz at 2.7V)
* - \ref GPIO_SLEWCTL_FAST (maximum 100 MHz at 2.7V)
*
* @return None
*
* @details This function is used to set specified GPIO operation mode.
*/
void GPIO_SetSlewCtl(GPIO_T *port, uint32_t u32PinMask, uint32_t u32Mode)
{
uint32_t u32Idx;
for(u32Idx = 0ul; u32Idx < GPIO_PIN_MAX; u32Idx++)
{
if(u32PinMask & (1ul << u32Idx))
{
port->SLEWCTL = (port->SLEWCTL & ~(0x3ul << (u32Idx << 1))) | (u32Mode << (u32Idx << 1));
}
}
}
/**
* @brief Set GPIO Pull-up and Pull-down control
*
* @param[in] port GPIO port. It could be PA, PB, PC, PD, PE, PF, PG or PH.
* @param[in] u32PinMask The single or multiple pins of specified GPIO port. \n
* It could be BIT0 ~ BIT15 for PA, PB and PE. \n
* It could be BIT0 ~ BIT13 for PC. \n
* It could be BIT0 ~ BIT12, BIT14 for PD. \n
* It could be BIT0 ~ BIT11 for PF. \n
* It could be BIT2 ~ BIT3, BIT9 ~ BIT15 for PG. \n
* It could be BIT4 ~ BIT11 for PH.
* @param[in] u32Mode The pin mode of specified GPIO pin. It could be
* - \ref GPIO_PUSEL_DISABLE
* - \ref GPIO_PUSEL_PULL_UP
* - \ref GPIO_PUSEL_PULL_DOWN
*
* @return None
*
* @details Set the pin mode of specified GPIO pin.
*/
void GPIO_SetPullCtl(GPIO_T *port, uint32_t u32PinMask, uint32_t u32Mode)
{
uint32_t u32Idx;
for(u32Idx = 0ul; u32Idx < GPIO_PIN_MAX; u32Idx++)
{
if(u32PinMask & (1ul << u32Idx))
{
port->PUSEL = (port->PUSEL & ~(0x3ul << (u32Idx << 1))) | (u32Mode << (u32Idx << 1));
}
}
}
/**@}*/ /* end of group GPIO_EXPORTED_FUNCTIONS */
/**@}*/ /* end of group GPIO_Driver */
/**@}*/ /* end of group Standard_Driver */

View File

@ -0,0 +1,441 @@
/**************************************************************************//**
* @file sys.c
* @version V3.00
* @brief M2354 series System Manager (SYS) driver source file
*
* @copyright SPDX-License-Identifier: Apache-2.0
* @copyright Copyright (C) 2020 Nuvoton Technology Corp. All rights reserved.
*****************************************************************************/
#include "NuMicro.h"
/** @addtogroup Standard_Driver Standard Driver
@{
*/
/** @addtogroup SYS_Driver SYS Driver
@{
*/
/** @addtogroup SYS_EXPORTED_FUNCTIONS SYS Exported Functions
@{
*/
/**
* @brief Clear reset source
* @param[in] u32Src is system reset source. Including :
* - \ref SYS_RSTSTS_CPULKRF_Msk
* - \ref SYS_RSTSTS_CPURF_Msk
* - \ref SYS_RSTSTS_SYSRF_Msk
* - \ref SYS_RSTSTS_BODRF_Msk
* - \ref SYS_RSTSTS_LVRF_Msk
* - \ref SYS_RSTSTS_WDTRF_Msk
* - \ref SYS_RSTSTS_PINRF_Msk
* - \ref SYS_RSTSTS_PORF_Msk
* @return None
* @details This function clear the selected system reset source.
*/
void SYS_ClearResetSrc(uint32_t u32Src)
{
SYS->RSTSTS = u32Src;
}
/**
* @brief Get Brown-out detector output status
* @param None
* @retval 0 System voltage is higher than BODVL setting or BODEN is 0.
* @retval 1 System voltage is lower than BODVL setting.
* @details This function get Brown-out detector output status.
*/
uint32_t SYS_GetBODStatus(void)
{
return ((SYS->BODCTL & SYS_BODCTL_BODOUT_Msk) >> SYS_BODCTL_BODOUT_Pos);
}
/**
* @brief Get reset status register value
* @param None
* @return Reset source
* @details This function get the system reset status register value.
*/
uint32_t SYS_GetResetSrc(void)
{
return (SYS->RSTSTS);
}
/**
* @brief Check if register is locked nor not
* @param None
* @retval 0 Write-protection function is disabled.
* 1 Write-protection function is enabled.
* @details This function check register write-protection bit setting.
*/
uint32_t SYS_IsRegLocked(void)
{
return SYS->REGLCTL & 1UL ? 0UL : 1UL;
}
/**
* @brief Get product ID
* @param None
* @return Product ID
* @details This function get product ID.
*/
uint32_t SYS_ReadPDID(void)
{
return SYS->PDID;
}
/**
* @brief Reset chip with chip reset
* @param None
* @return None
* @details This function reset chip with chip reset.
* The register write-protection function should be disabled before using this function.
*/
void SYS_ResetChip(void)
{
SYS->IPRST0 |= SYS_IPRST0_CHIPRST_Msk;
}
/**
* @brief Reset chip with CPU reset
* @param None
* @return None
* @details This function reset CPU with CPU reset.
* The register write-protection function should be disabled before using this function.
*/
void SYS_ResetCPU(void)
{
SYS->IPRST0 |= SYS_IPRST0_CPURST_Msk;
}
/**
* @brief Reset selected module
* @param[in] u32ModuleIndex is module index. Including :
* - \ref PDMA0_RST
* - \ref PDMA1_RST
* - \ref EBI_RST
* - \ref USBH_RST
* - \ref SDH0_RST
* - \ref CRC_RST
* - \ref CRPT_RST
* - \ref KS_RST
* - \ref GPIO_RST
* - \ref TMR0_RST
* - \ref TMR1_RST
* - \ref TMR2_RST
* - \ref TMR3_RST
* - \ref TMR4_RST
* - \ref TMR5_RST
* - \ref ACMP01_RST
* - \ref I2C0_RST
* - \ref I2C1_RST
* - \ref I2C2_RST
* - \ref QSPI0_RST
* - \ref SPI0_RST
* - \ref SPI1_RST
* - \ref SPI2_RST
* - \ref SPI3_RST
* - \ref UART0_RST
* - \ref UART1_RST
* - \ref UART2_RST
* - \ref UART3_RST
* - \ref UART4_RST
* - \ref UART5_RST
* - \ref CAN0_RST
* - \ref OTG_RST
* - \ref USBD_RST
* - \ref EADC_RST
* - \ref I2S0_RST
* - \ref LCD_RST
* - \ref TRNG_RST
* - \ref SC0_RST
* - \ref SC1_RST
* - \ref SC2_RST
* - \ref USCI0_RST
* - \ref USCI1_RST
* - \ref DAC_RST
* - \ref EPWM0_RST
* - \ref EPWM1_RST
* - \ref BPWM0_RST
* - \ref BPWM1_RST
* - \ref QEI0_RST
* - \ref QEI1_RST
* - \ref ECAP0_RST
* - \ref ECAP1_RST
* @return None
* @details This function reset selected module.
*/
void SYS_ResetModule(uint32_t u32ModuleIndex)
{
uint32_t u32TmpVal = 0UL, u32TmpAddr = 0UL;
/* Generate reset signal to the corresponding module */
u32TmpVal = (1UL << (u32ModuleIndex & 0x00ffffffUL));
u32TmpAddr = (uint32_t)&SYS->IPRST0 + ((u32ModuleIndex >> 24UL));
*(uint32_t *)u32TmpAddr |= u32TmpVal;
/* Release corresponding module from reset state */
u32TmpVal = ~(1UL << (u32ModuleIndex & 0x00ffffffUL));
*(uint32_t *)u32TmpAddr &= u32TmpVal;
}
/**
* @brief Enable and configure Brown-out detector function
* @param[in] i32Mode is reset or interrupt mode. Including :
* - \ref SYS_BODCTL_BOD_RST_EN
* - \ref SYS_BODCTL_BOD_INTERRUPT_EN
* @param[in] u32BODLevel is Brown-out voltage level. Including :
* - \ref SYS_BODCTL_BODVL_1_6V
* - \ref SYS_BODCTL_BODVL_1_8V
* - \ref SYS_BODCTL_BODVL_2_0V
* - \ref SYS_BODCTL_BODVL_2_2V
* - \ref SYS_BODCTL_BODVL_2_4V
* - \ref SYS_BODCTL_BODVL_2_6V
* - \ref SYS_BODCTL_BODVL_2_8V
* - \ref SYS_BODCTL_BODVL_3_0V
* @return None
* @details This function configure Brown-out detector reset or interrupt mode, enable Brown-out function and set Brown-out voltage level.
* The register write-protection function should be disabled before using this function.
*/
void SYS_EnableBOD(int32_t i32Mode, uint32_t u32BODLevel)
{
/* Enable Brown-out Detector function */
/* Enable Brown-out interrupt or reset function */
/* Select Brown-out Detector threshold voltage */
while(SYS->BODCTL & SYS_BODCTL_WRBUSY_Msk);
SYS->BODCTL = (SYS->BODCTL & ~(SYS_BODCTL_BODRSTEN_Msk | SYS_BODCTL_BODVL_Msk)) |
((uint32_t)i32Mode) | (u32BODLevel) | (SYS_BODCTL_BODEN_Msk);
}
/**
* @brief Disable Brown-out detector function
* @param None
* @return None
* @details This function disable Brown-out detector function.
* The register write-protection function should be disabled before using this function.
*/
void SYS_DisableBOD(void)
{
while(SYS->BODCTL & SYS_BODCTL_WRBUSY_Msk);
SYS->BODCTL &= ~SYS_BODCTL_BODEN_Msk;
}
/**
* @brief Set Power Level
* @param[in] u32PowerLevel is power level setting. Including :
* - \ref SYS_PLCTL_PLSEL_PL0 : Supports system clock up to 96MHz.
* - \ref SYS_PLCTL_PLSEL_PL1 : Supports system clock up to 84MHz.
* - \ref SYS_PLCTL_PLSEL_PL2 : Supports system clock up to 48MHz.
* - \ref SYS_PLCTL_PLSEL_PL3 : Supports system clock up to 4MHz.
* @return None
* @details This function select power level.
* The register write-protection function should be disabled before using this function.
*/
void SYS_SetPowerLevel(uint32_t u32PowerLevel)
{
/* Set power voltage level */
while(SYS->PLCTL & SYS_PLCTL_WRBUSY_Msk);
SYS->PLCTL = (SYS->PLCTL & (~SYS_PLCTL_PLSEL_Msk)) | (u32PowerLevel);
while(SYS->PLSTS & SYS_PLSTS_PLCBUSY_Msk);
}
/**
* @brief Set Main Voltage Regulator Type
* @param[in] u32PowerRegulator is main voltage regulator type. Including :
* - \ref SYS_PLCTL_MVRS_LDO
* - \ref SYS_PLCTL_MVRS_DCDC
* @retval 0 main voltage regulator type setting is not finished
* @retval 1 main voltage regulator type setting is finished
* @details This function set main voltage regulator type.
* The main voltage regulator type setting to DCDC cannot finished if the inductor is not detected.
* The register write-protection function should be disabled before using this function.
*/
uint32_t SYS_SetPowerRegulator(uint32_t u32PowerRegulator)
{
int32_t i32TimeOutCnt = 400;
uint32_t u32Ret = 1U;
uint32_t u32PowerRegStatus;
/* Get main voltage regulator type status */
u32PowerRegStatus = SYS->PLSTS & SYS_PLSTS_CURMVR_Msk;
/* Set main voltage regulator type */
if((u32PowerRegulator == SYS_PLCTL_MVRS_DCDC) && (u32PowerRegStatus == SYS_PLSTS_CURMVR_LDO))
{
/* Set main voltage regulator type to DCDC if status is LDO */
while(SYS->PLCTL & SYS_PLCTL_WRBUSY_Msk);
SYS->PLCTL |= SYS_PLCTL_MVRS_Msk;
/* Wait inductor detection and main voltage regulator type change ready */
while((SYS->PLSTS & SYS_PLSTS_CURMVR_Msk) != SYS_PLSTS_CURMVR_DCDC)
{
if(i32TimeOutCnt-- <= 0)
{
u32Ret = 0U; /* Main voltage regulator type change time-out */
break;
}
}
}
else if(u32PowerRegulator == SYS_PLCTL_MVRS_LDO)
{
/* Set main voltage regulator type to LDO if status is DCDC */
while(SYS->PLCTL & SYS_PLCTL_WRBUSY_Msk);
SYS->PLCTL &= (~SYS_PLCTL_MVRS_Msk);
/* Wait main voltage regulator type change ready */
while((SYS->PLSTS & SYS_PLSTS_CURMVR_Msk) != SYS_PLSTS_CURMVR_LDO)
{
if(i32TimeOutCnt-- <= 0)
{
u32Ret = 0U; /* Main voltage regulator type change time-out */
break;
}
}
}
/* Clear main voltage regulator type change error flag */
if(SYS->PLSTS & SYS_PLSTS_MVRCERR_Msk)
{
SYS->PLSTS = SYS_PLSTS_MVRCERR_Msk;
u32Ret = 0U;
}
return u32Ret;
}
/**
* @brief Set System SRAM Power Mode
* @param[in] u32SRAMSel is SRAM region selection. Including :
* - \ref SYS_SRAMPC0_SRAM0PM0_Msk : 0x2000_0000 - 0x2000_0FFF
* - \ref SYS_SRAMPC0_SRAM0PM1_Msk : 0x2000_1000 - 0x2000_1FFF
* - \ref SYS_SRAMPC0_SRAM0PM2_Msk : 0x2000_2000 - 0x2000_3FFF
* - \ref SYS_SRAMPC0_SRAM0PM3_Msk : 0x2000_4000 - 0x2000_5FFF
* - \ref SYS_SRAMPC0_SRAM0PM4_Msk : 0x2000_6000 - 0x2000_7FFF
* - \ref SYS_SRAMPC0_SRAM1PM0_Msk : 0x2000_8000 - 0x2000_BFFF
* - \ref SYS_SRAMPC0_SRAM1PM1_Msk : 0x2000_C000 - 0x2000_FFFF
* - \ref SYS_SRAMPC0_SRAM1PM2_Msk : 0x2001_0000 - 0x2001_3FFF
* - \ref SYS_SRAMPC0_SRAM1PM3_Msk : 0x2001_4000 - 0x2001_7FFF
* - \ref SYS_SRAMPC0_SRAM1PM4_Msk : 0x2001_8000 - 0x2001_BFFF
* - \ref SYS_SRAMPC0_SRAM1PM5_Msk : 0x2001_C000 - 0x2001_FFFF
* - \ref SYS_SRAMPC0_SRAM1PM6_Msk : 0x2002_0000 - 0x2002_3FFF
* - \ref SYS_SRAMPC0_SRAM1PM7_Msk : 0x2002_4000 - 0x2002_7FFF
* - \ref SYS_SRAMPC0_SRAM2PM0_Msk : 0x2002_8000 - 0x2002_BFFF
* - \ref SYS_SRAMPC0_SRAM2PM1_Msk : 0x2002_C000 - 0x2002_FFFF
* - \ref SYS_SRAMPC1_SRAM2PM2_Msk : 0x2003_0000 - 0x2003_3FFF
* - \ref SYS_SRAMPC1_SRAM2PM3_Msk : 0x2003_4000 - 0x2003_7FFF
* - \ref SYS_SRAMPC1_SRAM2PM4_Msk : 0x2003_8000 - 0x2003_BFFF
* - \ref SYS_SRAMPC1_SRAM2PM5_Msk : 0x2003_C000 - 0x2003_FFFF
* @param[in] u32PowerMode is SRAM power mode. Including :
* - \ref SYS_SRAMPC0_SRAM_NORMAL
* - \ref SYS_SRAMPC0_SRAM_RETENTION
* - \ref SYS_SRAMPC0_SRAM_POWER_SHUT_DOWN
* - \ref SYS_SRAMPC1_SRAM_NORMAL
* - \ref SYS_SRAMPC1_SRAM_RETENTION
* - \ref SYS_SRAMPC1_SRAM_POWER_SHUT_DOWN
* @return None
* @details This function set system SRAM power mode.
* The register write-protection function should be disabled before using this function.
*/
void SYS_SetSSRAMPowerMode(uint32_t u32SRAMSel, uint32_t u32PowerMode)
{
uint32_t u32SRAMSelPos = 0UL;
/* Get system SRAM power mode setting position */
while(u32SRAMSelPos < 30UL)
{
if(u32SRAMSel & (1 << u32SRAMSelPos))
{
break;
}
else
{
u32SRAMSelPos++;
}
}
/* Set system SRAM power mode setting */
if(u32PowerMode & BIT31)
{
while(SYS->SRAMPC1 & SYS_SRAMPC1_PCBUSY_Msk);
SYS->SRAMPC1 = (SYS->SRAMPC1 & (~u32SRAMSel)) | (u32PowerMode << u32SRAMSelPos);
}
else
{
while(SYS->SRAMPC0 & SYS_SRAMPC0_PCBUSY_Msk);
SYS->SRAMPC0 = (SYS->SRAMPC0 & (~u32SRAMSel)) | (u32PowerMode << u32SRAMSelPos);
}
}
/**
* @brief Set Peripheral SRAM Power Mode
* @param[in] u32SRAMSel is SRAM region selection. Including :
* - \ref SYS_SRAMPC1_CAN_Msk
* - \ref SYS_SRAMPC1_USBD_Msk
* - \ref SYS_SRAMPC1_PDMA0_Msk
* - \ref SYS_SRAMPC1_PDMA1_Msk
* - \ref SYS_SRAMPC1_FMCCACHE_Msk
* - \ref SYS_SRAMPC1_RSA_Msk
* - \ref SYS_SRAMPC1_KS_Msk
* @param[in] u32PowerMode is SRAM power mode. Including :
* - \ref SYS_SRAMPC1_SRAM_NORMAL
* - \ref SYS_SRAMPC1_SRAM_RETENTION
* - \ref SYS_SRAMPC1_SRAM_POWER_SHUT_DOWN
* @return None
* @details This function set peripheral SRAM power mode.
* The register write-protection function should be disabled before using this function.
*/
void SYS_SetPSRAMPowerMode(uint32_t u32SRAMSel, uint32_t u32PowerMode)
{
uint32_t u32SRAMSelPos = 16UL;
/* Get peripheral SRAM power mode setting position */
while(u32SRAMSelPos < 30UL)
{
if(u32SRAMSel & (1 << u32SRAMSelPos))
{
break;
}
else
{
u32SRAMSelPos++;
}
}
/* Set peripheral SRAM power mode setting */
while(SYS->SRAMPC1 & SYS_SRAMPC1_PCBUSY_Msk);
SYS->SRAMPC1 = (SYS->SRAMPC1 & (~u32SRAMSel)) | (u32PowerMode << u32SRAMSelPos);
}
/**
* @brief Set Reference Voltage
* @param[in] u32VRefCTL is reference voltage setting. Including :
* - \ref SYS_VREFCTL_VREF_PIN
* - \ref SYS_VREFCTL_VREF_1_6V
* - \ref SYS_VREFCTL_VREF_2_0V
* - \ref SYS_VREFCTL_VREF_2_5V
* - \ref SYS_VREFCTL_VREF_3_0V
* - \ref SYS_VREFCTL_VREF_AVDD
* @return None
* @details This function select reference voltage.
* The register write-protection function should be disabled before using this function.
*/
void SYS_SetVRef(uint32_t u32VRefCTL)
{
/* Set reference voltage */
SYS->VREFCTL = (SYS->VREFCTL & (~SYS_VREFCTL_VREFCTL_Msk)) | (u32VRefCTL);
}
/**@}*/ /* end of group SYS_EXPORTED_FUNCTIONS */
/**@}*/ /* end of group SYS_Driver */
/**@}*/ /* end of group Standard_Driver */

View File

@ -0,0 +1,687 @@
/**************************************************************************//**
* @file uart.c
* @version V3.00
* @brief M2354 series UART Interface Controller (UART) driver source file
*
* @copyright SPDX-License-Identifier: Apache-2.0
* @copyright Copyright (C) 2020 Nuvoton Technology Corp. All rights reserved.
*****************************************************************************/
#include <stdio.h>
#include "NuMicro.h"
/** @addtogroup Standard_Driver Standard Driver
@{
*/
/** @addtogroup UART_Driver UART Driver
@{
*/
/** @addtogroup UART_EXPORTED_FUNCTIONS UART Exported Functions
@{
*/
/**
* @brief Clear UART specified interrupt flag
*
* @param[in] uart The pointer of the specified UART module.
* @param[in] u32InterruptFlag The specified interrupt of UART module.
* - \ref UART_INTSTS_SWBEINT_Msk : Single-wire Bit Error Detect Interrupt
* - \ref UART_INTSTS_LININT_Msk : LIN Bus interrupt
* - \ref UART_INTSTS_WKINT_Msk : Wake-up interrupt
* - \ref UART_INTSTS_BUFERRINT_Msk : Buffer Error interrupt
* - \ref UART_INTSTS_MODEMINT_Msk : MODEM Status Interrupt
* - \ref UART_INTSTS_RLSINT_Msk : Receive Line Status interrupt
*
* @return None
*
* @details The function is used to clear UART specified interrupt flag.
*/
void UART_ClearIntFlag(UART_T* uart, uint32_t u32InterruptFlag)
{
if(u32InterruptFlag & UART_INTSTS_SWBEINT_Msk) /* Clear Bit Error Detection Interrupt */
{
uart->FIFOSTS = UART_INTSTS_SWBEIF_Msk;
}
if(u32InterruptFlag & UART_INTSTS_RLSINT_Msk) /* Clear Receive Line Status Interrupt */
{
uart->FIFOSTS = UART_FIFOSTS_BIF_Msk | UART_FIFOSTS_FEF_Msk | UART_FIFOSTS_FEF_Msk | UART_FIFOSTS_ADDRDETF_Msk;
}
if(u32InterruptFlag & UART_INTSTS_MODEMINT_Msk) /* Clear MODEM Status Interrupt */
{
uart->MODEMSTS |= UART_MODEMSTS_CTSDETF_Msk;
}
if(u32InterruptFlag & UART_INTSTS_BUFERRINT_Msk) /* Clear Buffer Error Interrupt */
{
uart->FIFOSTS = UART_FIFOSTS_RXOVIF_Msk | UART_FIFOSTS_TXOVIF_Msk;
}
if(u32InterruptFlag & UART_INTSTS_WKINT_Msk) /* Clear Wake-up Interrupt */
{
uart->WKSTS = UART_WKSTS_CTSWKF_Msk | UART_WKSTS_DATWKF_Msk |
UART_WKSTS_RFRTWKF_Msk | UART_WKSTS_RS485WKF_Msk |
UART_WKSTS_TOUTWKF_Msk;
}
if(u32InterruptFlag & UART_INTSTS_LININT_Msk) /* Clear LIN Bus Interrupt */
{
uart->INTSTS = UART_INTSTS_LINIF_Msk;
uart->LINSTS = UART_LINSTS_BITEF_Msk | UART_LINSTS_BRKDETF_Msk |
UART_LINSTS_SLVSYNCF_Msk | UART_LINSTS_SLVIDPEF_Msk |
UART_LINSTS_SLVHEF_Msk | UART_LINSTS_SLVHDETF_Msk ;
}
}
/**
* @brief Disable UART interrupt
*
* @param[in] uart The pointer of the specified UART module.
*
* @return None
*
* @details The function is used to disable UART interrupt.
*/
void UART_Close(UART_T* uart)
{
uart->INTEN = 0ul;
}
/**
* @brief Disable UART auto flow control function
*
* @param[in] uart The pointer of the specified UART module.
*
* @return None
*
* @details The function is used to disable UART auto flow control.
*/
void UART_DisableFlowCtrl(UART_T* uart)
{
uart->INTEN &= ~(UART_INTEN_ATORTSEN_Msk | UART_INTEN_ATOCTSEN_Msk);
}
/**
* @brief Disable UART specified interrupt
*
* @param[in] uart The pointer of the specified UART module.
* @param[in] u32InterruptFlag The specified interrupt of UART module.
* - \ref UART_INTEN_TXENDIEN_Msk : Transmitter Empty Interrupt
* - \ref UART_INTEN_SWBEIEN_Msk : Single-wire Bit Error Detect Interrupt
* - \ref UART_INTEN_ABRIEN_Msk : Auto-baud Rate Interrupt
* - \ref UART_INTEN_LINIEN_Msk : Lin Bus interrupt
* - \ref UART_INTEN_WKIEN_Msk : Wake-up interrupt
* - \ref UART_INTEN_BUFERRIEN_Msk : Buffer Error interrupt
* - \ref UART_INTEN_RXTOIEN_Msk : Rx Time-out Interrupt
* - \ref UART_INTEN_MODEMIEN_Msk : MODEM Status Interrupt
* - \ref UART_INTEN_RLSIEN_Msk : Receive Line Status Interrupt
* - \ref UART_INTEN_THREIEN_Msk : Transmit Holding Register Empty Interrupt
* - \ref UART_INTEN_RDAIEN_Msk : Receive Data Available Interrupt
*
* @return None
*
* @details The function is used to disable UART specified interrupt and disable NVIC UART IRQ.
*/
void UART_DisableInt(UART_T* uart, uint32_t u32InterruptFlag)
{
/* Disable UART specified interrupt */
UART_DISABLE_INT(uart, u32InterruptFlag);
}
/**
* @brief Enable UART auto flow control function
*
* @param[in] uart The pointer of the specified UART module.
*
* @return None
*
* @details The function is used to Enable UART auto flow control.
*/
/**
* @brief Enable UART auto flow control function
*
* @param[in] uart The pointer of the specified UART module.
*
* @return None
*
* @details The function is used to Enable UART auto flow control.
*/
void UART_EnableFlowCtrl(UART_T* uart)
{
/* Set RTS pin output is low level active */
uart->MODEM |= UART_MODEM_RTSACTLV_Msk;
/* Set CTS pin input is low level active */
uart->MODEMSTS |= UART_MODEMSTS_CTSACTLV_Msk;
/* Set RTS and CTS auto flow control enable */
uart->INTEN |= UART_INTEN_ATORTSEN_Msk | UART_INTEN_ATOCTSEN_Msk;
}
/**
* @brief Enable UART specified interrupt
*
* @param[in] uart The pointer of the specified UART module.
* @param[in] u32InterruptFlag The specified interrupt of UART module:
* - \ref UART_INTEN_TXENDIEN_Msk : Transmitter Empty Interrupt
* - \ref UART_INTEN_ABRIEN_Msk : Auto-baud Rate Interrupt
* - \ref UART_INTEN_LINIEN_Msk : Lin Bus interrupt
* - \ref UART_INTEN_WKIEN_Msk : Wake-up interrupt
* - \ref UART_INTEN_BUFERRIEN_Msk : Buffer Error interrupt
* - \ref UART_INTEN_RXTOIEN_Msk : Rx Time-out Interrupt
* - \ref UART_INTEN_MODEMIEN_Msk : MODEM Status Interrupt
* - \ref UART_INTEN_RLSIEN_Msk : Receive Line Status Interrupt
* - \ref UART_INTEN_THREIEN_Msk : Transmit Holding Register Empty Interrupt
* - \ref UART_INTEN_RDAIEN_Msk : Receive Data Available Interrupt
*
* @return None
*
* @details The function is used to enable UART specified interrupt and enable NVIC UART IRQ.
*/
void UART_EnableInt(UART_T* uart, uint32_t u32InterruptFlag)
{
/* Enable UART specified interrupt */
UART_ENABLE_INT(uart, u32InterruptFlag);
}
/**
* @brief Open and set UART function
*
* @param[in] uart The pointer of the specified UART module.
* @param[in] u32baudrate The baudrate of UART module.
*
* @return None
*
* @details This function use to enable UART function and set baud-rate.
*/
void UART_Open(UART_T* uart, uint32_t u32baudrate)
{
uint32_t u32UartClkSrcSel, u32UartClkDivNum;
uint32_t au32ClkTbl[8] = { __HXT, 0ul, __LXT, __HIRC, 0ul, 0ul, 0ul, 0ul};
uint32_t u32BaudDiv = 0ul;
/* Get UART clock source selection and UART clock divider number */
switch((uint32_t)uart)
{
case UART0_BASE:
case UART0_BASE+NS_OFFSET:
u32UartClkSrcSel = CLK_GetModuleClockSource(UART0_MODULE);
u32UartClkDivNum = CLK_GetModuleClockDivider(UART0_MODULE);
if(u32UartClkSrcSel == 4ul)
au32ClkTbl[4] = CLK_GetPCLK0Freq();
break;
case UART1_BASE:
case UART1_BASE+NS_OFFSET:
u32UartClkSrcSel = CLK_GetModuleClockSource(UART1_MODULE);
u32UartClkDivNum = CLK_GetModuleClockDivider(UART1_MODULE);
if(u32UartClkSrcSel == 4ul)
au32ClkTbl[4] = CLK_GetPCLK1Freq();
break;
case UART2_BASE:
case UART2_BASE+NS_OFFSET:
u32UartClkSrcSel = CLK_GetModuleClockSource(UART2_MODULE);
u32UartClkDivNum = CLK_GetModuleClockDivider(UART2_MODULE);
if(u32UartClkSrcSel == 4ul)
au32ClkTbl[4] = CLK_GetPCLK0Freq();
break;
case UART3_BASE:
case UART3_BASE+NS_OFFSET:
u32UartClkSrcSel = CLK_GetModuleClockSource(UART3_MODULE);
u32UartClkDivNum = CLK_GetModuleClockDivider(UART3_MODULE);
if(u32UartClkSrcSel == 4ul)
au32ClkTbl[4] = CLK_GetPCLK1Freq();
break;
case UART4_BASE:
case UART4_BASE+NS_OFFSET:
u32UartClkSrcSel = CLK_GetModuleClockSource(UART4_MODULE);
u32UartClkDivNum = CLK_GetModuleClockDivider(UART4_MODULE);
if(u32UartClkSrcSel == 4ul)
au32ClkTbl[4] = CLK_GetPCLK0Freq();
break;
case UART5_BASE:
case UART5_BASE+NS_OFFSET:
u32UartClkSrcSel = CLK_GetModuleClockSource(UART5_MODULE);
u32UartClkDivNum = CLK_GetModuleClockDivider(UART5_MODULE);
if(u32UartClkSrcSel == 4ul)
au32ClkTbl[4] = CLK_GetPCLK1Freq();
break;
default:
return;
}
/* Select UART function */
uart->FUNCSEL = UART_FUNCSEL_UART;
/* Set UART line configuration */
uart->LINE = UART_WORD_LEN_8 | UART_PARITY_NONE | UART_STOP_BIT_1;
/* Set UART Rx and RTS trigger level */
uart->FIFO &= ~(UART_FIFO_RFITL_Msk | UART_FIFO_RTSTRGLV_Msk);
/* Get PLL clock frequency if UART clock source selection is PLL */
if(u32UartClkSrcSel == 1ul)
{
au32ClkTbl[u32UartClkSrcSel] = CLK_GetPLLClockFreq();
}
/* Set UART baud rate */
if(u32baudrate != 0ul)
{
u32BaudDiv = UART_BAUD_MODE2_DIVIDER((au32ClkTbl[u32UartClkSrcSel]) / (u32UartClkDivNum + 1ul), u32baudrate);
if(u32BaudDiv > 0xFFFFul)
{
uart->BAUD = (UART_BAUD_MODE0 | UART_BAUD_MODE0_DIVIDER((au32ClkTbl[u32UartClkSrcSel]) / (u32UartClkDivNum + 1ul), u32baudrate));
}
else
{
uart->BAUD = (UART_BAUD_MODE2 | u32BaudDiv);
}
}
}
/**
* @brief Read UART data
*
* @param[in] uart The pointer of the specified UART module.
* @param[in] pu8RxBuf The buffer to receive the data of receive FIFO.
* @param[in] u32ReadBytes The the read bytes number of data.
*
* @return u32Count Receive byte count
*
* @details The function is used to read Rx data from RX FIFO and the data will be stored in pu8RxBuf.
*/
uint32_t UART_Read(UART_T* uart, uint8_t pu8RxBuf[], uint32_t u32ReadBytes)
{
uint32_t u32Count, u32delayno;
uint32_t u32Exit = 0ul;
for(u32Count = 0ul; u32Count < u32ReadBytes; u32Count++)
{
u32delayno = 0ul;
while(uart->FIFOSTS & UART_FIFOSTS_RXEMPTY_Msk) /* Check RX empty => failed */
{
u32delayno++;
if(u32delayno >= 0x40000000ul)
{
u32Exit = 1ul;
break;
}
else
{
}
}
if(u32Exit == 1ul)
{
break;
}
else
{
pu8RxBuf[u32Count] = (uint8_t)uart->DAT; /* Get Data from UART RX */
}
}
return u32Count;
}
/**
* @brief Set UART line configuration
*
* @param[in] uart The pointer of the specified UART module.
* @param[in] u32baudrate The register value of baudrate of UART module.
* If u32baudrate = 0, UART baudrate will not change.
* @param[in] u32data_width The data length of UART module.
* - \ref UART_WORD_LEN_5
* - \ref UART_WORD_LEN_6
* - \ref UART_WORD_LEN_7
* - \ref UART_WORD_LEN_8
* @param[in] u32parity The parity setting (none/odd/even/mark/space) of UART module.
* - \ref UART_PARITY_NONE
* - \ref UART_PARITY_ODD
* - \ref UART_PARITY_EVEN
* - \ref UART_PARITY_MARK
* - \ref UART_PARITY_SPACE
* @param[in] u32stop_bits The stop bit length (1/1.5/2 bit) of UART module.
* - \ref UART_STOP_BIT_1
* - \ref UART_STOP_BIT_1_5
* - \ref UART_STOP_BIT_2
*
* @return None
*
* @details This function use to config UART line setting.
*/
void UART_SetLineConfig(UART_T* uart, uint32_t u32baudrate, uint32_t u32data_width, uint32_t u32parity, uint32_t u32stop_bits)
{
uint32_t u32UartClkSrcSel, u32UartClkDivNum;
uint32_t au32ClkTbl[8] = { __HXT, 0ul, __LXT, __HIRC, 0ul, 0ul, 0ul, 0ul};
uint32_t u32BaudDiv = 0ul;
/* Get UART clock source selection and UART clock divider number */
switch((uint32_t)uart)
{
case UART0_BASE:
case UART0_BASE+NS_OFFSET:
u32UartClkSrcSel = CLK_GetModuleClockSource(UART0_MODULE);
u32UartClkDivNum = CLK_GetModuleClockDivider(UART0_MODULE);
if(u32UartClkSrcSel == 4ul)
au32ClkTbl[4] = CLK_GetPCLK0Freq();
break;
case UART1_BASE:
case UART1_BASE+NS_OFFSET:
u32UartClkSrcSel = CLK_GetModuleClockSource(UART1_MODULE);
u32UartClkDivNum = CLK_GetModuleClockDivider(UART1_MODULE);
if(u32UartClkSrcSel == 4ul)
au32ClkTbl[4] = CLK_GetPCLK1Freq();
break;
case UART2_BASE:
case UART2_BASE+NS_OFFSET:
u32UartClkSrcSel = CLK_GetModuleClockSource(UART2_MODULE);
u32UartClkDivNum = CLK_GetModuleClockDivider(UART2_MODULE);
if(u32UartClkSrcSel == 4ul)
au32ClkTbl[4] = CLK_GetPCLK0Freq();
break;
case UART3_BASE:
case UART3_BASE+NS_OFFSET:
u32UartClkSrcSel = CLK_GetModuleClockSource(UART3_MODULE);
u32UartClkDivNum = CLK_GetModuleClockDivider(UART3_MODULE);
if(u32UartClkSrcSel == 4ul)
au32ClkTbl[4] = CLK_GetPCLK1Freq();
break;
case UART4_BASE:
case UART4_BASE+NS_OFFSET:
u32UartClkSrcSel = CLK_GetModuleClockSource(UART4_MODULE);
u32UartClkDivNum = CLK_GetModuleClockDivider(UART4_MODULE);
if(u32UartClkSrcSel == 4ul)
au32ClkTbl[4] = CLK_GetPCLK0Freq();
break;
case UART5_BASE:
case UART5_BASE+NS_OFFSET:
u32UartClkSrcSel = CLK_GetModuleClockSource(UART5_MODULE);
u32UartClkDivNum = CLK_GetModuleClockDivider(UART5_MODULE);
if(u32UartClkSrcSel == 4ul)
au32ClkTbl[4] = CLK_GetPCLK1Freq();
break;
default:
return;
}
/* Get PLL clock frequency if UART clock source selection is PLL */
if(u32UartClkSrcSel == 1ul)
{
au32ClkTbl[1] = CLK_GetPLLClockFreq();
}
/* Set UART baud rate */
if(u32baudrate != 0ul)
{
u32BaudDiv = UART_BAUD_MODE2_DIVIDER((au32ClkTbl[u32UartClkSrcSel]) / (u32UartClkDivNum + 1ul), u32baudrate);
if(u32BaudDiv > 0xFFFFul)
{
uart->BAUD = (UART_BAUD_MODE0 | UART_BAUD_MODE0_DIVIDER((au32ClkTbl[u32UartClkSrcSel]) / (u32UartClkDivNum + 1ul), u32baudrate));
}
else
{
uart->BAUD = (UART_BAUD_MODE2 | u32BaudDiv);
}
}
/* Set UART line configuration */
uart->LINE = u32data_width | u32parity | u32stop_bits;
}
/**
* @brief Set Rx timeout count
*
* @param[in] uart The pointer of the specified UART module.
* @param[in] u32TOC Rx timeout counter.
*
* @return None
*
* @details This function use to set Rx timeout count.
*/
void UART_SetTimeoutCnt(UART_T* uart, uint32_t u32TOC)
{
/* Set time-out interrupt comparator */
uart->TOUT = (uart->TOUT & ~UART_TOUT_TOIC_Msk) | (u32TOC);
/* Set time-out counter enable */
uart->INTEN |= UART_INTEN_TOCNTEN_Msk;
}
/**
* @brief Select and configure IrDA function
*
* @param[in] uart The pointer of the specified UART module.
* @param[in] u32Buadrate The baudrate of UART module.
* @param[in] u32Direction The direction of UART module in IrDA mode:
* - \ref UART_IRDA_TXEN
* - \ref UART_IRDA_RXEN
*
* @return None
*
* @details The function is used to configure IrDA relative settings. It consists of TX or RX mode and baudrate.
*/
void UART_SelectIrDAMode(UART_T* uart, uint32_t u32Buadrate, uint32_t u32Direction)
{
uint32_t u32UartClkSrcSel = 0UL, u32UartClkDivNum = 1UL;
uint32_t au32ClkTbl[8] = { __HXT, 0ul, __LXT, __HIRC, 0ul, 0ul, 0ul, 0ul};
uint32_t u32BaudDiv;
/* Select IrDA function mode */
uart->FUNCSEL = UART_FUNCSEL_IrDA;
/* Get UART clock source selection and UART clock divider number */
switch((uint32_t)uart)
{
case UART0_BASE:
case UART0_BASE+NS_OFFSET:
u32UartClkSrcSel = CLK_GetModuleClockSource(UART0_MODULE);
u32UartClkDivNum = CLK_GetModuleClockDivider(UART0_MODULE);
if(u32UartClkSrcSel == 4ul)
au32ClkTbl[4] = CLK_GetPCLK0Freq();
break;
case UART1_BASE:
case UART1_BASE+NS_OFFSET:
u32UartClkSrcSel = CLK_GetModuleClockSource(UART1_MODULE);
u32UartClkDivNum = CLK_GetModuleClockDivider(UART1_MODULE);
if(u32UartClkSrcSel == 4ul)
au32ClkTbl[4] = CLK_GetPCLK1Freq();
break;
case UART2_BASE:
case UART2_BASE+NS_OFFSET:
u32UartClkSrcSel = CLK_GetModuleClockSource(UART2_MODULE);
u32UartClkDivNum = CLK_GetModuleClockDivider(UART2_MODULE);
if(u32UartClkSrcSel == 4ul)
au32ClkTbl[4] = CLK_GetPCLK0Freq();
break;
case UART3_BASE:
case UART3_BASE+NS_OFFSET:
u32UartClkSrcSel = CLK_GetModuleClockSource(UART3_MODULE);
u32UartClkDivNum = CLK_GetModuleClockDivider(UART3_MODULE);
if(u32UartClkSrcSel == 4ul)
au32ClkTbl[4] = CLK_GetPCLK1Freq();
break;
case UART4_BASE:
case UART4_BASE+NS_OFFSET:
u32UartClkSrcSel = CLK_GetModuleClockSource(UART4_MODULE);
u32UartClkDivNum = CLK_GetModuleClockDivider(UART4_MODULE);
if(u32UartClkSrcSel == 4ul)
au32ClkTbl[4] = CLK_GetPCLK0Freq();
break;
case UART5_BASE:
case UART5_BASE+NS_OFFSET:
u32UartClkSrcSel = CLK_GetModuleClockSource(UART5_MODULE);
u32UartClkDivNum = CLK_GetModuleClockDivider(UART5_MODULE);
if(u32UartClkSrcSel == 4ul)
au32ClkTbl[4] = CLK_GetPCLK1Freq();
break;
default:
return;
}
/* Get PLL clock frequency if UART clock source selection is PLL */
if(u32UartClkSrcSel == 1ul)
{
au32ClkTbl[1] = CLK_GetPLLClockFreq();
}
/* Set UART IrDA baud rate in mode 0 */
if(u32Buadrate != 0ul)
{
u32BaudDiv = UART_BAUD_MODE0_DIVIDER((au32ClkTbl[u32UartClkSrcSel]) / (u32UartClkDivNum + 1ul), u32Buadrate);
if(u32BaudDiv < 0xFFFFul)
{
uart->BAUD = (UART_BAUD_MODE0 | u32BaudDiv);
}
}
/* Configure IrDA relative settings */
if(u32Direction == UART_IRDA_RXEN)
{
uart->IRDA |= UART_IRDA_RXINV_Msk; /* Rx signal is inverse */
uart->IRDA &= ~UART_IRDA_TXEN_Msk;
}
else
{
uart->IRDA &= ~UART_IRDA_TXINV_Msk; /* Tx signal is not inverse */
uart->IRDA |= UART_IRDA_TXEN_Msk;
}
}
/**
* @brief Select and configure RS485 function
*
* @param[in] uart The pointer of the specified UART module.
* @param[in] u32Mode The operation mode(NMM/AUD/AAD).
* - \ref UART_ALTCTL_RS485NMM_Msk
* - \ref UART_ALTCTL_RS485AUD_Msk
* - \ref UART_ALTCTL_RS485AAD_Msk
* @param[in] u32Addr The RS485 address.
*
* @return None
*
* @details The function is used to set RS485 relative setting.
*/
void UART_SelectRS485Mode(UART_T* uart, uint32_t u32Mode, uint32_t u32Addr)
{
/* Select UART RS485 function mode */
uart->FUNCSEL = UART_FUNCSEL_RS485;
/* Set RS585 configuration */
uart->ALTCTL &= ~(UART_ALTCTL_RS485NMM_Msk | UART_ALTCTL_RS485AUD_Msk | UART_ALTCTL_RS485AAD_Msk | UART_ALTCTL_ADDRMV_Msk);
uart->ALTCTL |= (u32Mode | (u32Addr << UART_ALTCTL_ADDRMV_Pos));
}
/**
* @brief Select and configure LIN function
*
* @param[in] uart The pointer of the specified UART module.
* @param[in] u32Mode The LIN direction :
* - \ref UART_ALTCTL_LINTXEN_Msk
* - \ref UART_ALTCTL_LINRXEN_Msk
* @param[in] u32BreakLength The breakfield length.
*
* @return None
*
* @details The function is used to set LIN relative setting.
*/
void UART_SelectLINMode(UART_T* uart, uint32_t u32Mode, uint32_t u32BreakLength)
{
/* Select LIN function mode */
uart->FUNCSEL = UART_FUNCSEL_LIN;
/* Select LIN function setting : Tx enable, Rx enable and break field length */
uart->ALTCTL &= ~(UART_ALTCTL_LINTXEN_Msk | UART_ALTCTL_LINRXEN_Msk | UART_ALTCTL_BRKFL_Msk);
uart->ALTCTL |= (u32Mode | (u32BreakLength << UART_ALTCTL_BRKFL_Pos));
}
/**
* @brief Write UART data
*
* @param[in] uart The pointer of the specified UART module.
* @param[in] pu8TxBuf The buffer to send the data to UART transmission FIFO.
* @param[out] u32WriteBytes The byte number of data.
*
* @return u32Count transfer byte count
*
* @details The function is to write data into TX buffer to transmit data by UART.
*/
uint32_t UART_Write(UART_T* uart, uint8_t pu8TxBuf[], uint32_t u32WriteBytes)
{
uint32_t u32Count, u32delayno;
uint32_t u32Exit = 0ul;
for(u32Count = 0ul; u32Count != u32WriteBytes; u32Count++)
{
u32delayno = 0ul;
while(UART_IS_TX_FULL(uart)) /* Wait Tx not full and Time-out manner */
{
u32delayno++;
if(u32delayno >= 0x40000000ul)
{
u32Exit = 1ul;
break;
}
else
{
}
}
if(u32Exit == 1ul)
{
break;
}
else
{
uart->DAT = pu8TxBuf[u32Count]; /* Send UART Data from buffer */
}
}
return u32Count;
}
/**
* @brief Select Single Wire mode function
*
* @param[in] uart The pointer of the specified UART module.
*
* @return None
*
* @details The function is used to select Single Wire mode.
*/
void UART_SelectSingleWireMode(UART_T *uart)
{
/* Select UART SingleWire function mode */
uart->FUNCSEL = ((uart->FUNCSEL & (~UART_FUNCSEL_FUNCSEL_Msk)) | UART_FUNCSEL_SINGLE_WIRE);
}
/**@}*/ /* end of group UART_EXPORTED_FUNCTIONS */
/**@}*/ /* end of group UART_Driver */
/**@}*/ /* end of group Standard_Driver */

View File

@ -0,0 +1,564 @@
/**************************************************************************//**
* @file system_M2354.c
* @version V2.00
* @brief System Setting Source File
*
* @copyright SPDX-License-Identifier: Apache-2.0
* @copyright Copyright (C) 2020 Nuvoton Technology Corp. All rights reserved.
******************************************************************************/
#if defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) /* ARM Compiler 6 */
#include <arm_cmse.h>
#endif
#include <stdio.h>
#include <stdint.h>
#include "NuMicro.h"
#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U)
#include "partition_M2354.h"
#endif
extern void *InterruptVectors; /* see startup file */
/*----------------------------------------------------------------------------
Clock Variable definitions
*----------------------------------------------------------------------------*/
uint32_t SystemCoreClock = __HSI; /*!< System Clock Frequency (Core Clock) */
uint32_t CyclesPerUs = (__HSI / 1000000UL);/*!< Cycles per micro second */
uint32_t PllClock = __HSI; /*!< PLL Output Clock Frequency */
void FMC_NSBA_Setup(void);
void SCU_Setup(void);
void NSC_Init(void);
void TZ_SAU_Setup(void);
#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U)
extern void SCU_IRQHandler(void);
#else
extern void SCU_IRQHandler(void)__attribute__((noreturn));
#endif
#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U)
/**
* @brief Setup Non-secure boundary
*
* @details This function is used to set Non-secure boundary according to
* the configuration of partition header file
*/
void FMC_NSBA_Setup(void)
{
/* Skip NSBA Setupt according config */
if(FMC_INIT_NSBA == 0)
return;
/* Check if NSBA value with current active NSBA */
if(SCU->FNSADDR != FMC_SECURE_ROM_SIZE)
{
/* Unlock Protected Register */
SYS_UnlockReg();
/* Enable ISP and config update */
FMC->ISPCTL = FMC_ISPCTL_ISPEN_Msk | FMC_ISPCTL_CFGUEN_Msk;
/* Config Base of NSBA */
FMC->ISPADDR = FMC_NSCBA_BASE ;
/* Read Non-secure base address config */
FMC->ISPCMD = FMC_ISPCMD_READ;
FMC->ISPTRG = FMC_ISPTRG_ISPGO_Msk;
while(FMC->ISPTRG);
//while(PA0);
/* Setting NSBA when it is empty */
if(FMC->ISPDAT != 0xfffffffful)
{
/* Erase old setting */
FMC->ISPCMD = FMC_ISPCMD_PAGE_ERASE;
FMC->ISPTRG = FMC_ISPTRG_ISPGO_Msk;
while(FMC->ISPTRG);
}
/* Set new base */
FMC->ISPDAT = FMC_SECURE_ROM_SIZE;
FMC->ISPCMD = FMC_ISPCMD_PROGRAM;
FMC->ISPTRG = FMC_ISPTRG_ISPGO_Msk;
while(FMC->ISPTRG);
/* Force Chip Reset to valid new setting */
SYS->IPRST0 = SYS_IPRST0_CHIPRST_Msk;
}
}
/**
\brief Setup SCU Configuration Unit
\details
*/
void SCU_Setup(void)
{
int32_t i;
SCU->PNSSET[0] = SCU_INIT_PNSSET0_VAL;
SCU->PNSSET[1] = SCU_INIT_PNSSET1_VAL;
SCU->PNSSET[2] = SCU_INIT_PNSSET2_VAL;
SCU->PNSSET[3] = SCU_INIT_PNSSET3_VAL;
SCU->PNSSET[4] = SCU_INIT_PNSSET4_VAL;
SCU->PNSSET[5] = SCU_INIT_PNSSET5_VAL;
SCU->PNSSET[6] = SCU_INIT_PNSSET6_VAL;
SCU->IONSSET[0] = SCU_INIT_IONSSET0_VAL;
SCU->IONSSET[1] = SCU_INIT_IONSSET1_VAL;
SCU->IONSSET[2] = SCU_INIT_IONSSET2_VAL;
SCU->IONSSET[3] = SCU_INIT_IONSSET3_VAL;
SCU->IONSSET[4] = SCU_INIT_IONSSET4_VAL;
SCU->IONSSET[5] = SCU_INIT_IONSSET5_VAL;
SCU->IONSSET[6] = SCU_INIT_IONSSET6_VAL;
SCU->IONSSET[7] = SCU_INIT_IONSSET7_VAL;
/* Set Non-secure SRAM */
for(i = 15; i >= SCU_SECURE_SRAM_SIZE / 16384; i--)
{
SCU->SRAMNSSET |= (1U << i);
}
/* Set interrupt to non-secure according to PNNSET settings */
if(SCU_INIT_PNSSET0_VAL & BIT9) NVIC->ITNS[1] |= BIT22; /* Int of USBH_INT */
if(SCU_INIT_PNSSET0_VAL & BIT13) NVIC->ITNS[2] |= BIT0 ; /* Int of SDHOST0_INT */
if(SCU_INIT_PNSSET0_VAL & BIT24) NVIC->ITNS[3] |= BIT2 ; /* Int of PDMA1_INT */
if(SCU_INIT_PNSSET1_VAL & BIT18) NVIC->ITNS[2] |= BIT7 ; /* Int of CRYPTO */
if(SCU_INIT_PNSSET2_VAL & BIT2) NVIC->ITNS[3] |= BIT15; /* Int of EWDT_INT */
if(SCU_INIT_PNSSET2_VAL & BIT2) NVIC->ITNS[3] |= BIT16; /* Int of EWWDT_INT */
if(SCU_INIT_PNSSET2_VAL & BIT3) NVIC->ITNS[1] |= BIT10; /* Int of EADC0_INT */
if(SCU_INIT_PNSSET2_VAL & BIT3) NVIC->ITNS[1] |= BIT11; /* Int of EADC1_INT */
if(SCU_INIT_PNSSET2_VAL & BIT3) NVIC->ITNS[1] |= BIT14; /* Int of EADC2_INT */
if(SCU_INIT_PNSSET2_VAL & BIT3) NVIC->ITNS[1] |= BIT15; /* Int of EADC3_INT */
if(SCU_INIT_PNSSET2_VAL & BIT5) NVIC->ITNS[1] |= BIT12; /* Int of ACMP01_INT */
if(SCU_INIT_PNSSET2_VAL & BIT7) NVIC->ITNS[1] |= BIT9 ; /* Int of DAC_INT */
if(SCU_INIT_PNSSET2_VAL & BIT8) NVIC->ITNS[2] |= BIT4 ; /* Int of I2S0_INT */
if(SCU_INIT_PNSSET2_VAL & BIT13) NVIC->ITNS[1] |= BIT23; /* Int of USBOTG_INT */
if(SCU_INIT_PNSSET2_VAL & BIT17) NVIC->ITNS[1] |= BIT2 ; /* Int of TMR2_INT */
if(SCU_INIT_PNSSET2_VAL & BIT17) NVIC->ITNS[1] |= BIT3 ; /* Int of TMR3_INT */
if(SCU_INIT_PNSSET2_VAL & BIT18) NVIC->ITNS[3] |= BIT18; /* Int of TMR4_INT */
if(SCU_INIT_PNSSET2_VAL & BIT18) NVIC->ITNS[3] |= BIT19; /* Int of TMR5_INT */
if(SCU_INIT_PNSSET2_VAL & BIT24) NVIC->ITNS[0] |= BIT25; /* Int of EPWM0_P0_INT */
if(SCU_INIT_PNSSET2_VAL & BIT24) NVIC->ITNS[0] |= BIT26; /* Int of EPWM0_P1_INT */
if(SCU_INIT_PNSSET2_VAL & BIT24) NVIC->ITNS[0] |= BIT27; /* Int of EPWM0_P2_INT */
if(SCU_INIT_PNSSET2_VAL & BIT25) NVIC->ITNS[0] |= BIT29; /* Int of EPWM1_P0_INT */
if(SCU_INIT_PNSSET2_VAL & BIT25) NVIC->ITNS[0] |= BIT30; /* Int of EPWM1_P1_INT */
if(SCU_INIT_PNSSET2_VAL & BIT25) NVIC->ITNS[0] |= BIT31; /* Int of EPWM1_P2_INT */
if(SCU_INIT_PNSSET2_VAL & BIT26) NVIC->ITNS[2] |= BIT14; /* Int of BPWM0_INT */
if(SCU_INIT_PNSSET2_VAL & BIT27) NVIC->ITNS[2] |= BIT15; /* Int of BPWM1_INT */
if(SCU_INIT_PNSSET3_VAL & BIT0) NVIC->ITNS[0] |= BIT22; /* Int of QSPI0_INT */
if(SCU_INIT_PNSSET3_VAL & BIT1) NVIC->ITNS[0] |= BIT23; /* Int of SPI0_INT */
if(SCU_INIT_PNSSET3_VAL & BIT2) NVIC->ITNS[1] |= BIT19; /* Int of SPI1_INT */
if(SCU_INIT_PNSSET3_VAL & BIT3) NVIC->ITNS[1] |= BIT20; /* Int of SPI2_INT */
if(SCU_INIT_PNSSET3_VAL & BIT4) NVIC->ITNS[1] |= BIT30; /* Int of SPI3_INT */
if(SCU_INIT_PNSSET3_VAL & BIT16) NVIC->ITNS[1] |= BIT4 ; /* Int of UART0_INT */
if(SCU_INIT_PNSSET3_VAL & BIT17) NVIC->ITNS[1] |= BIT5 ; /* Int of UART1_INT */
if(SCU_INIT_PNSSET3_VAL & BIT18) NVIC->ITNS[1] |= BIT16; /* Int of UART2_INT */
if(SCU_INIT_PNSSET3_VAL & BIT19) NVIC->ITNS[1] |= BIT17; /* Int of UART3_INT */
if(SCU_INIT_PNSSET3_VAL & BIT20) NVIC->ITNS[2] |= BIT10; /* Int of UART4_INT */
if(SCU_INIT_PNSSET3_VAL & BIT21) NVIC->ITNS[2] |= BIT11; /* Int of UART5_INT */
if(SCU_INIT_PNSSET4_VAL & BIT0) NVIC->ITNS[1] |= BIT6 ; /* Int of I2C0_INT */
if(SCU_INIT_PNSSET4_VAL & BIT1) NVIC->ITNS[1] |= BIT7 ; /* Int of I2C1_INT */
if(SCU_INIT_PNSSET4_VAL & BIT2) NVIC->ITNS[2] |= BIT18; /* Int of I2C2_INT */
if(SCU_INIT_PNSSET4_VAL & BIT16) NVIC->ITNS[1] |= BIT26; /* Int of SC0_INT */
if(SCU_INIT_PNSSET4_VAL & BIT17) NVIC->ITNS[1] |= BIT27; /* Int of SC1_INT */
if(SCU_INIT_PNSSET4_VAL & BIT18) NVIC->ITNS[1] |= BIT28; /* Int of SC2_INT */
if(SCU_INIT_PNSSET5_VAL & BIT0) NVIC->ITNS[1] |= BIT24; /* Int of CAN0_INT */
if(SCU_INIT_PNSSET5_VAL & BIT16) NVIC->ITNS[2] |= BIT20; /* Int of QEI0_INT */
if(SCU_INIT_PNSSET5_VAL & BIT17) NVIC->ITNS[2] |= BIT21; /* Int of QEI1_INT */
if(SCU_INIT_PNSSET5_VAL & BIT20) NVIC->ITNS[2] |= BIT22; /* Int of ECAP0_INT */
if(SCU_INIT_PNSSET5_VAL & BIT21) NVIC->ITNS[2] |= BIT23; /* Int of ECAP1_INT */
if(SCU_INIT_PNSSET5_VAL & BIT25) NVIC->ITNS[3] |= BIT5 ; /* Int of TRNG_INT */
if(SCU_INIT_PNSSET5_VAL & BIT27) NVIC->ITNS[3] |= BIT4 ; /* Int of LCD_INT */
if(SCU_INIT_PNSSET6_VAL & BIT0) NVIC->ITNS[1] |= BIT21; /* Int of USBD_INT */
if(SCU_INIT_PNSSET6_VAL & BIT16) NVIC->ITNS[2] |= BIT12; /* Int of USCI0_INT */
if(SCU_INIT_PNSSET6_VAL & BIT17) NVIC->ITNS[2] |= BIT13; /* Int of USCI1_INT */
if(SCU_INIT_IONSSET_VAL & BIT0) NVIC->ITNS[0] |= BIT16; /* Int of PA */
if(SCU_INIT_IONSSET_VAL & BIT1) NVIC->ITNS[0] |= BIT17; /* Int of PB */
if(SCU_INIT_IONSSET_VAL & BIT2) NVIC->ITNS[0] |= BIT18; /* Int of PC */
if(SCU_INIT_IONSSET_VAL & BIT3) NVIC->ITNS[0] |= BIT19; /* Int of PD */
if(SCU_INIT_IONSSET_VAL & BIT4) NVIC->ITNS[0] |= BIT20; /* Int of PE */
if(SCU_INIT_IONSSET_VAL & BIT5) NVIC->ITNS[0] |= BIT21; /* Int of PF */
if(SCU_INIT_IONSSET_VAL & BIT6) NVIC->ITNS[2] |= BIT8 ; /* Int of PG */
if(SCU_INIT_IONSSET_VAL & BIT7) NVIC->ITNS[2] |= BIT24; /* Int of PH */
if(SCU_INIT_IONSSET_VAL & BIT8) NVIC->ITNS[0] |= BIT10; /* Int of EINT0 */
if(SCU_INIT_IONSSET_VAL & BIT9) NVIC->ITNS[0] |= BIT11; /* Int of EINT1 */
if(SCU_INIT_IONSSET_VAL & BIT10) NVIC->ITNS[0] |= BIT12; /* Int of EINT2 */
if(SCU_INIT_IONSSET_VAL & BIT11) NVIC->ITNS[0] |= BIT13; /* Int of EINT3 */
if(SCU_INIT_IONSSET_VAL & BIT12) NVIC->ITNS[0] |= BIT14; /* Int of EINT4 */
if(SCU_INIT_IONSSET_VAL & BIT13) NVIC->ITNS[0] |= BIT15; /* Int of EINT5 */
if(SCU_INIT_IONSSET_VAL & BIT14) NVIC->ITNS[2] |= BIT9; /* Int of EINT6 */
if(SCU_INIT_IONSSET_VAL & BIT15) NVIC->ITNS[2] |= BIT25; /* Int of EINT7 */
/* Enable SCU Int status */
SCU->SVIOIEN = (uint32_t)(-1);
SCU->PVIOIEN = (uint32_t)(-1);
NVIC_EnableIRQ(SCU_IRQn);
}
#if defined( __ICCARM__ )
__WEAK
#else
__attribute__((weak))
#endif
void SCU_IRQHandler(void)
{
char const *master[] = {"CPU", 0, 0, "PDMA0", "SDH0", "CRPT", "USBH", 0, 0, 0, 0, "PDMA1"};
char const *ipname[] = {"APB0", "APB1", 0, 0, "GPIO", "EBI", "USBH", "CRC", "SDH0", 0, "PDMA0", "PDMA1"
, "SRAM0", "SRAM1", "FMC", "FLASH", "SCU", "SYS", "CRPT", "KS", "SIORAM"
};
const uint8_t info[] = {0x34, 0x3C, 0, 0, 0x44, 0x4C, 0x54, 0x5C, 0x64, 0, 0x74, 0x7C, 0x84, 0x8C, 0x94, 0x9C, 0xA4, 0xAC, 0xB4, 0xBC, 0xC4};
uint32_t u32Reg, u32Addr;
uint32_t i;
/* TrustZone access policy */
u32Reg = SCU->SVINTSTS;
if(u32Reg)
{
/* Get violation address and source */
for(i = 0; i < sizeof(ipname); i++)
{
if(u32Reg & (1 << i))
{
u32Addr = M32(SCU_BASE + info[i] + 4);
printf(" %s(0x%08x) Alarm! illegal access by %s\n", ipname[i], u32Addr, master[M32(SCU_BASE + info[i])]);
SCU->SVINTSTS = (1 << i);
break;
}
}
}
/* Privilege */
u32Reg = SCU->PVINTSTS;
if(u32Reg)
{
/* Get violation address and source */
for(i = 0; i < sizeof(ipname); i++)
{
if(u32Reg & (1 << i))
{
printf("\n%s Alarm! Caused by unprivilege access\n\n", ipname[i]);
SCU->PVINTSTS = (1 << i);
break;
}
}
}
}
/**
\brief Setup a Nonsecure callable Region
\details The base and limit of Nonsecure callable region is dependent on the
application code size.
*/
void NSC_Init(void)
{
uint32_t u32Region;
uint32_t u32Base, u32Limit;
#if defined (__ICCARM__)
# pragma section = "NSC"
u32Base = (uint32_t)__section_begin("NSC");
u32Limit = (uint32_t)__section_end("NSC");
#elif defined(__ARMCC_VERSION)
#pragma clang diagnostic push
#pragma clang diagnostic ignored "-Wdollar-in-identifier-extension"
extern uint32_t Image$$NSC_ROM$$XO$$Base[];
extern uint32_t Image$$NSC_ROM$$XO$$Limit[];
u32Base = (uint32_t)Image$$NSC_ROM$$XO$$Base;
u32Limit = (uint32_t)Image$$NSC_ROM$$XO$$Limit;
#pragma clang diagnostic pop
#else
extern uint32_t __start_NSC[];
extern uint32_t __end_NSC[];
u32Base = (uint32_t)__start_NSC;
u32Limit = (uint32_t)__end_NSC;
#endif
/* SAU region 3 is dedicated for NSC */
u32Region = 3;
SAU->RNR = (u32Region & SAU_RNR_REGION_Msk);
SAU->RBAR = (u32Base & SAU_RBAR_BADDR_Msk);
SAU->RLAR = (u32Limit & SAU_RLAR_LADDR_Msk) |
((1ul << SAU_RLAR_NSC_Pos) & SAU_RLAR_NSC_Msk) | 1ul;
}
/**
\brief Setup a SAU Region
\details Writes the region information contained in SAU_Region to the
registers SAU_RNR, SAU_RBAR, and SAU_RLAR
*/
void TZ_SAU_Setup(void)
{
#if defined (__SAU_PRESENT) && (__SAU_PRESENT == 1U)
#if defined (SAU_INIT_REGION0) && (SAU_INIT_REGION0 == 1U)
SAU_INIT_REGION(0);
#endif
#if defined (SAU_INIT_REGION1) && (SAU_INIT_REGION1 == 1U)
SAU_INIT_REGION(1);
#endif
#if defined (SAU_INIT_REGION2) && (SAU_INIT_REGION2 == 1U)
SAU_INIT_REGION(2);
#endif
#if defined (SAU_INIT_REGION3) && (SAU_INIT_REGION3 == 1U)
SAU_INIT_REGION(3);
#endif
#if defined (SAU_INIT_REGION4) && (SAU_INIT_REGION4 == 1U)
SAU_INIT_REGION(4);
#endif
#if defined (SAU_INIT_REGION5) && (SAU_INIT_REGION5 == 1U)
SAU_INIT_REGION(5);
#endif
#if defined (SAU_INIT_REGION6) && (SAU_INIT_REGION6 == 1U)
SAU_INIT_REGION(6);
#endif
#if defined (SAU_INIT_REGION7) && (SAU_INIT_REGION7 == 1U)
SAU_INIT_REGION(7);
#endif
/* repeat this for all possible SAU regions */
#if defined (SAU_INIT_CTRL) && (SAU_INIT_CTRL == 1U)
SAU->CTRL = ((SAU_INIT_CTRL_ENABLE << SAU_CTRL_ENABLE_Pos) & SAU_CTRL_ENABLE_Msk) |
((SAU_INIT_CTRL_ALLNS << SAU_CTRL_ALLNS_Pos) & SAU_CTRL_ALLNS_Msk) ;
#endif
#endif /* defined (__SAU_PRESENT) && (__SAU_PRESENT == 1U) */
#if defined (SCB_CSR_AIRCR_INIT) && (SCB_CSR_AIRCR_INIT == 1U)
SCB->SCR = (SCB->SCR & ~(SCB_SCR_SLEEPDEEPS_Msk)) |
((SCB_CSR_DEEPSLEEPS_VAL << SCB_SCR_SLEEPDEEPS_Pos) & SCB_SCR_SLEEPDEEPS_Msk);
SCB->AIRCR = (0x05FA << 16) |
((SCB_AIRCR_SYSRESETREQS_VAL << SCB_AIRCR_SYSRESETREQS_Pos) & SCB_AIRCR_SYSRESETREQS_Msk) |
((SCB_AIRCR_BFHFNMINS_VAL << SCB_AIRCR_BFHFNMINS_Pos) & SCB_AIRCR_BFHFNMINS_Msk) |
((SCB_AIRCR_PRIS_VAL << SCB_AIRCR_PRIS_Pos) & SCB_AIRCR_PRIS_Msk);
#endif /* defined (SCB_CSR_AIRCR_INIT) && (SCB_CSR_AIRCR_INIT == 1U) */
#if defined (SCB_ICSR_INIT) && (SCB_ICSR_INIT == 1U)
SCB->ICSR = (SCB->ICSR & ~(SCB_ICSR_STTNS_Msk)) |
((SCB_ICSR_STTNS_VAL << SCB_ICSR_STTNS_Pos) & SCB_ICSR_STTNS_Msk);
#endif /* defined (SCB_ICSR_INIT) && (SCB_ICSR_INIT == 1U) */
/* repeat this for all possible ITNS elements */
/* Initial Nonsecure callable region */
NSC_Init();
}
#else
#if defined( __ICCARM__ )
__WEAK
#else
__attribute__((weak))
#endif
void SCU_IRQHandler(void)
{
while(1);
}
#endif
/**
* @brief Update the Variable SystemCoreClock
*
* @details This function is used to update the variable SystemCoreClock
* and must be called whenever the core clock is changed.
*/
void SystemCoreClockUpdate(void)
{
/* Update PLL Clock */
PllClock = CLK_GetPLLClockFreq();
/* Update System Core Clock */
SystemCoreClock = CLK_GetCPUFreq();
/* Update Cycles per micro second */
CyclesPerUs = (SystemCoreClock + 500000UL) / 1000000UL;
}
/**
* @brief System Initialization
*
* @details The necessary initialization of system. Global variables are forbidden here.
*/
void SystemInit(void)
{
#if 0
if((__PC() & NS_OFFSET) == 0)
{
/* Unlock protected registers */
do
{
SYS->REGLCTL = 0x59;
SYS->REGLCTL = 0x16;
SYS->REGLCTL = 0x88;
}
while(!SYS->REGLCTL);
/* Enable Crypto power switch */
SYS->PSWCTL = SYS_PSWCTL_CRPTPWREN_Msk;
/* Enable all GPIO, SRAM and Trace clock */
CLK->AHBCLK |= (0xffful << 20) | (1ul << 14);
}
#endif
#if defined (__VTOR_PRESENT) && (__VTOR_PRESENT == 1U)
SCB->VTOR = (uint32_t) &InterruptVectors;
#endif
#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3)
TZ_SAU_Setup();
SCU_Setup();
FMC_NSBA_Setup();
#endif
#ifdef INIT_SYSCLK_AT_BOOTING
#endif
}
#if USE_ASSERT
/**
* @brief Assert Error Message
*
* @param[in] file the source file name
* @param[in] line line number
*
* @details The function prints the source file name and line number where
* the ASSERT_PARAM() error occurs, and then stops in an infinite loop.
*/
void AssertError(uint8_t * file, uint32_t line)
{
printf("[%s] line %d : wrong parameters.\r\n", file, line);
/* Infinite loop */
while(1) ;
}
#endif
#if (defined(__ICCARM__) && (__VER__ >= 7080000) && (__VER__ < 8020000))
#if (__ARM_FEATURE_CMSE == 3U)
/**
\brief Get Process Stack Pointer (non-secure)
\details Returns the current value of the non-secure Process Stack Pointer (PSP) when in secure state.
\return PSP Register value
*/
uint32_t __TZ_get_PSP_NS(void)
{
register uint32_t result;
__ASM volatile("MRS %0, psp_ns" : "=r"(result));
return(result);
}
/**
\brief Set Process Stack Pointer (non-secure)
\details Assigns the given value to the non-secure Process Stack Pointer (PSP) when in secure state.
\param [in] topOfProcStack Process Stack Pointer value to set
*/
void __TZ_set_PSP_NS(uint32_t topOfProcStack)
{
__ASM volatile("MSR psp_ns, %0" : : "r"(topOfProcStack));
}
/**
\brief Get Main Stack Pointer (non-secure)
\details Returns the current value of the non-secure Main Stack Pointer (MSP) when in secure state.
\return MSP Register value
*/
int32_t __TZ_get_MSP_NS(void)
{
register uint32_t result;
__ASM volatile("MRS %0, msp_ns" : "=r"(result));
return(result);
}
/**
\brief Set Main Stack Pointer (non-secure)
\details Assigns the given value to the non-secure Main Stack Pointer (MSP) when in secure state.
\param [in] topOfMainStack Main Stack Pointer value to set
*/
void __TZ_set_MSP_NS(uint32_t topOfMainStack)
{
__ASM volatile("MSR msp_ns, %0" : : "r"(topOfMainStack));
}
/**
\brief Get Priority Mask (non-secure)
\details Returns the current state of the non-secure priority mask bit from the Priority Mask Register when in secure state.
\return Priority Mask value
*/
uint32_t __TZ_get_PRIMASK_NS(void)
{
uint32_t result;
__ASM volatile("MRS %0, primask_ns" : "=r"(result));
return(result);
}
/**
\brief Set Priority Mask (non-secure)
\details Assigns the given value to the non-secure Priority Mask Register when in secure state.
\param [in] priMask Priority Mask
*/
void __TZ_set_PRIMASK_NS(uint32_t priMask)
{
__ASM volatile("MSR primask_ns, %0" : : "r"(priMask) : "memory");
}
#endif
#endif

View File

@ -0,0 +1,382 @@
/**************************************************************************//**
* @file nu_acmp.h
* @version V3.00
* @brief ACMP Driver Header File
*
* @copyright SPDX-License-Identifier: Apache-2.0
* @copyright Copyright (C) 2020 Nuvoton Technology Corp. All rights reserved.
******************************************************************************/
#ifndef __NU_ACMP_H__
#define __NU_ACMP_H__
#ifdef __cplusplus
extern "C"
{
#endif
/** @addtogroup Standard_Driver Standard Driver
@{
*/
/** @addtogroup ACMP_Driver ACMP Driver
@{
*/
/** @addtogroup ACMP_EXPORTED_CONSTANTS ACMP Exported Constants
@{
*/
/*---------------------------------------------------------------------------------------------------------*/
/* ACMP_CTL constant definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define ACMP_CTL_FILTSEL_OFF (0UL << 13) /*!< ACMP_CTL setting for filter function disabled. */
#define ACMP_CTL_FILTSEL_1PCLK (1UL << 13) /*!< ACMP_CTL setting for 1 PCLK filter count. */
#define ACMP_CTL_FILTSEL_2PCLK (2UL << 13) /*!< ACMP_CTL setting for 2 PCLK filter count. */
#define ACMP_CTL_FILTSEL_4PCLK (3UL << 13) /*!< ACMP_CTL setting for 4 PCLK filter count. */
#define ACMP_CTL_FILTSEL_8PCLK (4UL << 13) /*!< ACMP_CTL setting for 8 PCLK filter count. */
#define ACMP_CTL_FILTSEL_16PCLK (5UL << 13) /*!< ACMP_CTL setting for 16 PCLK filter count. */
#define ACMP_CTL_FILTSEL_32PCLK (6UL << 13) /*!< ACMP_CTL setting for 32 PCLK filter count. */
#define ACMP_CTL_FILTSEL_64PCLK (7UL << 13) /*!< ACMP_CTL setting for 64 PCLK filter count. */
#define ACMP_CTL_INTPOL_RF (0UL << 8) /*!< ACMP_CTL setting for selecting rising edge and falling edge as interrupt condition. */
#define ACMP_CTL_INTPOL_R (1UL << 8) /*!< ACMP_CTL setting for selecting rising edge as interrupt condition. */
#define ACMP_CTL_INTPOL_F (2UL << 8) /*!< ACMP_CTL setting for selecting falling edge as interrupt condition. */
#define ACMP_CTL_POSSEL_P0 (0UL << 6) /*!< ACMP_CTL setting for selecting ACMPx_P0 pin as the source of ACMP V+. */
#define ACMP_CTL_POSSEL_P1 (1UL << 6) /*!< ACMP_CTL setting for selecting ACMPx_P1 pin as the source of ACMP V+. */
#define ACMP_CTL_POSSEL_P2 (2UL << 6) /*!< ACMP_CTL setting for selecting ACMPx_P2 pin as the source of ACMP V+. */
#define ACMP_CTL_POSSEL_P3 (3UL << 6) /*!< ACMP_CTL setting for selecting ACMPx_P3 pin as the source of ACMP V+. */
#define ACMP_CTL_NEGSEL_PIN (0UL << 4) /*!< ACMP_CTL setting for selecting the voltage of ACMP negative input pin as the source of ACMP V-. */
#define ACMP_CTL_NEGSEL_CRV (1UL << 4) /*!< ACMP_CTL setting for selecting internal comparator reference voltage as the source of ACMP V-. */
#define ACMP_CTL_NEGSEL_VBG (2UL << 4) /*!< ACMP_CTL setting for selecting internal Band-gap voltage as the source of ACMP V-. */
#define ACMP_CTL_NEGSEL_DAC (3UL << 4) /*!< ACMP_CTL setting for selecting DAC output voltage as the source of ACMP V-. */
#define ACMP_CTL_HYSTERESIS_30MV (3UL << 24) /*!< ACMP_CTL setting for enabling the hysteresis function at 30mV. */
#define ACMP_CTL_HYSTERESIS_20MV (2UL << 24) /*!< ACMP_CTL setting for enabling the hysteresis function at 20mV. */
#define ACMP_CTL_HYSTERESIS_10MV (1UL << 24) /*!< ACMP_CTL setting for enabling the hysteresis function at 10mV. */
#define ACMP_CTL_HYSTERESIS_DISABLE (0UL << 2) /*!< ACMP_CTL setting for disabling the hysteresis function. */
/*---------------------------------------------------------------------------------------------------------*/
/* ACMP_VREF constant definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define ACMP_VREF_CRVSSEL_VDDA (0UL << 6) /*!< ACMP_VREF setting for selecting analog supply voltage VDDA as the CRV source voltage */
#define ACMP_VREF_CRVSSEL_INTVREF (1UL << 6) /*!< ACMP_VREF setting for selecting internal reference voltage as the CRV source voltage */
/**@}*/ /* end of group ACMP_EXPORTED_CONSTANTS */
/** @addtogroup ACMP_EXPORTED_FUNCTIONS ACMP Exported Functions
@{
*/
/*---------------------------------------------------------------------------------------------------------*/
/* Define Macros and functions */
/*---------------------------------------------------------------------------------------------------------*/
/**
* @brief This macro is used to enable output inverse function
* @param[in] acmp The pointer of the specified ACMP module
* @param[in] u32ChNum The ACMP number
* @return None
* @details This macro will set ACMPOINV bit of ACMP_CTL register to enable output inverse function.
*/
#define ACMP_ENABLE_OUTPUT_INVERSE(acmp, u32ChNum) ((acmp)->CTL[(u32ChNum)] |= ACMP_CTL_ACMPOINV_Msk)
/**
* @brief This macro is used to disable output inverse function
* @param[in] acmp The pointer of the specified ACMP module
* @param[in] u32ChNum The ACMP number
* @return None
* @details This macro will clear ACMPOINV bit of ACMP_CTL register to disable output inverse function.
*/
#define ACMP_DISABLE_OUTPUT_INVERSE(acmp, u32ChNum) ((acmp)->CTL[(u32ChNum)] &= ~ACMP_CTL_ACMPOINV_Msk)
/**
* @brief This macro is used to select ACMP negative input source
* @param[in] acmp The pointer of the specified ACMP module
* @param[in] u32ChNum The ACMP number
* @param[in] u32Src is comparator negative input selection. Including:
* - \ref ACMP_CTL_NEGSEL_PIN
* - \ref ACMP_CTL_NEGSEL_CRV
* - \ref ACMP_CTL_NEGSEL_VBG
* - \ref ACMP_CTL_NEGSEL_DAC
* @return None
* @details This macro will set NEGSEL (ACMP_CTL[5:4]) to determine the source of negative input.
*/
#define ACMP_SET_NEG_SRC(acmp, u32ChNum, u32Src) ((acmp)->CTL[(u32ChNum)] = ((acmp)->CTL[(u32ChNum)] & ~ACMP_CTL_NEGSEL_Msk) | (u32Src))
/**
* @brief This macro is used to enable hysteresis function
* @param[in] acmp The pointer of the specified ACMP module
* @param[in] u32ChNum The ACMP number
* @return None
*/
#define ACMP_ENABLE_HYSTERESIS(acmp, u32ChNum) ((acmp)->CTL[(u32ChNum)] |= ACMP_CTL_HYSTERESIS_30MV)
/**
* @brief This macro is used to disable hysteresis function
* @param[in] acmp The pointer of the specified ACMP module
* @param[in] u32ChNum The ACMP number
* @return None
* @details This macro will set HYSSEL of ACMP_CTL register to disable hysteresis function.
*/
#define ACMP_DISABLE_HYSTERESIS(acmp, u32ChNum) ((acmp)->CTL[(u32ChNum)] &= ~ACMP_CTL_HYSSEL_Msk)
/**
* @brief This macro is used to select hysteresis level
* @param[in] acmp The pointer of the specified ACMP module
* @param[in] u32ChNum The ACMP number
* @param[in] u32HysSel The hysteresis function option. Including:
* - \ref ACMP_CTL_HYSTERESIS_30MV
* - \ref ACMP_CTL_HYSTERESIS_20MV
* - \ref ACMP_CTL_HYSTERESIS_10MV
* - \ref ACMP_CTL_HYSTERESIS_DISABLE
* @return None
*/
#define ACMP_CONFIG_HYSTERESIS(acmp, u32ChNum, u32HysSel) ((acmp)->CTL[(u32ChNum)] = ((acmp)->CTL[(u32ChNum)] & ~ACMP_CTL_HYSSEL_Msk) | (u32HysSel))
/**
* @brief This macro is used to enable interrupt
* @param[in] acmp The pointer of the specified ACMP module
* @param[in] u32ChNum The ACMP number
* @return None
* @details This macro will set ACMPIE bit of ACMP_CTL register to enable interrupt function.
* If wake-up function is enabled, the wake-up interrupt will be enabled as well.
*/
#define ACMP_ENABLE_INT(acmp, u32ChNum) ((acmp)->CTL[(u32ChNum)] |= ACMP_CTL_ACMPIE_Msk)
/**
* @brief This macro is used to disable interrupt
* @param[in] acmp The pointer of the specified ACMP module
* @param[in] u32ChNum The ACMP number
* @return None
* @details This macro will clear ACMPIE bit of ACMP_CTL register to disable interrupt function.
*/
#define ACMP_DISABLE_INT(acmp, u32ChNum) ((acmp)->CTL[(u32ChNum)] &= ~ACMP_CTL_ACMPIE_Msk)
/**
* @brief This macro is used to enable ACMP
* @param[in] acmp The pointer of the specified ACMP module
* @param[in] u32ChNum The ACMP number
* @return None
* @details This macro will set ACMPEN bit of ACMP_CTL register to enable analog comparator.
*/
#define ACMP_ENABLE(acmp, u32ChNum) ((acmp)->CTL[(u32ChNum)] |= ACMP_CTL_ACMPEN_Msk)
/**
* @brief This macro is used to disable ACMP
* @param[in] acmp The pointer of the specified ACMP module
* @param[in] u32ChNum The ACMP number
* @return None
* @details This macro will clear ACMPEN bit of ACMP_CTL register to disable analog comparator.
*/
#define ACMP_DISABLE(acmp, u32ChNum) ((acmp)->CTL[(u32ChNum)] &= ~ACMP_CTL_ACMPEN_Msk)
/**
* @brief This macro is used to get ACMP output value
* @param[in] acmp The pointer of the specified ACMP module
* @param[in] u32ChNum The ACMP number
* @return ACMP output value
* @details This macro will return the ACMP output value.
*/
#define ACMP_GET_OUTPUT(acmp, u32ChNum) (((acmp)->STATUS & (ACMP_STATUS_ACMPO0_Msk<<((u32ChNum))))?1:0)
/**
* @brief This macro is used to get ACMP interrupt flag
* @param[in] acmp The pointer of the specified ACMP module
* @param[in] u32ChNum The ACMP number
* @return ACMP interrupt occurred (1) or not (0)
* @details This macro will return the ACMP interrupt flag.
*/
#define ACMP_GET_INT_FLAG(acmp, u32ChNum) (((acmp)->STATUS & (ACMP_STATUS_ACMPIF0_Msk<<((u32ChNum))))?1:0)
/**
* @brief This macro is used to clear ACMP interrupt flag
* @param[in] acmp The pointer of the specified ACMP module
* @param[in] u32ChNum The ACMP number
* @return None
* @details This macro will write 1 to ACMPIFn bit of ACMP_STATUS register to clear interrupt flag.
*/
#define ACMP_CLR_INT_FLAG(acmp, u32ChNum) ((acmp)->STATUS = (ACMP_STATUS_ACMPIF0_Msk<<((u32ChNum))))
/**
* @brief This macro is used to clear ACMP wake-up interrupt flag
* @param[in] acmp The pointer of the specified ACMP module
* @param[in] u32ChNum The ACMP number
* @return None
* @details This macro will write 1 to WKIFn bit of ACMP_STATUS register to clear interrupt flag.
*/
#define ACMP_CLR_WAKEUP_INT_FLAG(acmp, u32ChNum) ((acmp)->STATUS = (ACMP_STATUS_WKIF0_Msk<<((u32ChNum))))
/**
* @brief This macro is used to enable ACMP wake-up function
* @param[in] acmp The pointer of the specified ACMP module
* @param[in] u32ChNum The ACMP number
* @return None
* @details This macro will set WKEN (ACMP_CTL[16]) to enable ACMP wake-up function.
*/
#define ACMP_ENABLE_WAKEUP(acmp, u32ChNum) ((acmp)->CTL[(u32ChNum)] |= ACMP_CTL_WKEN_Msk)
/**
* @brief This macro is used to disable ACMP wake-up function
* @param[in] acmp The pointer of the specified ACMP module
* @param[in] u32ChNum The ACMP number
* @return None
* @details This macro will clear WKEN (ACMP_CTL[16]) to disable ACMP wake-up function.
*/
#define ACMP_DISABLE_WAKEUP(acmp, u32ChNum) ((acmp)->CTL[(u32ChNum)] &= ~ACMP_CTL_WKEN_Msk)
/**
* @brief This macro is used to select ACMP positive input pin
* @param[in] acmp The pointer of the specified ACMP module
* @param[in] u32ChNum The ACMP number
* @param[in] u32Pin Comparator positive pin selection. Including:
* - \ref ACMP_CTL_POSSEL_P0
* - \ref ACMP_CTL_POSSEL_P1
* - \ref ACMP_CTL_POSSEL_P2
* - \ref ACMP_CTL_POSSEL_P3
* @return None
* @details This macro will set POSSEL (ACMP_CTL[7:6]) to determine the comparator positive input pin.
*/
#define ACMP_SELECT_P(acmp, u32ChNum, u32Pin) ((acmp)->CTL[(u32ChNum)] = ((acmp)->CTL[(u32ChNum)] & ~ACMP_CTL_POSSEL_Msk) | (u32Pin))
/**
* @brief This macro is used to enable ACMP filter function
* @param[in] acmp The pointer of the specified ACMP module
* @param[in] u32ChNum The ACMP number
* @return None
* @details This macro will set OUTSEL (ACMP_CTL[12]) to enable output filter function.
*/
#define ACMP_ENABLE_FILTER(acmp, u32ChNum) ((acmp)->CTL[(u32ChNum)] |= ACMP_CTL_OUTSEL_Msk)
/**
* @brief This macro is used to disable ACMP filter function
* @param[in] acmp The pointer of the specified ACMP module
* @param[in] u32ChNum The ACMP number
* @return None
* @details This macro will clear OUTSEL (ACMP_CTL[12]) to disable output filter function.
*/
#define ACMP_DISABLE_FILTER(acmp, u32ChNum) ((acmp)->CTL[(u32ChNum)] &= ~ACMP_CTL_OUTSEL_Msk)
/**
* @brief This macro is used to set ACMP filter function
* @param[in] acmp The pointer of the specified ACMP module
* @param[in] u32ChNum The ACMP number
* @param[in] u32Cnt is comparator filter count setting.
* - \ref ACMP_CTL_FILTSEL_OFF
* - \ref ACMP_CTL_FILTSEL_1PCLK
* - \ref ACMP_CTL_FILTSEL_2PCLK
* - \ref ACMP_CTL_FILTSEL_4PCLK
* - \ref ACMP_CTL_FILTSEL_8PCLK
* - \ref ACMP_CTL_FILTSEL_16PCLK
* - \ref ACMP_CTL_FILTSEL_32PCLK
* - \ref ACMP_CTL_FILTSEL_64PCLK
* @return None
* @details When ACMP output filter function is enabled, the output sampling count is determined by FILTSEL (ACMP_CTL[15:13]).
*/
#define ACMP_SET_FILTER(acmp, u32ChNum, u32Cnt) ((acmp)->CTL[(u32ChNum)] = ((acmp)->CTL[(u32ChNum)] & ~ACMP_CTL_FILTSEL_Msk) | (u32Cnt))
/**
* @brief This macro is used to select comparator reference voltage
* @param[in] acmp The pointer of the specified ACMP module
* @param[in] u32Level The comparator reference voltage setting.
* The formula is:
* comparator reference voltage = CRV source voltage x (1/6 + u32Level/24)
* The range of u32Level is 0 ~ 15.
* @return None
* @details When CRV is selected as ACMP negative input source, the CRV level is determined by CRVCTL (ACMP_VREF[3:0]).
*/
#define ACMP_CRV_SEL(acmp, u32Level) ((acmp)->VREF = ((acmp)->VREF & ~ACMP_VREF_CRVCTL_Msk) | ((u32Level)<<ACMP_VREF_CRVCTL_Pos))
/**
* @brief This macro is used to select the source of CRV
* @param[in] acmp The pointer of the specified ACMP module
* @param[in] u32Src is the source of CRV. Including:
* - \ref ACMP_VREF_CRVSSEL_VDDA
* - \ref ACMP_VREF_CRVSSEL_INTVREF
* @return None
* @details The source of CRV can be VDDA or internal reference voltage. The internal reference voltage level is determined by SYS_VREFCTL register.
*/
#define ACMP_SELECT_CRV_SRC(acmp, u32Src) ((acmp)->VREF = ((acmp)->VREF & ~ACMP_VREF_CRVSSEL_Msk) | (u32Src))
/**
* @brief This macro is used to select ACMP interrupt condition
* @param[in] acmp The pointer of the specified ACMP module
* @param[in] u32ChNum The ACMP number
* @param[in] u32Cond Comparator interrupt condition selection. Including:
* - \ref ACMP_CTL_INTPOL_RF
* - \ref ACMP_CTL_INTPOL_R
* - \ref ACMP_CTL_INTPOL_F
* @return None
* @details The ACMP output interrupt condition can be rising edge, falling edge or any edge.
*/
#define ACMP_SELECT_INT_COND(acmp, u32ChNum, u32Cond) ((acmp)->CTL[(u32ChNum)] = ((acmp)->CTL[(u32ChNum)] & ~ACMP_CTL_INTPOL_Msk) | (u32Cond))
/**
* @brief This macro is used to enable ACMP window latch mode
* @param[in] acmp The pointer of the specified ACMP module
* @param[in] u32ChNum The ACMP number
* @return None
* @details This macro will set WLATEN (ACMP_CTL[17]) to enable ACMP window latch mode.
* When ACMP0/1_WLAT pin is at high level, ACMPO0/1 passes through window latch
* block; when ACMP0/1_WLAT pin is at low level, the output of window latch block,
* WLATOUT, is frozen.
*/
#define ACMP_ENABLE_WINDOW_LATCH(acmp, u32ChNum) ((acmp)->CTL[(u32ChNum)] |= ACMP_CTL_WLATEN_Msk)
/**
* @brief This macro is used to disable ACMP window latch mode
* @param[in] acmp The pointer of the specified ACMP module
* @param[in] u32ChNum The ACMP number
* @return None
* @details This macro will clear WLATEN (ACMP_CTL[17]) to disable ACMP window latch mode.
*/
#define ACMP_DISABLE_WINDOW_LATCH(acmp, u32ChNum) ((acmp)->CTL[(u32ChNum)] &= ~ACMP_CTL_WLATEN_Msk)
/**
* @brief This macro is used to enable ACMP window compare mode
* @param[in] acmp The pointer of the specified ACMP module
* @param[in] u32ChNum The ACMP number
* @return None
* @details This macro will set WCMPSEL (ACMP_CTL[18]) to enable ACMP window compare mode.
* When window compare mode is enabled, user can connect the specific analog voltage
* source to either the positive inputs of both comparators or the negative inputs of
* both comparators. The upper bound and lower bound of the designated range are
* determined by the voltages applied to the other inputs of both comparators. If the
* output of a comparator is low and the other comparator outputs high, which means two
* comparators implies the upper and lower bound. User can directly monitor a specific
* analog voltage source via ACMPWO (ACMP_STATUS[16]).
*/
#define ACMP_ENABLE_WINDOW_COMPARE(acmp, u32ChNum) ((acmp)->CTL[(u32ChNum)] |= ACMP_CTL_WCMPSEL_Msk)
/**
* @brief This macro is used to disable ACMP window compare mode
* @param[in] acmp The pointer of the specified ACMP module
* @param[in] u32ChNum The ACMP number
* @return None
* @details This macro will clear WCMPSEL (ACMP_CTL[18]) to disable ACMP window compare mode.
*/
#define ACMP_DISABLE_WINDOW_COMPARE(acmp, u32ChNum) ((acmp)->CTL[(u32ChNum)] &= ~ACMP_CTL_WCMPSEL_Msk)
/* Function prototype declaration */
void ACMP_Open(ACMP_T *acmp, uint32_t u32ChNum, uint32_t u32NegSrc, uint32_t u32HysSel);
void ACMP_Close(ACMP_T *acmp, uint32_t u32ChNum);
/**@}*/ /* end of group ACMP_EXPORTED_FUNCTIONS */
/**@}*/ /* end of group ACMP_Driver */
/**@}*/ /* end of group Standard_Driver */
#ifdef __cplusplus
}
#endif
#endif /* __NU_ACMP_H__ */

View File

@ -0,0 +1,360 @@
/**************************************************************************//**
* @file nu_bpwm.h
* @version V1.00
* @brief M2354 series BPWM driver header file
*
* @copyright SPDX-License-Identifier: Apache-2.0
* @copyright Copyright (C) 2020 Nuvoton Technology Corp. All rights reserved.
*****************************************************************************/
#ifndef __NU_BPWM_H__
#define __NU_BPWM_H__
#ifdef __cplusplus
extern "C"
{
#endif
/** @addtogroup Standard_Driver Standard Driver
@{
*/
/** @addtogroup BPWM_Driver BPWM Driver
@{
*/
/** @addtogroup BPWM_EXPORTED_CONSTANTS BPWM Exported Constants
@{
*/
#define BPWM_CHANNEL_NUM (6UL) /*!< BPWM channel number */
#define BPWM_CH_0_MASK (0x1UL) /*!< BPWM channel 0 mask \hideinitializer */
#define BPWM_CH_1_MASK (0x2UL) /*!< BPWM channel 1 mask \hideinitializer */
#define BPWM_CH_2_MASK (0x4UL) /*!< BPWM channel 2 mask \hideinitializer */
#define BPWM_CH_3_MASK (0x8UL) /*!< BPWM channel 3 mask \hideinitializer */
#define BPWM_CH_4_MASK (0x10UL) /*!< BPWM channel 4 mask \hideinitializer */
#define BPWM_CH_5_MASK (0x20UL) /*!< BPWM channel 5 mask \hideinitializer */
/*---------------------------------------------------------------------------------------------------------*/
/* Counter Type Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define BPWM_UP_COUNTER (0UL) /*!< Up counter type */
#define BPWM_DOWN_COUNTER (1UL) /*!< Down counter type */
#define BPWM_UP_DOWN_COUNTER (2UL) /*!< Up-Down counter type */
/*---------------------------------------------------------------------------------------------------------*/
/* Aligned Type Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define BPWM_EDGE_ALIGNED (1UL) /*!< BPWM working in edge aligned type(down count) */
#define BPWM_CENTER_ALIGNED (2UL) /*!< BPWM working in center aligned type */
/*---------------------------------------------------------------------------------------------------------*/
/* Output Level Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define BPWM_OUTPUT_NOTHING (0UL) /*!< BPWM output nothing */
#define BPWM_OUTPUT_LOW (1UL) /*!< BPWM output low */
#define BPWM_OUTPUT_HIGH (2UL) /*!< BPWM output high */
#define BPWM_OUTPUT_TOGGLE (3UL) /*!< BPWM output toggle */
/*---------------------------------------------------------------------------------------------------------*/
/* Synchronous Start Function Control Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define BPWM_SSCTL_SSRC_PWM0 (0UL<<BPWM_SSCTL_SSRC_Pos) /*!< Synchronous start source comes from PWM0 */
#define BPWM_SSCTL_SSRC_PWM1 (1UL<<BPWM_SSCTL_SSRC_Pos) /*!< Synchronous start source comes from PWM1 */
#define BPWM_SSCTL_SSRC_BPWM0 (2UL<<BPWM_SSCTL_SSRC_Pos) /*!< Synchronous start source comes from BPWM0 */
#define BPWM_SSCTL_SSRC_BPWM1 (3UL<<BPWM_SSCTL_SSRC_Pos) /*!< Synchronous start source comes from BPWM1 */
/*---------------------------------------------------------------------------------------------------------*/
/* Trigger Source Select Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define BPWM_TRIGGER_ADC_EVEN_ZERO_POINT (0UL) /*!< BPWM trigger ADC while counter of even channel matches zero point \hideinitializer */
#define BPWM_TRIGGER_ADC_EVEN_PERIOD_POINT (1UL) /*!< BPWM trigger ADC while counter of even channel matches period point \hideinitializer */
#define BPWM_TRIGGER_ADC_EVEN_ZERO_OR_PERIOD_POINT (2UL) /*!< BPWM trigger ADC while counter of even channel matches zero or period point \hideinitializer */
#define BPWM_TRIGGER_ADC_EVEN_CMP_UP_COUNT_POINT (3UL) /*!< BPWM trigger ADC while counter of even channel matches up count to comparator point \hideinitializer */
#define BPWM_TRIGGER_ADC_EVEN_CMP_DOWN_COUNT_POINT (4UL) /*!< BPWM trigger ADC while counter of even channel matches down count to comparator point \hideinitializer */
#define BPWM_TRIGGER_ADC_ODD_CMP_UP_COUNT_POINT (8UL) /*!< BPWM trigger ADC while counter of odd channel matches up count to comparator point \hideinitializer */
#define BPWM_TRIGGER_ADC_ODD_CMP_DOWN_COUNT_POINT (9UL) /*!< BPWM trigger ADC while counter of odd channel matches down count to comparator point \hideinitializer */
/*---------------------------------------------------------------------------------------------------------*/
/* Capture Control Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define BPWM_CAPTURE_INT_RISING_LATCH (1UL) /*!< BPWM capture interrupt if channel has rising transition */
#define BPWM_CAPTURE_INT_FALLING_LATCH (0x100UL) /*!< BPWM capture interrupt if channel has falling transition */
/*---------------------------------------------------------------------------------------------------------*/
/* Duty Interrupt Type Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define BPWM_DUTY_INT_DOWN_COUNT_MATCH_CMP (1 << BPWM_INTEN_CMPDIEN0_Pos) /*!< BPWM duty interrupt triggered if down count match comparator \hideinitializer */
#define BPWM_DUTY_INT_UP_COUNT_MATCH_CMP (1 << BPWM_INTEN_CMPUIEN0_Pos) /*!< BPWM duty interrupt triggered if up down match comparator \hideinitializer */
/*---------------------------------------------------------------------------------------------------------*/
/* Load Mode Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define BPWM_LOAD_MODE_IMMEDIATE (1 << BPWM_CTL0_IMMLDEN0_Pos) /*!< BPWM immediately load mode \hideinitializer */
#define BPWM_LOAD_MODE_CENTER (1 << BPWM_CTL0_CTRLD0_Pos) /*!< BPWM center load mode \hideinitializer */
/*---------------------------------------------------------------------------------------------------------*/
/* Clock Source Select Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define BPWM_CLKSRC_BPWM_CLK (0UL) /*!< BPWM Clock source selects to BPWM0_CLK or BPWM1_CLK \hideinitializer */
#define BPWM_CLKSRC_TIMER0 (1UL) /*!< BPWM Clock source selects to TIMER0 overflow \hideinitializer */
#define BPWM_CLKSRC_TIMER1 (2UL) /*!< BPWM Clock source selects to TIMER1 overflow \hideinitializer */
#define BPWM_CLKSRC_TIMER2 (3UL) /*!< BPWM Clock source selects to TIMER2 overflow \hideinitializer */
#define BPWM_CLKSRC_TIMER3 (4UL) /*!< BPWM Clock source selects to TIMER3 overflow \hideinitializer */
/**@}*/ /* end of group BPWM_EXPORTED_CONSTANTS */
/** @addtogroup BPWM_EXPORTED_FUNCTIONS BPWM Exported Functions
@{
*/
/**
* @brief Enable timer synchronous start counting function of specified channel(s)
* @param[in] bpwm The pointer of the specified BPWM module
* @param[in] u32ChannelMask Combination of enabled channels. This parameter is not used.
* @param[in] u32SyncSrc Synchronous start source selection, valid values are:
* - \ref BPWM_SSCTL_SSRC_PWM0
* - \ref BPWM_SSCTL_SSRC_PWM1
* - \ref BPWM_SSCTL_SSRC_BPWM0
* - \ref BPWM_SSCTL_SSRC_BPWM1
* @return None
* @details This macro is used to enable timer synchronous start counting function of specified channel(s).
* @note All channels share channel 0's setting.
* \hideinitializer
*/
#define BPWM_ENABLE_TIMER_SYNC(bpwm, u32ChannelMask, u32SyncSrc) ((bpwm)->SSCTL = ((bpwm)->SSCTL & ~BPWM_SSCTL_SSRC_Msk) | (u32SyncSrc) | BPWM_SSCTL_SSEN0_Msk)
/**
* @brief Disable timer synchronous start counting function of specified channel(s)
* @param[in] bpwm The pointer of the specified BPWM module
* @param[in] u32ChannelMask Combination of enabled channels. This parameter is not used.
* @return None
* @details This macro is used to disable timer synchronous start counting function of specified channel(s).
* @note All channels share channel 0's setting.
* \hideinitializer
*/
#define BPWM_DISABLE_TIMER_SYNC(bpwm, u32ChannelMask) ((bpwm)->SSCTL &= ~BPWM_SSCTL_SSEN0_Msk)
/**
* @brief This macro enable BPWM counter synchronous start counting function.
* @param[in] bpwm The pointer of the specified BPWM module
* @return None
* @details This macro is used to make selected BPWM0 and BPWM1 channel(s) start counting at the same time.
* To configure synchronous start counting channel(s) by BPWM_ENABLE_TIMER_SYNC() and BPWM_DISABLE_TIMER_SYNC().
* \hideinitializer
*/
#define BPWM_TRIGGER_SYNC_START(bpwm) ((bpwm)->SSTRG = BPWM_SSTRG_CNTSEN_Msk)
/**
* @brief This macro enable output inverter of specified channel(s)
* @param[in] bpwm The pointer of the specified BPWM module
* @param[in] u32ChannelMask Combination of enabled channels. Each bit corresponds to a channel
* Bit 0 represents channel 0, bit 1 represents channel 1...
* @return None
* \hideinitializer
*/
#define BPWM_ENABLE_OUTPUT_INVERTER(bpwm, u32ChannelMask) ((bpwm)->POLCTL = (u32ChannelMask))
/**
* @brief This macro get captured rising data
* @param[in] bpwm The pointer of the specified BPWM module
* @param[in] u32ChannelNum BPWM channel number. Valid values are between 0~5
* @return None
* \hideinitializer
*/
#define BPWM_GET_CAPTURE_RISING_DATA(bpwm, u32ChannelNum) ((bpwm)->CAPDAT[(u32ChannelNum)].RCAPDAT)
/**
* @brief This macro get captured falling data
* @param[in] bpwm The pointer of the specified BPWM module
* @param[in] u32ChannelNum BPWM channel number. Valid values are between 0~5
* @return None
* \hideinitializer
*/
#define BPWM_GET_CAPTURE_FALLING_DATA(bpwm, u32ChannelNum) ((bpwm)->CAPDAT[(u32ChannelNum)].FCAPDAT)
/**
* @brief This macro mask output logic to high or low
* @param[in] bpwm The pointer of the specified BPWM module
* @param[in] u32ChannelMask Combination of enabled channels. Each bit corresponds to a channel
* Bit 0 represents channel 0, bit 1 represents channel 1...
* @param[in] u32LevelMask Output logic to high or low
* @return None
* @details This macro is used to mask output logic to high or low of specified channel(s).
* @note If u32ChannelMask parameter is 0, then mask function will be disabled.
* \hideinitializer
*/
#define BPWM_MASK_OUTPUT(bpwm, u32ChannelMask, u32LevelMask) \
{ \
(bpwm)->MSKEN = (u32ChannelMask); \
(bpwm)->MSK = (u32LevelMask); \
}
/**
* @brief This macro set the prescaler of all channels
* @param[in] bpwm The pointer of the specified BPWM module
* @param[in] u32ChannelNum BPWM channel number. This parameter is not used.
* @param[in] u32Prescaler Clock prescaler of specified channel. Valid values are between 1 ~ 0xFFF
* @return None
* \hideinitializer
*/
#define BPWM_SET_PRESCALER(bpwm, u32ChannelNum, u32Prescaler) ((bpwm)->CLKPSC = (u32Prescaler))
/**
* @brief This macro set the duty of the selected channel
* @param[in] bpwm The pointer of the specified BPWM module
* @param[in] u32ChannelNum BPWM channel number. Valid values are between 0~5
* @param[in] u32CMR Duty of specified channel. Valid values are between 0~0xFFFF
* @return None
* @note This new setting will take effect on next BPWM period
* \hideinitializer
*/
#define BPWM_SET_CMR(bpwm, u32ChannelNum, u32CMR) ((bpwm)->CMPDAT[(u32ChannelNum)] = (u32CMR))
/**
* @brief This macro get the duty of the selected channel
* @param[in] bpwm The pointer of the specified BPWM module
* @param[in] u32ChannelNum BPWM channel number. Valid values are between 0~5
* @return Return the comparator of specified channel. Valid values are between 0~0xFFFF
* @details This macro is used to get the comparator of specified channel.
* \hideinitializer
*/
#define BPWM_GET_CMR(bpwm, u32ChannelNum) ((bpwm)->CMPDAT[(u32ChannelNum)])
/**
* @brief This macro set the period of all channels
* @param[in] bpwm The pointer of the specified BPWM module
* @param[in] u32ChannelNum BPWM channel number. This parameter is not used.
* @param[in] u32CNR Period of specified channel. Valid values are between 0~0xFFFF
* @return None
* @note This new setting will take effect on next BPWM period
* @note BPWM counter will stop if period length set to 0
* \hideinitializer
*/
#define BPWM_SET_CNR(bpwm, u32ChannelNum, u32CNR) ((bpwm)->PERIOD = (u32CNR))
/**
* @brief This macro get the period of all channels
* @param[in] bpwm The pointer of the specified BPWM module
* @param[in] u32ChannelNum BPWM channel number. This parameter is not used.
* @return None
* \hideinitializer
*/
#define BPWM_GET_CNR(bpwm, u32ChannelNum) ((bpwm)->PERIOD)
/**
* @brief This macro set the BPWM aligned type
* @param[in] bpwm The pointer of the specified BPWM module
* @param[in] u32ChannelMask Combination of enabled channels. This parameter is not used.
* @param[in] u32AlignedType BPWM aligned type, valid values are:
* - \ref BPWM_EDGE_ALIGNED
* - \ref BPWM_CENTER_ALIGNED
* @return None
* @note All channels share channel 0's setting.
* \hideinitializer
*/
#define BPWM_SET_ALIGNED_TYPE(bpwm, u32ChannelMask, u32AlignedType) ((bpwm)->CTL1 = (u32AlignedType))
/**
* @brief Clear counter of channel 0
* @param[in] bpwm The pointer of the specified BPWM module
* @param[in] u32ChannelMask Combination of enabled channels. This parameter is not used.
* @return None
* @details This macro is used to clear counter of channel 0
* \hideinitializer
*/
#define BPWM_CLR_COUNTER(bpwm, u32ChannelMask) ((bpwm)->CNTCLR = (BPWM_CNTCLR_CNTCLR0_Msk))
/**
* @brief Set output level at zero, compare up, period(center) and compare down of specified channel(s)
* @param[in] bpwm The pointer of the specified BPWM module
* @param[in] u32ChannelMask Combination of enabled channels. Each bit corresponds to a channel
* Bit 0 represents channel 0, bit 1 represents channel 1...
* @param[in] u32ZeroLevel output level at zero point, valid values are:
* - \ref BPWM_OUTPUT_NOTHING
* - \ref BPWM_OUTPUT_LOW
* - \ref BPWM_OUTPUT_HIGH
* - \ref BPWM_OUTPUT_TOGGLE
* @param[in] u32CmpUpLevel output level at compare up point, valid values are:
* - \ref BPWM_OUTPUT_NOTHING
* - \ref BPWM_OUTPUT_LOW
* - \ref BPWM_OUTPUT_HIGH
* - \ref BPWM_OUTPUT_TOGGLE
* @param[in] u32PeriodLevel output level at period(center) point, valid values are:
* - \ref BPWM_OUTPUT_NOTHING
* - \ref BPWM_OUTPUT_LOW
* - \ref BPWM_OUTPUT_HIGH
* - \ref BPWM_OUTPUT_TOGGLE
* @param[in] u32CmpDownLevel output level at compare down point, valid values are:
* - \ref BPWM_OUTPUT_NOTHING
* - \ref BPWM_OUTPUT_LOW
* - \ref BPWM_OUTPUT_HIGH
* - \ref BPWM_OUTPUT_TOGGLE
* @return None
* @details This macro is used to Set output level at zero, compare up, period(center) and compare down of specified channel(s)
* \hideinitializer
*/
#define BPWM_SET_OUTPUT_LEVEL(bpwm, u32ChannelMask, u32ZeroLevel, u32CmpUpLevel, u32PeriodLevel, u32CmpDownLevel) \
do{ \
uint32_t i; \
for(i = 0UL; i < 6UL; i++) { \
if((u32ChannelMask) & (1UL << i)) { \
(bpwm)->WGCTL0 = (((bpwm)->WGCTL0 & ~(3UL << (i << 1))) | ((u32ZeroLevel) << (i << 1))); \
(bpwm)->WGCTL0 = (((bpwm)->WGCTL0 & ~(3UL << (BPWM_WGCTL0_PRDPCTL0_Pos + (i << 1)))) | ((u32PeriodLevel) << (BPWM_WGCTL0_PRDPCTL0_Pos + (i << 1)))); \
(bpwm)->WGCTL1 = (((bpwm)->WGCTL1 & ~(3UL << (i << 1))) | ((u32CmpUpLevel) << (i << 1))); \
(bpwm)->WGCTL1 = (((bpwm)->WGCTL1 & ~(3UL << (BPWM_WGCTL1_CMPDCTL0_Pos + (i << 1)))) | ((u32CmpDownLevel) << (BPWM_WGCTL1_CMPDCTL0_Pos + (i << 1)))); \
} \
} \
}while(0)
/*---------------------------------------------------------------------------------------------------------*/
/* Define BPWM functions prototype */
/*---------------------------------------------------------------------------------------------------------*/
uint32_t BPWM_ConfigCaptureChannel(BPWM_T *bpwm, uint32_t u32ChannelNum, uint32_t u32UnitTimeNsec, uint32_t u32CaptureEdge);
uint32_t BPWM_ConfigOutputChannel(BPWM_T *bpwm, uint32_t u32ChannelNum, uint32_t u32Frequency, uint32_t u32DutyCycle);
void BPWM_Start(BPWM_T *bpwm, uint32_t u32ChannelMask);
void BPWM_Stop(BPWM_T *bpwm, uint32_t u32ChannelMask);
void BPWM_ForceStop(BPWM_T *bpwm, uint32_t u32ChannelMask);
void BPWM_EnableADCTrigger(BPWM_T *bpwm, uint32_t u32ChannelNum, uint32_t u32Condition);
void BPWM_DisableADCTrigger(BPWM_T *bpwm, uint32_t u32ChannelNum);
void BPWM_ClearADCTriggerFlag(BPWM_T *bpwm, uint32_t u32ChannelNum, uint32_t u32Condition);
uint32_t BPWM_GetADCTriggerFlag(BPWM_T *bpwm, uint32_t u32ChannelNum);
void BPWM_EnableCapture(BPWM_T *bpwm, uint32_t u32ChannelMask);
void BPWM_DisableCapture(BPWM_T *bpwm, uint32_t u32ChannelMask);
void BPWM_EnableOutput(BPWM_T *bpwm, uint32_t u32ChannelMask);
void BPWM_DisableOutput(BPWM_T *bpwm, uint32_t u32ChannelMask);
void BPWM_EnableCaptureInt(BPWM_T *bpwm, uint32_t u32ChannelNum, uint32_t u32Edge);
void BPWM_DisableCaptureInt(BPWM_T *bpwm, uint32_t u32ChannelNum, uint32_t u32Edge);
void BPWM_ClearCaptureIntFlag(BPWM_T *bpwm, uint32_t u32ChannelNum, uint32_t u32Edge);
uint32_t BPWM_GetCaptureIntFlag(BPWM_T *bpwm, uint32_t u32ChannelNum);
void BPWM_EnableDutyInt(BPWM_T *bpwm, uint32_t u32ChannelNum, uint32_t u32IntDutyType);
void BPWM_DisableDutyInt(BPWM_T *bpwm, uint32_t u32ChannelNum);
void BPWM_ClearDutyIntFlag(BPWM_T *bpwm, uint32_t u32ChannelNum);
uint32_t BPWM_GetDutyIntFlag(BPWM_T *bpwm, uint32_t u32ChannelNum);
void BPWM_EnablePeriodInt(BPWM_T *bpwm, uint32_t u32ChannelNum, uint32_t u32IntPeriodType);
void BPWM_DisablePeriodInt(BPWM_T *bpwm, uint32_t u32ChannelNum);
void BPWM_ClearPeriodIntFlag(BPWM_T *bpwm, uint32_t u32ChannelNum);
uint32_t BPWM_GetPeriodIntFlag(BPWM_T *bpwm, uint32_t u32ChannelNum);
void BPWM_EnableZeroInt(BPWM_T *bpwm, uint32_t u32ChannelNum);
void BPWM_DisableZeroInt(BPWM_T *bpwm, uint32_t u32ChannelNum);
void BPWM_ClearZeroIntFlag(BPWM_T *bpwm, uint32_t u32ChannelNum);
uint32_t BPWM_GetZeroIntFlag(BPWM_T *bpwm, uint32_t u32ChannelNum);
void BPWM_EnableLoadMode(BPWM_T *bpwm, uint32_t u32ChannelNum, uint32_t u32LoadMode);
void BPWM_DisableLoadMode(BPWM_T *bpwm, uint32_t u32ChannelNum, uint32_t u32LoadMode);
void BPWM_SetClockSource(BPWM_T *bpwm, uint32_t u32ChannelNum, uint32_t u32ClkSrcSel);
uint32_t BPWM_GetWrapAroundFlag(BPWM_T *bpwm, uint32_t u32ChannelNum);
void BPWM_ClearWrapAroundFlag(BPWM_T *bpwm, uint32_t u32ChannelNum);
/**@}*/ /* end of group BPWM_EXPORTED_FUNCTIONS */
/**@}*/ /* end of group BPWM_Driver */
/**@}*/ /* end of group Standard_Driver */
#ifdef __cplusplus
}
#endif
#endif /* __NU_BPWM_H__ */

View File

@ -0,0 +1,188 @@
/**************************************************************************//**
* @file nu_can.h
* @version V3.00
* @brief CAN Driver Header File
*
* @copyright SPDX-License-Identifier: Apache-2.0
* @copyright Copyright (C) 2020 Nuvoton Technology Corp. All rights reserved.
******************************************************************************/
#ifndef __NU_CAN_H__
#define __NU_CAN_H__
#ifdef __cplusplus
extern "C"
{
#endif
/** @addtogroup Standard_Driver Standard Driver
@{
*/
/** @addtogroup CAN_Driver CAN Driver
@{
*/
/** @addtogroup CAN_EXPORTED_CONSTANTS CAN Exported Constants
@{
*/
/*---------------------------------------------------------------------------------------------------------*/
/* CAN Test Mode Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define CAN_NORMAL_MODE 0U /*!< CAN select normal mode */
#define CAN_BASIC_MODE 1U /*!< CAN select basic mode */
/*---------------------------------------------------------------------------------------------------------*/
/* Message ID Type Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define CAN_STD_ID 0UL /*!< CAN select standard ID */
#define CAN_EXT_ID 1UL /*!< CAN select extended ID */
/*---------------------------------------------------------------------------------------------------------*/
/* Message Frame Type Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define CAN_REMOTE_FRAME 0 /*!< CAN frame select remote frame */
#define CAN_DATA_FRAME 1 /*!< CAN frame select data frame */
/**@}*/ /* end of group CAN_EXPORTED_CONSTANTS */
/** @addtogroup CAN_EXPORTED_STRUCTS CAN Exported Structs
@{
*/
/**
* @details CAN message structure
*/
typedef struct
{
uint32_t IdType; /*!< ID type */
uint32_t FrameType; /*!< Frame type */
uint32_t Id; /*!< Message ID */
uint8_t DLC; /*!< Data length */
uint8_t Data[8]; /*!< Data */
uint8_t padding[3]; /*!< Just for padding for memory alignment*/
} STR_CANMSG_T;
/**
* @details CAN mask message structure
*/
typedef struct
{
uint8_t u8Xtd; /*!< Extended ID */
uint8_t u8Dir; /*!< Direction */
uint32_t u32Id; /*!< Message ID */
uint8_t u8IdType; /*!< ID type*/
} STR_CANMASK_T;
/**@}*/ /* end of group CAN_EXPORTED_STRUCTS */
/** @cond HIDDEN_SYMBOLS */
#define MSG(id) (id)
/** @endcond HIDDEN_SYMBOLS */
/** @addtogroup CAN_EXPORTED_FUNCTIONS CAN Exported Functions
@{
*/
/**
* @brief Get interrupt status.
*
* @param[in] can The base address of can module.
*
* @return CAN module status register value.
*
* @details Status Interrupt is generated by bits BOff (CAN_STATUS[7]), EWarn (CAN_STATUS[6]),
* EPass (CAN_STATUS[5]), RxOk (CAN_STATUS[4]), TxOk (CAN_STATUS[3]), and LEC (CAN_STATUS[2:0]).
*/
#define CAN_GET_INT_STATUS(can) ((can)->STATUS)
/**
* @brief Get specified interrupt pending status.
*
* @param[in] can The base address of can module.
*
* @return The source of the interrupt.
*
* @details If several interrupts are pending, the CAN Interrupt Register will point to the pending interrupt
* with the highest priority, disregarding their chronological order.
*/
#define CAN_GET_INT_PENDING_STATUS(can) ((can)->IIDR)
/**
* @brief Disable wake-up function.
*
* @param[in] can The base address of can module.
*
* @return None
*
* @details The macro is used to disable wake-up function.
*/
#define CAN_DISABLE_WAKEUP(can) ((can)->WU_EN = 0)
/**
* @brief Enable wake-up function.
*
* @param[in] can The base address of can module.
*
* @return None
*
* @details User can wake-up system when there is a falling edge in the CAN_Rx pin.
*/
#define CAN_ENABLE_WAKEUP(can) ((can)->WU_EN = CAN_WU_EN_WAKUP_EN_Msk)
/**
* @brief Get specified Message Object new data into bit value.
*
* @param[in] can The base address of can module.
* @param[in] u32MsgNum Specified Message Object number, valid value are from 0 to 31.
*
* @return Specified Message Object new data into bit value.
*
* @details The NewDat bit (CAN_IFn_MCON[15]) of a specific Message Object can be set/reset by the software through the IFn Message Interface Registers
* or by the Message Handler after reception of a Data Frame or after a successful transmission.
*/
#define CAN_GET_NEW_DATA_IN_BIT(can, u32MsgNum) ((u32MsgNum) < 16 ? (can)->NDAT1 & (1 << (u32MsgNum)) : (can)->NDAT2 & (1 << ((u32MsgNum)-16)))
/*---------------------------------------------------------------------------------------------------------*/
/* Define CAN functions prototype */
/*---------------------------------------------------------------------------------------------------------*/
uint32_t CAN_SetBaudRate(CAN_T *tCAN, uint32_t u32BaudRate);
void CAN_Close(CAN_T *tCAN);
uint32_t CAN_Open(CAN_T *tCAN, uint32_t u32BaudRate, uint32_t u32Mode);
void CAN_CLR_INT_PENDING_BIT(CAN_T *tCAN, uint8_t u32MsgNum);
void CAN_EnableInt(CAN_T *tCAN, uint32_t u32Mask);
void CAN_DisableInt(CAN_T *tCAN, uint32_t u32Mask);
int32_t CAN_Transmit(CAN_T *tCAN, uint32_t u32MsgNum, STR_CANMSG_T* pCanMsg);
int32_t CAN_Receive(CAN_T *tCAN, uint32_t u32MsgNum, STR_CANMSG_T* pCanMsg);
int32_t CAN_SetMultiRxMsg(CAN_T *tCAN, uint32_t u32MsgNum, uint32_t u32MsgCount, uint32_t u32IDType, uint32_t u32ID);
int32_t CAN_SetRxMsg(CAN_T *tCAN, uint32_t u32MsgNum, uint32_t u32IDType, uint32_t u32ID);
int32_t CAN_SetRxMsgAndMsk(CAN_T *tCAN, uint32_t u32MsgNum, uint32_t u32IDType, uint32_t u32ID, uint32_t u32IDMask);
int32_t CAN_SetTxMsg(CAN_T *tCAN, uint32_t u32MsgNum, STR_CANMSG_T* pCanMsg);
int32_t CAN_TriggerTxMsg(CAN_T *tCAN, uint32_t u32MsgNum);
void CAN_EnterInitMode(CAN_T *tCAN, uint8_t u8Mask);
void CAN_LeaveInitMode(CAN_T *tCAN);
void CAN_WaitMsg(CAN_T *tCAN);
uint32_t CAN_GetCANBitRate(CAN_T *tCAN);
void CAN_EnterTestMode(CAN_T *tCAN, uint8_t u8TestMask);
void CAN_LeaveTestMode(CAN_T *tCAN);
uint32_t CAN_IsNewDataReceived(CAN_T *tCAN, uint8_t u8MsgObj);
int32_t CAN_BasicSendMsg(CAN_T *tCAN, STR_CANMSG_T* pCanMsg);
int32_t CAN_BasicReceiveMsg(CAN_T *tCAN, STR_CANMSG_T* pCanMsg);
int32_t CAN_SetRxMsgObjAndMsk(CAN_T *tCAN, uint8_t u8MsgObj, uint8_t u8idType, uint32_t u32id, uint32_t u32idmask, uint8_t u8singleOrFifoLast);
int32_t CAN_SetRxMsgObj(CAN_T *tCAN, uint8_t u8MsgObj, uint8_t u8idType, uint32_t u32id, uint8_t u8singleOrFifoLast);
int32_t CAN_ReadMsgObj(CAN_T *tCAN, uint8_t u8MsgObj, uint8_t u8Release, STR_CANMSG_T* pCanMsg);
/**@}*/ /* end of group CAN_EXPORTED_FUNCTIONS */
/**@}*/ /* end of group CAN_Driver */
/**@}*/ /* end of group Standard_Driver */
#ifdef __cplusplus
}
#endif
#endif /* __NU_CAN_H__ */

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,115 @@
/**************************************************************************//**
* @file nu_crc.h
* @version V3.00
* @brief Cyclic Redundancy Check(CRC) driver header file
*
* @copyright SPDX-License-Identifier: Apache-2.0
* @copyright Copyright (C) 2020 Nuvoton Technology Corp. All rights reserved.
*****************************************************************************/
#ifndef __NU_CRC_H__
#define __NU_CRC_H__
#ifdef __cplusplus
extern "C"
{
#endif
/** @addtogroup Standard_Driver Standard Driver
@{
*/
/** @addtogroup CRC_Driver CRC Driver
@{
*/
/** @addtogroup CRC_EXPORTED_CONSTANTS CRC Exported Constants
@{
*/
/*---------------------------------------------------------------------------------------------------------*/
/* CRC Polynomial Mode Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define CRC_CCITT (0UL << CRC_CTL_CRCMODE_Pos) /*!<CRC Polynomial Mode - CCITT \hideinitializer */
#define CRC_8 (1UL << CRC_CTL_CRCMODE_Pos) /*!<CRC Polynomial Mode - CRC8 \hideinitializer */
#define CRC_16 (2UL << CRC_CTL_CRCMODE_Pos) /*!<CRC Polynomial Mode - CRC16 \hideinitializer */
#define CRC_32 (3UL << CRC_CTL_CRCMODE_Pos) /*!<CRC Polynomial Mode - CRC32 \hideinitializer */
/*---------------------------------------------------------------------------------------------------------*/
/* Checksum, Write data Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define CRC_CHECKSUM_COM (CRC_CTL_CHKSFMT_Msk) /*!<CRC Checksum Complement \hideinitializer */
#define CRC_CHECKSUM_RVS (CRC_CTL_CHKSREV_Msk) /*!<CRC Checksum Reverse \hideinitializer */
#define CRC_WDATA_COM (CRC_CTL_DATFMT_Msk) /*!<CRC Write Data Complement \hideinitializer */
#define CRC_WDATA_RVS (CRC_CTL_DATREV_Msk) /*!<CRC Write Data Reverse \hideinitializer */
/*---------------------------------------------------------------------------------------------------------*/
/* CPU Write Data Length Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define CRC_CPU_WDATA_8 (0UL << CRC_CTL_DATLEN_Pos) /*!<CRC CPU Write Data length is 8-bit \hideinitializer */
#define CRC_CPU_WDATA_16 (1UL << CRC_CTL_DATLEN_Pos) /*!<CRC CPU Write Data length is 16-bit \hideinitializer */
#define CRC_CPU_WDATA_32 (2UL << CRC_CTL_DATLEN_Pos) /*!<CRC CPU Write Data length is 32-bit \hideinitializer */
/**@}*/ /* end of group CRC_EXPORTED_CONSTANTS */
/** @addtogroup CRC_EXPORTED_FUNCTIONS CRC Exported Functions
@{
*/
/**
* @brief Set CRC Seed Value
*
* @param[in] crc The pointer of CRC module.
* @param[in] u32Seed Seed value
*
* @return None
*
* @details This macro is used to set CRC seed value.
*
* @note User must to perform CRC_CHKSINIT(CRC_CTL[1] CRC Engine Reset) to reload the new seed value
* to CRC controller.
* \hideinitializer
*/
#define CRC_SET_SEED(crc, u32Seed) do{ (crc)->SEED = (u32Seed); (crc)->CTL |= CRC_CTL_CHKSINIT_Msk; } while(0)
/**
* @brief Get CRC Seed Value
*
* @param[in] crc The pointer of CRC module.
*
* @return CRC seed value
*
* @details This macro gets the current CRC seed value.
* \hideinitializer
*/
#define CRC_GET_SEED(crc) ((crc)->SEED)
/**
* @brief CRC Write Data
*
* @param[in] crc The pointer of CRC module.
* @param[in] u32Data Write data
*
* @return None
*
* @details User can write data directly to CRC Write Data Register(CRC_DAT) by this macro to perform CRC operation.
* \hideinitializer
*/
#define CRC_WRITE_DATA(crc, u32Data) ((crc)->DAT = (u32Data))
void CRC_Open(uint32_t u32Mode, uint32_t u32Attribute, uint32_t u32Seed, uint32_t u32DataLen);
uint32_t CRC_GetChecksum(void);
/**@}*/ /* end of group CRC_EXPORTED_FUNCTIONS */
/**@}*/ /* end of group CRC_Driver */
/**@}*/ /* end of group Standard_Driver */
#ifdef __cplusplus
}
#endif
#endif /* __NU_CRC_H__ */

View File

@ -0,0 +1,559 @@
/**************************************************************************//**
* @file nu_crypto.h
* @version V3.00
* @brief Cryptographic Accelerator driver header file
*
* @copyright SPDX-License-Identifier: Apache-2.0
* @copyright Copyright (C) 2020 Nuvoton Technology Corp. All rights reserved.
******************************************************************************/
#ifndef __NU_CRYPTO_H__
#define __NU_CRYPTO_H__
#ifdef __cplusplus
extern "C"
{
#endif
/** @addtogroup Standard_Driver Standard Driver
@{
*/
/** @addtogroup CRYPTO_Driver CRYPTO Driver
@{
*/
/** @addtogroup CRYPTO_EXPORTED_CONSTANTS CRYPTO Exported Constants
@{
*/
#define PRNG_KEY_SIZE_128 ( 0UL) /*!< Select to generate 128-bit random key \hideinitializer */
#define PRNG_KEY_SIZE_163 ( 1UL) /*!< Select to generate 163-bit random key \hideinitializer */
#define PRNG_KEY_SIZE_192 ( 2UL) /*!< Select to generate 192-bit random key \hideinitializer */
#define PRNG_KEY_SIZE_224 ( 3UL) /*!< Select to generate 224-bit random key \hideinitializer */
#define PRNG_KEY_SIZE_255 ( 4UL) /*!< Select to generate 255-bit random key \hideinitializer */
#define PRNG_KEY_SIZE_256 ( 6UL) /*!< Select to generate 256-bit random key \hideinitializer */
#define PRNG_KEY_SIZE_283 ( 7UL) /*!< Select to generate 283-bit random key (Key Store Only) \hideinitializer */
#define PRNG_KEY_SIZE_384 ( 8UL) /*!< Select to generate 384-bit random key (Key Store Only) \hideinitializer */
#define PRNG_KEY_SIZE_409 ( 9UL) /*!< Select to generate 409-bit random key (Key Store Only) \hideinitializer */
#define PRNG_KEY_SIZE_512 (10UL) /*!< Select to generate 512-bit random key (Key Store Only) \hideinitializer */
#define PRNG_KEY_SIZE_521 (11UL) /*!< Select to generate 521-bit random key (Key Store Only) \hideinitializer */
#define PRNG_KEY_SIZE_571 (12UL) /*!< Select to generate 571-bit random key (Key Store Only) \hideinitializer */
#define PRNG_SEED_CONT (0UL) /*!< PRNG using current seed \hideinitializer */
#define PRNG_SEED_RELOAD (1UL) /*!< PRNG reload new seed \hideinitializer */
#define AES_KEY_SIZE_128 (0UL) /*!< AES select 128-bit key length \hideinitializer */
#define AES_KEY_SIZE_192 (1UL) /*!< AES select 192-bit key length \hideinitializer */
#define AES_KEY_SIZE_256 (2UL) /*!< AES select 256-bit key length \hideinitializer */
#define AES_MODE_ECB (0UL) /*!< AES select ECB mode \hideinitializer */
#define AES_MODE_CBC (1UL) /*!< AES select CBC mode \hideinitializer */
#define AES_MODE_CFB (2UL) /*!< AES select CFB mode \hideinitializer */
#define AES_MODE_OFB (3UL) /*!< AES select OFB mode \hideinitializer */
#define AES_MODE_CTR (4UL) /*!< AES select CTR mode \hideinitializer */
#define AES_MODE_CBC_CS1 (0x10UL) /*!< AES select CBC CS1 mode \hideinitializer */
#define AES_MODE_CBC_CS2 (0x11UL) /*!< AES select CBC CS2 mode \hideinitializer */
#define AES_MODE_CBC_CS3 (0x12UL) /*!< AES select CBC CS3 mode \hideinitializer */
#define AES_MODE_GCM (0x20UL)
#define AES_MODE_GHASH (0x21UL)
#define AES_MODE_CCM (0x22UL)
#define SM4_MODE_ECB (0x200UL) /*!< SM4 select ECB mode \hideinitializer */
#define SM4_MODE_CBC (0x201UL) /*!< SM4 select CBC mode \hideinitializer */
#define SM4_MODE_CFB (0x202UL) /*!< SM4 select CFB mode \hideinitializer */
#define SM4_MODE_OFB (0x203UL) /*!< SM4 select OFB mode \hideinitializer */
#define SM4_MODE_CTR (0x204UL) /*!< SM4 select CTR mode \hideinitializer */
#define SM4_MODE_CBC_CS1 (0x210UL) /*!< SM4 select CBC CS1 mode \hideinitializer */
#define SM4_MODE_CBC_CS2 (0x211UL) /*!< SM4 select CBC CS2 mode \hideinitializer */
#define SM4_MODE_CBC_CS3 (0x212UL) /*!< SM4 select CBC CS3 mode \hideinitializer */
#define SM4_MODE_GCM (0x220UL)
#define SM4_MODE_GHASH (0x221UL)
#define SM4_MODE_CCM (0x222UL)
#define AES_NO_SWAP (0UL) /*!< AES do not swap input and output data \hideinitializer */
#define AES_OUT_SWAP (1UL) /*!< AES swap output data \hideinitializer */
#define AES_IN_SWAP (2UL) /*!< AES swap input data \hideinitializer */
#define AES_IN_OUT_SWAP (3UL) /*!< AES swap both input and output data \hideinitializer */
#define DES_MODE_ECB (0x000UL) /*!< DES select ECB mode \hideinitializer */
#define DES_MODE_CBC (0x100UL) /*!< DES select CBC mode \hideinitializer */
#define DES_MODE_CFB (0x200UL) /*!< DES select CFB mode \hideinitializer */
#define DES_MODE_OFB (0x300UL) /*!< DES select OFB mode \hideinitializer */
#define DES_MODE_CTR (0x400UL) /*!< DES select CTR mode \hideinitializer */
#define TDES_MODE_ECB (0x004UL) /*!< TDES select ECB mode \hideinitializer */
#define TDES_MODE_CBC (0x104UL) /*!< TDES select CBC mode \hideinitializer */
#define TDES_MODE_CFB (0x204UL) /*!< TDES select CFB mode \hideinitializer */
#define TDES_MODE_OFB (0x304UL) /*!< TDES select OFB mode \hideinitializer */
#define TDES_MODE_CTR (0x404UL) /*!< TDES select CTR mode \hideinitializer */
#define TDES_NO_SWAP (0UL) /*!< TDES do not swap data \hideinitializer */
#define TDES_WHL_SWAP (1UL) /*!< TDES swap high-low word \hideinitializer */
#define TDES_OUT_SWAP (2UL) /*!< TDES swap output data \hideinitializer */
#define TDES_OUT_WHL_SWAP (3UL) /*!< TDES swap output data and high-low word \hideinitializer */
#define TDES_IN_SWAP (4UL) /*!< TDES swap input data \hideinitializer */
#define TDES_IN_WHL_SWAP (5UL) /*!< TDES swap input data and high-low word \hideinitializer */
#define TDES_IN_OUT_SWAP (6UL) /*!< TDES swap both input and output data \hideinitializer */
#define TDES_IN_OUT_WHL_SWAP (7UL) /*!< TDES swap input, output and high-low word \hideinitializer */
#define SHA_MODE_SHA1 (0UL) /*!< SHA select SHA-1 160-bit \hideinitializer */
#define SHA_MODE_SHA224 (5UL) /*!< SHA select SHA-224 224-bit \hideinitializer */
#define SHA_MODE_SHA256 (4UL) /*!< SHA select SHA-256 256-bit \hideinitializer */
#define SHA_MODE_SHA384 (7UL) /*!< SHA select SHA-384 384-bit \hideinitializer */
#define SHA_MODE_SHA512 (6UL) /*!< SHA select SHA-512 512-bit \hideinitializer */
#define HMAC_MODE_SHA1 (8UL) /*!< HMAC select SHA-1 160-bit \hideinitializer */
#define HMAC_MODE_SHA224 (13UL) /*!< HMAC select SHA-224 224-bit \hideinitializer */
#define HMAC_MODE_SHA256 (12UL) /*!< HMAC select SHA-256 256-bit \hideinitializer */
#define HMAC_MODE_SHA384 (15UL) /*!< HMAC select SHA-384 384-bit \hideinitializer */
#define HMAC_MODE_SHA512 (14UL) /*!< HMAC select SHA-512 512-bit \hideinitializer */
#define SHA_NO_SWAP (0UL) /*!< SHA do not swap input and output data \hideinitializer */
#define SHA_OUT_SWAP (1UL) /*!< SHA swap output data \hideinitializer */
#define SHA_IN_SWAP (2UL) /*!< SHA swap input data \hideinitializer */
#define SHA_IN_OUT_SWAP (3UL) /*!< SHA swap both input and output data \hideinitializer */
#define CRYPTO_DMA_FIRST (0x4UL) /*!< Do first encrypt/decrypt in DMA cascade \hideinitializer */
#define CRYPTO_DMA_ONE_SHOT (0x5UL) /*!< Do one shot encrypt/decrypt with DMA \hideinitializer */
#define CRYPTO_DMA_CONTINUE (0x6UL) /*!< Do continuous encrypt/decrypt in DMA cascade \hideinitializer */
#define CRYPTO_DMA_LAST (0x7UL) /*!< Do last encrypt/decrypt in DMA cascade \hideinitializer */
//---------------------------------------------------
#define RSA_MAX_KLEN (4096)
#define RSA_KBUF_HLEN (RSA_MAX_KLEN/4 + 8)
#define RSA_KBUF_BLEN (RSA_MAX_KLEN + 32)
#define RSA_KEY_SIZE_1024 (0UL) /*!< RSA select 1024-bit key length \hideinitializer */
#define RSA_KEY_SIZE_2048 (1UL) /*!< RSA select 2048-bit key length \hideinitializer */
#define RSA_KEY_SIZE_3072 (2UL) /*!< RSA select 3072-bit key length \hideinitializer */
#define RSA_KEY_SIZE_4096 (3UL) /*!< RSA select 4096-bit key length \hideinitializer */
#define RSA_MODE_NORMAL (0x000UL) /*!< RSA select normal mode \hideinitializer */
#define RSA_MODE_CRT (0x004UL) /*!< RSA select CRT mode \hideinitializer */
#define RSA_MODE_CRTBYPASS (0x00CUL) /*!< RSA select CRT bypass mode \hideinitializer */
#define RSA_MODE_SCAP (0x100UL) /*!< RSA select SCAP mode \hideinitializer */
#define RSA_MODE_CRT_SCAP (0x104UL) /*!< RSA select CRT SCAP mode \hideinitializer */
#define RSA_MODE_CRTBYPASS_SCAP (0x10CUL) /*!< RSA select CRT bypass SCAP mode \hideinitializer */
typedef enum
{
/*!< ECC curve \hideinitializer */
CURVE_P_192, /*!< ECC curve P-192 \hideinitializer */
CURVE_P_224, /*!< ECC curve P-224 \hideinitializer */
CURVE_P_256, /*!< ECC curve P-256 \hideinitializer */
CURVE_P_384, /*!< ECC curve P-384 \hideinitializer */
CURVE_P_521, /*!< ECC curve P-521 \hideinitializer */
CURVE_K_163, /*!< ECC curve K-163 \hideinitializer */
CURVE_K_233, /*!< ECC curve K-233 \hideinitializer */
CURVE_K_283, /*!< ECC curve K-283 \hideinitializer */
CURVE_K_409, /*!< ECC curve K-409 \hideinitializer */
CURVE_K_571, /*!< ECC curve K-571 \hideinitializer */
CURVE_B_163, /*!< ECC curve B-163 \hideinitializer */
CURVE_B_233, /*!< ECC curve B-233 \hideinitializer */
CURVE_B_283, /*!< ECC curve B-283 \hideinitializer */
CURVE_B_409, /*!< ECC curve B-409 \hideinitializer */
CURVE_B_571, /*!< ECC curve K-571 \hideinitializer */
CURVE_KO_192, /*!< ECC 192-bits "Koblitz" curve \hideinitializer */
CURVE_KO_224, /*!< ECC 224-bits "Koblitz" curve \hideinitializer */
CURVE_KO_256, /*!< ECC 256-bits "Koblitz" curve \hideinitializer */
CURVE_BP_256, /*!< ECC Brainpool 256-bits curve \hideinitializer */
CURVE_BP_384, /*!< ECC Brainpool 256-bits curve \hideinitializer */
CURVE_BP_512, /*!< ECC Brainpool 256-bits curve \hideinitializer */
CURVE_25519, /*!< ECC curve-25519 \hideinitializer */
CURVE_SM2_256, /*!< SM2 \hideinitializer */
CURVE_UNDEF = -0x7fffffff, /*!< Invalid curve \hideinitializer */
}
E_ECC_CURVE;
typedef struct e_curve_t
{
E_ECC_CURVE curve_id;
int32_t Echar;
char Ea[144];
char Eb[144];
char Px[144];
char Py[144];
int32_t Epl;
char Pp[176];
int32_t Eol;
char Eorder[176];
int32_t key_len;
int32_t irreducible_k1;
int32_t irreducible_k2;
int32_t irreducible_k3;
int32_t GF;
} ECC_CURVE;
/* RSA working buffer for normal mode */
typedef struct
{
uint32_t au32RsaOutput[128]; /* The RSA answer. */
uint32_t au32RsaN[128]; /* The base of modulus operation word. */
uint32_t au32RsaM[128]; /* The base of exponentiation words. */
uint32_t au32RsaE[128]; /* The exponent of exponentiation words. */
} RSA_BUF_NORMAL_T;
/* RSA working buffer for CRT ( + CRT bypass) mode */
typedef struct
{
uint32_t au32RsaOutput[128]; /* The RSA answer. */
uint32_t au32RsaN[128]; /* The base of modulus operation word. */
uint32_t au32RsaM[128]; /* The base of exponentiation words. */
uint32_t au32RsaE[128]; /* The exponent of exponentiation words. */
uint32_t au32RsaP[128]; /* The Factor of Modulus Operation. */
uint32_t au32RsaQ[128]; /* The Factor of Modulus Operation. */
uint32_t au32RsaTmpCp[128]; /* The Temporary Value(Cp) of RSA CRT. */
uint32_t au32RsaTmpCq[128]; /* The Temporary Value(Cq) of RSA CRT. */
uint32_t au32RsaTmpDp[128]; /* The Temporary Value(Dp) of RSA CRT. */
uint32_t au32RsaTmpDq[128]; /* The Temporary Value(Dq) of RSA CRT. */
uint32_t au32RsaTmpRp[128]; /* The Temporary Value(Rp) of RSA CRT. */
uint32_t au32RsaTmpRq[128]; /* The Temporary Value(Rq) of RSA CRT. */
} RSA_BUF_CRT_T;
/* RSA working buffer for SCAP mode */
typedef struct
{
uint32_t au32RsaOutput[128]; /* The RSA answer. */
uint32_t au32RsaN[128]; /* The base of modulus operation word. */
uint32_t au32RsaM[128]; /* The base of exponentiation words. */
uint32_t au32RsaE[128]; /* The exponent of exponentiation words. */
uint32_t au32RsaP[128]; /* The Factor of Modulus Operation. */
uint32_t au32RsaQ[128]; /* The Factor of Modulus Operation. */
uint32_t au32RsaTmpBlindKey[128]; /* The Temporary Value(blind key) of RSA SCAP. */
} RSA_BUF_SCAP_T;
/* RSA working buffer for CRT ( + CRT bypass ) + SCAP mode */
typedef struct
{
uint32_t au32RsaOutput[128]; /* The RSA answer. */
uint32_t au32RsaN[128]; /* The base of modulus operation word. */
uint32_t au32RsaM[128]; /* The base of exponentiation words. */
uint32_t au32RsaE[128]; /* The exponent of exponentiation words. */
uint32_t au32RsaP[128]; /* The Factor of Modulus Operation. */
uint32_t au32RsaQ[128]; /* The Factor of Modulus Operation. */
uint32_t au32RsaTmpCp[128]; /* The Temporary Value(Cp) of RSA CRT. */
uint32_t au32RsaTmpCq[128]; /* The Temporary Value(Cq) of RSA CRT. */
uint32_t au32RsaTmpDp[128]; /* The Temporary Value(Dp) of RSA CRT. */
uint32_t au32RsaTmpDq[128]; /* The Temporary Value(Dq) of RSA CRT. */
uint32_t au32RsaTmpRp[128]; /* The Temporary Value(Rp) of RSA CRT. */
uint32_t au32RsaTmpRq[128]; /* The Temporary Value(Rq) of RSA CRT. */
uint32_t au32RsaTmpBlindKey[128]; /* The Temporary Value(blind key) of RSA SCAP. */
} RSA_BUF_CRT_SCAP_T;
/* RSA working buffer for using key store */
typedef struct
{
uint32_t au32RsaOutput[128]; /* The RSA answer. */
uint32_t au32RsaN[128]; /* The base of modulus operation word. */
uint32_t au32RsaM[128]; /* The base of exponentiation words. */
} RSA_BUF_KS_T;
/**@}*/ /* end of group CRYPTO_EXPORTED_CONSTANTS */
/** @addtogroup CRYPTO_EXPORTED_MACROS CRYPTO Exported Macros
@{
*/
/*----------------------------------------------------------------------------------------------*/
/* Macros */
/*----------------------------------------------------------------------------------------------*/
/**
* @brief This macro enables PRNG interrupt.
* @param crpt Specified crypto module
* @return None
* \hideinitializer
*/
#define PRNG_ENABLE_INT(crpt) ((crpt)->INTEN |= CRPT_INTEN_PRNGIEN_Msk)
/**
* @brief This macro disables PRNG interrupt.
* @param crpt Specified crypto module
* @return None
* \hideinitializer
*/
#define PRNG_DISABLE_INT(crpt) ((crpt)->INTEN &= ~CRPT_INTEN_PRNGIEN_Msk)
/**
* @brief This macro gets PRNG interrupt flag.
* @param crpt Specified crypto module
* @return PRNG interrupt flag.
* \hideinitializer
*/
#define PRNG_GET_INT_FLAG(crpt) ((crpt)->INTSTS & CRPT_INTSTS_PRNGIF_Msk)
/**
* @brief This macro clears PRNG interrupt flag.
* @param crpt Specified crypto module
* @return None
* \hideinitializer
*/
#define PRNG_CLR_INT_FLAG(crpt) ((crpt)->INTSTS = CRPT_INTSTS_PRNGIF_Msk)
/**
* @brief This macro enables AES interrupt.
* @param crpt Specified crypto module
* @return None
* \hideinitializer
*/
#define AES_ENABLE_INT(crpt) ((crpt)->INTEN |= (CRPT_INTEN_AESIEN_Msk|CRPT_INTEN_AESEIEN_Msk))
/**
* @brief This macro disables AES interrupt.
* @param crpt Specified crypto module
* @return None
* \hideinitializer
*/
#define AES_DISABLE_INT(crpt) ((crpt)->INTEN &= ~(CRPT_INTEN_AESIEN_Msk|CRPT_INTEN_AESEIEN_Msk))
/**
* @brief This macro gets AES interrupt flag.
* @param crpt Specified crypto module
* @return AES interrupt flag.
* \hideinitializer
*/
#define AES_GET_INT_FLAG(crpt) ((crpt)->INTSTS & (CRPT_INTSTS_AESIF_Msk|CRPT_INTSTS_AESEIF_Msk))
/**
* @brief This macro clears AES interrupt flag.
* @param crpt Specified crypto module
* @return None
* \hideinitializer
*/
#define AES_CLR_INT_FLAG(crpt) ((crpt)->INTSTS = (CRPT_INTSTS_AESIF_Msk|CRPT_INTSTS_AESEIF_Msk))
/**
* @brief This macro enables AES key protection.
* @param crpt Specified crypto module
* @return None
* \hideinitializer
*/
#define AES_ENABLE_KEY_PROTECT(crpt) ((crpt)->AES_CTL |= CRPT_AES_CTL_KEYPRT_Msk)
/**
* @brief This macro disables AES key protection.
* @param crpt Specified crypto module
* @return None
* \hideinitializer
*/
#define AES_DISABLE_KEY_PROTECT(crpt) ((crpt)->AES_CTL = ((crpt)->AES_CTL & ~CRPT_AES_CTL_KEYPRT_Msk) | (0x16UL<<CRPT_AES_CTL_KEYUNPRT_Pos)); \
((crpt)->AES_CTL &= ~CRPT_AES_CTL_KEYPRT_Msk)
/**
* @brief This macro enables TDES interrupt.
* @param crpt Specified crypto module
* @return None
* \hideinitializer
*/
#define TDES_ENABLE_INT(crpt) ((crpt)->INTEN |= (CRPT_INTEN_TDESIEN_Msk|CRPT_INTEN_TDESEIEN_Msk))
/**
* @brief This macro disables TDES interrupt.
* @param crpt Specified crypto module
* @return None
* \hideinitializer
*/
#define TDES_DISABLE_INT(crpt) ((crpt)->INTEN &= ~(CRPT_INTEN_TDESIEN_Msk|CRPT_INTEN_TDESEIEN_Msk))
/**
* @brief This macro gets TDES interrupt flag.
* @param crpt Specified crypto module
* @return TDES interrupt flag.
* \hideinitializer
*/
#define TDES_GET_INT_FLAG(crpt) ((crpt)->INTSTS & (CRPT_INTSTS_TDESIF_Msk|CRPT_INTSTS_TDESEIF_Msk))
/**
* @brief This macro clears TDES interrupt flag.
* @param crpt Specified crypto module
* @return None
* \hideinitializer
*/
#define TDES_CLR_INT_FLAG(crpt) ((crpt)->INTSTS = (CRPT_INTSTS_TDESIF_Msk|CRPT_INTSTS_TDESEIF_Msk))
/**
* @brief This macro enables TDES key protection.
* @param crpt Specified crypto module
* @return None
* \hideinitializer
*/
#define TDES_ENABLE_KEY_PROTECT(crpt) ((crpt)->TDES_CTL |= CRPT_TDES_CTL_KEYPRT_Msk)
/**
* @brief This macro disables TDES key protection.
* @param crpt Specified crypto module
* @return None
* \hideinitializer
*/
#define TDES_DISABLE_KEY_PROTECT(crpt) ((crpt)->TDES_CTL = ((crpt)->TDES_CTL & ~CRPT_TDES_CTL_KEYPRT_Msk) | (0x16UL<<CRPT_TDES_CTL_KEYUNPRT_Pos)); \
((crpt)->TDES_CTL &= ~CRPT_TDES_CTL_KEYPRT_Msk)
/**
* @brief This macro enables SHA interrupt.
* @param crpt Specified crypto module
* @return None
* \hideinitializer
*/
#define SHA_ENABLE_INT(crpt) ((crpt)->INTEN |= (CRPT_INTEN_HMACIEN_Msk|CRPT_INTEN_HMACEIEN_Msk))
/**
* @brief This macro disables SHA interrupt.
* @param crpt Specified crypto module
* @return None
* \hideinitializer
*/
#define SHA_DISABLE_INT(crpt) ((crpt)->INTEN &= ~(CRPT_INTEN_HMACIEN_Msk|CRPT_INTEN_HMACEIEN_Msk))
/**
* @brief This macro gets SHA interrupt flag.
* @param crpt Specified crypto module
* @return SHA interrupt flag.
* \hideinitializer
*/
#define SHA_GET_INT_FLAG(crpt) ((crpt)->INTSTS & (CRPT_INTSTS_HMACIF_Msk|CRPT_INTSTS_HMACEIF_Msk))
/**
* @brief This macro clears SHA interrupt flag.
* @param crpt Specified crypto module
* @return None
* \hideinitializer
*/
#define SHA_CLR_INT_FLAG(crpt) ((crpt)->INTSTS = (CRPT_INTSTS_HMACIF_Msk|CRPT_INTSTS_HMACEIF_Msk))
/**
* @brief This macro enables ECC interrupt.
* @param crpt Specified crypto module
* @return None
* \hideinitializer
*/
#define ECC_ENABLE_INT(crpt) ((crpt)->INTEN |= (CRPT_INTEN_ECCIEN_Msk|CRPT_INTEN_ECCEIEN_Msk))
/**
* @brief This macro disables ECC interrupt.
* @param crpt Specified crypto module
* @return None
* \hideinitializer
*/
#define ECC_DISABLE_INT(crpt) ((crpt)->INTEN &= ~(CRPT_INTEN_ECCIEN_Msk|CRPT_INTEN_ECCEIEN_Msk))
/**
* @brief This macro gets ECC interrupt flag.
* @param crpt Specified crypto module
* @return ECC interrupt flag.
* \hideinitializer
*/
#define ECC_GET_INT_FLAG(crpt) ((crpt)->INTSTS & (CRPT_INTSTS_ECCIF_Msk|CRPT_INTSTS_ECCEIF_Msk))
/**
* @brief This macro clears ECC interrupt flag.
* @param crpt Specified crypto module
* @return None
* \hideinitializer
*/
#define ECC_CLR_INT_FLAG(crpt) ((crpt)->INTSTS = (CRPT_INTSTS_ECCIF_Msk|CRPT_INTSTS_ECCEIF_Msk))
/**
* @brief This macro enables RSA interrupt.
* @param crpt Specified crypto module
* @return None
* \hideinitializer
*/
#define RSA_ENABLE_INT(crpt) ((crpt)->INTEN |= (CRPT_INTEN_RSAIEN_Msk|CRPT_INTEN_RSAEIEN_Msk))
/**
* @brief This macro disables RSA interrupt.
* @param crpt Specified crypto module
* @return None
* \hideinitializer
*/
#define RSA_DISABLE_INT(crpt) ((crpt)->INTEN &= ~(CRPT_INTEN_RSAIEN_Msk|CRPT_INTEN_RSAEIEN_Msk))
/**
* @brief This macro gets RSA interrupt flag.
* @param crpt Specified crypto module
* @return ECC interrupt flag.
* \hideinitializer
*/
#define RSA_GET_INT_FLAG(crpt) ((crpt)->INTSTS & (CRPT_INTSTS_RSAIF_Msk|CRPT_INTSTS_RSAEIF_Msk))
/**
* @brief This macro clears RSA interrupt flag.
* @param crpt Specified crypto module
* @return None
* \hideinitializer
*/
#define RSA_CLR_INT_FLAG(crpt) ((crpt)->INTSTS = (CRPT_INTSTS_RSAIF_Msk|CRPT_INTSTS_RSAEIF_Msk))
/**@}*/ /* end of group CRYPTO_EXPORTED_MACROS */
/** @addtogroup CRYPTO_EXPORTED_FUNCTIONS CRYPTO Exported Functions
@{
*/
/*---------------------------------------------------------------------------------------------------------*/
/* Functions */
/*---------------------------------------------------------------------------------------------------------*/
void PRNG_Open(CRPT_T *crpt, uint32_t u32KeySize, uint32_t u32SeedReload, uint32_t u32Seed);
void PRNG_Start(CRPT_T *crpt);
void PRNG_Read(CRPT_T *crpt, uint32_t u32RandKey[]);
void AES_Open(CRPT_T *crpt, uint32_t u32Channel, uint32_t u32EncDec, uint32_t u32OpMode, uint32_t u32KeySize, uint32_t u32SwapType);
void AES_Start(CRPT_T *crpt, int32_t u32Channel, uint32_t u32DMAMode);
void AES_SetKey(CRPT_T *crpt, uint32_t u32Channel, uint32_t au32Keys[], uint32_t u32KeySize);
void AES_SetKey_KS(CRPT_T *crpt, KS_MEM_Type mem, int32_t i32KeyIdx);
void AES_SetInitVect(CRPT_T *crpt, uint32_t u32Channel, uint32_t au32IV[]);
void AES_SetDMATransfer(CRPT_T *crpt, uint32_t u32Channel, uint32_t u32SrcAddr, uint32_t u32DstAddr, uint32_t u32TransCnt);
void SHA_Open(CRPT_T *crpt, uint32_t u32OpMode, uint32_t u32SwapType, uint32_t hmac_key_len);
void SHA_Start(CRPT_T *crpt, uint32_t u32DMAMode);
void SHA_SetDMATransfer(CRPT_T *crpt, uint32_t u32SrcAddr, uint32_t u32TransCnt);
void SHA_Read(CRPT_T *crpt, uint32_t u32Digest[]);
void ECC_DriverISR(CRPT_T *crpt);
int ECC_IsPrivateKeyValid(CRPT_T *crpt, E_ECC_CURVE ecc_curve, char private_k[]);
int32_t ECC_GenerateSecretZ(CRPT_T *crpt, E_ECC_CURVE ecc_curve, char *private_k, char public_k1[], char public_k2[], char secret_z[]);
int32_t ECC_GeneratePublicKey(CRPT_T *crpt, E_ECC_CURVE ecc_curve, char *private_k, char public_k1[], char public_k2[]);
int32_t ECC_GenerateSignature(CRPT_T *crpt, E_ECC_CURVE ecc_curve, char *message, char *d, char *k, char *R, char *S);
int32_t ECC_VerifySignature(CRPT_T *crpt, E_ECC_CURVE ecc_curve, char *message, char *public_k1, char *public_k2, char *R, char *S);
int32_t RSA_Open(CRPT_T *crpt, uint32_t u32OpMode, uint32_t u32KeySize, void *psRSA_Buf, uint32_t u32BufSize, uint32_t u32UseKS);
int32_t RSA_SetKey(CRPT_T *crpt, char *Key);
int32_t RSA_SetDMATransfer(CRPT_T *crpt, char *Src, char *n, char *P, char *Q);
void RSA_Start(CRPT_T *crpt);
int32_t RSA_Read(CRPT_T *crpt, char * Output);
int32_t RSA_SetKey_KS(CRPT_T *crpt, uint32_t u32KeyNum, uint32_t u32KSMemType, uint32_t u32BlindKeyNum);
int32_t RSA_SetDMATransfer_KS(CRPT_T *crpt, char *Src, char *n, uint32_t u32PNum,
uint32_t u32QNum, uint32_t u32CpNum, uint32_t u32CqNum, uint32_t u32DpNum,
uint32_t u32DqNum, uint32_t u32RpNum, uint32_t u32RqNum);
int32_t ECC_GeneratePublicKey_KS(CRPT_T *crpt, E_ECC_CURVE ecc_curve, KS_MEM_Type mem, int32_t i32KeyIdx, char public_k1[], char public_k2[], uint32_t u32ExtraOp);
int32_t ECC_GenerateSignature_KS(CRPT_T *crpt, E_ECC_CURVE ecc_curve, char *message, KS_MEM_Type mem_d, int32_t i32KeyIdx_d, KS_MEM_Type mem_k, int32_t i32KeyIdx_k, char *R, char *S);
int32_t ECC_VerifySignature_KS(CRPT_T *crpt, E_ECC_CURVE ecc_curve, char *message, KS_MEM_Type mem_pk1, int32_t i32KeyIdx_pk1, KS_MEM_Type mem_pk2, int32_t i32KeyIdx_pk2, char *R, char *S);
int32_t ECC_GenerateSecretZ_KS(CRPT_T *crpt, E_ECC_CURVE ecc_curve, KS_MEM_Type mem, int32_t i32KeyIdx, char public_k1[], char public_k2[]);
void CRPT_Reg2Hex(int32_t count, uint32_t volatile reg[], char output[]);
void CRPT_Hex2Reg(char input[], uint32_t volatile reg[]);
int32_t ECC_GetCurve(CRPT_T *crpt, E_ECC_CURVE ecc_curve, ECC_CURVE *curve);
/**@}*/ /* end of group CRYPTO_EXPORTED_FUNCTIONS */
/**@}*/ /* end of group CRYPTO_Driver */
/**@}*/ /* end of group Standard_Driver */
#ifdef __cplusplus
}
#endif
#endif /* __NU_CRYPTO_H__ */

View File

@ -0,0 +1,255 @@
/******************************************************************************
* @file nu_dac.h
* @version V1.00
* @brief M2354 series DAC driver header file
*
* @copyright SPDX-License-Identifier: Apache-2.0
* @copyright Copyright (C) 2020 Nuvoton Technology Corp. All rights reserved.
*****************************************************************************/
#ifndef __NU_DAC_H__
#define __NU_DAC_H__
#ifdef __cplusplus
extern "C"
{
#endif
/** @addtogroup Standard_Driver Standard Driver
@{
*/
/** @addtogroup DAC_Driver DAC Driver
@{
*/
/** @addtogroup DAC_EXPORTED_CONSTANTS DAC Exported Constants
@{
*/
/*---------------------------------------------------------------------------------------------------------*/
/* DAC_CTL Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define DAC_CTL_LALIGN_RIGHT_ALIGN (0UL<<DAC_CTL_LALIGN_Pos) /*!< Right alignment. */
#define DAC_CTL_LALIGN_LEFT_ALIGN (1UL<<DAC_CTL_LALIGN_Pos) /*!< Left alignment */
#define DAC_WRITE_DAT_TRIGGER (0UL) /*!< Write DAC_DAT trigger */
#define DAC_SOFTWARE_TRIGGER (0UL|DAC_CTL_TRGEN_Msk) /*!< Software trigger */
#define DAC_LOW_LEVEL_TRIGGER ((0UL<<DAC_CTL_ETRGSEL_Pos)|(1UL<<DAC_CTL_TRGSEL_Pos)|DAC_CTL_TRGEN_Msk) /*!< STDAC pin low level trigger */
#define DAC_HIGH_LEVEL_TRIGGER ((1UL<<DAC_CTL_ETRGSEL_Pos)|(1UL<<DAC_CTL_TRGSEL_Pos)|DAC_CTL_TRGEN_Msk) /*!< STDAC pin high level trigger */
#define DAC_FALLING_EDGE_TRIGGER ((2UL<<DAC_CTL_ETRGSEL_Pos)|(1UL<<DAC_CTL_TRGSEL_Pos)|DAC_CTL_TRGEN_Msk) /*!< STDAC pin falling edge trigger */
#define DAC_RISING_EDGE_TRIGGER ((3UL<<DAC_CTL_ETRGSEL_Pos)|(1UL<<DAC_CTL_TRGSEL_Pos)|DAC_CTL_TRGEN_Msk) /*!< STDAC pin rising edge trigger */
#define DAC_TIMER0_TRIGGER ((2UL<<DAC_CTL_TRGSEL_Pos)|DAC_CTL_TRGEN_Msk) /*!< Timer 0 trigger */
#define DAC_TIMER1_TRIGGER ((3UL<<DAC_CTL_TRGSEL_Pos)|DAC_CTL_TRGEN_Msk) /*!< Timer 1 trigger */
#define DAC_TIMER2_TRIGGER ((4UL<<DAC_CTL_TRGSEL_Pos)|DAC_CTL_TRGEN_Msk) /*!< Timer 2 trigger */
#define DAC_TIMER3_TRIGGER ((5UL<<DAC_CTL_TRGSEL_Pos)|DAC_CTL_TRGEN_Msk) /*!< Timer 3 trigger */
#define DAC_EPWM0_TRIGGER ((6UL<<DAC_CTL_TRGSEL_Pos)|DAC_CTL_TRGEN_Msk) /*!< EPWM0 trigger */
#define DAC_EPWM1_TRIGGER ((7UL<<DAC_CTL_TRGSEL_Pos)|DAC_CTL_TRGEN_Msk) /*!< EPWM1 trigger */
#define DAC_TRIGGER_MODE_DISABLE (0UL<<DAC_CTL_TRGEN_Pos) /*!< Trigger mode disable */
#define DAC_TRIGGER_MODE_ENABLE (1UL<<DAC_CTL_TRGEN_Pos) /*!< Trigger mode enable */
/**@}*/ /* end of group DAC_EXPORTED_CONSTANTS */
/** @addtogroup DAC_EXPORTED_FUNCTIONS DAC Exported Functions
@{
*/
/*---------------------------------------------------------------------------------------------------------*/
/* DAC Macro Definitions */
/*---------------------------------------------------------------------------------------------------------*/
/**
* @brief Start the D/A conversion.
* @param[in] dac The pointer of the specified DAC module.
* @return None
* @details User writes SWTRG bit (DAC_SWTRG[0]) to generate one shot pulse and it is cleared to 0 by hardware automatically.
*/
#define DAC_START_CONV(dac) ((dac)->SWTRG = DAC_SWTRG_SWTRG_Msk)
/**
* @brief Enable DAC data left-aligned.
* @param[in] dac The pointer of the specified DAC module.
* @return None
* @details User has to load data into DAC_DAT[15:4] bits. DAC_DAT[31:16] and DAC_DAT[3:0] are ignored in DAC conversion.
*/
#define DAC_ENABLE_LEFT_ALIGN(dac) ((dac)->CTL |= DAC_CTL_LALIGN_Msk)
/**
* @brief Enable DAC data right-aligned.
* @param[in] dac The pointer of the specified DAC module.
* @return None
* @details User has to load data into DAC_DAT[11:0] bits, DAC_DAT[31:12] are ignored in DAC conversion.
*/
#define DAC_ENABLE_RIGHT_ALIGN(dac) ((dac)->CTL &= ~DAC_CTL_LALIGN_Msk)
/**
* @brief Enable output voltage buffer.
* @param[in] dac The pointer of the specified DAC module.
* @return None
* @details The DAC integrates a voltage output buffer that can be used to reduce output impedance and
* drive external loads directly without having to add an external operational amplifier.
*/
#define DAC_ENABLE_BYPASS_BUFFER(dac) ((dac)->CTL |= DAC_CTL_BYPASS_Msk)
/**
* @brief Disable output voltage buffer.
* @param[in] dac The pointer of the specified DAC module.
* @return None
* @details This macro is used to disable output voltage buffer.
*/
#define DAC_DISABLE_BYPASS_BUFFER(dac) ((dac)->CTL &= ~DAC_CTL_BYPASS_Msk)
/**
* @brief Enable the interrupt.
* @param[in] dac The pointer of the specified DAC module.
* @param[in] u32Ch Not used in M2355 Series DAC.
* @return None
* @details This macro is used to enable DAC interrupt.
*/
#define DAC_ENABLE_INT(dac, u32Ch) ((dac)->CTL |= DAC_CTL_DACIEN_Msk)
/**
* @brief Disable the interrupt.
* @param[in] dac The pointer of the specified DAC module.
* @param[in] u32Ch Not used in M2355 Series DAC.
* @return None
* @details This macro is used to disable DAC interrupt.
*/
#define DAC_DISABLE_INT(dac, u32Ch) ((dac)->CTL &= ~DAC_CTL_DACIEN_Msk)
/**
* @brief Enable DMA under-run interrupt.
* @param[in] dac The pointer of the specified DAC module.
* @return None
* @details This macro is used to enable DMA under-run interrupt.
*/
#define DAC_ENABLE_DMAUDR_INT(dac) ((dac)->CTL |= DAC_CTL_DMAURIEN_Msk)
/**
* @brief Disable DMA under-run interrupt.
* @param[in] dac The pointer of the specified DAC module.
* @return None
* @details This macro is used to disable DMA under-run interrupt.
*/
#define DAC_DISABLE_DMAUDR_INT(dac) ((dac)->CTL &= ~DAC_CTL_DMAURIEN_Msk)
/**
* @brief Enable PDMA mode.
* @param[in] dac The pointer of the specified DAC module.
* @return None
* @details DAC DMA request is generated when a hardware trigger event occurs while DMAEN (DAC_CTL[2]) is set.
*/
#define DAC_ENABLE_PDMA(dac) ((dac)->CTL |= DAC_CTL_DMAEN_Msk)
/**
* @brief Disable PDMA mode.
* @param[in] dac The pointer of the specified DAC module.
* @return None
* @details This macro is used to disable DMA mode.
*/
#define DAC_DISABLE_PDMA(dac) ((dac)->CTL &= ~DAC_CTL_DMAEN_Msk)
/**
* @brief Write data for conversion.
* @param[in] dac The pointer of the specified DAC module.
* @param[in] u32Ch Not used in M2355 Series DAC.
* @param[in] u32Data Decides the data for conversion, valid range are between 0~0xFFF.
* @return None
* @details 12 bit left alignment: user has to load data into DAC_DAT[15:4] bits.
* 12 bit right alignment: user has to load data into DAC_DAT[11:0] bits.
*/
#define DAC_WRITE_DATA(dac, u32Ch, u32Data) ((dac)->DAT = (u32Data))
/**
* @brief Read DAC 12-bit holding data.
* @param[in] dac The pointer of the specified DAC module.
* @param[in] u32Ch Not used in M2355 Series DAC.
* @return Return DAC 12-bit holding data.
* @details This macro is used to read DAC_DAT register.
*/
#define DAC_READ_DATA(dac, u32Ch) ((dac)->DAT)
/**
* @brief Get the busy state of DAC.
* @param[in] dac The pointer of the specified DAC module.
* @param[in] u32Ch Not used in M2355 Series DAC.
* @retval 0 Idle state.
* @retval 1 Busy state.
* @details This macro is used to read BUSY bit (DAC_STATUS[8]) to get busy state.
*/
#define DAC_IS_BUSY(dac, u32Ch) (((dac)->STATUS & DAC_STATUS_BUSY_Msk) >> DAC_STATUS_BUSY_Pos)
/**
* @brief Get the interrupt flag.
* @param[in] dac The pointer of the specified DAC module.
* @param[in] u32Ch Not used in M2355 Series DAC.
* @retval 0 DAC is in conversion state.
* @retval 1 DAC conversion finish.
* @details This macro is used to read FINISH bit (DAC_STATUS[0]) to get DAC conversion complete finish flag.
*/
#define DAC_GET_INT_FLAG(dac, u32Ch) ((dac)->STATUS & DAC_STATUS_FINISH_Msk)
/**
* @brief Get the DMA under-run flag.
* @param[in] dac The pointer of the specified DAC module.
* @retval 0 No DMA under-run error condition occurred.
* @retval 1 DMA under-run error condition occurred.
* @details This macro is used to read DMAUDR bit (DAC_STATUS[1]) to get DMA under-run state.
*/
#define DAC_GET_DMAUDR_FLAG(dac) (((dac)->STATUS & DAC_STATUS_DMAUDR_Msk) >> DAC_STATUS_DMAUDR_Pos)
/**
* @brief This macro clear the interrupt status bit.
* @param[in] dac The pointer of the specified DAC module.
* @param[in] u32Ch Not used in M2355 Series DAC.
* @return None
* @details User writes FINISH bit (DAC_STATUS[0]) to clear DAC conversion complete finish flag.
*/
#define DAC_CLR_INT_FLAG(dac, u32Ch) ((dac)->STATUS = DAC_STATUS_FINISH_Msk)
/**
* @brief This macro clear the DMA under-run flag.
* @param[in] dac The pointer of the specified DAC module.
* @return None
* @details User writes DMAUDR bit (DAC_STATUS[1]) to clear DMA under-run flag.
*/
#define DAC_CLR_DMAUDR_FLAG(dac) ((dac)->STATUS = DAC_STATUS_DMAUDR_Msk)
/**
* @brief Enable DAC group mode
* @param[in] dac The pointer of the specified DAC module.
* @return None
* @note Only DAC0 has this control bit.
* \hideinitializer
*/
#define DAC_ENABLE_GROUP_MODE(dac) ((dac)->CTL |= DAC_CTL_GRPEN_Msk)
/**
* @brief Disable DAC group mode
* @param[in] dac The pointer of the specified DAC module.
* @return None
* @note Only DAC0 has this control bit.
* \hideinitializer
*/
#define DAC_DISABLE_GROUP_MODE(dac) ((dac)->CTL &= ~DAC_CTL_GRPEN_Msk)
void DAC_Open(DAC_T *dac, uint32_t u32Ch, uint32_t u32TrgSrc);
void DAC_Close(DAC_T *dac, uint32_t u32Ch);
uint32_t DAC_SetDelayTime(DAC_T *dac, uint32_t u32Delay);
/**@}*/ /* end of group DAC_EXPORTED_FUNCTIONS */
/**@}*/ /* end of group DAC_Driver */
/**@}*/ /* end of group Standard_Driver */
#ifdef __cplusplus
}
#endif
#endif /* __NU_DAC_H__ */

View File

@ -0,0 +1,130 @@
/**************************************************************************//**
* @file nu_dpm.h
* @version V3.00
* @brief Debug Protection Mechanism (DPM) driver header file
*
* @copyright SPDX-License-Identifier: Apache-2.0
* @copyright Copyright (C) 2020 Nuvoton Technology Corp. All rights reserved.
*****************************************************************************/
#ifndef __NU_DPM_H__
#define __NU_DPM_H__
#ifdef __cplusplus
extern "C"
{
#endif
/** @addtogroup Standard_Driver Standard Driver
@{
*/
/** @addtogroup DPM_Driver DPM Driver
@{
*/
/** @addtogroup DPM_EXPORTED_CONSTANTS DPM Exported Constants
@{
*/
/*---------------------------------------------------------------------------------------------------------*/
/* DPM Control Register Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define SECURE_DPM 0 /*!< Secure DPM module */
#define NONSECURE_DPM 1 /*!< Non-secure DPM module */
#define DPM_CTL_WVCODE (0x5AUL<<DPM_CTL_WVCODE_Pos) /*!< Secure DPM control register write verify code */
#define DPM_CTL_RVCODE (0xA5UL<<DPM_CTL_RVCODE_Pos) /*!< Secure DPM control register read verify code */
#define DPM_NSCTL_WVCODE (0x5AUL<<DPM_CTL_WVCODE_Pos) /*!< Non-secure DPM control register write verify code */
#define DPM_NSCTL_RVCODE (0xA5UL<<DPM_CTL_RVCODE_Pos) /*!< Non-secure DPM control register read verify code */
/**@}*/ /* end of group WDT_EXPORTED_CONSTANTS */
/** @addtogroup DPM_EXPORTED_FUNCTIONS DPM Exported Functions
@{
*/
/**
* @brief Enable DPM Interrupt
* @param None
* @return None
* @details This macro enables DPM interrupt.
* This macro is for Secure DPM and Secure region only.
*/
#define DPM_ENABLE_INT() \
do{ \
while(DPM->STS & DPM_STS_BUSY_Msk); \
DPM->CTL = (DPM->CTL & (~DPM_CTL_WVCODE_Msk)) | (DPM_CTL_WVCODE|DPM_CTL_INTEN_Msk); \
}while(0)
/**
* @brief Disable DPM Interrupt
* @param None
* @return None
* @details This macro disables DPM interrupt.
* This macro is for Secure DPM and Secure region only.
*/
#define DPM_DISABLE_INT() \
do{ \
while(DPM->STS & DPM_STS_BUSY_Msk); \
DPM->CTL = (DPM->CTL & (~(DPM_CTL_WVCODE_Msk|DPM_CTL_INTEN_Msk))) | (DPM_CTL_WVCODE); \
}while(0)
/**
* @brief Enable Debugger to Access DPM Registers
* @param None
* @return None
* @details This macro enables debugger to access Secure and Non-secure DPM registers.
* This macro is for Secure DPM and Secure region only.
*/
#define DPM_ENABLE_DBG_ACCESS() \
do{ \
while(DPM->STS & DPM_STS_BUSY_Msk); \
DPM->CTL = (DPM->CTL & (~(DPM_CTL_WVCODE_Msk|DPM_CTL_DACCDIS_Msk))) | (DPM_CTL_WVCODE); \
}while(0)
/**
* @brief Disable Debugger to Access DPM Registers
* @param None
* @return None
* @details This macro disables debugger to access Secure and Non-secure DPM registers.
* This macro is for Secure DPM and Secure region only.
*/
#define DPM_DISABLE_DBG_ACCESS() \
do{ \
while(DPM->STS & DPM_STS_BUSY_Msk); \
DPM->CTL = (DPM->CTL & (~DPM_CTL_WVCODE_Msk)) | (DPM_CTL_WVCODE|DPM_CTL_DACCDIS_Msk); \
}while(0)
void DPM_SetDebugDisable(uint32_t u32dpm);
void DPM_SetDebugLock(uint32_t u32dpm);
uint32_t DPM_GetDebugDisable(uint32_t u32dpm);
uint32_t DPM_GetDebugLock(uint32_t u32dpm);
uint32_t DPM_SetPasswordUpdate(uint32_t u32dpm, uint32_t au32Pwd[]);
uint32_t DPM_SetPasswordCompare(uint32_t u32dpm, uint32_t au32Pwd[]);
uint32_t DPM_GetPasswordErrorFlag(uint32_t u32dpm);
uint32_t DPM_GetIntFlag(void);
void DPM_ClearPasswordErrorFlag(uint32_t u32dpm);
void DPM_EnableDebuggerWriteAccess(uint32_t u32dpm);
void DPM_DisableDebuggerWriteAccess(uint32_t u32dpm);
/**@}*/ /* end of group DPM_EXPORTED_FUNCTIONS */
/**@}*/ /* end of group DPM_Driver */
/**@}*/ /* end of group Standard_Driver */
#ifdef __cplusplus
}
#endif
#endif /* __NU_DPM_H__ */

View File

@ -0,0 +1,560 @@
/******************************************************************************
* @file nu_eadc.h
* @version V0.10
* @brief M2354 series EADC driver header file
*
* @copyright SPDX-License-Identifier: Apache-2.0
* @copyright Copyright (C) 2020 Nuvoton Technology Corp. All rights reserved.
*****************************************************************************/
#ifndef __NU_EADC_H__
#define __NU_EADC_H__
#ifdef __cplusplus
extern "C"
{
#endif
/** @addtogroup Standard_Driver Standard Driver
@{
*/
/** @addtogroup EADC_Driver EADC Driver
@{
*/
/** @addtogroup EADC_EXPORTED_CONSTANTS EADC Exported Constants
@{
*/
/*---------------------------------------------------------------------------------------------------------*/
/* EADC_CTL Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define EADC_CTL_DIFFEN_SINGLE_END (0UL<<EADC_CTL_DIFFEN_Pos) /*!< Single-end input mode */
#define EADC_CTL_DIFFEN_DIFFERENTIAL (1UL<<EADC_CTL_DIFFEN_Pos) /*!< Differential input mode */
#define EADC_CTL_DMOF_STRAIGHT_BINARY (0UL<<EADC_CTL_DMOF_Pos) /*!< Select the straight binary format as the output format of the conversion result */
#define EADC_CTL_DMOF_TWOS_COMPLEMENT (1UL<<EADC_CTL_DMOF_Pos) /*!< Select the 2's complement format as the output format of the conversion result */
/*---------------------------------------------------------------------------------------------------------*/
/* EADC_SCTL Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define EADC_SCTL_CHSEL(x) ((x) << EADC_SCTL_CHSEL_Pos) /*!< A/D sample module channel selection */
#define EADC_SCTL_TRGDLYDIV(x) ((x) << EADC_SCTL_TRGDLYDIV_Pos) /*!< A/D sample module start of conversion trigger delay clock divider selection */
#define EADC_SCTL_TRGDLYCNT(x) ((x) << EADC_SCTL_TRGDLYCNT_Pos) /*!< A/D sample module start of conversion trigger delay time */
#define EADC_SOFTWARE_TRIGGER (0UL<<EADC_SCTL_TRGSEL_Pos) /*!< Software trigger */
#define EADC_FALLING_EDGE_TRIGGER (EADC_SCTL_EXTFEN_Msk | (1UL<<EADC_SCTL_TRGSEL_Pos)) /*!< STADC pin falling edge trigger */
#define EADC_RISING_EDGE_TRIGGER (EADC_SCTL_EXTREN_Msk | (1UL<<EADC_SCTL_TRGSEL_Pos)) /*!< STADC pin rising edge trigger */
#define EADC_FALLING_RISING_EDGE_TRIGGER (EADC_SCTL_EXTFEN_Msk | EADC_SCTL_EXTREN_Msk | (1UL<<EADC_SCTL_TRGSEL_Pos)) /*!< STADC pin both falling and rising edge trigger */
#define EADC_ADINT0_TRIGGER (2UL<<EADC_SCTL_TRGSEL_Pos) /*!< ADC ADINT0 interrupt EOC pulse trigger */
#define EADC_ADINT1_TRIGGER (3UL<<EADC_SCTL_TRGSEL_Pos) /*!< ADC ADINT1 interrupt EOC pulse trigger */
#define EADC_TIMER0_TRIGGER (4UL<<EADC_SCTL_TRGSEL_Pos) /*!< Timer0 overflow pulse trigger */
#define EADC_TIMER1_TRIGGER (5UL<<EADC_SCTL_TRGSEL_Pos) /*!< Timer1 overflow pulse trigger */
#define EADC_TIMER2_TRIGGER (6UL<<EADC_SCTL_TRGSEL_Pos) /*!< Timer2 overflow pulse trigger */
#define EADC_TIMER3_TRIGGER (7UL<<EADC_SCTL_TRGSEL_Pos) /*!< Timer3 overflow pulse trigger */
#define EADC_TIMER4_TRIGGER (8UL<<EADC_SCTL_TRGSEL_Pos) /*!< Timer4 overflow pulse trigger */
#define EADC_TIMER5_TRIGGER (9UL<<EADC_SCTL_TRGSEL_Pos) /*!< Timer5 overflow pulse trigger */
#define EADC_PWM0TG0_TRIGGER (0xAUL<<EADC_SCTL_TRGSEL_Pos) /*!< EPWM0TG0 trigger */
#define EADC_PWM0TG1_TRIGGER (0xBUL<<EADC_SCTL_TRGSEL_Pos) /*!< EPWM0TG1 trigger */
#define EADC_PWM0TG2_TRIGGER (0xCUL<<EADC_SCTL_TRGSEL_Pos) /*!< EPWM0TG2 trigger */
#define EADC_PWM0TG3_TRIGGER (0xDUL<<EADC_SCTL_TRGSEL_Pos) /*!< EPWM0TG3 trigger */
#define EADC_PWM0TG4_TRIGGER (0xEUL<<EADC_SCTL_TRGSEL_Pos) /*!< EPWM0TG4 trigger */
#define EADC_PWM0TG5_TRIGGER (0xFUL<<EADC_SCTL_TRGSEL_Pos) /*!< EPWM0TG5 trigger */
#define EADC_PWM1TG0_TRIGGER (0x10UL<<EADC_SCTL_TRGSEL_Pos) /*!< EPWM1TG0 trigger */
#define EADC_PWM1TG1_TRIGGER (0x11UL<<EADC_SCTL_TRGSEL_Pos) /*!< EPWM1TG1 trigger */
#define EADC_PWM1TG2_TRIGGER (0x12UL<<EADC_SCTL_TRGSEL_Pos) /*!< EPWM1TG2 trigger */
#define EADC_PWM1TG3_TRIGGER (0x13UL<<EADC_SCTL_TRGSEL_Pos) /*!< EPWM1TG3 trigger */
#define EADC_PWM1TG4_TRIGGER (0x14UL<<EADC_SCTL_TRGSEL_Pos) /*!< EPWM1TG4 trigger */
#define EADC_PWM1TG5_TRIGGER (0x15UL<<EADC_SCTL_TRGSEL_Pos) /*!< EPWM1TG5 trigger */
#define EADC_BPWM0TG_TRIGGER (0x16UL<<EADC_SCTL_TRGSEL_Pos) /*!< BPWM0TG trigger */
#define EADC_BPWM1TG_TRIGGER (0x17UL<<EADC_SCTL_TRGSEL_Pos) /*!< BPWM1TG trigger */
#define EADC_SCTL_TRGDLYDIV_DIVIDER_1 (0UL<<EADC_SCTL_TRGDLYDIV_Pos) /*!< Trigger delay clock frequency is ADC_CLK/1 */
#define EADC_SCTL_TRGDLYDIV_DIVIDER_2 (0x1UL<<EADC_SCTL_TRGDLYDIV_Pos) /*!< Trigger delay clock frequency is ADC_CLK/2 */
#define EADC_SCTL_TRGDLYDIV_DIVIDER_4 (0x2UL<<EADC_SCTL_TRGDLYDIV_Pos) /*!< Trigger delay clock frequency is ADC_CLK/4 */
#define EADC_SCTL_TRGDLYDIV_DIVIDER_16 (0x3UL<<EADC_SCTL_TRGDLYDIV_Pos) /*!< Trigger delay clock frequency is ADC_CLK/16 */
/*---------------------------------------------------------------------------------------------------------*/
/* EADC_CMP Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define EADC_CMP_CMPCOND_LESS_THAN (0UL<<EADC_CMP_CMPCOND_Pos) /*!< The compare condition is "less than" */
#define EADC_CMP_CMPCOND_GREATER_OR_EQUAL (1UL<<EADC_CMP_CMPCOND_Pos) /*!< The compare condition is "greater than or equal to" */
#define EADC_CMP_CMPWEN_ENABLE (EADC_CMP_CMPWEN_Msk) /*!< Compare window mode enable */
#define EADC_CMP_CMPWEN_DISABLE (~EADC_CMP_CMPWEN_Msk) /*!< Compare window mode disable */
#define EADC_CMP_ADCMPIE_ENABLE (EADC_CMP_ADCMPIE_Msk) /*!< A/D result compare interrupt enable */
#define EADC_CMP_ADCMPIE_DISABLE (~EADC_CMP_ADCMPIE_Msk) /*!< A/D result compare interrupt disable */
/**@}*/ /* end of group EADC_EXPORTED_CONSTANTS */
/** @addtogroup EADC_EXPORTED_FUNCTIONS EADC Exported Functions
@{
*/
/*---------------------------------------------------------------------------------------------------------*/
/* EADC Macro Definitions */
/*---------------------------------------------------------------------------------------------------------*/
/**
* @brief A/D Converter Control Circuits Reset.
* @param[in] eadc The pointer of the specified EADC module.
* @return None
* @details ADCRST bit (EADC_CT[1]) remains 1 during ADC reset, when ADC reset end, the ADCRST bit is automatically cleared to 0.
*/
#define EADC_CONV_RESET(eadc) ((eadc)->CTL |= EADC_CTL_ADCRST_Msk)
/**
* @brief Enable Sample Module PDMA transfer.
* @param[in] eadc The pointer of the specified EADC module.
* @param[in] u32ModuleMask the combination of sample module interrupt status bits. Each bit corresponds to a sample module interrupt status.
* This parameter decides which sample module interrupts will be disabled, valid range are between 1~0x7FFFF.
* @return None
* @details When A/D conversion is completed, the converted data is loaded into EADC_DATn (n: 0 ~ 18) register,
* user can enable this bit to generate a PDMA data transfer request.
* \hideinitializer
*/
#define EADC_ENABLE_SAMPLE_MODULE_PDMA(eadc, u32ModuleMask) ((eadc)->PDMACTL |= u32ModuleMask)
/**
* @brief Disable Sample Module PDMA transfer.
* @param[in] eadc The pointer of the specified EADC module.
* @param[in] u32ModuleMask the combination of sample module interrupt status bits. Each bit corresponds to a sample module interrupt status.
* This parameter decides which sample module interrupts will be disabled, valid range are between 1~0x7FFFF.
* @return None
* @details This macro is used to disable sample module PDMA transfer.
* \hideinitializer
*/
#define EADC_DISABLE_SAMPLE_MODULE_PDMA(eadc, u32ModuleMask) ((eadc)->PDMACTL &= (~u32ModuleMask))
/**
* @brief Enable double buffer mode.
* @param[in] eadc The pointer of the specified EADC module.
* @param[in] u32ModuleNum Decides the sample module number, valid value are from 0 to 3.
* @return None
* @details The ADC controller supports a double buffer mode in sample module 0~3.
* If user enable DBMEN (EADC_SCTLn[23], n=0~3), the double buffer mode will enable.
*/
#define EADC_ENABLE_DOUBLE_BUFFER(eadc, u32ModuleNum) ((eadc)->SCTL[(u32ModuleNum)] |= EADC_SCTL_DBMEN_Msk)
/**
* @brief Disable double buffer mode.
* @param[in] eadc The pointer of the specified EADC module.
* @param[in] u32ModuleNum Decides the sample module number, valid value are from 0 to 3.
* @return None
* @details Sample has one sample result register.
*/
#define EADC_DISABLE_DOUBLE_BUFFER(eadc, u32ModuleNum) ((eadc)->SCTL[(u32ModuleNum)] &= ~EADC_SCTL_DBMEN_Msk)
/**
* @brief Set ADIFn at A/D end of conversion.
* @param[in] eadc The pointer of the specified EADC module.
* @param[in] u32ModuleNum Decides the sample module number, valid value are from 0 to 15.
* @return None
* @details The A/D converter generates ADIFn (EADC_STATUS2[3:0], n=0~3) at the start of conversion.
*/
#define EADC_ENABLE_INT_POSITION(eadc, u32ModuleNum) ((eadc)->SCTL[(u32ModuleNum)] |= EADC_SCTL_INTPOS_Msk)
/**
* @brief Set ADIFn at A/D start of conversion.
* @param[in] eadc The pointer of the specified EADC module.
* @param[in] u32ModuleNum Decides the sample module number, valid value are from 0 to 15.
* @return None
* @details The A/D converter generates ADIFn (EADC_STATUS2[3:0], n=0~3) at the end of conversion.
*/
#define EADC_DISABLE_INT_POSITION(eadc, u32ModuleNum) ((eadc)->SCTL[(u32ModuleNum)] &= ~EADC_SCTL_INTPOS_Msk)
/**
* @brief Enable the interrupt.
* @param[in] eadc The pointer of the specified EADC module.
* @param[in] u32Mask Decides the combination of interrupt status bits. Each bit corresponds to a interrupt status.
* This parameter decides which interrupts will be enabled. Bit 0 is ADCIEN0, bit 1 is ADCIEN1..., bit 3 is ADCIEN3.
* @return None
* @details The A/D converter generates a conversion end ADIFn (EADC_STATUS2[n]) upon the end of specific sample module A/D conversion.
* If ADCIENn bit (EADC_CTL[n+2]) is set then conversion end interrupt request ADINTn is generated (n=0~3).
*/
#define EADC_ENABLE_INT(eadc, u32Mask) ((eadc)->CTL |= ((u32Mask) << EADC_CTL_ADCIEN0_Pos))
/**
* @brief Disable the interrupt.
* @param[in] eadc The pointer of the specified EADC module.
* @param[in] u32Mask Decides the combination of interrupt status bits. Each bit corresponds to a interrupt status.
* This parameter decides which interrupts will be disabled. Bit 0 is ADCIEN0, bit 1 is ADCIEN1..., bit 3 is ADCIEN3.
* @return None
* @details Specific sample module A/D ADINT0 interrupt function Disabled.
*/
#define EADC_DISABLE_INT(eadc, u32Mask) ((eadc)->CTL &= ~((u32Mask) << EADC_CTL_ADCIEN0_Pos))
/**
* @brief Enable the sample module interrupt.
* @param[in] eadc The pointer of the specified EADC module.
* @param[in] u32IntSel Decides which interrupt source will be used, valid value are from 0 to 3.
* @param[in] u32ModuleMask the combination of sample module interrupt status bits. Each bit corresponds to a sample module interrupt status.
* This parameter decides which sample module interrupts will be enabled, valid range are between 1~0x7FFFF.
* @return None
* @details There are 4 ADC interrupts ADINT0~3, and each of these interrupts has its own interrupt vector address.
*/
#define EADC_ENABLE_SAMPLE_MODULE_INT(eadc, u32IntSel, u32ModuleMask) ((eadc)->INTSRC[(u32IntSel)] |= (u32ModuleMask))
/**
* @brief Disable the sample module interrupt.
* @param[in] eadc The pointer of the specified EADC module.
* @param[in] u32IntSel Decides which interrupt source will be used, valid value are from 0 to 3.
* @param[in] u32ModuleMask the combination of sample module interrupt status bits. Each bit corresponds to a sample module interrupt status.
* This parameter decides which sample module interrupts will be disabled, valid range are between 1~0x7FFFF.
* @return None
* @details There are 4 ADC interrupts ADINT0~3, and each of these interrupts has its own interrupt vector address.
*/
#define EADC_DISABLE_SAMPLE_MODULE_INT(eadc, u32IntSel, u32ModuleMask) ((eadc)->INTSRC[(u32IntSel)] &= (uint32_t)(~(u32ModuleMask)))
/**
* @brief Set the input mode output format.
* @param[in] eadc The pointer of the specified EADC module.
* @param[in] u32Format Decides the output format. Valid values are:
* - \ref EADC_CTL_DMOF_STRAIGHT_BINARY :Select the straight binary format as the output format of the conversion result.
* - \ref EADC_CTL_DMOF_TWOS_COMPLEMENT :Select the 2's complement format as the output format of the conversion result.
* @return None
* @details The macro is used to set A/D input mode output format.
*/
#define EADC_SET_DMOF(eadc, u32Format) ((eadc)->CTL = ((eadc)->CTL & ~EADC_CTL_DMOF_Msk) | (u32Format))
/**
* @brief Start the A/D conversion.
* @param[in] eadc The pointer of the specified EADC module.
* @param[in] u32ModuleMask The combination of sample module. Each bit corresponds to a sample module.
* This parameter decides which sample module will be conversion, valid range are between 1~0x7FFFF.
* Bit 0 is sample module 0, bit 1 is sample module 1..., bit 18 is sample module 18.
* @return None
* @details After write EADC_SWTRG register to start ADC conversion, the EADC_PENDSTS register will show which SAMPLE will conversion.
*/
#define EADC_START_CONV(eadc, u32ModuleMask) ((eadc)->SWTRG = (u32ModuleMask))
/**
* @brief Cancel the conversion for sample module.
* @param[in] eadc The pointer of the specified EADC module.
* @param[in] u32ModuleMask The combination of sample module. Each bit corresponds to a sample module.
* This parameter decides which sample module will stop the conversion, valid range are between 1~0x7FFFF.
* Bit 0 is sample module 0, bit 1 is sample module 1..., bit 18 is sample module18.
* @return None
* @details If user want to disable the conversion of the sample module, user can write EADC_PENDSTS register to clear it.
*/
#define EADC_STOP_CONV(eadc, u32ModuleMask) ((eadc)->PENDSTS = (u32ModuleMask))
/**
* @brief Get the conversion pending flag.
* @param[in] eadc The pointer of the specified EADC module.
* @return Return the conversion pending sample module.
* @details This STPFn(EADC_PENDSTS[18:0]) bit remains 1 during pending state, when the respective ADC conversion is end,
* the STPFn (n=0~18) bit is automatically cleared to 0.
*/
#define EADC_GET_PENDING_CONV(eadc) ((eadc)->PENDSTS)
/**
* @brief Get the conversion data of the user-specified sample module.
* @param[in] eadc The pointer of the specified EADC module.
* @param[in] u32ModuleNum Decides the sample module number, valid value are from 0 to 18.
* @return Return the conversion data of the user-specified sample module.
* @details This macro is used to read RESULT bit (EADC_DATn[15:0], n=0~18) field to get conversion data.
*/
#define EADC_GET_CONV_DATA(eadc, u32ModuleNum) ((eadc)->DAT[(u32ModuleNum)] & EADC_DAT_RESULT_Msk)
/**
* @brief Get the data overrun flag of the user-specified sample module.
* @param[in] eadc The pointer of the specified EADC module.
* @param[in] u32ModuleMask The combination of data overrun status bits. Each bit corresponds to a data overrun status, valid range are between 1~0x7FFFF.
* @return Return the data overrun flag of the user-specified sample module.
* @details This macro is used to read OV bit (EADC_STATUS0[31:16], EADC_STATUS1[18:16]) field to get data overrun status.
*/
#define EADC_GET_DATA_OVERRUN_FLAG(eadc, u32ModuleMask) ((((eadc)->STATUS0 >> EADC_STATUS0_OV_Pos) | ((eadc)->STATUS1 & EADC_STATUS1_OV_Msk)) & (u32ModuleMask))
/**
* @brief Get the data valid flag of the user-specified sample module.
* @param[in] eadc The pointer of the specified EADC module.
* @param[in] u32ModuleMask The combination of data valid status bits. Each bit corresponds to a data valid status, valid range are between 1~0x7FFFF.
* @return Return the data valid flag of the user-specified sample module.
* @details This macro is used to read VALID bit (EADC_STATUS0[15:0], EADC_STATUS1[2:0]) field to get data valid status.
*/
#define EADC_GET_DATA_VALID_FLAG(eadc, u32ModuleMask) ((((eadc)->STATUS0 & EADC_STATUS0_VALID_Msk) | (((eadc)->STATUS1 & EADC_STATUS1_VALID_Msk) << 16)) & (u32ModuleMask))
/**
* @brief Get the double data of the user-specified sample module.
* @param[in] eadc The pointer of the specified EADC module.
* @param[in] u32ModuleNum Decides the sample module number, valid value are from 0 to 18.
* @return Return the double data of the user-specified sample module.
* @details This macro is used to read RESULT bit (EADC_DDATn[15:0], n=0~3) field to get conversion data.
*/
#define EADC_GET_DOUBLE_DATA(eadc, u32ModuleNum) ((eadc)->DDAT[(u32ModuleNum)] & EADC_DDAT0_RESULT_Msk)
/**
* @brief Get the user-specified interrupt flags.
* @param[in] eadc The pointer of the specified EADC module.
* @param[in] u32Mask The combination of interrupt status bits. Each bit corresponds to a interrupt status.
* Bit 0 is ADIF0, bit 1 is ADIF1..., bit 3 is ADIF3.
* Bit 4 is ADCMPF0, bit 5 is ADCMPF1..., bit 7 is ADCMPF3.
* @return Return the user-specified interrupt flags.
* @details This macro is used to get the user-specified interrupt flags.
*/
#define EADC_GET_INT_FLAG(eadc, u32Mask) ((eadc)->STATUS2 & (u32Mask))
/**
* @brief Get the user-specified sample module overrun flags.
* @param[in] eadc The pointer of the specified EADC module.
* @param[in] u32ModuleMask The combination of sample module overrun status bits. Each bit corresponds to a sample module overrun status, valid range are between 1~0x7FFFF.
* @return Return the user-specified sample module overrun flags.
* @details This macro is used to get the user-specified sample module overrun flags.
*/
#define EADC_GET_SAMPLE_MODULE_OV_FLAG(eadc, u32ModuleMask) ((eadc)->OVSTS & (u32ModuleMask))
/**
* @brief Clear the selected interrupt status bits.
* @param[in] eadc The pointer of the specified EADC module.
* @param[in] u32Mask The combination of compare interrupt status bits. Each bit corresponds to a compare interrupt status.
* Bit 0 is ADIF0, bit 1 is ADIF1..., bit 3 is ADIF3.
* Bit 4 is ADCMPF0, bit 5 is ADCMPF1..., bit 7 is ADCMPF3.
* @return None
* @details This macro is used to clear clear the selected interrupt status bits.
*/
#define EADC_CLR_INT_FLAG(eadc, u32Mask) ((eadc)->STATUS2 = (u32Mask))
/**
* @brief Clear the selected sample module overrun status bits.
* @param[in] eadc The pointer of the specified EADC module.
* @param[in] u32ModuleMask The combination of sample module overrun status bits. Each bit corresponds to a sample module overrun status.
* Bit 0 is SPOVF0, bit 1 is SPOVF1..., bit 18 is SPOVF18.
* @return None
* @details This macro is used to clear the selected sample module overrun status bits.
*/
#define EADC_CLR_SAMPLE_MODULE_OV_FLAG(eadc, u32ModuleMask) ((eadc)->OVSTS = (u32ModuleMask))
/**
* @brief Check all sample module A/D result data register overrun flags.
* @param[in] eadc The pointer of the specified EADC module.
* @retval 0 None of sample module data register overrun flag is set to 1.
* @retval 1 Any one of sample module data register overrun flag is set to 1.
* @details The AOV bit (EADC_STATUS2[27]) will keep 1 when any one of sample module data register overrun flag OVn (EADC_DATn[16]) is set to 1.
*/
#define EADC_IS_DATA_OV(eadc) (((eadc)->STATUS2 & EADC_STATUS2_AOV_Msk) >> EADC_STATUS2_AOV_Pos)
/**
* @brief Check all sample module A/D result data register valid flags.
* @param[in] eadc The pointer of the specified EADC module.
* @retval 0 None of sample module data register valid flag is set to 1.
* @retval 1 Any one of sample module data register valid flag is set to 1.
* @details The AVALID bit (EADC_STATUS2[26]) will keep 1 when any one of sample module data register valid flag VALIDn (EADC_DATn[17]) is set to 1.
*/
#define EADC_IS_DATA_VALID(eadc) (((eadc)->STATUS2 & EADC_STATUS2_AVALID_Msk) >> EADC_STATUS2_AVALID_Pos)
/**
* @brief Check all A/D sample module start of conversion overrun flags.
* @param[in] eadc The pointer of the specified EADC module.
* @retval 0 None of sample module event overrun flag is set to 1.
* @retval 1 Any one of sample module event overrun flag is set to 1.
* @details The STOVF bit (EADC_STATUS2[25]) will keep 1 when any one of sample module event overrun flag SPOVFn (EADC_OVSTS[n]) is set to 1.
*/
#define EADC_IS_SAMPLE_MODULE_OV(eadc) (((eadc)->STATUS2 & EADC_STATUS2_STOVF_Msk) >> EADC_STATUS2_STOVF_Pos)
/**
* @brief Check all A/D interrupt flag overrun bits.
* @param[in] eadc The pointer of the specified EADC module.
* @retval 0 None of ADINT interrupt flag is overwritten to 1.
* @retval 1 Any one of ADINT interrupt flag is overwritten to 1.
* @details The ADOVIF bit (EADC_STATUS2[24]) will keep 1 when any one of ADINT interrupt flag ADOVIFn (EADC_STATUS2[11:8]) is overwritten to 1.
*/
#define EADC_IS_INT_FLAG_OV(eadc) (((eadc)->STATUS2 & EADC_STATUS2_ADOVIF_Msk) >> EADC_STATUS2_ADOVIF_Pos)
/**
* @brief Get the busy state of EADC.
* @param[in] eadc The pointer of the specified EADC module.
* @retval 0 Idle state.
* @retval 1 Busy state.
* @details This macro is used to read BUSY bit (EADC_STATUS2[23]) to get busy state.
*/
#define EADC_IS_BUSY(eadc) (((eadc)->STATUS2 & EADC_STATUS2_BUSY_Msk) >> EADC_STATUS2_BUSY_Pos)
/**
* @brief Configure the comparator 0 and enable it.
* @param[in] eadc The pointer of the specified EADC module.
* @param[in] u32ModuleNum specifies the compare sample module, valid value are from 0 to 18.
* @param[in] u32Condition specifies the compare condition. Valid values are:
* - \ref EADC_CMP_CMPCOND_LESS_THAN :The compare condition is "less than the compare value"
* - \ref EADC_CMP_CMPCOND_GREATER_OR_EQUAL :The compare condition is "greater than or equal to the compare value
* @param[in] u16CMPData specifies the compare value, valid range are between 0~0xFFF.
* @param[in] u32MatchCount specifies the match count setting, valid range are between 0~0xF.
* @return None
* @details For example, ADC_ENABLE_CMP0(EADC, 5, ADC_ADCMPR_CMPCOND_GREATER_OR_EQUAL, 0x800, 10, EADC_CMP_CMPWEN_DISABLE, EADC_CMP_ADCMPIE_ENABLE);
* Means EADC will assert comparator 0 flag if sample module 5 conversion result is greater or
* equal to 0x800 for 10 times continuously, and a compare interrupt request is generated.
*/
#define EADC_ENABLE_CMP0(eadc,\
u32ModuleNum,\
u32Condition,\
u16CMPData,\
u32MatchCount) ((eadc)->CMP[0] |=(((u32ModuleNum) << EADC_CMP_CMPSPL_Pos)|\
(u32Condition) |\
((u16CMPData) << EADC_CMP_CMPDAT_Pos)| \
(((u32MatchCount) - 1UL) << EADC_CMP_CMPMCNT_Pos)|\
EADC_CMP_ADCMPEN_Msk))
/**
* @brief Configure the comparator 1 and enable it.
* @param[in] eadc The pointer of the specified EADC module.
* @param[in] u32ModuleNum specifies the compare sample module, valid value are from 0 to 18.
* @param[in] u32Condition specifies the compare condition. Valid values are:
* - \ref EADC_CMP_CMPCOND_LESS_THAN :The compare condition is "less than the compare value"
* - \ref EADC_CMP_CMPCOND_GREATER_OR_EQUAL :The compare condition is "greater than or equal to the compare value
* @param[in] u16CMPData specifies the compare value, valid range are between 0~0xFFF.
* @param[in] u32MatchCount specifies the match count setting, valid range are between 0~0xF.
* @return None
* @details For example, ADC_ENABLE_CMP1(EADC, 5, ADC_ADCMPR_CMPCOND_GREATER_OR_EQUAL, 0x800, 10, EADC_CMP_ADCMPIE_ENABLE);
* Means EADC will assert comparator 1 flag if sample module 5 conversion result is greater or
* equal to 0x800 for 10 times continuously, and a compare interrupt request is generated.
*/
#define EADC_ENABLE_CMP1(eadc,\
u32ModuleNum,\
u32Condition,\
u16CMPData,\
u32MatchCount) ((eadc)->CMP[1] |=(((u32ModuleNum) << EADC_CMP_CMPSPL_Pos)|\
(u32Condition) |\
((u16CMPData) << EADC_CMP_CMPDAT_Pos)| \
(((u32MatchCount) - 1UL) << EADC_CMP_CMPMCNT_Pos)|\
EADC_CMP_ADCMPEN_Msk))
/**
* @brief Configure the comparator 2 and enable it.
* @param[in] eadc The pointer of the specified EADC module.
* @param[in] u32ModuleNum specifies the compare sample module, valid value are from 0 to 18.
* @param[in] u32Condition specifies the compare condition. Valid values are:
* - \ref EADC_CMP_CMPCOND_LESS_THAN :The compare condition is "less than the compare value"
* - \ref EADC_CMP_CMPCOND_GREATER_OR_EQUAL :The compare condition is "greater than or equal to the compare value
* @param[in] u16CMPData specifies the compare value, valid range are between 0~0xFFF.
* @param[in] u32MatchCount specifies the match count setting, valid range are between 0~0xF.
* @return None
* @details For example, ADC_ENABLE_CMP2(EADC, 5, ADC_ADCMPR_CMPCOND_GREATER_OR_EQUAL, 0x800, 10, EADC_CMP_CMPWEN_DISABLE, EADC_CMP_ADCMPIE_ENABLE);
* Means EADC will assert comparator 2 flag if sample module 5 conversion result is greater or
* equal to 0x800 for 10 times continuously, and a compare interrupt request is generated.
*/
#define EADC_ENABLE_CMP2(eadc,\
u32ModuleNum,\
u32Condition,\
u16CMPData,\
u32MatchCount) ((eadc)->CMP[2] |=(((u32ModuleNum) << EADC_CMP_CMPSPL_Pos)|\
(u32Condition) |\
((u16CMPData) << EADC_CMP_CMPDAT_Pos)| \
(((u32MatchCount) - 1UL) << EADC_CMP_CMPMCNT_Pos)|\
EADC_CMP_ADCMPEN_Msk))
/**
* @brief Configure the comparator 3 and enable it.
* @param[in] eadc The pointer of the specified EADC module.
* @param[in] u32ModuleNum specifies the compare sample module, valid value are from 0 to 18.
* @param[in] u32Condition specifies the compare condition. Valid values are:
* - \ref EADC_CMP_CMPCOND_LESS_THAN :The compare condition is "less than the compare value"
* - \ref EADC_CMP_CMPCOND_GREATER_OR_EQUAL :The compare condition is "greater than or equal to the compare value
* @param[in] u16CMPData specifies the compare value, valid range are between 0~0xFFF.
* @param[in] u32MatchCount specifies the match count setting, valid range are between 1~0xF.
* @return None
* @details For example, ADC_ENABLE_CMP3(EADC, 5, ADC_ADCMPR_CMPCOND_GREATER_OR_EQUAL, 0x800, 10, EADC_CMP_ADCMPIE_ENABLE);
* Means EADC will assert comparator 3 flag if sample module 5 conversion result is greater or
* equal to 0x800 for 10 times continuously, and a compare interrupt request is generated.
*/
#define EADC_ENABLE_CMP3(eadc,\
u32ModuleNum,\
u32Condition,\
u16CMPData,\
u32MatchCount) ((eadc)->CMP[3] |=(((u32ModuleNum) << EADC_CMP_CMPSPL_Pos)|\
(u32Condition) |\
((u16CMPData) << EADC_CMP_CMPDAT_Pos)| \
(((u32MatchCount) - 1UL) << EADC_CMP_CMPMCNT_Pos)|\
EADC_CMP_ADCMPEN_Msk))
/**
* @brief Enable the compare window mode.
* @param[in] eadc The pointer of the specified EADC module.
* @param[in] u32CMP Specifies the compare register, valid value are 0 and 2.
* @return None
* @details ADCMPF0 (EADC_STATUS2[4]) will be set when both EADC_CMP0 and EADC_CMP1 compared condition matched.
*/
#define EADC_ENABLE_CMP_WINDOW_MODE(eadc, u32CMP) ((eadc)->CMP[(u32CMP)] |= EADC_CMP_CMPWEN_Msk)
/**
* @brief Disable the compare window mode.
* @param[in] eadc The pointer of the specified EADC module.
* @param[in] u32CMP Specifies the compare register, valid value are 0 and 2.
* @return None
* @details ADCMPF2 (EADC_STATUS2[6]) will be set when both EADC_CMP2 and EADC_CMP3 compared condition matched.
*/
#define EADC_DISABLE_CMP_WINDOW_MODE(eadc, u32CMP) ((eadc)->CMP[(u32CMP)] &= ~EADC_CMP_CMPWEN_Msk)
/**
* @brief Enable the compare interrupt.
* @param[in] eadc The pointer of the specified EADC module.
* @param[in] u32CMP Specifies the compare register, valid value are from 0 to 3.
* @return None
* @details If the compare function is enabled and the compare condition matches the setting of CMPCOND (EADC_CMPn[2], n=0~3)
* and CMPMCNT (EADC_CMPn[11:8], n=0~3), ADCMPFn (EADC_STATUS2[7:4], n=0~3) will be asserted, in the meanwhile,
* if ADCMPIE is set to 1, a compare interrupt request is generated.
*/
#define EADC_ENABLE_CMP_INT(eadc, u32CMP) ((eadc)->CMP[(u32CMP)] |= EADC_CMP_ADCMPIE_Msk)
/**
* @brief Disable the compare interrupt.
* @param[in] eadc The pointer of the specified EADC module.
* @param[in] u32CMP Specifies the compare register, valid value are from 0 to 3.
* @return None
* @details This macro is used to disable the compare interrupt.
*/
#define EADC_DISABLE_CMP_INT(eadc, u32CMP) ((eadc)->CMP[(u32CMP)] &= ~EADC_CMP_ADCMPIE_Msk)
/**
* @brief Disable comparator 0.
* @param[in] eadc The pointer of the specified EADC module.
* @return None
* @details This macro is used to disable comparator 0.
*/
#define EADC_DISABLE_CMP0(eadc) ((eadc)->CMP[0] = 0UL)
/**
* @brief Disable comparator 1.
* @param[in] eadc The pointer of the specified EADC module.
* @return None
* @details This macro is used to disable comparator 1.
*/
#define EADC_DISABLE_CMP1(eadc) ((eadc)->CMP[1] = 0UL)
/**
* @brief Disable comparator 2.
* @param[in] eadc The pointer of the specified EADC module.
* @return None
* @details This macro is used to disable comparator 2.
*/
#define EADC_DISABLE_CMP2(eadc) ((eadc)->CMP[2] = 0UL)
/**
* @brief Disable comparator 3.
* @param[in] eadc The pointer of the specified EADC module.
* @return None
* @details This macro is used to disable comparator 3.
*/
#define EADC_DISABLE_CMP3(eadc) ((eadc)->CMP[3] = 0UL)
/*---------------------------------------------------------------------------------------------------------*/
/* Define EADC functions prototype */
/*---------------------------------------------------------------------------------------------------------*/
void EADC_Open(EADC_T *eadc, uint32_t u32InputMode);
void EADC_Close(EADC_T *eadc);
void EADC_ConfigSampleModule(EADC_T *eadc, uint32_t u32ModuleNum, uint32_t u32TriggerSrc, uint32_t u32Channel);
void EADC_SetTriggerDelayTime(EADC_T *eadc, uint32_t u32ModuleNum, uint32_t u32TriggerDelayTime, uint32_t u32DelayClockDivider);
void EADC_SetExtendSampleTime(EADC_T *eadc, uint32_t u32ModuleNum, uint32_t u32ExtendSampleTime);
/**@}*/ /* end of group EADC_EXPORTED_FUNCTIONS */
/**@}*/ /* end of group EADC_Driver */
/**@}*/ /* end of group Standard_Driver */
#ifdef __cplusplus
}
#endif
#endif /* __NU_EADC_H__ */

View File

@ -0,0 +1,369 @@
/**************************************************************************//**
* @file nu_ebi.h
* @version V3.00
* @brief External Bus Interface(EBI) driver header file
*
* @copyright SPDX-License-Identifier: Apache-2.0
* @copyright Copyright (C) 2020 Nuvoton Technology Corp. All rights reserved.
*****************************************************************************/
#ifndef __NU_EBI_H__
#define __NU_EBI_H__
#ifdef __cplusplus
extern "C"
{
#endif
/** @addtogroup Standard_Driver Standard Driver
@{
*/
/** @addtogroup EBI_Driver EBI Driver
@{
*/
/** @addtogroup EBI_EXPORTED_CONSTANTS EBI Exported Constants
@{
*/
/*---------------------------------------------------------------------------------------------------------*/
/* Miscellaneous Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define EBI_BANK0_BASE_ADDR 0x60000000UL /*!< EBI bank0 base address \hideinitializer */
#define EBI_BANK1_BASE_ADDR 0x60100000UL /*!< EBI bank1 base address \hideinitializer */
#define EBI_BANK2_BASE_ADDR 0x60200000UL /*!< EBI bank2 base address \hideinitializer */
#define EBI_BANK0_BASE_ADDR_NS 0x70000000UL /*!< EBI bank0 base address for Non-Secure \hideinitializer */
#define EBI_BANK1_BASE_ADDR_NS 0x70100000UL /*!< EBI bank1 base address for Non-Secure \hideinitializer */
#define EBI_BANK2_BASE_ADDR_NS 0x70200000UL /*!< EBI bank2 base address for Non-Secure \hideinitializer */
#define EBI_MAX_SIZE 0x00100000UL /*!< Maximum EBI size for each bank is 1 MB \hideinitializer */
/*---------------------------------------------------------------------------------------------------------*/
/* Constants for EBI bank number */
/*---------------------------------------------------------------------------------------------------------*/
#define EBI_BANK0 0UL /*!< EBI bank 0 \hideinitializer */
#define EBI_BANK1 1UL /*!< EBI bank 1 \hideinitializer */
#define EBI_BANK2 2UL /*!< EBI bank 2 \hideinitializer */
/*---------------------------------------------------------------------------------------------------------*/
/* Constants for EBI data bus width */
/*---------------------------------------------------------------------------------------------------------*/
#define EBI_BUSWIDTH_8BIT 8UL /*!< EBI bus width is 8-bit \hideinitializer */
#define EBI_BUSWIDTH_16BIT 16UL /*!< EBI bus width is 16-bit \hideinitializer */
/*---------------------------------------------------------------------------------------------------------*/
/* Constants for EBI CS Active Level */
/*---------------------------------------------------------------------------------------------------------*/
#define EBI_CS_ACTIVE_LOW 0UL /*!< EBI CS active level is low \hideinitializer */
#define EBI_CS_ACTIVE_HIGH 1UL /*!< EBI CS active level is high \hideinitializer */
/*---------------------------------------------------------------------------------------------------------*/
/* Constants for EBI MCLK divider and Timing */
/*---------------------------------------------------------------------------------------------------------*/
#define EBI_MCLKDIV_1 0x0UL /*!< EBI output clock(MCLK) is HCLK/1 \hideinitializer */
#define EBI_MCLKDIV_2 0x1UL /*!< EBI output clock(MCLK) is HCLK/2 \hideinitializer */
#define EBI_MCLKDIV_4 0x2UL /*!< EBI output clock(MCLK) is HCLK/4 \hideinitializer */
#define EBI_MCLKDIV_8 0x3UL /*!< EBI output clock(MCLK) is HCLK/8 \hideinitializer */
#define EBI_MCLKDIV_16 0x4UL /*!< EBI output clock(MCLK) is HCLK/16 \hideinitializer */
#define EBI_MCLKDIV_32 0x5UL /*!< EBI output clock(MCLK) is HCLK/32 \hideinitializer */
#define EBI_MCLKDIV_64 0x6UL /*!< EBI output clock(MCLK) is HCLK/64 \hideinitializer */
#define EBI_MCLKDIV_128 0x7UL /*!< EBI output clock(MCLK) is HCLK/128 \hideinitializer */
#define EBI_TIMING_FASTEST 0x0UL /*!< EBI timing is the fastest \hideinitializer */
#define EBI_TIMING_VERYFAST 0x1UL /*!< EBI timing is very fast \hideinitializer */
#define EBI_TIMING_FAST 0x2UL /*!< EBI timing is fast \hideinitializer */
#define EBI_TIMING_NORMAL 0x3UL /*!< EBI timing is normal \hideinitializer */
#define EBI_TIMING_SLOW 0x4UL /*!< EBI timing is slow \hideinitializer */
#define EBI_TIMING_VERYSLOW 0x5UL /*!< EBI timing is very slow \hideinitializer */
#define EBI_TIMING_SLOWEST 0x6UL /*!< EBI timing is the slowest \hideinitializer */
#define EBI_OPMODE_NORMAL 0x0UL /*!< EBI bus operate in normal mode \hideinitializer */
#define EBI_OPMODE_CACCESS (EBI_CTL_CACCESS_Msk) /*!< EBI bus operate in Continuous Data Access mode \hideinitializer */
#define EBI_OPMODE_ADSEPARATE (EBI_CTL_ADSEPEN_Msk) /*!< EBI bus operate in AD Separate mode \hideinitializer */
/**@}*/ /* end of group EBI_EXPORTED_CONSTANTS */
/** @addtogroup EBI_EXPORTED_FUNCTIONS EBI Exported Functions
@{
*/
/**
* @brief Read 8-bit data on EBI bank0
*
* @param[in] ebi The pointer of EBI module.
* @param[in] u32Addr The data address on EBI bank0.
*
* @return 8-bit Data
*
* @details This macro is used to read 8-bit data from specify address on EBI bank0.
* \hideinitializer
*/
#define EBI0_READ_DATA8(ebi, u32Addr) (*((volatile unsigned char *)((((ebi)==EBI_S)? EBI_BANK0_BASE_ADDR:EBI_BANK0_BASE_ADDR_NS)+(u32Addr))))
/**
* @brief Write 8-bit data to EBI bank0
*
* @param[in] ebi The pointer of EBI module.
* @param[in] u32Addr The data address on EBI bank0.
* @param[in] u32Data Specify data to be written.
*
* @return None
*
* @details This macro is used to write 8-bit data to specify address on EBI bank0.
* \hideinitializer
*/
#define EBI0_WRITE_DATA8(ebi, u32Addr, u32Data) (*((volatile unsigned char *)((((ebi)==EBI_S)? EBI_BANK0_BASE_ADDR:EBI_BANK0_BASE_ADDR_NS)+(u32Addr))) = (u32Data))
/**
* @brief Read 16-bit data on EBI bank0
*
* @param[in] ebi The pointer of EBI module.
* @param[in] u32Addr The data address on EBI bank0.
*
* @return 16-bit Data
*
* @details This macro is used to read 16-bit data from specify address on EBI bank0.
* \hideinitializer
*/
#define EBI0_READ_DATA16(ebi, u32Addr) (*((volatile unsigned short *)((((ebi)==EBI_S)? EBI_BANK0_BASE_ADDR:EBI_BANK0_BASE_ADDR_NS)+(u32Addr))))
/**
* @brief Write 16-bit data to EBI bank0
*
* @param[in] ebi The pointer of EBI module.
* @param[in] u32Addr The data address on EBI bank0.
* @param[in] u32Data Specify data to be written.
*
* @return None
*
* @details This macro is used to write 16-bit data to specify address on EBI bank0.
* \hideinitializer
*/
#define EBI0_WRITE_DATA16(ebi, u32Addr, u32Data) (*((volatile unsigned short *)((((ebi)==EBI_S)? EBI_BANK0_BASE_ADDR:EBI_BANK0_BASE_ADDR_NS)+(u32Addr))) = (u32Data))
/**
* @brief Read 32-bit data on EBI bank0
*
* @param[in] ebi The pointer of EBI module.
* @param[in] u32Addr The data address on EBI bank0.
*
* @return 32-bit Data
*
* @details This macro is used to read 32-bit data from specify address on EBI bank0.
* \hideinitializer
*/
#define EBI0_READ_DATA32(ebi, u32Addr) (*((volatile unsigned int *)((((ebi)==EBI_S)? EBI_BANK0_BASE_ADDR:EBI_BANK0_BASE_ADDR_NS)+(u32Addr))))
/**
* @brief Write 32-bit data to EBI bank0
*
* @param[in] ebi The pointer of EBI module.
* @param[in] u32Addr The data address on EBI bank0.
* @param[in] u32Data Specify data to be written.
*
* @return None
*
* @details This macro is used to write 32-bit data to specify address on EBI bank0.
* \hideinitializer
*/
#define EBI0_WRITE_DATA32(ebi, u32Addr, u32Data) (*((volatile unsigned int *)((((ebi)==EBI_S)? EBI_BANK0_BASE_ADDR:EBI_BANK0_BASE_ADDR_NS)+(u32Addr))) = (u32Data))
/**
* @brief Read 8-bit data on EBI bank1
*
* @param[in] ebi The pointer of EBI module.
* @param[in] u32Addr The data address on EBI bank1.
*
* @return 8-bit Data
*
* @details This macro is used to read 8-bit data from specify address on EBI bank1.
* \hideinitializer
*/
#define EBI1_READ_DATA8(ebi, u32Addr) (*((volatile unsigned char *)((((ebi)==EBI_S)? EBI_BANK1_BASE_ADDR:EBI_BANK1_BASE_ADDR_NS)+(u32Addr))))
/**
* @brief Write 8-bit data to EBI bank1
*
* @param[in] ebi The pointer of EBI module.
* @param[in] u32Addr The data address on EBI bank1.
* @param[in] u32Data Specify data to be written.
*
* @return None
*
* @details This macro is used to write 8-bit data to specify address on EBI bank1.
* \hideinitializer
*/
#define EBI1_WRITE_DATA8(ebi, u32Addr, u32Data) (*((volatile unsigned char *)((((ebi)==EBI_S)? EBI_BANK1_BASE_ADDR:EBI_BANK1_BASE_ADDR_NS)+(u32Addr))) = (u32Data))
/**
* @brief Read 16-bit data on EBI bank1
*
* @param[in] ebi The pointer of EBI module.
* @param[in] u32Addr The data address on EBI bank1.
*
* @return 16-bit Data
*
* @details This macro is used to read 16-bit data from specify address on EBI bank1.
* \hideinitializer
*/
#define EBI1_READ_DATA16(ebi, u32Addr) (*((volatile unsigned short *)((((ebi)==EBI_S)? EBI_BANK1_BASE_ADDR:EBI_BANK1_BASE_ADDR_NS)+(u32Addr))))
/**
* @brief Write 16-bit data to EBI bank1
*
* @param[in] ebi The pointer of EBI module.
* @param[in] u32Addr The data address on EBI bank1.
* @param[in] u32Data Specify data to be written.
*
* @return None
*
* @details This macro is used to write 16-bit data to specify address on EBI bank1.
* \hideinitializer
*/
#define EBI1_WRITE_DATA16(ebi, u32Addr, u32Data) (*((volatile unsigned short *)((((ebi)==EBI_S)? EBI_BANK1_BASE_ADDR:EBI_BANK1_BASE_ADDR_NS)+(u32Addr))) = (u32Data))
/**
* @brief Read 32-bit data on EBI bank1
*
* @param[in] ebi The pointer of EBI module.
* @param[in] u32Addr The data address on EBI bank1.
*
* @return 32-bit Data
*
* @details This macro is used to read 32-bit data from specify address on EBI bank1.
* \hideinitializer
*/
#define EBI1_READ_DATA32(ebi, u32Addr) (*((volatile unsigned int *)((((ebi)==EBI_S)? EBI_BANK1_BASE_ADDR:EBI_BANK1_BASE_ADDR_NS)+(u32Addr))))
/**
* @brief Write 32-bit data to EBI bank1
*
* @param[in] ebi The pointer of EBI module.
* @param[in] u32Addr The data address on EBI bank1.
* @param[in] u32Data Specify data to be written.
*
* @return None
*
* @details This macro is used to write 32-bit data to specify address on EBI bank1.
* \hideinitializer
*/
#define EBI1_WRITE_DATA32(ebi, u32Addr, u32Data) (*((volatile unsigned int *)((((ebi)==EBI_S)? EBI_BANK1_BASE_ADDR:EBI_BANK1_BASE_ADDR_NS)+(u32Addr))) = (u32Data))
/**
* @brief Read 8-bit data on EBI bank2
*
* @param[in] ebi The pointer of EBI module.
* @param[in] u32Addr The data address on EBI bank2.
*
* @return 8-bit Data
*
* @details This macro is used to read 8-bit data from specify address on EBI bank2.
* \hideinitializer
*/
#define EBI2_READ_DATA8(ebi, u32Addr) (*((volatile unsigned char *)((((ebi)==EBI_S)? EBI_BANK2_BASE_ADDR:EBI_BANK2_BASE_ADDR_NS)+(u32Addr))))
/**
* @brief Write 8-bit data to EBI bank2
*
* @param[in] ebi The pointer of EBI module.
* @param[in] u32Addr The data address on EBI bank2.
* @param[in] u32Data Specify data to be written.
*
* @return None
*
* @details This macro is used to write 8-bit data to specify address on EBI bank2.
* \hideinitializer
*/
#define EBI2_WRITE_DATA8(ebi, u32Addr, u32Data) (*((volatile unsigned char *)((((ebi)==EBI_S)? EBI_BANK2_BASE_ADDR:EBI_BANK2_BASE_ADDR_NS)+(u32Addr))) = (u32Data))
/**
* @brief Read 16-bit data on EBI bank2
*
* @param[in] ebi The pointer of EBI module.
* @param[in] u32Addr The data address on EBI bank2.
*
* @return 16-bit Data
*
* @details This macro is used to read 16-bit data from specify address on EBI bank2.
*/
#define EBI2_READ_DATA16(ebi, u32Addr) (*((volatile unsigned short *)((((ebi)==EBI_S)? EBI_BANK2_BASE_ADDR:EBI_BANK2_BASE_ADDR_NS)+(u32Addr))))
/**
* @brief Write 16-bit data to EBI bank2
*
* @param[in] ebi The pointer of EBI module.
* @param[in] u32Addr The data address on EBI bank2.
* @param[in] u32Data Specify data to be written.
*
* @return None
*
* @details This macro is used to write 16-bit data to specify address on EBI bank2.
* \hideinitializer
*/
#define EBI2_WRITE_DATA16(ebi, u32Addr, u32Data) (*((volatile unsigned short *)((((ebi)==EBI_S)? EBI_BANK2_BASE_ADDR:EBI_BANK2_BASE_ADDR_NS)+(u32Addr))) = (u32Data))
/**
* @brief Read 32-bit data on EBI bank2
*
* @param[in] ebi The pointer of EBI module.
* @param[in] u32Addr The data address on EBI bank2.
*
* @return 32-bit Data
*
* @details This macro is used to read 32-bit data from specify address on EBI bank2.
* \hideinitializer
*/
#define EBI2_READ_DATA32(ebi, u32Addr) (*((volatile unsigned int *)((((ebi)==EBI_S)? EBI_BANK2_BASE_ADDR:EBI_BANK2_BASE_ADDR_NS)+(u32Addr))))
/**
* @brief Write 32-bit data to EBI bank2
*
* @param[in] ebi The pointer of EBI module.
* @param[in] u32Addr The data address on EBI bank2.
* @param[in] u32Data Specify data to be written.
*
* @return None
*
* @details This macro is used to write 32-bit data to specify address on EBI bank2.
* \hideinitializer
*/
#define EBI2_WRITE_DATA32(ebi, u32Addr, u32Data) (*((volatile unsigned int *)((((ebi)==EBI_S)? EBI_BANK2_BASE_ADDR:EBI_BANK2_BASE_ADDR_NS)+(u32Addr))) = (u32Data))
/**
* @brief Enable EBI Write Buffer
*
* @param[in] ebi The pointer of EBI module.
*
* @return None
*
* @details This macro is used to improve EBI write operation for all EBI banks.
* \hideinitializer
*/
#define EBI_ENABLE_WRITE_BUFFER(ebi) ((ebi)->CTL0 |= EBI_CTL_WBUFEN_Msk)
/**
* @brief Disable EBI Write Buffer
*
* @param[in] ebi The pointer of EBI module.
*
* @return None
*
* @details This macro is used to disable EBI write buffer function.
* \hideinitializer
*/
#define EBI_DISABLE_WRITE_BUFFER(ebi) ((ebi)->CTL0 &= ~EBI_CTL_WBUFEN_Msk)
void EBI_Open(uint32_t u32Bank, uint32_t u32DataWidth, uint32_t u32TimingClass, uint32_t u32BusMode, uint32_t u32CSActiveLevel);
void EBI_Close(uint32_t u32Bank);
void EBI_SetBusTiming(uint32_t u32Bank, uint32_t u32TimingConfig, uint32_t u32MclkDiv);
/**@}*/ /* end of group EBI_EXPORTED_FUNCTIONS */
/**@}*/ /* end of group EBI_Driver */
/**@}*/ /* end of group Standard_Driver */
#ifdef __cplusplus
}
#endif
#endif /* __NU_EBI_H__ */

View File

@ -0,0 +1,458 @@
/**************************************************************************//**
* @file nu_ecap.h
* @version V3.00
* @brief EnHanced Input Capture Timer(ECAP) driver header file
*
* @copyright SPDX-License-Identifier: Apache-2.0
* @copyright Copyright (C) 2020 Nuvoton Technology Corp. All rights reserved.
*****************************************************************************/
#ifndef __NU_ECAP_H__
#define __NU_ECAP_H__
#ifdef __cplusplus
extern "C"
{
#endif
/** @addtogroup Standard_Driver Standard Driver
@{
*/
/** @addtogroup ECAP_Driver ECAP Driver
@{
*/
/** @addtogroup ECAP_EXPORTED_CONSTANTS ECAP Exported Constants
@{
*/
#define ECAP_IC0 (0UL) /*!< ECAP IC0 Unit \hideinitializer */
#define ECAP_IC1 (1UL) /*!< ECAP IC1 Unit \hideinitializer */
#define ECAP_IC2 (2UL) /*!< ECAP IC2 Unit \hideinitializer */
/*---------------------------------------------------------------------------------------------------------*/
/* ECAP CTL0 constant definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define ECAP_NOISE_FILTER_CLKDIV_1 (0UL<<ECAP_CTL0_NFCLKSEL_Pos) /*!< Noise filter clock divide by 1 \hideinitializer */
#define ECAP_NOISE_FILTER_CLKDIV_2 (1UL<<ECAP_CTL0_NFCLKSEL_Pos) /*!< Noise filter clock divide by 2 \hideinitializer */
#define ECAP_NOISE_FILTER_CLKDIV_4 (2UL<<ECAP_CTL0_NFCLKSEL_Pos) /*!< Noise filter clock divide by 4 \hideinitializer */
#define ECAP_NOISE_FILTER_CLKDIV_16 (3UL<<ECAP_CTL0_NFCLKSEL_Pos) /*!< Noise filter clock divide by 16 \hideinitializer */
#define ECAP_NOISE_FILTER_CLKDIV_32 (4UL<<ECAP_CTL0_NFCLKSEL_Pos) /*!< Noise filter clock divide by 32 \hideinitializer */
#define ECAP_NOISE_FILTER_CLKDIV_64 (5UL<<ECAP_CTL0_NFCLKSEL_Pos) /*!< Noise filter clock divide by 64 \hideinitializer */
#define ECAP_CAP_INPUT_SRC_FROM_IC (0UL) /*!< CAP input source from IC \hideinitializer */
#define ECAP_CAP_INPUT_SRC_FROM_CH (2UL) /*!< CAP input source from CH of QEI \hideinitializer */
#define ECAP_DISABLE_COMPARE (0UL<<ECAP_CTL0_CMPEN_Pos) /*!< Input capture compare and reload function disable \hideinitializer */
#define ECAP_COMPARE_FUNCTION (1UL<<ECAP_CTL0_CMPEN_Pos) /*!< Input capture compare function \hideinitializer */
/*---------------------------------------------------------------------------------------------------------*/
/* ECAP CTL1 constant definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define ECAP_RISING_EDGE (0UL<<ECAP_CTL1_EDGESEL0_Pos) /*!< ECAP capture rising edge selection \hideinitializer */
#define ECAP_FALLING_EDGE (1UL<<ECAP_CTL1_EDGESEL0_Pos) /*!< ECAP capture falling edge selection \hideinitializer */
#define ECAP_RISING_FALLING_EDGE (2UL<<ECAP_CTL1_EDGESEL0_Pos) /*!< ECAP capture either rising or falling edge selection \hideinitializer */
#define ECAP_CAPTURE_TIMER_CLKDIV_1 (0UL<<ECAP_CTL1_CLKSEL_Pos) /*!< ECAP capture timer clock divide by 1 \hideinitializer */
#define ECAP_CAPTURE_TIMER_CLKDIV_4 (1UL<<ECAP_CTL1_CLKSEL_Pos) /*!< ECAP capture timer clock divide by 4 \hideinitializer */
#define ECAP_CAPTURE_TIMER_CLKDIV_16 (2UL<<ECAP_CTL1_CLKSEL_Pos) /*!< ECAP capture timer clock divide by 16 \hideinitializer */
#define ECAP_CAPTURE_TIMER_CLKDIV_32 (3UL<<ECAP_CTL1_CLKSEL_Pos) /*!< ECAP capture timer clock divide by 32 \hideinitializer */
#define ECAP_CAPTURE_TIMER_CLKDIV_64 (4UL<<ECAP_CTL1_CLKSEL_Pos) /*!< ECAP capture timer clock divide by 64 \hideinitializer */
#define ECAP_CAPTURE_TIMER_CLKDIV_96 (5UL<<ECAP_CTL1_CLKSEL_Pos) /*!< ECAP capture timer clock divide by 96 \hideinitializer */
#define ECAP_CAPTURE_TIMER_CLKDIV_112 (6UL<<ECAP_CTL1_CLKSEL_Pos) /*!< ECAP capture timer clock divide by 112 \hideinitializer */
#define ECAP_CAPTURE_TIMER_CLKDIV_128 (7UL<<ECAP_CTL1_CLKSEL_Pos) /*!< ECAP capture timer clock divide by 128 \hideinitializer */
#define ECAP_CAPTURE_TIMER_CLK_SRC_CAP_CLK (0UL<<ECAP_CTL1_CNTSRCSEL_Pos) /*!< ECAP capture timer/clock source from CAP_CLK \hideinitializer */
#define ECAP_CAPTURE_TIMER_CLK_SRC_CAP0 (1UL<<ECAP_CTL1_CNTSRCSEL_Pos) /*!< ECAP capture timer/clock source from CAP0 \hideinitializer */
#define ECAP_CAPTURE_TIMER_CLK_SRC_CAP1 (2UL<<ECAP_CTL1_CNTSRCSEL_Pos) /*!< ECAP capture timer/clock source from CAP1 \hideinitializer */
#define ECAP_CAPTURE_TIMER_CLK_SRC_CAP2 (3UL<<ECAP_CTL1_CNTSRCSEL_Pos) /*!< ECAP capture timer/clock source from CAP2 \hideinitializer */
/**@}*/ /* end of group ECAP_EXPORTED_CONSTANTS */
/** @addtogroup ECAP_EXPORTED_FUNCTIONS ECAP Exported Functions
@{
*/
/**
* @brief This macro is used to select noise filter clock pre-divide number
* @param[in] ecap Specify ECAP port
* @param[in] u32ClkSel The noise filter clock divide number
* - \ref ECAP_NOISE_FILTER_CLKDIV_1
* - \ref ECAP_NOISE_FILTER_CLKDIV_2
* - \ref ECAP_NOISE_FILTER_CLKDIV_4
* - \ref ECAP_NOISE_FILTER_CLKDIV_16
* - \ref ECAP_NOISE_FILTER_CLKDIV_32
* - \ref ECAP_NOISE_FILTER_CLKDIV_64
* @return None
* @details This macro will set the sampling frequency of the noise filter cock.
* \hideinitializer
*/
#define ECAP_SET_NOISE_FILTER_CLKDIV(ecap, u32ClkSel) ((ecap)->CTL0 = ((ecap)->CTL0 & ~ECAP_CTL0_NFCLKSEL_Msk)|(u32ClkSel))
/**
* @brief This macro is used to disable noise filter
* @param[in] ecap Specify ECAP port
* @return None
* @details This macro will disable the noise filter of input capture.
* \hideinitializer
*/
#define ECAP_NOISE_FILTER_DISABLE(ecap) ((ecap)->CTL0 |= ECAP_CTL0_CAPNFDIS_Msk)
/**
* @brief This macro is used to enable noise filter
* @param[in] ecap Specify ECAP port
* @param[in] u32ClkSel Select noise filter clock divide number
* - \ref ECAP_NOISE_FILTER_CLKDIV_1
* - \ref ECAP_NOISE_FILTER_CLKDIV_2
* - \ref ECAP_NOISE_FILTER_CLKDIV_4
* - \ref ECAP_NOISE_FILTER_CLKDIV_16
* - \ref ECAP_NOISE_FILTER_CLKDIV_32
* - \ref ECAP_NOISE_FILTER_CLKDIV_64
* @return None
* @details This macro will enable the noise filter of input capture and set noise filter clock divide.
* \hideinitializer
*/
#define ECAP_NOISE_FILTER_ENABLE(ecap, u32ClkSel) ((ecap)->CTL0 = ((ecap)->CTL0 & ~(ECAP_CTL0_CAPNFDIS_Msk|ECAP_CTL0_NFCLKSEL_Msk))|(u32ClkSel))
/**
* @brief This macro is used to enable input channel unit
* @param[in] ecap Specify ECAP port
* @param[in] u32Mask The input channel mask
* - \ref ECAP_CTL0_IC0EN_Msk
* - \ref ECAP_CTL0_IC1EN_Msk
* - \ref ECAP_CTL0_IC2EN_Msk
* @return None
* @details This macro will enable the input channel_n to input capture.
* \hideinitializer
*/
#define ECAP_ENABLE_INPUT_CHANNEL(ecap, u32Mask) ((ecap)->CTL0 |= (u32Mask))
/**
* @brief This macro is used to disable input channel unit
* @param[in] ecap Specify ECAP port
* @param[in] u32Mask The input channel mask
* - \ref ECAP_CTL0_IC0EN_Msk
* - \ref ECAP_CTL0_IC1EN_Msk
* - \ref ECAP_CTL0_IC2EN_Msk
* @return None
* @details This macro will disable the input channel_n to input capture.
* \hideinitializer
*/
#define ECAP_DISABLE_INPUT_CHANNEL(ecap, u32Mask) ((ecap)->CTL0 &= ~(u32Mask))
/**
* @brief This macro is used to select input channel source
* @param[in] ecap Specify ECAP port
* @param[in] u32Index The input channel number
* - \ref ECAP_IC0
* - \ref ECAP_IC1
* - \ref ECAP_IC2
* @param[in] u32Src The input source
* - \ref ECAP_CAP_INPUT_SRC_FROM_IC
* - \ref ECAP_CAP_INPUT_SRC_FROM_CH
* @return None
* @details This macro will select the input source from ICx, CHx.
* \hideinitializer
*/
#define ECAP_SEL_INPUT_SRC(ecap, u32Index, u32Src) ((ecap)->CTL0 = ((ecap)->CTL0 & ~(ECAP_CTL0_CAPSEL0_Msk<<((u32Index)<<1)))|(((u32Src)<<ECAP_CTL0_CAPSEL0_Pos)<<((u32Index)<<1)))
/**
* @brief This macro is used to enable input channel interrupt
* @param[in] ecap Specify ECAP port
* @param[in] u32Mask The input channel mask
* - \ref ECAP_CTL0_CAPIEN0_Msk
* - \ref ECAP_CTL0_CAPIEN1_Msk
* - \ref ECAP_CTL0_CAPIEN2_Msk
* @return None
* @details This macro will enable the input channel_n interrupt.
* \hideinitializer
*/
#define ECAP_ENABLE_INT(ecap, u32Mask) ((ecap)->CTL0 |= (u32Mask))
/**
* @brief This macro is used to disable input channel interrupt
* @param[in] ecap Specify ECAP port
* @param[in] u32Mask The input channel mask
* - \ref ECAP_IC0
* - \ref ECAP_IC1
* - \ref ECAP_IC2
* @return None
* @details This macro will disable the input channel_n interrupt.
* \hideinitializer
*/
#define ECAP_DISABLE_INT(ecap, u32Mask) ((ecap)->CTL0 &= ~(u32Mask))
/**
* @brief This macro is used to enable input channel overflow interrupt
* @param[in] ecap Specify ECAP port
* @return None
* @details This macro will enable the input channel overflow interrupt.
* \hideinitializer
*/
#define ECAP_ENABLE_OVF_INT(ecap) ((ecap)->CTL0 |= ECAP_CTL0_OVIEN_Msk)
/**
* @brief This macro is used to disable input channel overflow interrupt
* @param[in] ecap Specify ECAP port
* @return None
* @details This macro will disable the input channel overflow interrupt.
* \hideinitializer
*/
#define ECAP_DISABLE_OVF_INT(ecap) ((ecap)->CTL0 &= ~ECAP_CTL0_OVIEN_Msk)
/**
* @brief This macro is used to enable input channel compare-match interrupt
* @param[in] ecap Specify ECAP port
* @return None
* @details This macro will enable the input channel compare-match interrupt.
* \hideinitializer
*/
#define ECAP_ENABLE_CMP_MATCH_INT(ecap) ((ecap)->CTL0 |= ECAP_CTL0_CMPIEN_Msk)
/**
* @brief This macro is used to disable input channel compare-match interrupt
* @param[in] ecap Specify ECAP port
* @return None
* @details This macro will disable the input channel compare-match interrupt.
* \hideinitializer
*/
#define ECAP_DISABLE_CMP_MATCH_INT(ecap) ((ecap)->CTL0 &= ~ECAP_CTL0_CMPIEN_Msk)
/**
* @brief This macro is used to start capture counter
* @param[in] ecap Specify ECAP port
* @return None
* @details This macro will start capture counter up-counting.
* \hideinitializer
*/
#define ECAP_CNT_START(ecap) ((ecap)->CTL0 |= ECAP_CTL0_CNTEN_Msk)
/**
* @brief This macro is used to stop capture counter
* @param[in] ecap Specify ECAP port
* @return None
* @details This macro will stop capture counter up-counting.
* \hideinitializer
*/
#define ECAP_CNT_STOP(ecap) ((ecap)->CTL0 &= ~ECAP_CTL0_CNTEN_Msk)
/**
* @brief This macro is used to set event to clear capture counter
* @param[in] ecap Specify ECAP port
* @param[in] u32Event The input channel number
* - \ref ECAP_CTL0_CMPCLREN_Msk
* - \ref ECAP_CTL1_CAP0RLDEN_Msk
* - \ref ECAP_CTL1_CAP1RLDEN_Msk
* - \ref ECAP_CTL1_CAP2RLDEN_Msk
* - \ref ECAP_CTL1_OVRLDEN_Msk
* @return None
* @details This macro will enable and select compare or capture event that can clear capture counter.
* \hideinitializer
*/
#define ECAP_SET_CNT_CLEAR_EVENT(ecap, u32Event) do{ \
if((u32Event) & ECAP_CTL0_CMPCLREN_Msk) \
(ecap)->CTL0 |= ECAP_CTL0_CMPCLREN_Msk; \
else \
(ecap)->CTL0 &= ~ECAP_CTL0_CMPCLREN_Msk; \
(ecap)->CTL1 = ((ecap)->CTL1 &(uint32_t)(~0xF00)) | ((u32Event) & 0xF00); \
}while(0);
/**
* @brief This macro is used to enable compare function
* @param[in] ecap Specify ECAP port
* @return None
* @details This macro will enable the compare function.
* \hideinitializer
*/
#define ECAP_ENABLE_CMP(ecap) ((ecap)->CTL0 |= ECAP_CTL0_CMPEN_Msk)
/**
* @brief This macro is used to disable compare function
* @param[in] ecap Specify ECAP port
* @return None
* @details This macro will disable the compare function.
* \hideinitializer
*/
#define ECAP_DISABLE_CMP(ecap) ((ecap)->CTL0 &= ~ECAP_CTL0_CMPEN_Msk)
/**
* @brief This macro is used to enable input capture function.
* @param[in] ecap Specify ECAP port
* @return None
* @details This macro will enable input capture timer/counter.
* \hideinitializer
*/
#define ECAP_ENABLE_CNT(ecap) ((ecap)->CTL0 |= ECAP_CTL0_CAPEN_Msk)
/**
* @brief This macro is used to disable input capture function.
* @param[in] ecap Specify ECAP port
* @return None
* @details This macro will disable input capture timer/counter.
* \hideinitializer
*/
#define ECAP_DISABLE_CNT(ecap) ((ecap)->CTL0 &= ~ECAP_CTL0_CAPEN_Msk)
/**
* @brief This macro is used to select input channel edge detection
* @param[in] ecap Specify ECAP port
* @param[in] u32Index The input channel number
* - \ref ECAP_IC0
* - \ref ECAP_IC1
* - \ref ECAP_IC2
* @param[in] u32Edge The input source
* - \ref ECAP_RISING_EDGE
* - \ref ECAP_FALLING_EDGE
* - \ref ECAP_RISING_FALLING_EDGE
* @return None
* @details This macro will select input capture can detect falling edge, rising edge or either rising or falling edge change.
* \hideinitializer
*/
#define ECAP_SEL_CAPTURE_EDGE(ecap, u32Index, u32Edge) ((ecap)->CTL1 = ((ecap)->CTL1 & ~(ECAP_CTL1_EDGESEL0_Msk<<((u32Index)<<1)))|((u32Edge)<<((u32Index)<<1)))
/**
* @brief This macro is used to select ECAP counter reload trigger source
* @param[in] ecap Specify ECAP port
* @param[in] u32TrigSrc The input source
* - \ref ECAP_CTL1_CAP0RLDEN_Msk
* - \ref ECAP_CTL1_CAP1RLDEN_Msk
* - \ref ECAP_CTL1_CAP2RLDEN_Msk
* - \ref ECAP_CTL1_OVRLDEN_Msk
* @return None
* @details This macro will select capture counter reload trigger source.
* \hideinitializer
*/
#define ECAP_SEL_RELOAD_TRIG_SRC(ecap, u32TrigSrc) ((ecap)->CTL1 = ((ecap)->CTL1 & ~0xF00)|(u32TrigSrc))
/**
* @brief This macro is used to select capture timer clock divide.
* @param[in] ecap Specify ECAP port
* @param[in] u32Clkdiv The input source
* - \ref ECAP_CAPTURE_TIMER_CLKDIV_1
* - \ref ECAP_CAPTURE_TIMER_CLKDIV_4
* - \ref ECAP_CAPTURE_TIMER_CLKDIV_16
* - \ref ECAP_CAPTURE_TIMER_CLKDIV_32
* - \ref ECAP_CAPTURE_TIMER_CLKDIV_64
* - \ref ECAP_CAPTURE_TIMER_CLKDIV_96
* - \ref ECAP_CAPTURE_TIMER_CLKDIV_112
* - \ref ECAP_CAPTURE_TIMER_CLKDIV_128
* @return None
* @details This macro will select capture timer clock has a pre-divider with eight divided option.
* \hideinitializer
*/
#define ECAP_SEL_TIMER_CLK_DIV(ecap, u32Clkdiv) ((ecap)->CTL1 = ((ecap)->CTL1 & ~ECAP_CTL1_CLKSEL_Msk)|(u32Clkdiv))
/**
* @brief This macro is used to select capture timer/counter clock source
* @param[in] ecap Specify ECAP port
* @param[in] u32ClkSrc The input source
* - \ref ECAP_CAPTURE_TIMER_CLK_SRC_CAP_CLK
* - \ref ECAP_CAPTURE_TIMER_CLK_SRC_CAP0
* - \ref ECAP_CAPTURE_TIMER_CLK_SRC_CAP1
* - \ref ECAP_CAPTURE_TIMER_CLK_SRC_CAP2
* @return None
* @details This macro will select capture timer/clock clock source.
* \hideinitializer
*/
#define ECAP_SEL_TIMER_CLK_SRC(ecap, u32ClkSrc) ((ecap)->CTL1 = ((ecap)->CTL1 & ~ECAP_CTL1_CNTSRCSEL_Msk)|(u32ClkSrc))
/**
* @brief This macro is used to read input capture status
* @param[in] ecap Specify ECAP port
* @return Input capture status flags
* @details This macro will get the input capture interrupt status.
* \hideinitializer
*/
#define ECAP_GET_INT_STATUS(ecap) ((ecap)->STATUS)
/**
* @brief This macro is used to get input channel interrupt flag
* @param[in] ecap Specify ECAP port
* @param[in] u32Mask The input channel mask
* - \ref ECAP_STATUS_CAPTF0_Msk
* - \ref ECAP_STATUS_CAPTF1_Msk
* - \ref ECAP_STATUS_CAPTF2_Msk
* - \ref ECAP_STATUS_CAPOVF_Msk
* - \ref ECAP_STATUS_CAPCMPF_Msk
* @return None
* @details This macro will write 1 to get the input channel_n interrupt flag.
* \hideinitializer
*/
#define ECAP_GET_CAPTURE_FLAG(ecap, u32Mask) (((ecap)->STATUS & (u32Mask))?1:0)
/**
* @brief This macro is used to clear input channel interrupt flag
* @param[in] ecap Specify ECAP port
* @param[in] u32Mask The input channel mask
* - \ref ECAP_STATUS_CAPTF0_Msk
* - \ref ECAP_STATUS_CAPTF1_Msk
* - \ref ECAP_STATUS_CAPTF2_Msk
* - \ref ECAP_STATUS_CAPOVF_Msk
* - \ref ECAP_STATUS_CAPCMPF_Msk
* @return None
* @details This macro will write 1 to clear the input channel_n interrupt flag.
* \hideinitializer
*/
#define ECAP_CLR_CAPTURE_FLAG(ecap, u32Mask) ((ecap)->STATUS = (u32Mask))
/**
* @brief This macro is used to set input capture counter value
* @param[in] ecap Specify ECAP port
* @param[in] u32Val Counter value
* @return None
* @details This macro will set a counter value of input capture.
* \hideinitializer
*/
#define ECAP_SET_CNT_VALUE(ecap, u32Val) ((ecap)->CNT = (u32Val))
/**
* @brief This macro is used to get input capture counter value
* @param[in] ecap Specify ECAP port
* @return Capture counter value
* @details This macro will get a counter value of input capture.
* \hideinitializer
*/
#define ECAP_GET_CNT_VALUE(ecap) ((ecap)->CNT)
/**
* @brief This macro is used to get input capture counter hold value
* @param[in] ecap Specify ECAP port
* @param[in] u32Index The input channel number
* - \ref ECAP_IC0
* - \ref ECAP_IC1
* - \ref ECAP_IC2
* @return Capture counter hold value
* @details This macro will get a hold value of input capture channel_n.
* \hideinitializer
*/
#define ECAP_GET_CNT_HOLD_VALUE(ecap, u32Index) (*(__IO uint32_t *) (&((ecap)->HLD0) + (u32Index)))
/**
* @brief This macro is used to set input capture counter compare value
* @param[in] ecap Specify ECAP port
* @param[in] u32Val Input capture compare value
* @return None
* @details This macro will set a compare value of input capture counter.
* \hideinitializer
*/
#define ECAP_SET_CNT_CMP(ecap, u32Val) ((ecap)->CNTCMP = (u32Val))
void ECAP_Open(ECAP_T* ecap, uint32_t u32FuncMask);
void ECAP_Close(ECAP_T* ecap);
void ECAP_EnableINT(ECAP_T* ecap, uint32_t u32Mask);
void ECAP_DisableINT(ECAP_T* ecap, uint32_t u32Mask);
/**@}*/ /* end of group ECAP_EXPORTED_FUNCTIONS */
/**@}*/ /* end of group ECAP_Driver */
/**@}*/ /* end of group Standard_Driver */
#ifdef __cplusplus
}
#endif
#endif /*__NU_ECAP_H__*/

View File

@ -0,0 +1,650 @@
/**************************************************************************//**
* @file nu_epwm.h
* @version V3.00
* @brief M2354 series EPWM driver header file
*
* @copyright SPDX-License-Identifier: Apache-2.0
* @copyright Copyright (C) 2020 Nuvoton Technology Corp. All rights reserved.
*****************************************************************************/
#ifndef __NU_EPWM_H__
#define __NU_EPWM_H__
#ifdef __cplusplus
extern "C"
{
#endif
/** @addtogroup Standard_Driver Standard Driver
@{
*/
/** @addtogroup EPWM_Driver EPWM Driver
@{
*/
/** @addtogroup EPWM_EXPORTED_CONSTANTS EPWM Exported Constants
@{
*/
#define EPWM_CHANNEL_NUM (6UL) /*!< EPWM channel number */
#define EPWM_CH_0_MASK (0x1UL) /*!< EPWM channel 0 mask \hideinitializer */
#define EPWM_CH_1_MASK (0x2UL) /*!< EPWM channel 1 mask \hideinitializer */
#define EPWM_CH_2_MASK (0x4UL) /*!< EPWM channel 2 mask \hideinitializer */
#define EPWM_CH_3_MASK (0x8UL) /*!< EPWM channel 3 mask \hideinitializer */
#define EPWM_CH_4_MASK (0x10UL) /*!< EPWM channel 4 mask \hideinitializer */
#define EPWM_CH_5_MASK (0x20UL) /*!< EPWM channel 5 mask \hideinitializer */
/*---------------------------------------------------------------------------------------------------------*/
/* Counter Type Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define EPWM_UP_COUNTER (0UL) /*!< Up counter type */
#define EPWM_DOWN_COUNTER (1UL) /*!< Down counter type */
#define EPWM_UP_DOWN_COUNTER (2UL) /*!< Up-Down counter type */
/*---------------------------------------------------------------------------------------------------------*/
/* Aligned Type Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define EPWM_EDGE_ALIGNED (1UL) /*!< EPWM working in edge aligned type(down count) */
#define EPWM_CENTER_ALIGNED (2UL) /*!< EPWM working in center aligned type */
/*---------------------------------------------------------------------------------------------------------*/
/* Output Level Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define EPWM_OUTPUT_NOTHING (0UL) /*!< EPWM output nothing */
#define EPWM_OUTPUT_LOW (1UL) /*!< EPWM output low */
#define EPWM_OUTPUT_HIGH (2UL) /*!< EPWM output high */
#define EPWM_OUTPUT_TOGGLE (3UL) /*!< EPWM output toggle */
/*---------------------------------------------------------------------------------------------------------*/
/* Synchronous Start Function Control Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define EPWM_SSCTL_SSRC_EPWM0 (0UL<<EPWM_SSCTL_SSRC_Pos) /*!< Synchronous start source comes from EPWM0 */
#define EPWM_SSCTL_SSRC_EPWM1 (1UL<<EPWM_SSCTL_SSRC_Pos) /*!< Synchronous start source comes from EPWM1 */
#define EPWM_SSCTL_SSRC_BPWM0 (2UL<<EPWM_SSCTL_SSRC_Pos) /*!< Synchronous start source comes from BPWM0 */
#define EPWM_SSCTL_SSRC_BPWM1 (3UL<<EPWM_SSCTL_SSRC_Pos) /*!< Synchronous start source comes from BPWM1 */
/*---------------------------------------------------------------------------------------------------------*/
/* Trigger Source Select Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define EPWM_TRG_ADC_EVEN_ZERO (0UL) /*!< EPWM trigger ADC while counter of even channel matches zero point */
#define EPWM_TRG_ADC_EVEN_PERIOD (1UL) /*!< EPWM trigger ADC while counter of even channel matches period point */
#define EPWM_TRG_ADC_EVEN_ZERO_PERIOD (2UL) /*!< EPWM trigger ADC while counter of even channel matches zero or period point */
#define EPWM_TRG_ADC_EVEN_COMPARE_UP (3UL) /*!< EPWM trigger ADC while counter of even channel matches up count to comparator point */
#define EPWM_TRG_ADC_EVEN_COMPARE_DOWN (4UL) /*!< EPWM trigger ADC while counter of even channel matches down count to comparator point */
#define EPWM_TRG_ADC_ODD_ZERO (5UL) /*!< EPWM trigger ADC while counter of odd channel matches zero point */
#define EPWM_TRG_ADC_ODD_PERIOD (6UL) /*!< EPWM trigger ADC while counter of odd channel matches period point */
#define EPWM_TRG_ADC_ODD_ZERO_PERIOD (7UL) /*!< EPWM trigger ADC while counter of odd channel matches zero or period point */
#define EPWM_TRG_ADC_ODD_COMPARE_UP (8UL) /*!< EPWM trigger ADC while counter of odd channel matches up count to comparator point */
#define EPWM_TRG_ADC_ODD_COMPARE_DOWN (9UL) /*!< EPWM trigger ADC while counter of odd channel matches down count to comparator point */
#define EPWM_TRG_ADC_CH_0_FREE_CMP_UP (10UL) /*!< EPWM trigger ADC while counter of channel 0 matches up count to free comparator point */
#define EPWM_TRG_ADC_CH_0_FREE_CMP_DOWN (11UL) /*!< EPWM trigger ADC while counter of channel 0 matches down count to free comparator point */
#define EPWM_TRG_ADC_CH_2_FREE_CMP_UP (12UL) /*!< EPWM trigger ADC while counter of channel 2 matches up count to free comparator point */
#define EPWM_TRG_ADC_CH_2_FREE_CMP_DOWN (13UL) /*!< EPWM trigger ADC while counter of channel 2 matches down count to free comparator point */
#define EPWM_TRG_ADC_CH_4_FREE_CMP_UP (14UL) /*!< EPWM trigger ADC while counter of channel 4 matches up count to free comparator point */
#define EPWM_TRG_ADC_CH_4_FREE_CMP_DOWN (15UL) /*!< EPWM trigger ADC while counter of channel 4 matches down count to free comparator point */
#define EPWM_TRIGGER_DAC_ZERO (0x1UL) /*!< EPWM trigger DAC while counter down count to 0 \hideinitializer */
#define EPWM_TRIGGER_DAC_PERIOD (0x100UL) /*!< EPWM trigger DAC while counter matches (PERIOD + 1) \hideinitializer */
#define EPWM_TRIGGER_DAC_COMPARE_UP (0x10000UL) /*!< EPWM trigger DAC while counter up count to CMPDAT \hideinitializer */
#define EPWM_TRIGGER_DAC_COMPARE_DOWN (0x1000000UL) /*!< EPWM trigger DAC while counter down count to CMPDAT \hideinitializer */
/*---------------------------------------------------------------------------------------------------------*/
/* Fail brake Control Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define EPWM_FB_EDGE_ACMP0 (EPWM_BRKCTL0_1_CPO0EBEN_Msk) /*!< Comparator 0 as edge-detect fault brake source */
#define EPWM_FB_EDGE_ACMP1 (EPWM_BRKCTL0_1_CPO1EBEN_Msk) /*!< Comparator 1 as edge-detect fault brake source */
#define EPWM_FB_EDGE_BKP0 (EPWM_BRKCTL0_1_BRKP0EEN_Msk) /*!< BKP0 pin as edge-detect fault brake source */
#define EPWM_FB_EDGE_BKP1 (EPWM_BRKCTL0_1_BRKP1EEN_Msk) /*!< BKP1 pin as edge-detect fault brake source */
#define EPWM_FB_EDGE_ADCRM (EPWM_BRKCTL0_1_EADCEBEN_Msk) /*!< ADC Result Monitor (ADCRM) as edge-detect fault brake source */
#define EPWM_FB_EDGE_SYS_CSS (EPWM_BRKCTL0_1_SYSEBEN_Msk | EPWM_FAILBRK_CSSBRKEN_Msk) /*!< System fail condition: clock security system detection as edge-detect fault brake source */
#define EPWM_FB_EDGE_SYS_BOD (EPWM_BRKCTL0_1_SYSEBEN_Msk | EPWM_FAILBRK_BODBRKEN_Msk) /*!< System fail condition: brown-out detection as edge-detect fault brake source */
#define EPWM_FB_EDGE_SYS_RAM (EPWM_BRKCTL0_1_SYSEBEN_Msk | EPWM_FAILBRK_RAMBRKEN_Msk) /*!< System fail condition: SRAM parity error detection as edge-detect fault brake source */
#define EPWM_FB_EDGE_SYS_COR (EPWM_BRKCTL0_1_SYSEBEN_Msk | EPWM_FAILBRK_CORBRKEN_Msk) /*!< System fail condition: core lockup detection as edge-detect fault brake source */
#define EPWM_FB_LEVEL_ACMP0 (EPWM_BRKCTL0_1_CPO0LBEN_Msk) /*!< Comparator 0 as level-detect fault brake source */
#define EPWM_FB_LEVEL_ACMP1 (EPWM_BRKCTL0_1_CPO1LBEN_Msk) /*!< Comparator 1 as level-detect fault brake source */
#define EPWM_FB_LEVEL_BKP0 (EPWM_BRKCTL0_1_BRKP0LEN_Msk) /*!< BKP0 pin as level-detect fault brake source */
#define EPWM_FB_LEVEL_BKP1 (EPWM_BRKCTL0_1_BRKP1LEN_Msk) /*!< BKP1 pin as level-detect fault brake source */
#define EPWM_FB_LEVEL_ADCRM (EPWM_BRKCTL0_1_EADCLBEN_Msk) /*!< ADC Result Monitor (ADCRM) as level-detect fault brake source */
#define EPWM_FB_LEVEL_SYS_CSS (EPWM_BRKCTL0_1_SYSLBEN_Msk | EPWM_FAILBRK_CSSBRKEN_Msk) /*!< System fail condition: clock security system detection as level-detect fault brake source */
#define EPWM_FB_LEVEL_SYS_BOD (EPWM_BRKCTL0_1_SYSLBEN_Msk | EPWM_FAILBRK_BODBRKEN_Msk) /*!< System fail condition: brown-out detection as level-detect fault brake source */
#define EPWM_FB_LEVEL_SYS_RAM (EPWM_BRKCTL0_1_SYSLBEN_Msk | EPWM_FAILBRK_RAMBRKEN_Msk) /*!< System fail condition: SRAM parity error detection as level-detect fault brake source */
#define EPWM_FB_LEVEL_SYS_COR (EPWM_BRKCTL0_1_SYSLBEN_Msk | EPWM_FAILBRK_CORBRKEN_Msk) /*!< System fail condition: core lockup detection as level-detect fault brake source */
#define EPWM_FB_EDGE (0UL) /*!< edge-detect fault brake */
#define EPWM_FB_LEVEL (8UL) /*!< level-detect fault brake */
/*---------------------------------------------------------------------------------------------------------*/
/* Leading Edge Blanking Control Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define EPWM_LEBCTL_TRGTYPE_RISING (0UL<<EPWM_LEBCTL_TRGTYPE_Pos) /*!< EPWM Leading Edge Blanking Trigger Type Is Rising Edge \hideinitializer */
#define EPWM_LEBCTL_TRGTYPE_FALLING (1UL<<EPWM_LEBCTL_TRGTYPE_Pos) /*!< EPWM Leading Edge Blanking Trigger Type Is Falling Edge \hideinitializer */
#define EPWM_LEBCTL_TRGTYPE_RISING_OR_FALLING (2UL<<EPWM_LEBCTL_TRGTYPE_Pos) /*!< EPWM Leading Edge Blanking Trigger Type Is Rising or Falling Edge \hideinitializer */
#define EPWM_LEBCTL_SRCEN0 (EPWM_LEBCTL_SRCEN0_Msk) /*!< EPWM Leading Edge Blanking Source From EPWMx_CH0 Enable \hideinitializer */
#define EPWM_LEBCTL_SRCEN2 (EPWM_LEBCTL_SRCEN2_Msk) /*!< EPWM Leading Edge Blanking Source From EPWMx_CH2 Enable \hideinitializer */
#define EPWM_LEBCTL_SRCEN4 (EPWM_LEBCTL_SRCEN4_Msk) /*!< EPWM Leading Edge Blanking Source From EPWMx_CH4 Enable \hideinitializer */
#define EPWM_LEBCTL_SRCEN0_2 (EPWM_LEBCTL_SRCEN0_Msk|EPWM_LEBCTL_SRCEN2_Msk) /*!< EPWM Leading Edge Blanking Source From EPWMx_CH0 and EPWMx_CH2 Enable \hideinitializer */
#define EPWM_LEBCTL_SRCEN0_4 (EPWM_LEBCTL_SRCEN0_Msk|EPWM_LEBCTL_SRCEN4_Msk) /*!< EPWM Leading Edge Blanking Source From EPWMx_CH0 and EPWMx_CH4 Enable \hideinitializer */
#define EPWM_LEBCTL_SRCEN2_4 (EPWM_LEBCTL_SRCEN2_Msk|EPWM_LEBCTL_SRCEN4_Msk) /*!< EPWM Leading Edge Blanking Source From EPWMx_CH2 and EPWMx_CH4 Enable \hideinitializer */
#define EPWM_LEBCTL_SRCEN0_2_4 (EPWM_LEBCTL_SRCEN0_Msk|EPWM_LEBCTL_SRCEN2_Msk|EPWM_LEBCTL_SRCEN4_Msk) /*!< EPWM Leading Edge Blanking Source From EPWMx_CH0, EPWMx_CH2 and EPWMx_CH4 Enable \hideinitializer */
/*---------------------------------------------------------------------------------------------------------*/
/* Capture Control Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define EPWM_CAPTURE_INT_RISING_LATCH (1UL) /*!< EPWM capture interrupt if channel has rising transition */
#define EPWM_CAPTURE_INT_FALLING_LATCH (0x100UL) /*!< EPWM capture interrupt if channel has falling transition */
#define EPWM_CAPTURE_PDMA_RISING_LATCH (0x2UL) /*!< EPWM capture rising latched data transfer by PDMA */
#define EPWM_CAPTURE_PDMA_FALLING_LATCH (0x4UL) /*!< EPWM capture falling latched data transfer by PDMA */
#define EPWM_CAPTURE_PDMA_RISING_FALLING_LATCH (0x6UL) /*!< EPWM capture rising and falling latched data transfer by PDMA */
/*---------------------------------------------------------------------------------------------------------*/
/* Duty Interrupt Type Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define EPWM_DUTY_INT_DOWN_COUNT_MATCH_CMP (EPWM_INTEN0_CMPDIEN0_Msk) /*!< EPWM duty interrupt triggered if down count match comparator */
#define EPWM_DUTY_INT_UP_COUNT_MATCH_CMP (EPWM_INTEN0_CMPUIEN0_Msk) /*!< EPWM duty interrupt triggered if up down match comparator */
/*---------------------------------------------------------------------------------------------------------*/
/* Interrupt Flag Accumulator Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define EPWM_IFA_ZERO_POINT (0UL) /*!< EPWM counter equal to zero */
#define EPWM_IFA_PERIOD_POINT (1UL) /*!< EPWM counter equal to period */
#define EPWM_IFA_COMPARE_UP_COUNT_POINT (2UL) /*!< EPWM counter up count to comparator value */
#define EPWM_IFA_COMPARE_DOWN_COUNT_POINT (3UL) /*!< EPWM counter down count to comparator value */
/*---------------------------------------------------------------------------------------------------------*/
/* Load Mode Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define EPWM_LOAD_MODE_IMMEDIATE (EPWM_CTL0_IMMLDEN0_Msk) /*!< EPWM immediately load mode \hideinitializer */
#define EPWM_LOAD_MODE_WINDOW (EPWM_CTL0_WINLDEN0_Msk) /*!< EPWM window load mode \hideinitializer */
#define EPWM_LOAD_MODE_CENTER (EPWM_CTL0_CTRLD0_Msk) /*!< EPWM center load mode \hideinitializer */
/*---------------------------------------------------------------------------------------------------------*/
/* Synchronize Control Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define EPWM_SYNC_OUT_FROM_SYNCIN_SWSYNC (0UL) /*!< Synchronize source from SYNC_IN or SWSYNC \hideinitializer */
#define EPWM_SYNC_OUT_FROM_COUNT_TO_ZERO (1UL) /*!< Synchronize source from counter equal to 0 \hideinitializer */
#define EPWM_SYNC_OUT_FROM_COUNT_TO_COMPARATOR (2UL) /*!< Synchronize source from counter equal to CMPDAT1, CMPDAT3, CMPDAT5 \hideinitializer */
#define EPWM_SYNC_OUT_DISABLE (3UL) /*!< SYNC_OUT will not be generated \hideinitializer */
#define EPWM_PHS_DIR_DECREMENT (0UL) /*!< EPWM counter count decrement \hideinitializer */
#define EPWM_PHS_DIR_INCREMENT (1UL) /*!< EPWM counter count increment \hideinitializer */
/*---------------------------------------------------------------------------------------------------------*/
/* Noise Filter Clock Divide Select Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define EPWM_NF_CLK_DIV_1 (0UL) /*!< Noise filter clock is HCLK divide by 1 \hideinitializer */
#define EPWM_NF_CLK_DIV_2 (1UL) /*!< Noise filter clock is HCLK divide by 2 \hideinitializer */
#define EPWM_NF_CLK_DIV_4 (2UL) /*!< Noise filter clock is HCLK divide by 4 \hideinitializer */
#define EPWM_NF_CLK_DIV_8 (3UL) /*!< Noise filter clock is HCLK divide by 8 \hideinitializer */
#define EPWM_NF_CLK_DIV_16 (4UL) /*!< Noise filter clock is HCLK divide by 16 \hideinitializer */
#define EPWM_NF_CLK_DIV_32 (5UL) /*!< Noise filter clock is HCLK divide by 32 \hideinitializer */
#define EPWM_NF_CLK_DIV_64 (6UL) /*!< Noise filter clock is HCLK divide by 64 \hideinitializer */
#define EPWM_NF_CLK_DIV_128 (7UL) /*!< Noise filter clock is HCLK divide by 128 \hideinitializer */
/*---------------------------------------------------------------------------------------------------------*/
/* Clock Source Select Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define EPWM_CLKSRC_EPWM_CLK (0UL) /*!< EPWM Clock source selects to EPWM0_CLK or EPWM1_CLK \hideinitializer */
#define EPWM_CLKSRC_TIMER0 (1UL) /*!< EPWM Clock source selects to TIMER0 overflow \hideinitializer */
#define EPWM_CLKSRC_TIMER1 (2UL) /*!< EPWM Clock source selects to TIMER1 overflow \hideinitializer */
#define EPWM_CLKSRC_TIMER2 (3UL) /*!< EPWM Clock source selects to TIMER2 overflow \hideinitializer */
#define EPWM_CLKSRC_TIMER3 (4UL) /*!< EPWM Clock source selects to TIMER3 overflow \hideinitializer */
/*---------------------------------------------------------------------------------------------------------*/
/* Fault Detect Clock Source Select Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define EPWM_FDCTL_FDCKSEL_CLK_DIV_1 (0UL << EPWM_FDCTL0_FDCKSEL_Pos) /*!< Fault detect clock selects to fault detect clock divided by 1 \hideinitializer */
#define EPWM_FDCTL_FDCKSEL_CLK_DIV_2 (1UL << EPWM_FDCTL0_FDCKSEL_Pos) /*!< Fault detect clock selects to fault detect clock divided by 2 \hideinitializer */
#define EPWM_FDCTL_FDCKSEL_CLK_DIV_4 (2UL << EPWM_FDCTL0_FDCKSEL_Pos) /*!< Fault detect clock selects to fault detect clock divided by 4 \hideinitializer */
#define EPWM_FDCTL_FDCKSEL_CLK_DIV_8 (3UL << EPWM_FDCTL0_FDCKSEL_Pos) /*!< Fault detect clock selects to fault detect clock divided by 8 \hideinitializer */
/**@}*/ /* end of group EPWM_EXPORTED_CONSTANTS */
/** @addtogroup EPWM_EXPORTED_FUNCTIONS EPWM Exported Functions
@{
*/
/**
* @brief This macro enable complementary mode
* @param[in] epwm The pointer of the specified EPWM module
* @return None
* @details This macro is used to enable complementary mode of EPWM module.
* \hideinitializer
*/
#define EPWM_ENABLE_COMPLEMENTARY_MODE(epwm) ((epwm)->CTL1 = (epwm)->CTL1 | (0x7ul<<EPWM_CTL1_OUTMODE0_Pos))
/**
* @brief This macro disable complementary mode, and enable independent mode.
* @param[in] epwm The pointer of the specified EPWM module
* @return None
* @details This macro is used to disable complementary mode of EPWM module.
* \hideinitializer
*/
#define EPWM_DISABLE_COMPLEMENTARY_MODE(epwm) ((epwm)->CTL1 = (epwm)->CTL1 & ~(0x7ul<<EPWM_CTL1_OUTMODE0_Pos))
/**
* @brief This macro enable group mode
* @param[in] epwm The pointer of the specified EPWM module
* @return None
* @details This macro is used to enable group mode of EPWM module.
* \hideinitializer
*/
#define EPWM_ENABLE_GROUP_MODE(epwm) ((epwm)->CTL0 = (epwm)->CTL0 | EPWM_CTL0_GROUPEN_Msk)
/**
* @brief This macro disable group mode
* @param[in] epwm The pointer of the specified EPWM module
* @return None
* @details This macro is used to disable group mode of EPWM module.
* \hideinitializer
*/
#define EPWM_DISABLE_GROUP_MODE(epwm) ((epwm)->CTL0 = (epwm)->CTL0 & ~EPWM_CTL0_GROUPEN_Msk)
/**
* @brief Enable timer synchronous start counting function of specified channel(s)
* @param[in] epwm The pointer of the specified EPWM module
* @param[in] u32ChannelMask Combination of enabled channels. Each bit corresponds to a channel
* Bit 0 represents channel 0, bit 1 represents channel 1...
* @param[in] u32SyncSrc Synchronous start source selection, valid values are:
* - \ref EPWM_SSCTL_SSRC_EPWM0
* - \ref EPWM_SSCTL_SSRC_EPWM1
* - \ref EPWM_SSCTL_SSRC_BPWM0
* - \ref EPWM_SSCTL_SSRC_BPWM1
* @return None
* @details This macro is used to enable timer synchronous start counting function of specified channel(s).
* \hideinitializer
*/
#define EPWM_ENABLE_TIMER_SYNC(epwm, u32ChannelMask, u32SyncSrc) ((epwm)->SSCTL = ((epwm)->SSCTL & ~EPWM_SSCTL_SSRC_Msk) | (u32SyncSrc) | (u32ChannelMask))
/**
* @brief Disable timer synchronous start counting function of specified channel(s)
* @param[in] epwm The pointer of the specified EPWM module
* @param[in] u32ChannelMask Combination of enabled channels. Each bit corresponds to a channel
* Bit 0 represents channel 0, bit 1 represents channel 1...
* @return None
* @details This macro is used to disable timer synchronous start counting function of specified channel(s).
* \hideinitializer
*/
#define EPWM_DISABLE_TIMER_SYNC(epwm, u32ChannelMask) \
do{ \
int i;\
for(i = 0; i < 6; i++) { \
if((u32ChannelMask) & (1UL << i)) \
{ \
(epwm)->SSCTL &= ~(1UL << i); \
} \
} \
}while(0)
/**
* @brief This macro enable EPWM counter synchronous start counting function.
* @param[in] epwm The pointer of the specified EPWM module
* @return None
* @details This macro is used to make selected EPWM0 and EPWM1 channel(s) start counting at the same time.
* To configure synchronous start counting channel(s) by EPWM_ENABLE_TIMER_SYNC() and EPWM_DISABLE_TIMER_SYNC().
* \hideinitializer
*/
#define EPWM_TRIGGER_SYNC_START(epwm) ((epwm)->SSTRG = EPWM_SSTRG_CNTSEN_Msk)
/**
* @brief This macro enable output inverter of specified channel(s)
* @param[in] epwm The pointer of the specified EPWM module
* @param[in] u32ChannelMask Combination of enabled channels. Each bit corresponds to a channel
* Bit 0 represents channel 0, bit 1 represents channel 1...
* @return None
* @details This macro is used to enable output inverter of specified channel(s).
* \hideinitializer
*/
#define EPWM_ENABLE_OUTPUT_INVERTER(epwm, u32ChannelMask) ((epwm)->POLCTL = (u32ChannelMask))
/**
* @brief This macro get captured rising data
* @param[in] epwm The pointer of the specified EPWM module
* @param[in] u32ChannelNum EPWM channel number. Valid values are between 0~5
* @return None
* @details This macro is used to get captured rising data of specified channel.
* \hideinitializer
*/
#define EPWM_GET_CAPTURE_RISING_DATA(epwm, u32ChannelNum) ((epwm)->CAPDAT[(u32ChannelNum)].RCAPDAT)
/**
* @brief This macro get captured falling data
* @param[in] epwm The pointer of the specified EPWM module
* @param[in] u32ChannelNum EPWM channel number. Valid values are between 0~5
* @return None
* @details This macro is used to get captured falling data of specified channel.
* \hideinitializer
*/
#define EPWM_GET_CAPTURE_FALLING_DATA(epwm, u32ChannelNum) ((epwm)->CAPDAT[(u32ChannelNum)].FCAPDAT)
/**
* @brief This macro mask output logic to high or low
* @param[in] epwm The pointer of the specified EPWM module
* @param[in] u32ChannelMask Combination of enabled channels. Each bit corresponds to a channel
* Bit 0 represents channel 0, bit 1 represents channel 1...
* @param[in] u32LevelMask Output logic to high or low
* @return None
* @details This macro is used to mask output logic to high or low of specified channel(s).
* @note If u32ChannelMask parameter is 0, then mask function will be disabled.
* \hideinitializer
*/
#define EPWM_MASK_OUTPUT(epwm, u32ChannelMask, u32LevelMask) \
do{ \
(epwm)->MSKEN = (u32ChannelMask); \
(epwm)->MSK = (u32LevelMask); \
}while(0)
/**
* @brief This macro set the prescaler of the selected channel
* @param[in] epwm The pointer of the specified EPWM module
* @param[in] u32ChannelNum EPWM channel number. Valid values are between 0~5
* @param[in] u32Prescaler Clock prescaler of specified channel. Valid values are between 0 ~ 0xFFF
* @return None
* @details This macro is used to set the prescaler of specified channel.
* @note Every even channel N, and channel (N + 1) share a prescaler. So if channel 0 prescaler changed, channel 1 will also be affected.
* The clock of EPWM counter is divided by (u32Prescaler + 1).
* \hideinitializer
*/
#define EPWM_SET_PRESCALER(epwm, u32ChannelNum, u32Prescaler) ((epwm)->CLKPSC[(u32ChannelNum) >> 1] = (u32Prescaler))
/**
* @brief This macro get the prescaler of the selected channel
* @param[in] epwm The pointer of the specified EPWM module
* @param[in] u32ChannelNum EPWM channel number. Valid values are between 0~5
* @return Return Clock prescaler of specified channel. Valid values are between 0 ~ 0xFFF
* @details This macro is used to get the prescaler of specified channel.
* @note Every even channel N, and channel (N + 1) share a prescaler. So if channel 0 prescaler changed, channel 1 will also be affected.
* The clock of EPWM counter is divided by (u32Prescaler + 1).
* \hideinitializer
*/
#define EPWM_GET_PRESCALER(epwm, u32ChannelNum) ((epwm)->CLKPSC[(u32ChannelNum) >> 1U])
/**
* @brief This macro set the comparator of the selected channel
* @param[in] epwm The pointer of the specified EPWM module
* @param[in] u32ChannelNum EPWM channel number. Valid values are between 0~5
* @param[in] u32CMR Comparator of specified channel. Valid values are between 0~0xFFFF
* @return None
* @details This macro is used to set the comparator of specified channel.
* @note This new setting will take effect on next EPWM period.
* \hideinitializer
*/
#define EPWM_SET_CMR(epwm, u32ChannelNum, u32CMR) ((epwm)->CMPDAT[(u32ChannelNum)]= (u32CMR))
/**
* @brief This macro get the comparator of the selected channel
* @param[in] epwm The pointer of the specified EPWM module
* @param[in] u32ChannelNum EPWM channel number. Valid values are between 0~5
* @return Return the comparator of specified channel. Valid values are between 0~0xFFFF
* @details This macro is used to get the comparator of specified channel.
* \hideinitializer
*/
#define EPWM_GET_CMR(epwm, u32ChannelNum) ((epwm)->CMPDAT[(u32ChannelNum)])
/**
* @brief This macro set the free trigger comparator of the selected channel
* @param[in] epwm The pointer of the specified EPWM module
* @param[in] u32ChannelNum EPWM channel number. Valid values are between 0~5
* @param[in] u32FTCMR Free trigger comparator of specified channel. Valid values are between 0~0xFFFF
* @return None
* @details This macro is used to set the free trigger comparator of specified channel.
* @note This new setting will take effect on next EPWM period.
* \hideinitializer
*/
#define EPWM_SET_FTCMR(epwm, u32ChannelNum, u32FTCMR) (((epwm)->FTCMPDAT[((u32ChannelNum) >> 1U)]) = (u32FTCMR))
/**
* @brief This macro set the period of the selected channel
* @param[in] epwm The pointer of the specified EPWM module
* @param[in] u32ChannelNum EPWM channel number. Valid values are between 0~5
* @param[in] u32CNR Period of specified channel. Valid values are between 0~0xFFFF
* @return None
* @details This macro is used to set the period of specified channel.
* @note This new setting will take effect on next EPWM period.
* @note EPWM counter will stop if period length set to 0.
* \hideinitializer
*/
#define EPWM_SET_CNR(epwm, u32ChannelNum, u32CNR) ((epwm)->PERIOD[(u32ChannelNum)] = (u32CNR))
/**
* @brief This macro get the period of the selected channel
* @param[in] epwm The pointer of the specified EPWM module
* @param[in] u32ChannelNum EPWM channel number. Valid values are between 0~5
* @return Return the period of specified channel. Valid values are between 0~0xFFFF
* @details This macro is used to get the period of specified channel.
* \hideinitializer
*/
#define EPWM_GET_CNR(epwm, u32ChannelNum) ((epwm)->PERIOD[(u32ChannelNum)])
/**
* @brief This macro set the EPWM aligned type
* @param[in] epwm The pointer of the specified EPWM module
* @param[in] u32ChannelMask Combination of enabled channels. Each bit corresponds to a channel
* Bit 0 represents channel 0, bit 1 represents channel 1...
* @param[in] u32AlignedType EPWM aligned type, valid values are:
* - \ref EPWM_EDGE_ALIGNED
* - \ref EPWM_CENTER_ALIGNED
* @return None
* @details This macro is used to set the EPWM aligned type of specified channel(s).
* \hideinitializer
*/
#define EPWM_SET_ALIGNED_TYPE(epwm, u32ChannelMask, u32AlignedType) \
do{ \
uint32_t i; \
for(i = 0UL; i < 6UL; i++) { \
if((u32ChannelMask) & (1UL << i)) \
{ \
(epwm)->CTL1 = (((epwm)->CTL1 & ~(3UL << (i << 1))) | ((u32AlignedType) << (i << 1))); \
} \
} \
}while(0)
/**
* @brief Set load window of window loading mode for specified channel(s)
* @param[in] epwm The pointer of the specified EPWM module
* @param[in] u32ChannelMask Combination of enabled channels. Each bit corresponds to a channel
* Bit 0 represents channel 0, bit 1 represents channel 1...
* @return None
* @details This macro is used to set load window of window loading mode for specified channel(s).
* \hideinitializer
*/
#define EPWM_SET_LOAD_WINDOW(epwm, u32ChannelMask) ((epwm)->LOAD |= (u32ChannelMask))
/**
* @brief Trigger synchronous event from specified channel(s)
* @param[in] epwm The pointer of the specified EPWM module
* @param[in] u32ChannelNum EPWM channel number. Valid values are 0, 2, 4
* Bit 0 represents channel 0, bit 1 represents channel 2 and bit 2 represents channel 4
* @return None
* @details This macro is used to trigger synchronous event from specified channel(s).
* \hideinitializer
*/
#define EPWM_TRIGGER_SYNC(epwm, u32ChannelNum) ((epwm)->SWSYNC |= (1U << ((u32ChannelNum) >> 1)))
/**
* @brief Clear counter of specified channel(s)
* @param[in] epwm The pointer of the specified EPWM module
* @param[in] u32ChannelMask Combination of enabled channels. Each bit corresponds to a channel
* Bit 0 represents channel 0, bit 1 represents channel 1...
* @return None
* @details This macro is used to clear counter of specified channel(s).
* \hideinitializer
*/
#define EPWM_CLR_COUNTER(epwm, u32ChannelMask) ((epwm)->CNTCLR |= (u32ChannelMask))
/**
* @brief Set output level at zero, compare up, period(center) and compare down of specified channel(s)
* @param[in] epwm The pointer of the specified EPWM module
* @param[in] u32ChannelMask Combination of enabled channels. Each bit corresponds to a channel
* Bit 0 represents channel 0, bit 1 represents channel 1...
* @param[in] u32ZeroLevel output level at zero point, valid values are:
* - \ref EPWM_OUTPUT_NOTHING
* - \ref EPWM_OUTPUT_LOW
* - \ref EPWM_OUTPUT_HIGH
* - \ref EPWM_OUTPUT_TOGGLE
* @param[in] u32CmpUpLevel output level at compare up point, valid values are:
* - \ref EPWM_OUTPUT_NOTHING
* - \ref EPWM_OUTPUT_LOW
* - \ref EPWM_OUTPUT_HIGH
* - \ref EPWM_OUTPUT_TOGGLE
* @param[in] u32PeriodLevel output level at period(center) point, valid values are:
* - \ref EPWM_OUTPUT_NOTHING
* - \ref EPWM_OUTPUT_LOW
* - \ref EPWM_OUTPUT_HIGH
* - \ref EPWM_OUTPUT_TOGGLE
* @param[in] u32CmpDownLevel output level at compare down point, valid values are:
* - \ref EPWM_OUTPUT_NOTHING
* - \ref EPWM_OUTPUT_LOW
* - \ref EPWM_OUTPUT_HIGH
* - \ref EPWM_OUTPUT_TOGGLE
* @return None
* @details This macro is used to Set output level at zero, compare up, period(center) and compare down of specified channel(s).
* \hideinitializer
*/
#define EPWM_SET_OUTPUT_LEVEL(epwm, u32ChannelMask, u32ZeroLevel, u32CmpUpLevel, u32PeriodLevel, u32CmpDownLevel) \
do{ \
uint32_t i; \
for(i = 0UL; i < 6UL; i++) { \
if((u32ChannelMask) & (1UL << i)) { \
(epwm)->WGCTL0 = (((epwm)->WGCTL0 & ~(3UL << (i << 1))) | ((u32ZeroLevel) << (i << 1))); \
(epwm)->WGCTL0 = (((epwm)->WGCTL0 & ~(3UL << (EPWM_WGCTL0_PRDPCTL0_Pos + (i << 1)))) | ((u32PeriodLevel) << (EPWM_WGCTL0_PRDPCTL0_Pos + (i << 1)))); \
(epwm)->WGCTL1 = (((epwm)->WGCTL1 & ~(3UL << (i << 1))) | ((u32CmpUpLevel) << (i << 1))); \
(epwm)->WGCTL1 = (((epwm)->WGCTL1 & ~(3UL << (EPWM_WGCTL1_CMPDCTL0_Pos + (i << 1)))) | ((u32CmpDownLevel) << (EPWM_WGCTL1_CMPDCTL0_Pos + (i << 1)))); \
} \
} \
}while(0)
/**
* @brief Trigger brake event from specified channel(s)
* @param[in] epwm The pointer of the specified EPWM module
* @param[in] u32ChannelMask Combination of enabled channels. Each bit corresponds to a channel
* Bit 0 represents channel 0, bit 1 represents channel 2 and bit 2 represents channel 4
* @param[in] u32BrakeType Type of brake trigger.
* - \ref EPWM_FB_EDGE
* - \ref EPWM_FB_LEVEL
* @return None
* @details This macro is used to trigger brake event from specified channel(s).
* \hideinitializer
*/
#define EPWM_TRIGGER_BRAKE(epwm, u32ChannelMask, u32BrakeType) ((epwm)->SWBRK |= ((u32ChannelMask) << (u32BrakeType)))
/**
* @brief Set Dead zone clock source
* @param[in] epwm The pointer of the specified EPWM module
* @param[in] u32ChannelNum EPWM channel number. Valid values are between 0~5
* @param[in] u32AfterPrescaler Dead zone clock source is from prescaler output. Valid values are TRUE (after prescaler) or FALSE (before prescaler).
* @return None
* @details This macro is used to set Dead zone clock source. Every two channels share the same setting.
* @note The write-protection function should be disabled before using this function.
* \hideinitializer
*/
#define EPWM_SET_DEADZONE_CLK_SRC(epwm, u32ChannelNum, u32AfterPrescaler) \
(((epwm)->DTCTL[(u32ChannelNum) >> 1]) = ((epwm)->DTCTL[(u32ChannelNum) >> 1] & ~EPWM_DTCTL0_1_DTCKSEL_Msk) | \
((u32AfterPrescaler) << EPWM_DTCTL0_1_DTCKSEL_Pos))
/*---------------------------------------------------------------------------------------------------------*/
/* Define EPWM functions prototype */
/*---------------------------------------------------------------------------------------------------------*/
uint32_t EPWM_ConfigCaptureChannel(EPWM_T *epwm, uint32_t u32ChannelNum, uint32_t u32UnitTimeNsec, uint32_t u32CaptureEdge);
uint32_t EPWM_ConfigOutputChannel(EPWM_T *epwm, uint32_t u32ChannelNum, uint32_t u32Frequency, uint32_t u32DutyCycle);
void EPWM_Start(EPWM_T *epwm, uint32_t u32ChannelMask);
void EPWM_Stop(EPWM_T *epwm, uint32_t u32ChannelMask);
void EPWM_ForceStop(EPWM_T *epwm, uint32_t u32ChannelMask);
void EPWM_EnableADCTrigger(EPWM_T *epwm, uint32_t u32ChannelNum, uint32_t u32Condition);
void EPWM_DisableADCTrigger(EPWM_T *epwm, uint32_t u32ChannelNum);
int32_t EPWM_EnableADCTriggerPrescale(EPWM_T *epwm, uint32_t u32ChannelNum, uint32_t u32Prescale, uint32_t u32PrescaleCnt);
void EPWM_DisableADCTriggerPrescale(EPWM_T *epwm, uint32_t u32ChannelNum);
void EPWM_ClearADCTriggerFlag(EPWM_T *epwm, uint32_t u32ChannelNum, uint32_t u32Condition);
uint32_t EPWM_GetADCTriggerFlag(EPWM_T *epwm, uint32_t u32ChannelNum);
void EPWM_EnableDACTrigger(EPWM_T *epwm, uint32_t u32ChannelNum, uint32_t u32Condition);
void EPWM_DisableDACTrigger(EPWM_T *epwm, uint32_t u32ChannelNum);
void EPWM_ClearDACTriggerFlag(EPWM_T *epwm, uint32_t u32ChannelNum, uint32_t u32Condition);
uint32_t EPWM_GetDACTriggerFlag(EPWM_T *epwm, uint32_t u32ChannelNum);
void EPWM_EnableFaultBrake(EPWM_T *epwm, uint32_t u32ChannelMask, uint32_t u32LevelMask, uint32_t u32BrakeSource);
void EPWM_EnableCapture(EPWM_T *epwm, uint32_t u32ChannelMask);
void EPWM_DisableCapture(EPWM_T *epwm, uint32_t u32ChannelMask);
void EPWM_EnableOutput(EPWM_T *epwm, uint32_t u32ChannelMask);
void EPWM_DisableOutput(EPWM_T *epwm, uint32_t u32ChannelMask);
void EPWM_EnablePDMA(EPWM_T *epwm, uint32_t u32ChannelNum, uint32_t u32RisingFirst, uint32_t u32Mode);
void EPWM_DisablePDMA(EPWM_T *epwm, uint32_t u32ChannelNum);
void EPWM_EnableDeadZone(EPWM_T *epwm, uint32_t u32ChannelNum, uint32_t u32Duration);
void EPWM_DisableDeadZone(EPWM_T *epwm, uint32_t u32ChannelNum);
void EPWM_EnableCaptureInt(EPWM_T *epwm, uint32_t u32ChannelNum, uint32_t u32Edge);
void EPWM_DisableCaptureInt(EPWM_T *epwm, uint32_t u32ChannelNum, uint32_t u32Edge);
void EPWM_ClearCaptureIntFlag(EPWM_T *epwm, uint32_t u32ChannelNum, uint32_t u32Edge);
uint32_t EPWM_GetCaptureIntFlag(EPWM_T *epwm, uint32_t u32ChannelNum);
void EPWM_EnableDutyInt(EPWM_T *epwm, uint32_t u32ChannelNum, uint32_t u32IntDutyType);
void EPWM_DisableDutyInt(EPWM_T *epwm, uint32_t u32ChannelNum);
void EPWM_ClearDutyIntFlag(EPWM_T *epwm, uint32_t u32ChannelNum);
uint32_t EPWM_GetDutyIntFlag(EPWM_T *epwm, uint32_t u32ChannelNum);
void EPWM_EnableFaultBrakeInt(EPWM_T *epwm, uint32_t u32BrakeSource);
void EPWM_DisableFaultBrakeInt(EPWM_T *epwm, uint32_t u32BrakeSource);
void EPWM_ClearFaultBrakeIntFlag(EPWM_T *epwm, uint32_t u32BrakeSource);
uint32_t EPWM_GetFaultBrakeIntFlag(EPWM_T *epwm, uint32_t u32BrakeSource);
void EPWM_EnablePeriodInt(EPWM_T *epwm, uint32_t u32ChannelNum, uint32_t u32IntPeriodType);
void EPWM_DisablePeriodInt(EPWM_T *epwm, uint32_t u32ChannelNum);
void EPWM_ClearPeriodIntFlag(EPWM_T *epwm, uint32_t u32ChannelNum);
uint32_t EPWM_GetPeriodIntFlag(EPWM_T *epwm, uint32_t u32ChannelNum);
void EPWM_EnableZeroInt(EPWM_T *epwm, uint32_t u32ChannelNum);
void EPWM_DisableZeroInt(EPWM_T *epwm, uint32_t u32ChannelNum);
void EPWM_ClearZeroIntFlag(EPWM_T *epwm, uint32_t u32ChannelNum);
uint32_t EPWM_GetZeroIntFlag(EPWM_T *epwm, uint32_t u32ChannelNum);
void EPWM_EnableAcc(EPWM_T *epwm, uint32_t u32ChannelNum, uint32_t u32IntFlagCnt, uint32_t u32IntAccSrc);
void EPWM_DisableAcc(EPWM_T *epwm, uint32_t u32ChannelNum);
void EPWM_EnableAccInt(EPWM_T *epwm, uint32_t u32ChannelNum);
void EPWM_DisableAccInt(EPWM_T *epwm, uint32_t u32ChannelNum);
void EPWM_ClearAccInt(EPWM_T *epwm, uint32_t u32ChannelNum);
uint32_t EPWM_GetAccInt(EPWM_T *epwm, uint32_t u32ChannelNum);
void EPWM_EnableAccPDMA(EPWM_T *epwm, uint32_t u32ChannelNum);
void EPWM_DisableAccPDMA(EPWM_T *epwm, uint32_t u32ChannelNum);
void EPWM_EnableAccStopMode(EPWM_T *epwm, uint32_t u32ChannelNum);
void EPWM_DisableAccStopMode(EPWM_T *epwm, uint32_t u32ChannelNum);
void EPWM_ClearFTDutyIntFlag(EPWM_T *epwm, uint32_t u32ChannelNum);
uint32_t EPWM_GetFTDutyIntFlag(EPWM_T *epwm, uint32_t u32ChannelNum);
void EPWM_EnableLoadMode(EPWM_T *epwm, uint32_t u32ChannelNum, uint32_t u32LoadMode);
void EPWM_DisableLoadMode(EPWM_T *epwm, uint32_t u32ChannelNum, uint32_t u32LoadMode);
void EPWM_ConfigSyncPhase(EPWM_T *epwm, uint32_t u32ChannelNum, uint32_t u32SyncSrc, uint32_t u32Direction, uint32_t u32StartPhase);
void EPWM_EnableSyncPhase(EPWM_T *epwm, uint32_t u32ChannelMask);
void EPWM_DisableSyncPhase(EPWM_T *epwm, uint32_t u32ChannelMask);
void EPWM_EnableSyncNoiseFilter(EPWM_T *epwm, uint32_t u32ClkCnt, uint32_t u32ClkDivSel);
void EPWM_DisableSyncNoiseFilter(EPWM_T *epwm);
void EPWM_EnableSyncPinInverse(EPWM_T *epwm);
void EPWM_DisableSyncPinInverse(EPWM_T *epwm);
void EPWM_SetClockSource(EPWM_T *epwm, uint32_t u32ChannelNum, uint32_t u32ClkSrcSel);
void EPWM_EnableBrakeNoiseFilter(EPWM_T *epwm, uint32_t u32BrakePinNum, uint32_t u32ClkCnt, uint32_t u32ClkDivSel);
void EPWM_DisableBrakeNoiseFilter(EPWM_T *epwm, uint32_t u32BrakePinNum);
void EPWM_EnableBrakePinInverse(EPWM_T *epwm, uint32_t u32BrakePinNum);
void EPWM_DisableBrakePinInverse(EPWM_T *epwm, uint32_t u32BrakePinNum);
void EPWM_SetBrakePinSource(EPWM_T *epwm, uint32_t u32BrakePinNum, uint32_t u32SelAnotherModule);
void EPWM_SetLeadingEdgeBlanking(EPWM_T *epwm, uint32_t u32TrigSrcSel, uint32_t u32TrigType, uint32_t u32BlankingCnt, uint32_t u32BlankingEnable);
uint32_t EPWM_GetWrapAroundFlag(EPWM_T *epwm, uint32_t u32ChannelNum);
void EPWM_ClearWrapAroundFlag(EPWM_T *epwm, uint32_t u32ChannelNum);
void EPWM_EnableFaultDetect(EPWM_T *epwm, uint32_t u32ChannelNum, uint32_t u32AfterPrescaler, uint32_t u32ClkSel);
void EPWM_DisableFaultDetect(EPWM_T *epwm, uint32_t u32ChannelNum);
void EPWM_EnableFaultDetectOutput(EPWM_T *epwm, uint32_t u32ChannelNum);
void EPWM_DisableFaultDetectOutput(EPWM_T *epwm, uint32_t u32ChannelNum);
void EPWM_EnableFaultDetectDeglitch(EPWM_T *epwm, uint32_t u32ChannelNum, uint32_t u32DeglitchSmpCycle);
void EPWM_DisableFaultDetectDeglitch(EPWM_T *epwm, uint32_t u32ChannelNum);
void EPWM_EnableFaultDetectMask(EPWM_T *epwm, uint32_t u32ChannelNum, uint32_t u32MaskCnt);
void EPWM_DisableFaultDetectMask(EPWM_T *epwm, uint32_t u32ChannelNum);
void EPWM_EnableFaultDetectInt(EPWM_T *epwm, uint32_t u32ChannelNum);
void EPWM_DisableFaultDetectInt(EPWM_T *epwm, uint32_t u32ChannelNum);
void EPWM_ClearFaultDetectInt(EPWM_T *epwm, uint32_t u32ChannelNum);
uint32_t EPWM_GetFaultDetectInt(EPWM_T *epwm, uint32_t u32ChannelNum);
/**@}*/ /* end of group EPWM_EXPORTED_FUNCTIONS */
/**@}*/ /* end of group EPWM_Driver */
/**@}*/ /* end of group Standard_Driver */
#ifdef __cplusplus
}
#endif
#endif /* __NU_EPWM_H__ */

View File

@ -0,0 +1,218 @@
/**************************************************************************//**
* @file nu_ewdt.h
* @version V3.00
* @brief Extra Watchdog Timer(EWDT) driver header file
*
* @copyright SPDX-License-Identifier: Apache-2.0
* @copyright Copyright (C) 2020 Nuvoton Technology Corp. All rights reserved.
*****************************************************************************/
#ifndef __NU_EWDT_H__
#define __NU_EWDT_H__
#ifdef __cplusplus
extern "C"
{
#endif
/** @addtogroup Standard_Driver Standard Driver
@{
*/
/** @addtogroup EWDT_Driver EWDT Driver
@{
*/
/** @addtogroup EWDT_EXPORTED_CONSTANTS EWDT Exported Constants
@{
*/
/*---------------------------------------------------------------------------------------------------------*/
/* EWDT Time-out Interval Period Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define EWDT_TIMEOUT_2POW4 (0UL << EWDT_CTL_TOUTSEL_Pos) /*!< Setting EWDT time-out interval to 2^4 * EWDT clocks \hideinitializer */
#define EWDT_TIMEOUT_2POW6 (1UL << EWDT_CTL_TOUTSEL_Pos) /*!< Setting EWDT time-out interval to 2^6 * EWDT clocks \hideinitializer */
#define EWDT_TIMEOUT_2POW8 (2UL << EWDT_CTL_TOUTSEL_Pos) /*!< Setting EWDT time-out interval to 2^8 * EWDT clocks \hideinitializer */
#define EWDT_TIMEOUT_2POW10 (3UL << EWDT_CTL_TOUTSEL_Pos) /*!< Setting EWDT time-out interval to 2^10 * EWDT clocks \hideinitializer */
#define EWDT_TIMEOUT_2POW12 (4UL << EWDT_CTL_TOUTSEL_Pos) /*!< Setting EWDT time-out interval to 2^12 * EWDT clocks \hideinitializer */
#define EWDT_TIMEOUT_2POW14 (5UL << EWDT_CTL_TOUTSEL_Pos) /*!< Setting EWDT time-out interval to 2^14 * EWDT clocks \hideinitializer */
#define EWDT_TIMEOUT_2POW16 (6UL << EWDT_CTL_TOUTSEL_Pos) /*!< Setting EWDT time-out interval to 2^16 * EWDT clocks \hideinitializer */
#define EWDT_TIMEOUT_2POW18 (7UL << EWDT_CTL_TOUTSEL_Pos) /*!< Setting EWDT time-out interval to 2^18 * EWDT clocks \hideinitializer */
#define EWDT_TIMEOUT_2POW20 (8UL << EWDT_CTL_TOUTSEL_Pos) /*!< Setting EWDT time-out interval to 2^20 * EWDT clocks \hideinitializer */
/*---------------------------------------------------------------------------------------------------------*/
/* EWDT Reset Delay Period Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define EWDT_RESET_DELAY_1026CLK (0UL << EWDT_ALTCTL_RSTDSEL_Pos) /*!< Setting EWDT reset delay period to 1026 * EWDT clocks \hideinitializer */
#define EWDT_RESET_DELAY_130CLK (1UL << EWDT_ALTCTL_RSTDSEL_Pos) /*!< Setting EWDT reset delay period to 130 * EWDT clocks \hideinitializer */
#define EWDT_RESET_DELAY_18CLK (2UL << EWDT_ALTCTL_RSTDSEL_Pos) /*!< Setting EWDT reset delay period to 18 * EWDT clocks \hideinitializer */
#define EWDT_RESET_DELAY_3CLK (3UL << EWDT_ALTCTL_RSTDSEL_Pos) /*!< Setting EWDT reset delay period to 3 * EWDT clocks \hideinitializer */
/*---------------------------------------------------------------------------------------------------------*/
/* EWDT Free Reset Counter Keyword Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define EWDT_RESET_COUNTER_KEYWORD (0x00005AA5UL) /*!< Fill this value to EWDT_RSTCNT register to free reset EWDT counter \hideinitializer */
/**@}*/ /* end of group EWDT_EXPORTED_CONSTANTS */
/** @addtogroup EWDT_EXPORTED_FUNCTIONS EWDT Exported Functions
@{
*/
/**
* @brief Clear EWDT Reset System Flag
*
* @param None
*
* @return None
*
* @details This macro clears EWDT time-out reset system flag.
* \hideinitializer
*/
#define EWDT_CLEAR_RESET_FLAG() (EWDT->CTL = (EWDT->CTL & ~(EWDT_CTL_IF_Msk | EWDT_CTL_WKF_Msk)) | EWDT_CTL_RSTF_Msk)
/**
* @brief Clear EWDT Time-out Interrupt Flag
*
* @param None
*
* @return None
*
* @details This macro clears EWDT time-out interrupt flag.
* \hideinitializer
*/
#define EWDT_CLEAR_TIMEOUT_INT_FLAG() (EWDT->CTL = (EWDT->CTL & ~(EWDT_CTL_RSTF_Msk | EWDT_CTL_WKF_Msk)) | EWDT_CTL_IF_Msk)
/**
* @brief Clear EWDT Wake-up Flag
*
* @param None
*
* @return None
*
* @details This macro clears EWDT time-out wake-up system flag.
* \hideinitializer
*/
#define EWDT_CLEAR_TIMEOUT_WAKEUP_FLAG() (EWDT->CTL = (EWDT->CTL & ~(EWDT_CTL_RSTF_Msk | EWDT_CTL_IF_Msk)) | EWDT_CTL_WKF_Msk)
/**
* @brief Get EWDT Time-out Reset Flag
*
* @param None
*
* @retval 0 EWDT time-out reset system did not occur
* @retval 1 EWDT time-out reset system occurred
*
* @details This macro indicates system has been reset by EWDT time-out reset or not.
* \hideinitializer
*/
#define EWDT_GET_RESET_FLAG() ((EWDT->CTL & EWDT_CTL_RSTF_Msk)? 1UL : 0UL)
/**
* @brief Get EWDT Time-out Interrupt Flag
*
* @param None
*
* @retval 0 EWDT time-out interrupt did not occur
* @retval 1 EWDT time-out interrupt occurred
*
* @details This macro indicates EWDT time-out interrupt occurred or not.
* \hideinitializer
*/
#define EWDT_GET_TIMEOUT_INT_FLAG() ((EWDT->CTL & EWDT_CTL_IF_Msk)? 1UL : 0UL)
/**
* @brief Get EWDT Time-out Wake-up Flag
*
* @param None
*
* @retval 0 EWDT time-out interrupt does not cause CPU wake-up
* @retval 1 EWDT time-out interrupt event cause CPU wake-up
*
* @details This macro indicates EWDT time-out interrupt event has waked up system or not.
* \hideinitializer
*/
#define EWDT_GET_TIMEOUT_WAKEUP_FLAG() ((EWDT->CTL & EWDT_CTL_WKF_Msk)? 1UL : 0UL)
/**
* @brief Reset EWDT Counter
*
* @param None
*
* @return None
*
* @details This macro is used to reset the internal 20-bit EWDT up counter value.
* @note If EWDT is activated and time-out reset system function is enabled also, user should \n
* reset the 20-bit EWDT up counter value to avoid generate EWDT time-out reset signal to \n
* reset system before the EWDT time-out reset delay period expires.
* \hideinitializer
*/
#define EWDT_RESET_COUNTER() (EWDT->RSTCNT = EWDT_RESET_COUNTER_KEYWORD)
/*---------------------------------------------------------------------------------------------------------*/
/* static inline functions */
/*---------------------------------------------------------------------------------------------------------*/
/* Declare these inline functions here to avoid MISRA C 2004 rule 8.1 error */
__STATIC_INLINE void EWDT_Close(void);
__STATIC_INLINE void EWDT_EnableInt(void);
__STATIC_INLINE void EWDT_DisableInt(void);
/**
* @brief Stop EWDT Counting
*
* @param None
*
* @return None
*
* @details This function will stop EWDT counting and disable EWDT module.
*/
__STATIC_INLINE void EWDT_Close(void)
{
EWDT->CTL = 0UL;
while((EWDT->CTL & EWDT_CTL_SYNC_Msk) == EWDT_CTL_SYNC_Msk) {} /* Wait disable WDTEN bit completed, it needs 2 * EWDT_CLK. */
}
/**
* @brief Enable EWDT Time-out Interrupt
*
* @param None
*
* @return None
*
* @details This function will enable the EWDT time-out interrupt function.
*/
__STATIC_INLINE void EWDT_EnableInt(void)
{
EWDT->CTL |= EWDT_CTL_INTEN_Msk;
}
/**
* @brief Disable EWDT Time-out Interrupt
*
* @param None
*
* @return None
*
* @details This function will disable the EWDT time-out interrupt function.
*/
__STATIC_INLINE void EWDT_DisableInt(void)
{
/* Do not touch another write 1 clear bits */
EWDT->CTL &= ~(EWDT_CTL_INTEN_Msk | EWDT_CTL_RSTF_Msk | EWDT_CTL_IF_Msk | EWDT_CTL_WKF_Msk);
}
void EWDT_Open(uint32_t u32TimeoutInterval, uint32_t u32ResetDelay, uint32_t u32EnableReset, uint32_t u32EnableWakeup);
/**@}*/ /* end of group WDT_EXPORTED_FUNCTIONS */
/**@}*/ /* end of group WDT_Driver */
/**@}*/ /* end of group Standard_Driver */
#ifdef __cplusplus
}
#endif
#endif /* __NU_EWDT_H__ */

View File

@ -0,0 +1,150 @@
/**************************************************************************//**
* @file nu_ewwdt.h
* @version V3.00
* @brief Extra Window Watchdog Timer(EWWDT) driver header file
*
* @copyright SPDX-License-Identifier: Apache-2.0
* @copyright Copyright (C) 2020 Nuvoton Technology Corp. All rights reserved.
*****************************************************************************/
#ifndef __NU_EWWDT_H__
#define __NU_EWWDT_H__
#ifdef __cplusplus
extern "C"
{
#endif
/** @addtogroup Standard_Driver Standard Driver
@{
*/
/** @addtogroup EWWDT_Driver EWWDT Driver
@{
*/
/** @addtogroup EWWDT_EXPORTED_CONSTANTS EWWDT Exported Constants
@{
*/
/*---------------------------------------------------------------------------------------------------------*/
/* EWWDT Prescale Period Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define EWWDT_PRESCALER_1 (0 << EWWDT_CTL_PSCSEL_Pos) /*!< Select max time-out period to 1 * (64*EWWDT_CLK) \hideinitializer */
#define EWWDT_PRESCALER_2 (1 << EWWDT_CTL_PSCSEL_Pos) /*!< Select max time-out period to 2 * (64*EWWDT_CLK) \hideinitializer */
#define EWWDT_PRESCALER_4 (2 << EWWDT_CTL_PSCSEL_Pos) /*!< Select max time-out period to 4 * (64*EWWDT_CLK) \hideinitializer */
#define EWWDT_PRESCALER_8 (3 << EWWDT_CTL_PSCSEL_Pos) /*!< Select max time-out period to 8 * (64*EWWDT_CLK) \hideinitializer */
#define EWWDT_PRESCALER_16 (4 << EWWDT_CTL_PSCSEL_Pos) /*!< Select max time-out period to 16 * (64*EWWDT_CLK) \hideinitializer */
#define EWWDT_PRESCALER_32 (5 << EWWDT_CTL_PSCSEL_Pos) /*!< Select max time-out period to 32 * (64*EWWDT_CLK) \hideinitializer */
#define EWWDT_PRESCALER_64 (6 << EWWDT_CTL_PSCSEL_Pos) /*!< Select max time-out period to 64 * (64*EWWDT_CLK) \hideinitializer */
#define EWWDT_PRESCALER_128 (7 << EWWDT_CTL_PSCSEL_Pos) /*!< Select max time-out period to 128 * (64*EWWDT_CLK) \hideinitializer */
#define EWWDT_PRESCALER_192 (8 << EWWDT_CTL_PSCSEL_Pos) /*!< Select max time-out period to 192 * (64*EWWDT_CLK) \hideinitializer */
#define EWWDT_PRESCALER_256 (9 << EWWDT_CTL_PSCSEL_Pos) /*!< Select max time-out period to 256 * (64*EWWDT_CLK) \hideinitializer */
#define EWWDT_PRESCALER_384 (10 << EWWDT_CTL_PSCSEL_Pos) /*!< Select max time-out period to 384 * (64*EWWDT_CLK) \hideinitializer */
#define EWWDT_PRESCALER_512 (11 << EWWDT_CTL_PSCSEL_Pos) /*!< Select max time-out period to 512 * (64*EWWDT_CLK) \hideinitializer */
#define EWWDT_PRESCALER_768 (12 << EWWDT_CTL_PSCSEL_Pos) /*!< Select max time-out period to 768 * (64*EWWDT_CLK) \hideinitializer */
#define EWWDT_PRESCALER_1024 (13 << EWWDT_CTL_PSCSEL_Pos) /*!< Select max time-out period to 1024 * (64*EWWDT_CLK) \hideinitializer */
#define EWWDT_PRESCALER_1536 (14 << EWWDT_CTL_PSCSEL_Pos) /*!< Select max time-out period to 1536 * (64*EWWDT_CLK) \hideinitializer */
#define EWWDT_PRESCALER_2048 (15 << EWWDT_CTL_PSCSEL_Pos) /*!< Select max time-out period to 2048 * (64*EWWDT_CLK) \hideinitializer */
/*---------------------------------------------------------------------------------------------------------*/
/* EWWDT Reload Counter Keyword Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define EWWDT_RELOAD_WORD (0x00005AA5UL) /*!< Fill this value to EWWDT_RLDCNT register to reload EWWDT counter \hideinitializer */
/**@}*/ /* end of group EWWDT_EXPORTED_CONSTANTS */
/** @addtogroup EWWDT_EXPORTED_FUNCTIONS EWWDT Exported Functions
@{
*/
/**
* @brief Clear EWWDT Reset System Flag
*
* @param None
*
* @return None
*
* @details This macro is used to clear EWWDT time-out reset system flag.
* \hideinitializer
*/
#define EWWDT_CLEAR_RESET_FLAG() (EWWDT->STATUS = EWWDT_STATUS_WWDTRF_Msk)
/**
* @brief Clear EWWDT Compared Match Interrupt Flag
*
* @param None
*
* @return None
*
* @details This macro is used to clear EWWDT compared match interrupt flag.
* \hideinitializer
*/
#define EWWDT_CLEAR_INT_FLAG() (EWWDT->STATUS = EWWDT_STATUS_WWDTIF_Msk)
/**
* @brief Get EWWDT Reset System Flag
*
* @param None
*
* @retval 0 EWWDT time-out reset system did not occur
* @retval 1 EWWDT time-out reset system occurred
*
* @details This macro is used to indicate system has been reset by EWWDT time-out reset or not.
* \hideinitializer
*/
#define EWWDT_GET_RESET_FLAG() ((EWWDT->STATUS & EWWDT_STATUS_WWDTRF_Msk)? 1 : 0)
/**
* @brief Get EWWDT Compared Match Interrupt Flag
*
* @param None
*
* @retval 0 EWWDT compare match interrupt did not occur
* @retval 1 EWWDT compare match interrupt occurred
*
* @details This macro is used to indicate EWWDT counter value matches CMPDAT value or not.
* \hideinitializer
*/
#define EWWDT_GET_INT_FLAG() ((EWWDT->STATUS & EWWDT_STATUS_WWDTIF_Msk)? 1 : 0)
/**
* @brief Get EWWDT Counter
*
* @param None
*
* @return EWWDT Counter Value
*
* @details This macro reflects the current EWWDT counter value.
* \hideinitializer
*/
#define EWWDT_GET_COUNTER() (EWWDT->CNT)
/**
* @brief Reload EWWDT Counter
*
* @param None
*
* @return None
*
* @details This macro is used to reload the EWWDT counter value to 0x3F.
* @note User can only write EWWDT_RLDCNT register to reload EWWDT counter value when current EWWDT counter value \n
* between 0 and CMPDAT value. If user writes EWWDT_RLDCNT when current EWWDT counter value is larger than CMPDAT, \n
* EWWDT reset signal will generate immediately to reset system.
* \hideinitializer
*/
#define EWWDT_RELOAD_COUNTER() (EWWDT->RLDCNT = EWWDT_RELOAD_WORD)
void EWWDT_Open(uint32_t u32PreScale, uint32_t u32CmpValue, uint32_t u32EnableInt);
/**@}*/ /* end of group EWWDT_EXPORTED_FUNCTIONS */
/**@}*/ /* end of group EWWDT_Driver */
/**@}*/ /* end of group Standard_Driver */
#ifdef __cplusplus
}
#endif
#endif /* __NU_EWWDT_H__ */

View File

@ -0,0 +1,588 @@
/**************************************************************************//**
* @file nu_fmc.h
* @version V3.0
* $Revision: 2 $
* $Date: 19/11/27 3:11p $
* @brief M2355 Series Flash Memory Controller(FMC) driver header file
*
* @copyright SPDX-License-Identifier: Apache-2.0
* @copyright Copyright (C) 2020 Nuvoton Technology Corp. All rights reserved.
******************************************************************************/
#ifndef __NU_FMC_H__
#define __NU_FMC_H__
#ifdef __cplusplus
extern "C"
{
#endif
/** @addtogroup Standard_Driver Standard Driver
@{
*/
/** @addtogroup FMC_Driver FMC Driver
@{
*/
/** @addtogroup FMC_EXPORTED_CONSTANTS FMC Exported Constants
@{
*/
/*---------------------------------------------------------------------------------------------------------*/
/* Global constant definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define ISBEN 0UL
#define FMC_ISP ( (__PC() & 0x10000000) ? FMC_NS : FMC)
/*---------------------------------------------------------------------------------------------------------*/
/* Define Base Address */
/*---------------------------------------------------------------------------------------------------------*/
#define FMC_APROM_BASE 0x00000000UL /*!< APROM Base Address */
#define FMC_APROM_END 0x00100000UL /*!< APROM end address */
#define FMC_APROM_BANK0_END (FMC_APROM_END/2UL) /*!< APROM bank0 end address */
#define FMC_LDROM_BASE 0x00100000UL /*!< LDROM Base Address */
#define FMC_LDROM_END 0x00104000UL /*!< LDROM end address */
#define FMC_DTFSH_BASE 0x00110000UL /*!< LDROM Base Address */
#define FMC_DTFSH_END 0x00112000UL /*!< LDROM end address */
#define FMC_XOM_BASE 0x00200000UL /*!< XOM Base Address */
#define FMC_XOMR0_BASE 0x00200000UL /*!< XOMR 0 Base Address */
#define FMC_XOMR1_BASE 0x00200010UL /*!< XOMR 1 Base Address */
#define FMC_XOMR2_BASE 0x00200020UL /*!< XOMR 2 Base Address */
#define FMC_XOMR3_BASE 0x00200030UL /*!< XOMR 3 Base Address */
#define FMC_NSCBA_BASE 0x00210800UL /*!< Non-Secure base address */
#define FMC_SCRLOCK_BASE 0x00610000UL /*!< Secure Region Lock base address */
#define FMC_ARLOCK_BASE 0x00610008UL /*!< All Region Lock base address */
#define FMC_CONFIG_BASE 0x00300000UL /*!< CONFIG Base Address */
#define FMC_USER_CONFIG_0 0x00300000UL /*!< CONFIG 0 Address */
#define FMC_USER_CONFIG_1 0x00300004UL /*!< CONFIG 1 Address */
#define FMC_USER_CONFIG_2 0x00300008UL /*!< CONFIG 2 Address */
#define FMC_USER_CONFIG_3 0x0030000CUL /*!< CONFIG 3 Address */
#define FMC_OTP_BASE 0x00310000UL /*!< OTP flash base address */
#define FMC_FLASH_PAGE_SIZE 0x800UL /*!< Flash Page Size (2048 Bytes) */
#define FMC_PAGE_ADDR_MASK 0xFFFFF800UL /*!< Flash page address mask */
#define FMC_MULTI_WORD_PROG_LEN 512UL /*!< The maximum length of a multi-word program. */
#define FMC_APROM_SIZE FMC_APROM_END /*!< APROM Size */
#define FMC_BANK_SIZE (FMC_APROM_SIZE/2UL) /*!< APROM Bank Size */
#define FMC_LDROM_SIZE 0x4000UL /*!< LDROM Size (4 Kbytes) */
#define FMC_OTP_ENTRY_CNT 256UL /*!< OTP entry number */
/*---------------------------------------------------------------------------------------------------------*/
/* XOM region number constant definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define XOMR0 0UL /*!< XOM region 0 */
#define XOMR1 1UL /*!< XOM region 1 */
#define XOMR2 2UL /*!< XOM region 2 */
#define XOMR3 3UL /*!< XOM region 3 */
/*---------------------------------------------------------------------------------------------------------*/
/* ISPCTL constant definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define IS_BOOT_FROM_LDROM 0x1UL /*!< ISPCTL setting to select to boot from LDROM */
#define IS_BOOT_FROM_APROM 0x0UL /*!< ISPCTL setting to select to boot from APROM */
/*---------------------------------------------------------------------------------------------------------*/
/* ISPCMD constant definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define FMC_ISPCMD_READ 0x00UL /*!< ISP Command: Read Flash */
#define FMC_ISPCMD_READ_UID 0x04UL /*!< ISP Command: Read Unique ID */
#define FMC_ISPCMD_READ_ALL1 0x08UL /*!< ISP Command: Read all-one result */
#define FMC_ISPCMD_READ_CID 0x0BUL /*!< ISP Command: Read Company ID */
#define FMC_ISPCMD_READ_DID 0x0CUL /*!< ISP Command: Read Device ID */
#define FMC_ISPCMD_READ_CKS 0x0DUL /*!< ISP Command: Read Checksum */
#define FMC_ISPCMD_PROGRAM 0x21UL /*!< ISP Command: 32-bit Program Flash */
#define FMC_ISPCMD_PAGE_ERASE 0x22UL /*!< ISP Command: Page Erase Flash */
#define FMC_ISPCMD_BANK_ERASE 0x23UL /*!< ISP Command: Erase Flash bank 0 or 1 */
#define FMC_ISPCMD_PROGRAM_MUL 0x27UL /*!< ISP Command: Flash Multi-Word Program */
#define FMC_ISPCMD_RUN_ALL1 0x28UL /*!< ISP Command: Run all-one verification */
#define FMC_ISPCMD_BANK_REMAP 0x2CUL /*!< ISP Command: Bank Remap */
#define FMC_ISPCMD_RUN_CKS 0x2DUL /*!< ISP Command: Run Check Calculation */
#define FMC_ISPCMD_VECMAP 0x2EUL /*!< ISP Command: Set vector mapping */
#define FMC_ISPCMD_READ_64 0x40UL /*!< ISP Command: 64-bit read Flash */
#define FMC_ISPCMD_PROGRAM_64 0x61UL /*!< ISP Command: 64-bit program Flash */
#define READ_ALLONE_YES 0xA11FFFFFUL /*!< Check-all-one result is all one. */
#define READ_ALLONE_NOT 0xA1100000UL /*!< Check-all-one result is not all one. */
#define READ_ALLONE_CMD_FAIL 0xFFFFFFFFUL /*!< Check-all-one command failed. */
/**@}*/ /* end of group FMC_EXPORTED_CONSTANTS */
/** @addtogroup FMC_EXPORTED_FUNCTIONS FMC Exported Functions
@{
*/
/*---------------------------------------------------------------------------------------------------------*/
/* FMC Macro Definitions */
/*---------------------------------------------------------------------------------------------------------*/
/**
* @brief Enable ISP Function
*
* @param None
*
* @return None
*
* @details This function will set ISPEN bit of ISPCTL control register to enable ISP function.
*
*/
#define FMC_ENABLE_ISP() (FMC_ISP->ISPCTL |= FMC_ISPCTL_ISPEN_Msk) /*!< Enable ISP Function */
/**
* @brief Disable ISP Function
*
* @param None
*
* @return None
*
* @details This function will clear ISPEN bit of ISPCTL control register to disable ISP function.
*
*/
#define FMC_DISABLE_ISP() (FMC_ISP->ISPCTL &= ~FMC_ISPCTL_ISPEN_Msk) /*!< Disable ISP Function */
/**
* @brief Disable Non Secure ISP Function
*
* @param None
*
* @return None
*
* @details This function will clear ISPEN bit of ISPCTL control register to disable Non Secure ISP function.
*
*/
#define FMC_ENABLE_LD_UPDATE() (FMC->ISPCTL |= FMC_ISPCTL_LDUEN_Msk) /*!< Enable LDROM Update Function */
/**
* @brief Disable LDROM Update Function
*
* @param None
*
* @return None
*
* @details This function will set ISPEN bit of ISPCTL control register to disable LDROM update function.
*
*/
#define FMC_DISABLE_LD_UPDATE() (FMC->ISPCTL &= ~FMC_ISPCTL_LDUEN_Msk) /*!< Disable LDROM Update Function */
/**
* @brief Enable User Configuration Update Function
*
* @param None
*
* @return None
*
* @details This function will set CFGUEN bit of ISPCTL control register to enable User Configuration update function.
* User needs to set CFGUEN bit before they can update User Configuration area.
*
*/
#define FMC_ENABLE_CFG_UPDATE() (FMC->ISPCTL |= FMC_ISPCTL_CFGUEN_Msk) /*!< Enable CONFIG Update Function */
/**
* @brief Disable User Configuration Update Function
*
* @param None
*
* @return None
*
* @details This function will clear CFGUEN bit of ISPCTL control register to disable User Configuration update function.
*
*/
#define FMC_DISABLE_CFG_UPDATE() (FMC->ISPCTL &= ~FMC_ISPCTL_CFGUEN_Msk) /*!< Disable CONFIG Update Function */
/**
* @brief Enable APROM Update Function
*
* @param None
*
* @return None
*
* @details This function will set APUEN bit of ISPCTL control register to enable APROM update function.
* User needs to set APUEN bit before they can update APROM in APROM boot mode.
*
*/
#define FMC_ENABLE_AP_UPDATE() (FMC_ISP->ISPCTL |= FMC_ISPCTL_APUEN_Msk) /*!< Enable APROM Update Function */
/**
* @brief Disable APROM Update Function
*
* @param None
*
* @return None
*
* @details This function will clear APUEN bit of ISPCTL control register to disable APROM update function.
*
*/
#define FMC_DISABLE_AP_UPDATE() (FMC_ISP->ISPCTL &= ~FMC_ISPCTL_APUEN_Msk) /*!< Disable APROM Update Function */
/**
* @brief Get ISP Fail Flag
*
* @param None
*
* @return None
*
* @details This function is used to get ISP fail flag when do ISP actoin.
*
*/
#define FMC_GET_FAIL_FLAG() ((FMC_ISP->ISPCTL & FMC_ISPCTL_ISPFF_Msk) ? 1UL : 0UL) /*!< Get ISP fail flag */
/**
* @brief Clear ISP Fail Flag
*
* @param None
*
* @return None
*
* @details This function is used to clear ISP fail flag when ISP fail flag set.
*
*/
#define FMC_CLR_FAIL_FLAG() (FMC_ISP->ISPCTL |= FMC_ISPCTL_ISPFF_Msk) /*!< Clear ISP fail flag */
/**
* @brief Enable ISP Interrupt
*
* @param None
*
* @return None
*
* @details This function will enable ISP action interrupt.
*
*/
#define FMC_ENABLE_ISP_INT() (FMC_ISP->ISPCTL |= FMC_ISPCTL_INTEN_Msk) /*!< Enable ISP interrupt */
/**
* @brief Disable ISP Interrupt
*
* @param None
*
* @return None
*
* @details This function will disable ISP action interrupt.
*
*/
#define FMC_DISABLE_ISP_INT() (FMC_ISP->ISPCTL &= ~FMC_ISPCTL_INTEN_Msk) /*!< Disable ISP interrupt */
/**
* @brief Get ISP Interrupt Flag
*
* @param None
*
* @return None
*
* @details This function will get ISP action interrupt status
*
*/
#define FMC_GET_ISP_INT_FLAG() ((FMC_ISP->ISPSTS & FMC_ISPSTS_INTFLAG_Msk) ? 1UL : 0UL) /*!< Get ISP interrupt flag Status */
/**
* @brief Clear ISP Interrupt Flag
*
* @param None
*
* @return None
*
* @details This function will clear ISP interrupt flag
*
*/
#define FMC_CLEAR_ISP_INT_FLAG() (FMC_ISP->ISPSTS = FMC_ISPSTS_INTFLAG_Msk) /*!< Clear ISP interrupt flag*/
/**
* @brief Enable Data Flash Scrambling Function
*
* @param None
*
* @return None
*
* @details This function will set SCRAMEN bit of DFCTL control register to enable Data Flash Scrambling Function.
*
*/
#define FMC_ENABLE_SCRAMBLE() (FMC->DFCTL |= FMC_DFCTL_SCRAMEN_Msk) /*!< Enable Data Flash Scrambling Function */
/**
* @brief Disable Data Flash Scrambling Function
*
* @param None
*
* @return None
*
* @details This function will clear SCRAMEN bit of DFCTL control register to disable Data Flash Scrambling Function.
*
*/
#define FMC_DISABLE_SCRAMBLE() (FMC->DFCTL &= ~FMC_DFCTL_SCRAMEN_Msk) /*!< Disable Data Flash Scrambling Function */
/**
* @brief Enable Data Flash Silent Access Function
*
* @param None
*
* @return None
*
* @details This function will set SILENTEN bit of DFCTL control register to enable Data Flash Silent Access Function.
*
*/
#define FMC_ENABLE_SILENT() (FMC->DFCTL |= FMC_DFCTL_SILENTEN_Msk) /*!< Enable Data Flash Silent Access Function */
/**
* @brief Disable Data Flash Silent Access Function
*
* @param None
*
* @return None
*
* @details This function will clear SILENTEN bit of DFCTL control register to disable Data Flash Silent Access Function.
*
*/
#define FMC_DISABLE_SILENT() (FMC->DFCTL &= ~FMC_DFCTL_SILENTEN_Msk) /*!< Disable Data Flash Silent Access Function */
/**
* @brief Enable Data Flash Temper Attack Program Function
*
* @param None
*
* @return None
*
* @details This function will set TMPCLR bit of DFCTL control register to enable Data Flash Temper Attack Program Function.
*
*/
#define FMC_ENABLE_TMPCLR() (FMC->DFCTL |= FMC_DFCTL_TMPCLR_Msk) /*!< Enable Data Flash Temper Attack Program Function */
/**
* @brief Disable Data Flash Temper Attack Program Function
*
* @param None
*
* @return None
*
* @details This function will clear TMPCLR bit of DFCTL control register to disable Data Flash Temper Attack Program Function.
*
*/
#define FMC_DISABLE_TMPCLR() (FMC->DFCTL &= ~FMC_DFCTL_TMPCLR_Msk) /*!< Disable Data Flash Temper Attack Program Function */
/**
* @brief Get Data Flash Temper Attack Programming Done Flag
*
* @param None
*
* @return None
*
* @details This function will get Data Flash Temper Attack Programming Done flag
*
*/
#define FMC_GET_TMPCLRDONE_FLAG() ((FMC->DFSTS & FMC_DFSTS_TMPCLRDONE_Msk) ? 1UL : 0UL) /*!< Get Data Flash Temper Attack Programming Done Flag */
/**
* @brief Get Data Flash Temper Attack Programming Busy Flag
*
* @param None
*
* @return None
*
* @details This function will get Data Flash Temper Attack Programming Busy flag
*
*/
#define FMC_GET_TMPCLRBUSY_FLAG() ((FMC->DFSTS & FMC_DFSTS_TMPCLRBUSY_Msk) ? 1UL : 0UL) /*!< Get Data Flash Temper Attack Programming Busy Flag */
/**
* @brief Clear Data Flash Temper Attack Programming Done Flag
*
* @param None
*
* @return None
*
* @details This function will clear Data Flash Temper Attack Programming Done flag
*
*/
#define FMC_CLEAR_TMPCLRDONE_FLAG() (FMC->DFSTS |= FMC_DFSTS_TMPCLRDONE_Msk) /*!< Clear Data Flash Temper Attack Programming Done Flag */
/*---------------------------------------------------------------------------------------------------------*/
/* inline functions */
/*---------------------------------------------------------------------------------------------------------*/
__STATIC_INLINE uint32_t FMC_ReadCID(void);
__STATIC_INLINE uint32_t FMC_ReadPID(void);
__STATIC_INLINE uint32_t FMC_ReadUID(uint8_t u8Index);
__STATIC_INLINE uint32_t FMC_ReadUCID(uint32_t u32Index);
__STATIC_INLINE void FMC_SetVectorPageAddr(uint32_t u32PageAddr);
__STATIC_INLINE uint32_t FMC_GetVECMAP(void);
__STATIC_INLINE void FMC_SetScrambleKey(uint32_t u32ScrambleKey);
/**
* @brief Get current vector mapping address.
*
* @param None
*
* @return The current vector mapping address.
*
* @details To get VECMAP value which is the page address for remapping to vector page (0x0).
*
*/
__STATIC_INLINE uint32_t FMC_GetVECMAP(void)
{
return (FMC->ISPSTS & FMC_ISPSTS_VECMAP_Msk);
}
/**
* @brief Read company ID
*
* @param None
*
* @return The company ID (32-bit)
*
* @details The company ID of Nuvoton is fixed to be 0xDA
*/
__STATIC_INLINE uint32_t FMC_ReadCID(void)
{
FMC_ISP->ISPCMD = FMC_ISPCMD_READ_CID; /* Set ISP Command Code */
FMC_ISP->ISPADDR = 0x0u; /* Must keep 0x0 when read CID */
FMC_ISP->ISPTRG = FMC_ISPTRG_ISPGO_Msk; /* Trigger to start ISP procedure */
#if ISBEN
__ISB();
#endif /* To make sure ISP/CPU be Synchronized */
while(FMC_ISP->ISPTRG & FMC_ISPTRG_ISPGO_Msk) {} /* Waiting for ISP Done */
return FMC_ISP->ISPDAT;
}
/**
* @brief Read product ID
*
* @param None
*
* @return The product ID (32-bit)
*
* @details This function is used to read product ID.
*/
__STATIC_INLINE uint32_t FMC_ReadPID(void)
{
FMC_ISP->ISPCMD = FMC_ISPCMD_READ_DID; /* Set ISP Command Code */
FMC_ISP->ISPADDR = 0x04u; /* Must keep 0x4 when read PID */
FMC_ISP->ISPTRG = FMC_ISPTRG_ISPGO_Msk; /* Trigger to start ISP procedure */
#if ISBEN
__ISB();
#endif /* To make sure ISP/CPU be Synchronized */
while(FMC_ISP->ISPTRG & FMC_ISPTRG_ISPGO_Msk) {} /* Waiting for ISP Done */
return FMC_ISP->ISPDAT;
}
/**
* @brief Read Unique ID
*
* @param[in] u8Index UID index. 0 = UID[31:0], 1 = UID[63:32], 2 = UID[95:64]
*
* @return The 32-bit unique ID data of specified UID index.
*
* @details To read out 96-bit Unique ID.
*/
__STATIC_INLINE uint32_t FMC_ReadUID(uint8_t u8Index)
{
FMC_ISP->ISPCMD = FMC_ISPCMD_READ_UID;
FMC_ISP->ISPADDR = ((uint32_t)u8Index << 2u);
FMC_ISP->ISPDAT = 0u;
FMC_ISP->ISPTRG = 0x1u;
#if ISBEN
__ISB();
#endif
while(FMC_ISP->ISPTRG) {}
return FMC_ISP->ISPDAT;
}
/**
* @brief To read UCID
*
* @param[in] u32Index Index of the UCID to read. u32Index must be 0, 1, 2, or 3.
*
* @return The UCID of specified index
*
* @details This function is used to read unique chip ID (UCID).
*/
__STATIC_INLINE uint32_t FMC_ReadUCID(uint32_t u32Index)
{
FMC_ISP->ISPCMD = FMC_ISPCMD_READ_UID; /* Set ISP Command Code */
FMC_ISP->ISPADDR = (0x04u * u32Index) + 0x10u; /* The UCID is at offset 0x10 with word alignment. */
FMC_ISP->ISPTRG = FMC_ISPTRG_ISPGO_Msk; /* Trigger to start ISP procedure */
#if ISBEN
__ISB();
#endif /* To make sure ISP/CPU be Synchronized */
while(FMC_ISP->ISPTRG & FMC_ISPTRG_ISPGO_Msk) {} /* Waiting for ISP Done */
return FMC_ISP->ISPDAT;
}
/**
* @brief Set vector mapping address
*
* @param[in] u32PageAddr The page address to remap to address 0x0. The address must be page alignment.
*
* @return To set VECMAP to remap specified page address to 0x0.
*
* @details This function is used to set VECMAP to map specified page to vector page (0x0).
*/
__STATIC_INLINE void FMC_SetVectorPageAddr(uint32_t u32PageAddr)
{
FMC->ISPCMD = FMC_ISPCMD_VECMAP; /* Set ISP Command Code */
FMC->ISPADDR = u32PageAddr; /* The address of specified page which will be map to address 0x0. It must be page alignment. */
FMC->ISPTRG = 0x1u; /* Trigger to start ISP procedure */
#if ISBEN
__ISB();
#endif /* To make sure ISP/CPU be Synchronized */
while(FMC->ISPTRG) {} /* Waiting for ISP Done */
}
/**
* @brief Set Data Flash scrambling key
*
* @param[in] u32ScramKey The value of scrambling key.
*
* @return NULL
*
* @details This function is used to set Data Flash scrambling key.
*/
__STATIC_INLINE void FMC_SetScrambleKey(uint32_t u32ScrambleKey)
{
FMC->SCRKEY = u32ScrambleKey;
}
/*---------------------------------------------------------------------------------------------------------*/
/* Functions */
/*---------------------------------------------------------------------------------------------------------*/
extern uint32_t FMC_CheckAllOne(uint32_t u32addr, uint32_t u32count);
extern void FMC_Close(void);
extern int32_t FMC_ConfigXOM(uint32_t xom_num, uint32_t xom_base, uint8_t xom_page);
extern int32_t FMC_Erase(uint32_t u32PageAddr);
extern int32_t FMC_EraseBank(uint32_t u32BankAddr);
extern int32_t FMC_EraseXOM(uint32_t xom_num);
extern uint32_t FMC_GetChkSum(uint32_t u32addr, uint32_t u32count);
extern int32_t FMC_IsOTPLocked(uint32_t otp_num);
extern int32_t FMC_GetXOMState(uint32_t xom_num);
extern int32_t FMC_LockOTP(uint32_t otp_num);
extern void FMC_Open(void);
extern uint32_t FMC_Read(uint32_t u32Addr);
extern int32_t FMC_Read64(uint32_t u32addr, uint32_t * u32data0, uint32_t * u32data1);
extern int32_t FMC_ReadOTP(uint32_t otp_num, uint32_t *low_word, uint32_t *high_word);
extern int32_t FMC_ReadConfig(uint32_t u32Config[], uint32_t u32Count);
extern void FMC_Write(uint32_t u32Addr, uint32_t u32Data);
extern int32_t FMC_Write8Bytes(uint32_t u32addr, uint32_t u32data0, uint32_t u32data1);
extern int32_t FMC_WriteConfig(uint32_t au32Config[], uint32_t u32Count);
extern int32_t FMC_WriteMultiple(uint32_t u32Addr, uint32_t pu32Buf[], uint32_t u32Len);
extern int32_t FMC_WriteOTP(uint32_t otp_num, uint32_t low_word, uint32_t high_word);
extern int32_t FMC_WriteMultipleA(uint32_t u32Addr, uint32_t pu32Buf[], uint32_t u32Len);
extern int32_t FMC_RemapBank(uint32_t u32Bank);
/**@}*/ /* end of group FMC_EXPORTED_FUNCTIONS */
/**@}*/ /* end of group FMC_Driver */
/**@}*/ /* end of group Standard_Driver */
#ifdef __cplusplus
}
#endif
#endif /* __NU_FMC_H__ */

View File

@ -0,0 +1,55 @@
/**************************************************************************//**
* @file nu_fvc.h
* @version V3.00
* @brief Firmware Version Counter Driver Header
*
* @copyright SPDX-License-Identifier: Apache-2.0
* @copyright Copyright (C) 2020 Nuvoton Technology Corp. All rights reserved.
*****************************************************************************/
#ifndef __NU_FVC_H__
#define __NU_FVC_H__
#ifdef __cplusplus
extern "C"
{
#endif
/** @addtogroup Standard_Driver Standard Driver
@{
*/
/** @addtogroup FVC_Driver FVC Driver
@{
*/
/** @addtogroup FVC_EXPORTED_CONSTANTS FVC Exported Constants
@{
*/
#define FVC_VCODE (0x77100000ul) /*!< The key code for FVC_CTL write. */
/**@}*/ /* end of group FVC_EXPORTED_CONSTANTS */
/** @addtogroup FVC_EXPORTED_FUNCTIONS FVC Exported Functions
@{
*/
int32_t FVC_Open(void);
void FVC_EnableMonotone(void);
int32_t FVC_SetNVC(uint32_t u32NvcIdx, uint32_t u32Cnt);
int32_t FVC_GetNVC(uint32_t u32NvcIdx);
/**@}*/ /* end of group FVC_EXPORTED_FUNCTIONS */
/**@}*/ /* end of group FVC_Driver */
/**@}*/ /* end of group Standard_Driver */
#ifdef __cplusplus
}
#endif
#endif /* __NU_FVC_H__ */

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,523 @@
/**************************************************************************//**
* @file nu_i2c.h
* @version V3.0
* $Revision: 1 $
* $Date: 16/07/07 7:50p $
* @brief M2355 series I2C Serial Interface Controller(I2C) driver header file
*
* @copyright SPDX-License-Identifier: Apache-2.0
* @copyright Copyright (C) 2020 Nuvoton Technology Corp. All rights reserved.
******************************************************************************/
#ifndef __NU_I2C_H__
#define __NU_I2C_H__
#ifdef __cplusplus
extern "C"
{
#endif
/** @addtogroup Standard_Driver Standard Driver
@{
*/
/** @addtogroup I2C_Driver I2C Driver
@{
*/
/** @addtogroup I2C_EXPORTED_CONSTANTS I2C Exported Constants
@{
*/
/*---------------------------------------------------------------------------------------------------------*/
/* I2C_CTL constant definitions. */
/*---------------------------------------------------------------------------------------------------------*/
#define I2C_CTL_STA_SI (0x28U) /*!< I2C_CTL setting for I2C control bits. It would set STA and SI bits */
#define I2C_CTL_STA_SI_AA (0x2CU) /*!< I2C_CTL setting for I2C control bits. It would set STA, SI and AA bits */
#define I2C_CTL_STO_SI (0x18U) /*!< I2C_CTL setting for I2C control bits. It would set STO and SI bits */
#define I2C_CTL_STO_SI_AA (0x1CU) /*!< I2C_CTL setting for I2C control bits. It would set STO, SI and AA bits */
#define I2C_CTL_SI (0x08U) /*!< I2C_CTL setting for I2C control bits. It would set SI bit */
#define I2C_CTL_SI_AA (0x0CU) /*!< I2C_CTL setting for I2C control bits. It would set SI and AA bits */
#define I2C_CTL_STA (0x20U) /*!< I2C_CTL setting for I2C control bits. It would set STA bit */
#define I2C_CTL_STO (0x10U) /*!< I2C_CTL setting for I2C control bits. It would set STO bit */
#define I2C_CTL_AA (0x04U) /*!< I2C_CTL setting for I2C control bits. It would set AA bit */
/*---------------------------------------------------------------------------------------------------------*/
/* I2C GCMode constant definitions. */
/*---------------------------------------------------------------------------------------------------------*/
#define I2C_GCMODE_ENABLE (1U) /*!< Enable I2C GC Mode */
#define I2C_GCMODE_DISABLE (0U) /*!< Disable I2C GC Mode */
/*---------------------------------------------------------------------------------------------------------*/
/* I2C SMBUS constant definitions. */
/*---------------------------------------------------------------------------------------------------------*/
#define I2C_SMBH_ENABLE (1U) /*!< Enable SMBus Host Mode enable */
#define I2C_SMBD_ENABLE (0U) /*!< Enable SMBus Device Mode enable */
#define I2C_PECTX_ENABLE (1U) /*!< Enable SMBus Packet Error Check Transmit function */
#define I2C_PECTX_DISABLE (0U) /*!< Disable SMBus Packet Error Check Transmit function */
/**@}*/ /* end of group I2C_EXPORTED_CONSTANTS */
/** @addtogroup I2C_EXPORTED_FUNCTIONS I2C Exported Functions
@{
*/
/**
* @brief The macro is used to set I2C bus condition at One Time
*
* @param[in] i2c Specify I2C port
* @param[in] u8Ctrl A byte writes to I2C control register
*
* @return None
*
* @details Set I2C_CTL register to control I2C bus conditions of START, STOP, SI, ACK.
*/
#define I2C_SET_CONTROL_REG(i2c, u8Ctrl) ((i2c)->CTL0 = ((i2c)->CTL0 & ~0x3Cu) | (u8Ctrl))
/**
* @brief The macro is used to set START condition of I2C Bus
*
* @param[in] i2c Specify I2C port
*
* @return None
*
* @details Set the I2C bus START condition in I2C_CTL register.
*/
#define I2C_START(i2c) ((i2c)->CTL0 = ((i2c)->CTL0 | I2C_CTL0_SI_Msk) | I2C_CTL0_STA_Msk)
/**
* @brief The macro is used to wait I2C bus status get ready
*
* @param[in] i2c Specify I2C port
*
* @return None
*
* @details When a new status is presented of I2C bus, the SI flag will be set in I2C_CTL register.
*/
#define I2C_WAIT_READY(i2c) while(!((i2c)->CTL0 & I2C_CTL0_SI_Msk))
/**
* @brief The macro is used to Read I2C Bus Data Register
*
* @param[in] i2c Specify I2C port
*
* @return A byte of I2C data register
*
* @details I2C controller read data from bus and save it in I2CDAT register.
*/
#define I2C_GET_DATA(i2c) ((i2c)->DAT)
/**
* @brief Write a Data to I2C Data Register
*
* @param[in] i2c Specify I2C port
* @param[in] u8Data A byte that writes to data register
*
* @return None
*
* @details When write a data to I2C_DAT register, the I2C controller will shift it to I2C bus.
*/
#define I2C_SET_DATA(i2c, u8Data) ((i2c)->DAT = (u8Data))
/**
* @brief Get I2C Bus status code
*
* @param[in] i2c Specify I2C port
*
* @return I2C status code
*
* @details To get this status code to monitor I2C bus event.
*/
#define I2C_GET_STATUS(i2c) ((i2c)->STATUS0)
/**
* @brief Get Time-out flag from I2C Bus
*
* @param[in] i2c Specify I2C port
*
* @retval 0 I2C Bus time-out is not happened
* @retval 1 I2C Bus time-out is happened
*
* @details When I2C bus occurs time-out event, the time-out flag will be set.
*/
#define I2C_GET_TIMEOUT_FLAG(i2c) ( ((i2c)->TOCTL & I2C_TOCTL_TOIF_Msk) == I2C_TOCTL_TOIF_Msk ? 1u : 0u)
/**
* @brief To get wake-up flag from I2C Bus
*
* @param[in] i2c Specify I2C port
*
* @retval 0 Chip is not woken-up from power-down mode
* @retval 1 Chip is woken-up from power-down mode
*
* @details I2C bus occurs wake-up event, wake-up flag will be set.
*/
#define I2C_GET_WAKEUP_FLAG(i2c) ( ((i2c)->WKSTS & I2C_WKSTS_WKIF_Msk) == I2C_WKSTS_WKIF_Msk ? 1u : 0u)
/**
* @brief To clear wake-up flag
*
* @param[in] i2c Specify I2C port
*
* @return None
*
* @details If wake-up flag is set, use this macro to clear it.
*/
#define I2C_CLEAR_WAKEUP_FLAG(i2c) ((i2c)->WKSTS = I2C_WKSTS_WKIF_Msk)
/**
* @brief To get wake-up address frame ACK done flag from I2C Bus
*
* @param[in] i2c Specify I2C port
*
* @retval 0 The ACK bit cycle of address match frame is not done
* @retval 1 The ACK bit cycle of address match frame is done in power-down
*
* @details I2C bus occurs wake-up event and address frame ACK is done, this flag will be set.
*
* \hideinitializer
*/
#define I2C_GET_WAKEUP_DONE(i2c) ( ((i2c)->WKSTS & I2C_WKSTS_WKAKDONE_Msk) == I2C_WKSTS_WKAKDONE_Msk ? 1u : 0u)
/**
* @brief To clear address frame ACK done flag
*
* @param[in] i2c Specify I2C port
*
* @return None
*
* @details If wake-up done is set, use this macro to clear it.
*
* \hideinitializer
*/
#define I2C_CLEAR_WAKEUP_DONE(i2c) ((i2c)->WKSTS = I2C_WKSTS_WKAKDONE_Msk)
/**
* @brief To get read/write status bit in address wakeup frame
*
* @param[in] i2c Specify I2C port
*
* @retval 0 Write command be record on the address match wakeup frame
* @retval 1 Read command be record on the address match wakeup frame.
*
* @details I2C bus occurs wake-up event and address frame is received, this bit will record read/write status.
*
* \hideinitializer
*/
#define I2C_GET_WAKEUP_WR_STATUS(i2c) ( ((i2c)->WKSTS & I2C_WKSTS_WRSTSWK_Msk) == I2C_WKSTS_WRSTSWK_Msk ? 1u : 0u)
/**
* @brief To get SMBus Status
*
* @param[in] i2c Specify I2C port
*
* @return SMBus status
*
* @details To get the Bus Management status of I2C_BUSSTS register
*
*/
#define I2C_SMBUS_GET_STATUS(i2c) ((i2c)->BUSSTS)
/**
* @brief Get SMBus CRC value
*
* @param[in] i2c Specify I2C port
*
* @return Packet error check byte value
*
* @details The CRC check value after a transmission or a reception by count by using CRC8
*
*/
#define I2C_SMBUS_GET_PEC_VALUE(i2c) ((i2c)->PKTCRC)
/**
* @brief Set SMBus Bytes number of Transmission or reception
*
* @param[in] i2c Specify I2C port
* @param[in] u32PktSize Transmit / Receive bytes
*
* @return None
*
* @details The transmission or receive byte number in one transaction when PECEN is set. The maximum is 255 bytes.
*
*/
#define I2C_SMBUS_SET_PACKET_BYTE_COUNT(i2c, u32PktSize) ((i2c)->PKTSIZE = (u32PktSize))
/**
* @brief Enable SMBus Alert function
*
* @param[in] i2c Specify I2C port
*
* @return None
*
* @details Device Mode(BMHEN=0): If ALERTEN(I2C_BUSCTL[4]) is set, the Alert pin will pull lo, and reply ACK when get ARP from host
* Host Mode(BMHEN=1): If ALERTEN(I2C_BUSCTL[4]) is set, the Alert pin is supported to receive alert state(Lo trigger)
*
*/
#define I2C_SMBUS_ENABLE_ALERT(i2c) ((i2c)->BUSCTL |= I2C_BUSCTL_ALERTEN_Msk)
/**
* @brief Disable SMBus Alert pin function
*
* @param[in] i2c Specify I2C port
*
* @return None
*
* @details Device Mode(BMHEN=0): If ALERTEN(I2C_BUSCTL[4]) is clear, the Alert pin will pull hi, and reply NACK when get ARP from host
* Host Mode(BMHEN=1): If ALERTEN(I2C_BUSCTL[4]) is clear, the Alert pin is not supported to receive alert state(Lo trigger)
*
*/
#define I2C_SMBUS_DISABLE_ALERT(i2c) ((i2c)->BUSCTL &= ~I2C_BUSCTL_ALERTEN_Msk)
/**
* @brief Set SMBus SUSCON pin is output mode
*
* @param[in] i2c Specify I2C port
*
* @return None
*
* @details This function to set SUSCON(I2C_BUSCTL[6]) pin is output mode.
*
*
*/
#define I2C_SMBUS_SET_SUSCON_OUT(i2c) ((i2c)->BUSCTL |= I2C_BUSCTL_SCTLOEN_Msk)
/**
* @brief Set SMBus SUSCON pin is input mode
*
* @param[in] i2c Specify I2C port
*
* @return None
*
* @details This function to set SUSCON(I2C_BUSCTL[6]) pin is input mode.
*
*
*/
#define I2C_SMBUS_SET_SUSCON_IN(i2c) ((i2c)->BUSCTL &= ~I2C_BUSCTL_SCTLOEN_Msk)
/**
* @brief Set SMBus SUSCON pin output high state
*
* @param[in] i2c Specify I2C port
*
* @return None
*
* @details This function to set SUSCON(I2C_BUSCTL[6]) pin is output hi state.
*
*/
#define I2C_SMBUS_SET_SUSCON_HIGH(i2c) ((i2c)->BUSCTL |= I2C_BUSCTL_SCTLOSTS_Msk)
/**
* @brief Set SMBus SUSCON pin output low state
*
* @param[in] i2c Specify I2C port
*
* @return None
*
* @details This function to set SUSCON(I2C_BUSCTL[6]) pin is output lo state.
*
*/
#define I2C_SMBUS_SET_SUSCON_LOW(i2c) ((i2c)->BUSCTL &= ~I2C_BUSCTL_SCTLOSTS_Msk)
/**
* @brief Enable SMBus Acknowledge control by manual
*
* @param[in] i2c Specify I2C port
*
* @return None
*
* @details The 9th bit can response the ACK or NACK according the received data by user. When the byte is received, SCLK line stretching to low between the 8th and 9th SCLK pulse.
*
*/
#define I2C_SMBUS_ACK_MANUAL(i2c) ((i2c)->BUSCTL |= I2C_BUSCTL_ACKMEN_Msk)
/**
* @brief Disable SMBus Acknowledge control by manual
*
* @param[in] i2c Specify I2C port
*
* @return None
*
* @details Disable acknowledge response control by user.
*
*/
#define I2C_SMBUS_ACK_AUTO(i2c) ((i2c)->BUSCTL &= ~I2C_BUSCTL_ACKMEN_Msk)
/**
* @brief Enable SMBus Acknowledge manual interrupt
*
* @param[in] i2c Specify I2C port
*
* @return None
*
* @details This function is used to enable SMBUS acknowledge manual interrupt on the 9th clock cycle when SMBUS=1 and ACKMEN=1
*
*/
#define I2C_SMBUS_9THBIT_INT_ENABLE(i2c) ((i2c)->BUSCTL |= I2C_BUSCTL_ACKM9SI_Msk)
/**
* @brief Disable SMBus Acknowledge manual interrupt
*
* @param[in] i2c Specify I2C port
*
* @return None
*
* @details This function is used to disable SMBUS acknowledge manual interrupt on the 9th clock cycle when SMBUS=1 and ACKMEN=1
*
*/
#define I2C_SMBUS_9THBIT_INT_DISABLE(i2c) ((i2c)->BUSCTL &= ~I2C_BUSCTL_ACKM9SI_Msk)
/**
* @brief Enable SMBus PEC clear at REPEAT START
*
* @param[in] i2c Specify I2C port
*
* @return None
*
* @details This function is used to enable the condition of REAEAT START can clear the PEC calculation.
*
*/
#define I2C_SMBUS_RST_PEC_AT_START_ENABLE(i2c) ((i2c)->BUSCTL |= I2C_BUSCTL_PECCLR_Msk)
/**
* @brief Disable SMBus PEC clear at Repeat START
*
* @param[in] i2c Specify I2C port
*
* @return None
*
* @details This function is used to disable the condition of Repeat START can clear the PEC calculation.
*
*/
#define I2C_SMBUS_RST_PEC_AT_START_DISABLE(i2c) ((i2c)->BUSCTL &= ~I2C_BUSCTL_PECCLR_Msk)
/**
* @brief Enable RX PDMA function.
* @param[in] i2c The pointer of the specified I2C module.
* @return None.
* @details Set RXPDMAEN bit of I2C_CTL1 register to enable RX PDMA transfer function.
*/
#define I2C_ENABLE_RX_PDMA(i2c) ((i2c)->CTL1 |= I2C_CTL1_RXPDMAEN_Msk)
/**
* @brief Enable TX PDMA function.
* @param[in] i2c The pointer of the specified I2C module.
* @return None.
* @details Set TXPDMAEN bit of I2C_CTL1 register to enable TX PDMA transfer function.
*/
#define I2C_ENABLE_TX_PDMA(i2c) ((i2c)->CTL1 |= I2C_CTL1_TXPDMAEN_Msk)
/**
* @brief Disable RX PDMA transfer.
* @param[in] i2c The pointer of the specified I2C module.
* @return None.
* @details Clear RXPDMAEN bit of I2C_CTL1 register to disable RX PDMA transfer function.
*/
#define I2C_DISABLE_RX_PDMA(i2c) ((i2c)->CTL1 &= ~I2C_CTL1_RXPDMAEN_Msk)
/**
* @brief Disable TX PDMA transfer.
* @param[in] i2c The pointer of the specified I2C module.
* @return None.
* @details Clear TXPDMAEN bit of I2C_CTL1 register to disable TX PDMA transfer function.
*/
#define I2C_DISABLE_TX_PDMA(i2c) ((i2c)->CTL1 &= ~I2C_CTL1_TXPDMAEN_Msk)
/**
* @brief Enable PDMA stretch function.
* @param[in] i2c The pointer of the specified I2C module.
* @return None.
* @details Enable this function is to stretch bus by hardware after PDMA transfer is done if SI is not cleared.
*/
#define I2C_ENABLE_PDMA_STRETCH(i2c) ((i2c)->CTL1 |= I2C_CTL1_PDMASTR_Msk)
/**
* @brief Disable PDMA stretch function.
* @param[in] i2c The pointer of the specified I2C module.
* @return None.
* @details I2C wil send STOP after PDMA transfers done automatically.
*/
#define I2C_DISABLE_PDMA_STRETCH(i2c) ((i2c)->CTL1 &= ~I2C_CTL1_PDMASTR_Msk)
/**
* @brief Reset PDMA function.
* @param[in] i2c The pointer of the specified I2C module.
* @return None.
* @details I2C PDMA engine will be reset after this function is called.
*/
#define I2C_DISABLE_RST_PDMA(i2c) ((i2c)->CTL1 |= I2C_CTL1_PDMARST_Msk)
/*---------------------------------------------------------------------------------------------------------*/
/* inline functions */
/*---------------------------------------------------------------------------------------------------------*/
static __INLINE void I2C_STOP(I2C_T *i2c);
/**
* @brief The macro is used to set STOP condition of I2C Bus
*
* @param[in] i2c Specify I2C port
*
* @return None
*
* @details Set the I2C bus STOP condition in I2C_CTL register.
*/
static __INLINE void I2C_STOP(I2C_T *i2c)
{
(i2c)->CTL0 |= (I2C_CTL0_SI_Msk | I2C_CTL0_STO_Msk);
while(i2c->CTL0 & I2C_CTL0_STO_Msk) {}
}
void I2C_ClearTimeoutFlag(I2C_T *i2c);
void I2C_Close(I2C_T *i2c);
void I2C_Trigger(I2C_T *i2c, uint8_t u8Start, uint8_t u8Stop, uint8_t u8Si, uint8_t u8Ack);
void I2C_DisableInt(I2C_T *i2c);
void I2C_EnableInt(I2C_T *i2c);
uint32_t I2C_GetBusClockFreq(I2C_T *i2c);
uint32_t I2C_GetIntFlag(I2C_T *i2c);
uint32_t I2C_GetStatus(I2C_T *i2c);
uint32_t I2C_Open(I2C_T *i2c, uint32_t u32BusClock);
uint8_t I2C_GetData(I2C_T *i2c);
void I2C_SetSlaveAddr(I2C_T *i2c, uint8_t u8SlaveNo, uint8_t u8SlaveAddr, uint8_t u8GCMode);
void I2C_SetSlaveAddrMask(I2C_T *i2c, uint8_t u8SlaveNo, uint8_t u8SlaveAddrMask);
uint32_t I2C_SetBusClockFreq(I2C_T *i2c, uint32_t u32BusClock);
void I2C_EnableTimeout(I2C_T *i2c, uint8_t u8LongTimeout);
void I2C_DisableTimeout(I2C_T *i2c);
void I2C_EnableWakeup(I2C_T *i2c);
void I2C_DisableWakeup(I2C_T *i2c);
void I2C_SetData(I2C_T *i2c, uint8_t u8Data);
uint8_t I2C_WriteByte(I2C_T *i2c, uint8_t u8SlaveAddr, uint8_t u8Data);
uint32_t I2C_WriteMultiBytes(I2C_T *i2c, uint8_t u8SlaveAddr, uint8_t au8Data[], uint32_t u32wLen);
uint8_t I2C_WriteByteOneReg(I2C_T *i2c, uint8_t u8SlaveAddr, uint8_t u8DataAddr, uint8_t u8Data);
uint32_t I2C_WriteMultiBytesOneReg(I2C_T *i2c, uint8_t u8SlaveAddr, uint8_t u8DataAddr, uint8_t au8Data[], uint32_t u32wLen);
uint8_t I2C_WriteByteTwoRegs(I2C_T *i2c, uint8_t u8SlaveAddr, uint16_t u16DataAddr, uint8_t u8Data);
uint32_t I2C_WriteMultiBytesTwoRegs(I2C_T *i2c, uint8_t u8SlaveAddr, uint16_t u16DataAddr, uint8_t au8Data[], uint32_t u32wLen);
uint8_t I2C_ReadByte(I2C_T *i2c, uint8_t u8SlaveAddr);
uint32_t I2C_ReadMultiBytes(I2C_T *i2c, uint8_t u8SlaveAddr, uint8_t au8Rdata[], uint32_t u32rLen);
uint8_t I2C_ReadByteOneReg(I2C_T *i2c, uint8_t u8SlaveAddr, uint8_t u8DataAddr);
uint32_t I2C_ReadMultiBytesOneReg(I2C_T *i2c, uint8_t u8SlaveAddr, uint8_t u8DataAddr, uint8_t au8Rdata[], uint32_t u32rLen);
uint8_t I2C_ReadByteTwoRegs(I2C_T *i2c, uint8_t u8SlaveAddr, uint16_t u16DataAddr);
uint32_t I2C_ReadMultiBytesTwoRegs(I2C_T *i2c, uint8_t u8SlaveAddr, uint16_t u16DataAddr, uint8_t au8Rdata[], uint32_t u32rLen);
uint32_t I2C_SMBusGetStatus(I2C_T *i2c);
void I2C_SMBusClearInterruptFlag(I2C_T *i2c, uint8_t u8ClrSMBusIntFlag);
void I2C_SMBusSetPacketByteCount(I2C_T *i2c, uint32_t u32PktSize);
void I2C_SMBusOpen(I2C_T *i2c, uint8_t u8HostDevice);
void I2C_SMBusClose(I2C_T *i2c);
void I2C_SMBusPECTxEnable(I2C_T *i2c, uint8_t u8PECTxEn);
uint8_t I2C_SMBusGetPECValue(I2C_T *i2c);
void I2C_SMBusIdleTimeout(I2C_T *i2c, uint32_t u32Us, uint32_t u32Hclk);
void I2C_SMBusTimeout(I2C_T *i2c, uint32_t ms, uint32_t u32Pclk);
void I2C_SMBusClockLoTimeout(I2C_T *i2c, uint32_t ms, uint32_t u32Pclk);
/**@}*/ /* end of group I2C_EXPORTED_FUNCTIONS */
/**@}*/ /* end of group I2C_Driver */
/**@}*/ /* end of group Standard_Driver */
#ifdef __cplusplus
}
#endif
#endif

View File

@ -0,0 +1,355 @@
/****************************************************************************//**
* @file nu_i2s.h
* @version V3.00
* @brief M2354 series I2S driver header file
*
* @copyright SPDX-License-Identifier: Apache-2.0
* @copyright Copyright (C) 2020 Nuvoton Technology Corp. All rights reserved.
*****************************************************************************/
#ifndef __NU_I2S_H__
#define __NU_I2S_H__
#ifdef __cplusplus
extern "C"
{
#endif
/** @addtogroup Standard_Driver Standard Driver
@{
*/
/** @addtogroup I2S_Driver I2S Driver
@{
*/
/** @addtogroup I2S_EXPORTED_CONSTANTS I2S Exported Constants
@{
*/
#define I2S_DATABIT_8 (0UL << I2S_CTL0_DATWIDTH_Pos) /*!< I2S data width is 8-bit \hideinitializer */
#define I2S_DATABIT_16 (1UL << I2S_CTL0_DATWIDTH_Pos) /*!< I2S data width is 16-bit \hideinitializer */
#define I2S_DATABIT_24 (2UL << I2S_CTL0_DATWIDTH_Pos) /*!< I2S data width is 24-bit \hideinitializer */
#define I2S_DATABIT_32 (3UL << I2S_CTL0_DATWIDTH_Pos) /*!< I2S data width is 32-bit \hideinitializer */
/* Audio Format */
#define I2S_MONO I2S_CTL0_MONO_Msk /*!< Mono channel \hideinitializer */
#define I2S_STEREO (0UL) /*!< Stereo channel \hideinitializer */
#define I2S_ENABLE_MONO I2S_MONO
#define I2S_DISABLE_MONO I2S_STEREO
/* I2S Data Format */
#define I2S_FORMAT_I2S (0UL << I2S_CTL0_FORMAT_Pos) /*!< I2S data format \hideinitializer */
#define I2S_FORMAT_I2S_MSB (1UL << I2S_CTL0_FORMAT_Pos) /*!< I2S MSB data format \hideinitializer */
#define I2S_FORMAT_I2S_LSB (2UL << I2S_CTL0_FORMAT_Pos) /*!< I2S LSB data format \hideinitializer */
#define I2S_FORMAT_PCM (4UL << I2S_CTL0_FORMAT_Pos) /*!< PCM data format \hideinitializer */
#define I2S_FORMAT_PCM_MSB (5UL << I2S_CTL0_FORMAT_Pos) /*!< PCM MSB data format \hideinitializer */
#define I2S_FORMAT_PCM_LSB (6UL << I2S_CTL0_FORMAT_Pos) /*!< PCM LSB data format \hideinitializer */
/* I2S Data Format */
#define I2S_ORDER_AT_MSB 0UL /*!< Channel data is at MSB \hideinitializer */
#define I2S_ORDER_AT_LSB I2S_CTL0_ORDER_Msk /*!< Channel data is at LSB \hideinitializer */
/* I2S TDM Channel Number */
#define I2S_TDM_2CH 0UL /*!< Use TDM 2 channel \hideinitializer */
#define I2S_TDM_4CH 1UL /*!< Use TDM 4 channel \hideinitializer */
#define I2S_TDM_6CH 2UL /*!< Use TDM 6 channel \hideinitializer */
#define I2S_TDM_8CH 3UL /*!< Use TDM 8 channel \hideinitializer */
/* I2S TDM Channel Width */
#define I2S_TDM_WIDTH_8BIT 0UL /*!< TDM channel witch is 8-bit \hideinitializer */
#define I2S_TDM_WIDTH_16BIT 1UL /*!< TDM channel witch is 16-bit \hideinitializer */
#define I2S_TDM_WIDTH_24BIT 2UL /*!< TDM channel witch is 24-bit \hideinitializer */
#define I2S_TDM_WIDTH_32BIT 3UL /*!< TDM channel witch is 32-bit \hideinitializer */
/* I2S TDM Sync Width */
#define I2S_TDM_SYNC_ONE_BCLK 0UL /*!< TDM sync widht is one BLCK period \hideinitializer */
#define I2S_TDM_SYNC_ONE_CHANNEL 1UL /*!< TDM sync widht is one channel period \hideinitializer */
/* I2S Operation mode */
#define I2S_MODE_SLAVE I2S_CTL0_SLAVE_Msk /*!< As slave mode \hideinitializer */
#define I2S_MODE_MASTER 0UL /*!< As master mode \hideinitializer */
/* I2S FIFO Threshold */
#define I2S_FIFO_TX_LEVEL_WORD_0 0UL /*!< TX threshold is 0 word \hideinitializer */
#define I2S_FIFO_TX_LEVEL_WORD_1 (1UL << I2S_CTL1_TXTH_Pos) /*!< TX threshold is 1 word \hideinitializer */
#define I2S_FIFO_TX_LEVEL_WORD_2 (2UL << I2S_CTL1_TXTH_Pos) /*!< TX threshold is 2 words \hideinitializer */
#define I2S_FIFO_TX_LEVEL_WORD_3 (3UL << I2S_CTL1_TXTH_Pos) /*!< TX threshold is 3 words \hideinitializer */
#define I2S_FIFO_TX_LEVEL_WORD_4 (4UL << I2S_CTL1_TXTH_Pos) /*!< TX threshold is 4 words \hideinitializer */
#define I2S_FIFO_TX_LEVEL_WORD_5 (5UL << I2S_CTL1_TXTH_Pos) /*!< TX threshold is 5 words \hideinitializer */
#define I2S_FIFO_TX_LEVEL_WORD_6 (6UL << I2S_CTL1_TXTH_Pos) /*!< TX threshold is 6 words \hideinitializer */
#define I2S_FIFO_TX_LEVEL_WORD_7 (7UL << I2S_CTL1_TXTH_Pos) /*!< TX threshold is 7 words \hideinitializer */
#define I2S_FIFO_TX_LEVEL_WORD_8 (8UL << I2S_CTL1_TXTH_Pos) /*!< TX threshold is 8 words \hideinitializer */
#define I2S_FIFO_TX_LEVEL_WORD_9 (9UL << I2S_CTL1_TXTH_Pos) /*!< TX threshold is 9 words \hideinitializer */
#define I2S_FIFO_TX_LEVEL_WORD_10 (10UL << I2S_CTL1_TXTH_Pos) /*!< TX threshold is 10 words \hideinitializer */
#define I2S_FIFO_TX_LEVEL_WORD_11 (11UL << I2S_CTL1_TXTH_Pos) /*!< TX threshold is 11 words \hideinitializer */
#define I2S_FIFO_TX_LEVEL_WORD_12 (12UL << I2S_CTL1_TXTH_Pos) /*!< TX threshold is 12 words \hideinitializer */
#define I2S_FIFO_TX_LEVEL_WORD_13 (13UL << I2S_CTL1_TXTH_Pos) /*!< TX threshold is 13 words \hideinitializer */
#define I2S_FIFO_TX_LEVEL_WORD_14 (14UL << I2S_CTL1_TXTH_Pos) /*!< TX threshold is 14 words \hideinitializer */
#define I2S_FIFO_TX_LEVEL_WORD_15 (15UL << I2S_CTL1_TXTH_Pos) /*!< TX threshold is 15 words \hideinitializer */
#define I2S_FIFO_RX_LEVEL_WORD_1 0UL /*!< RX threshold is 1 word \hideinitializer */
#define I2S_FIFO_RX_LEVEL_WORD_2 (1UL << I2S_CTL1_RXTH_Pos) /*!< RX threshold is 2 words \hideinitializer */
#define I2S_FIFO_RX_LEVEL_WORD_3 (2UL << I2S_CTL1_RXTH_Pos) /*!< RX threshold is 3 words \hideinitializer */
#define I2S_FIFO_RX_LEVEL_WORD_4 (3UL << I2S_CTL1_RXTH_Pos) /*!< RX threshold is 4 words \hideinitializer */
#define I2S_FIFO_RX_LEVEL_WORD_5 (4UL << I2S_CTL1_RXTH_Pos) /*!< RX threshold is 5 words \hideinitializer */
#define I2S_FIFO_RX_LEVEL_WORD_6 (5UL << I2S_CTL1_RXTH_Pos) /*!< RX threshold is 6 words \hideinitializer */
#define I2S_FIFO_RX_LEVEL_WORD_7 (6UL << I2S_CTL1_RXTH_Pos) /*!< RX threshold is 7 words \hideinitializer */
#define I2S_FIFO_RX_LEVEL_WORD_8 (7UL << I2S_CTL1_RXTH_Pos) /*!< RX threshold is 8 words \hideinitializer */
#define I2S_FIFO_RX_LEVEL_WORD_9 (8UL << I2S_CTL1_RXTH_Pos) /*!< RX threshold is 9 words \hideinitializer */
#define I2S_FIFO_RX_LEVEL_WORD_10 (9UL << I2S_CTL1_RXTH_Pos) /*!< RX threshold is 10 words \hideinitializer */
#define I2S_FIFO_RX_LEVEL_WORD_11 (10UL << I2S_CTL1_RXTH_Pos) /*!< RX threshold is 11 words \hideinitializer */
#define I2S_FIFO_RX_LEVEL_WORD_12 (11UL << I2S_CTL1_RXTH_Pos) /*!< RX threshold is 12 words \hideinitializer */
#define I2S_FIFO_RX_LEVEL_WORD_13 (12UL << I2S_CTL1_RXTH_Pos) /*!< RX threshold is 13 words \hideinitializer */
#define I2S_FIFO_RX_LEVEL_WORD_14 (13UL << I2S_CTL1_RXTH_Pos) /*!< RX threshold is 14 words \hideinitializer */
#define I2S_FIFO_RX_LEVEL_WORD_15 (14UL << I2S_CTL1_RXTH_Pos) /*!< RX threshold is 15 words \hideinitializer */
#define I2S_FIFO_RX_LEVEL_WORD_16 (15UL << I2S_CTL1_RXTH_Pos) /*!< RX threshold is 16 words \hideinitializer */
/* I2S Record Channel */
#define I2S_MONO_RIGHT 0UL /*!< Record mono right channel \hideinitializer */
#define I2S_MONO_LEFT I2S_CTL0_RXLCH_Msk /*!< Record mono left channel \hideinitializer */
/* I2S Channel */
#define I2S_RIGHT 0UL /*!< Select right channel \hideinitializer */
#define I2S_LEFT 1UL /*!< Select left channel \hideinitializer */
/**@}*/ /* end of group I2S_EXPORTED_CONSTANTS */
/** @addtogroup I2S_EXPORTED_FUNCTIONS I2S Exported Functions
@{
*/
/**
* @brief Enable zero cross detect function.
* @param[in] i2s is the base address of I2S module.
* @param[in] u32ChMask is the mask for channel number (valid value is from (1~8).
* @return none
* \hideinitializer
*/
__STATIC_INLINE void I2S_ENABLE_TX_ZCD(I2S_T *i2s, uint32_t u32ChMask)
{
if((u32ChMask > 0UL) && (u32ChMask < 9UL))
{
i2s->CTL1 |= (1UL << (u32ChMask - 1UL));
}
}
/**
* @brief Disable zero cross detect function.
* @param[in] i2s is the base address of I2S module.
* @param[in] u32ChMask is the mask for channel number (valid value is from (1~8).
* @return none
* \hideinitializer
*/
__STATIC_INLINE void I2S_DISABLE_TX_ZCD(I2S_T *i2s, uint32_t u32ChMask)
{
if((u32ChMask > 0UL) && (u32ChMask < 9UL))
{
i2s->CTL1 &= ~(1UL << (u32ChMask - 1UL));
}
}
/**
* @brief Enable I2S Tx DMA function. I2S requests DMA to transfer data to Tx FIFO.
* @param[in] i2s is the base address of I2S module.
* @return none
* \hideinitializer
*/
#define I2S_ENABLE_TXDMA(i2s) ( (i2s)->CTL0 |= I2S_CTL0_TXPDMAEN_Msk )
/**
* @brief Disable I2S Tx DMA function. I2S requests DMA to transfer data to Tx FIFO.
* @param[in] i2s is the base address of I2S module.
* @return none
* \hideinitializer
*/
#define I2S_DISABLE_TXDMA(i2s) ( (i2s)->CTL0 &= ~I2S_CTL0_TXPDMAEN_Msk )
/**
* @brief Enable I2S Rx DMA function. I2S requests DMA to transfer data from Rx FIFO.
* @param[in] i2s is the base address of I2S module.
* @return none
* \hideinitializer
*/
#define I2S_ENABLE_RXDMA(i2s) ( (i2s)->CTL0 |= I2S_CTL0_RXPDMAEN_Msk )
/**
* @brief Disable I2S Rx DMA function. I2S requests DMA to transfer data from Rx FIFO.
* @param[in] i2s is the base address of I2S module.
* @return none
* \hideinitializer
*/
#define I2S_DISABLE_RXDMA(i2s) ( (i2s)->CTL0 &= ~I2S_CTL0_RXPDMAEN_Msk )
/**
* @brief Enable I2S Tx function .
* @param[in] i2s is the base address of I2S module.
* @return none
* \hideinitializer
*/
#define I2S_ENABLE_TX(i2s) ( (i2s)->CTL0 |= I2S_CTL0_TXEN_Msk )
/**
* @brief Disable I2S Tx function .
* @param[in] i2s is the base address of I2S module.
* @return none
* \hideinitializer
*/
#define I2S_DISABLE_TX(i2s) ( (i2s)->CTL0 &= ~I2S_CTL0_TXEN_Msk )
/**
* @brief Enable I2S Rx function .
* @param[in] i2s is the base address of I2S module.
* @return none
* \hideinitializer
*/
#define I2S_ENABLE_RX(i2s) ( (i2s)->CTL0 |= I2S_CTL0_RXEN_Msk )
/**
* @brief Disable I2S Rx function .
* @param[in] i2s is the base address of I2S module.
* @return none
* \hideinitializer
*/
#define I2S_DISABLE_RX(i2s) ( (i2s)->CTL0 &= ~I2S_CTL0_RXEN_Msk )
/**
* @brief Enable Tx Mute function .
* @param[in] i2s is the base address of I2S module.
* @return none
* \hideinitializer
*/
#define I2S_ENABLE_TX_MUTE(i2s) ( (i2s)->CTL0 |= I2S_CTL0_MUTE_Msk )
/**
* @brief Disable Tx Mute function .
* @param[in] i2s is the base address of I2S module.
* @return none
* \hideinitializer
*/
#define I2S_DISABLE_TX_MUTE(i2s) ( (i2s)->CTL0 &= ~I2S_CTL0_MUTE_Msk )
/**
* @brief Clear Tx FIFO. Internal pointer is reset to FIFO start point.
* @param[in] i2s is the base address of I2S module.
* @return none
* \hideinitializer
*/
#define I2S_CLR_TX_FIFO(i2s) ( (i2s)->CTL0 |= I2S_CTL0_TXFBCLR_Msk )
/**
* @brief Clear Rx FIFO. Internal pointer is reset to FIFO start point.
* @param[in] i2s is the base address of I2S module.
* @return none
* \hideinitializer
*/
#define I2S_CLR_RX_FIFO(i2s) ( (i2s)->CTL0 |= I2S_CTL0_RXFBCLR_Msk )
/**
* @brief This function sets the recording source channel when mono mode is used.
* @param[in] i2s is the base address of I2S module.
* @param[in] u32Ch left or right channel. Valid values are:
* - \ref I2S_MONO_LEFT
* - \ref I2S_MONO_RIGHT
* @return none
* \hideinitializer
*/
__STATIC_INLINE void I2S_SET_MONO_RX_CHANNEL(I2S_T *i2s, uint32_t u32Ch)
{
u32Ch == I2S_MONO_LEFT ?
(i2s->CTL0 |= I2S_CTL0_RXLCH_Msk) :
(i2s->CTL0 &= ~I2S_CTL0_RXLCH_Msk);
}
/**
* @brief Write data to I2S Tx FIFO.
* @param[in] i2s is the base address of I2S module.
* @param[in] u32Data: The data written to FIFO.
* @return none
* \hideinitializer
*/
#define I2S_WRITE_TX_FIFO(i2s, u32Data) ( (i2s)->TXFIFO = (u32Data) )
/**
* @brief Read Rx FIFO.
* @param[in] i2s is the base address of I2S module.
* @return Data in Rx FIFO.
* \hideinitializer
*/
#define I2S_READ_RX_FIFO(i2s) ( (i2s)->RXFIFO )
/**
* @brief This function gets the interrupt flag according to the mask parameter.
* @param[in] i2s is the base address of I2S module.
* @param[in] u32Mask is the mask for the all interrupt flags.
* @return The masked bit value of interrupt flag.
* \hideinitializer
*/
#define I2S_GET_INT_FLAG(i2s, u32Mask) ( (i2s)->STATUS0 & (u32Mask) )
/**
* @brief This function clears the interrupt flag according to the mask parameter.
* @param[in] i2s is the base address of I2S module.
* @param[in] u32Mask is the mask for the all interrupt flags.
* @return none
* \hideinitializer
*/
#define I2S_CLR_INT_FLAG(i2s, u32Mask) ( (i2s)->STATUS0 |= (u32Mask) )
/**
* @brief This function gets the zero crossing interrupt flag according to the mask parameter.
* @param[in] i2s is the base address of I2S module.
* @param[in] u32Mask is the mask for the all interrupt flags.
* @return The masked bit value of interrupt flag.
* \hideinitializer
*/
#define I2S_GET_ZC_INT_FLAG(i2s, u32Mask) ( (i2s)->STATUS1 & (u32Mask) )
/**
* @brief This function clears the zero crossing interrupt flag according to the mask parameter.
* @param[in] i2s is the base address of I2S module.
* @param[in] u32Mask is the mask for the all interrupt flags.
* @return none
* \hideinitializer
*/
#define I2S_CLR_ZC_INT_FLAG(i2s, u32Mask) ( (i2s)->STATUS1 |= (u32Mask) )
/**
* @brief Get transmit FIFO level
* @param[in] i2s is the base address of I2S module.
* @return FIFO level
* \hideinitializer
*/
#define I2S_GET_TX_FIFO_LEVEL(i2s) ( (((i2s)->STATUS1 & I2S_STATUS1_TXCNT_Msk) >> I2S_STATUS1_TXCNT_Pos) & 0xF )
/**
* @brief Get receive FIFO level
* @param[in] i2s is the base address of I2S module.
* @return FIFO level
* \hideinitializer
*/
#define I2S_GET_RX_FIFO_LEVEL(i2s) ( (((i2s)->STATUS1 & I2S_STATUS1_RXCNT_Msk) >> I2S_STATUS1_RXCNT_Pos) & 0xF )
uint32_t I2S_Open(I2S_T *i2s, uint32_t u32MasterSlave, uint32_t u32SampleRate, uint32_t u32WordWidth, uint32_t u32MonoData, uint32_t u32DataFormat);
void I2S_Close(I2S_T *i2s);
void I2S_EnableInt(I2S_T *i2s, uint32_t u32Mask);
void I2S_DisableInt(I2S_T *i2s, uint32_t u32Mask);
uint32_t I2S_EnableMCLK(I2S_T *i2s, uint32_t u32BusClock);
void I2S_DisableMCLK(I2S_T *i2s);
void I2S_SetFIFO(I2S_T *i2s, uint32_t u32TxThreshold, uint32_t u32RxThreshold);
void I2S_ConfigureTDM(I2S_T *i2s, uint32_t u32ChannelWidth, uint32_t u32ChannelNum, uint32_t u32SyncWidth);
/**@}*/ /* end of group I2S_EXPORTED_FUNCTIONS */
/**@}*/ /* end of group I2S_Driver */
/**@}*/ /* end of group Standard_Driver */
#ifdef __cplusplus
}
#endif
#endif /* __NU_I2S_H__ */

View File

@ -0,0 +1,132 @@
/**************************************************************************//**
* @file nu_keystore.h
* @version V3.00
* @brief Key Store Driver Header
*
* @copyright SPDX-License-Identifier: Apache-2.0
* @copyright Copyright (C) 2020 Nuvoton Technology Corp. All rights reserved.
*****************************************************************************/
#ifndef __NU_KEYSTORE_H__
#define __NU_KEYSTORE_H__
#ifdef __cplusplus
extern "C"
{
#endif
/** @addtogroup Standard_Driver Standard Driver
@{
*/
/** @addtogroup KS_Driver Key Store Driver
@{
*/
/** @addtogroup KS_EXPORTED_CONSTANTS Key Store Exported Constants
@{
*/
#define KS_TOMETAKEY(x) (((uint32_t)(x) << KS_METADATA_NUMBER_Pos) & KS_METADATA_NUMBER_Msk)
#define KS_TOKEYIDX(x) (((uint32_t)(x) & KS_METADATA_NUMBER_Msk) >> KS_METADATA_NUMBER_Pos)
typedef enum KSMEM
{
KS_SRAM = 0, /*!< Volatile Memory */
KS_FLASH = 1, /*!< Non-volatile Memory */
KS_OTP = 2 /*!< One-Time Programming Memory */
} KS_MEM_Type;
#define KS_OP_READ (0 << KS_CTL_OPMODE_Pos)
#define KS_OP_WRITE (1 << KS_CTL_OPMODE_Pos)
#define KS_OP_ERASE (2 << KS_CTL_OPMODE_Pos)
#define KS_OP_ERASE_ALL (3 << KS_CTL_OPMODE_Pos)
#define KS_OP_REVOKE (4 << KS_CTL_OPMODE_Pos)
#define KS_OP_REMAN (5 << KS_CTL_OPMODE_Pos)
#define KS_OWNER_AES (0ul)
#define KS_OWNER_HMAC (1ul)
#define KS_OWNER_RSA_EXP (2ul)
#define KS_OWNER_RSA_MID (3ul)
#define KS_OWNER_ECC (4ul)
#define KS_OWNER_CPU (5ul)
#define KS_META_AES (0ul << KS_METADATA_OWNER_Pos) /*!< AES Access Only */
#define KS_META_HMAC (1ul << KS_METADATA_OWNER_Pos) /*!< HMAC Access Only */
#define KS_META_RSA_EXP (2ul << KS_METADATA_OWNER_Pos) /*!< RSA_EXP Access Only */
#define KS_META_RSA_MID (3ul << KS_METADATA_OWNER_Pos) /*!< RSA_MID Access Only */
#define KS_META_ECC (4ul << KS_METADATA_OWNER_Pos) /*!< ECC Access Only */
#define KS_META_CPU (5ul << KS_METADATA_OWNER_Pos) /*!< CPU Access Only */
#define KS_META_128 ( 0ul << KS_METADATA_SIZE_Pos) /*!< Key size 128 bits */
#define KS_META_163 ( 1ul << KS_METADATA_SIZE_Pos) /*!< Key size 163 bits */
#define KS_META_192 ( 2ul << KS_METADATA_SIZE_Pos) /*!< Key size 192 bits */
#define KS_META_224 ( 3ul << KS_METADATA_SIZE_Pos) /*!< Key size 224 bits */
#define KS_META_233 ( 4ul << KS_METADATA_SIZE_Pos) /*!< Key size 233 bits */
#define KS_META_255 ( 5ul << KS_METADATA_SIZE_Pos) /*!< Key size 255 bits */
#define KS_META_256 ( 6ul << KS_METADATA_SIZE_Pos) /*!< Key size 256 bits */
#define KS_META_283 ( 7ul << KS_METADATA_SIZE_Pos) /*!< Key size 283 bits */
#define KS_META_384 ( 8ul << KS_METADATA_SIZE_Pos) /*!< Key size 384 bits */
#define KS_META_409 ( 9ul << KS_METADATA_SIZE_Pos) /*!< Key size 409 bits */
#define KS_META_512 (10ul << KS_METADATA_SIZE_Pos) /*!< Key size 512 bits */
#define KS_META_521 (11ul << KS_METADATA_SIZE_Pos) /*!< Key size 521 bits */
#define KS_META_571 (12ul << KS_METADATA_SIZE_Pos) /*!< Key size 571 bits */
#define KS_META_1024 (16ul << KS_METADATA_SIZE_Pos) /*!< Key size 1024 bits */
#define KS_META_1536 (17ul << KS_METADATA_SIZE_Pos) /*!< Key size 1024 bits */
#define KS_META_2048 (18ul << KS_METADATA_SIZE_Pos) /*!< Key size 2048 bits */
#define KS_META_3072 (19ul << KS_METADATA_SIZE_Pos) /*!< Key size 1024 bits */
#define KS_META_4096 (20ul << KS_METADATA_SIZE_Pos) /*!< Key size 4096 bits */
#define KS_META_BOOT ( 1ul << KS_METADATA_BS_Pos) /*!< Key only used for boot ROM only */
#define KS_META_READABLE (1ul << KS_METADATA_READABLE_Pos) /*!< Allow the key to be read by software */
#define KS_META_PRIV (1ul << KS_METADATA_PRIV_Pos) /*!< Privilege key */
#define KS_META_NONPRIV (0ul << KS_METADATA_PRIV_Pos) /*!< Non-privilege key */
#define KS_META_SECURE (1ul << KS_METADATA_SEC_Pos) /*!< Secure key */
#define KS_META_NONSECURE (0ul << KS_METADATA_SEC_Pos) /*!< Non-secure key */
/**
* @brief Enable scramble function
* @details This function is used to enable scramle function of Key Store.
*/
#define KS_SCRAMBLING() KS->CTL |= KS_CTL_SCMB_Msk
/**@}*/ /* end of group KS_EXPORTED_CONSTANTS */
/** @addtogroup KS_EXPORTED_FUNCTIONS Key Store Exported Functions
@{
*/
void KS_Open(void);
int32_t KS_Read(KS_MEM_Type type, int32_t i32KeyIdx, uint32_t au32Key[], uint32_t u32WordCnt);
int32_t KS_Write(KS_MEM_Type eType, uint32_t u32Meta, uint32_t au32Key[]);
int32_t KS_WriteOTP(int32_t i32KeyIdx, uint32_t u32Meta, uint32_t au32Key[]);
int32_t KS_EraseKey(int32_t i32KeyIdx);
int32_t KS_EraseAll(KS_MEM_Type eType);
int32_t KS_RevokeKey(KS_MEM_Type eType, int32_t i32KeyIdx);
uint32_t KS_GetRemainSize(KS_MEM_Type eType);
int32_t KS_ToggleSRAM(void);
uint32_t KS_GetKeyWordCnt(uint32_t u32Meta);
uint32_t KS_GetRemainKeyCount(KS_MEM_Type mem);
/**@}*/ /* end of group KS_EXPORTED_FUNCTIONS */
/**@}*/ /* end of group KS_Driver */
/**@}*/ /* end of group Standard_Driver */
#ifdef __cplusplus
}
#endif
#endif /* __NU_KEYSTORE_H__ */

View File

@ -0,0 +1,531 @@
/**************************************************************************//**
* @file nu_lcd.h
* @version V3.00
* @brief Liquid-Crystal Display(LCD) driver header file
*
* @copyright SPDX-License-Identifier: Apache-2.0
* @copyright Copyright (C) 2020 Nuvoton Technology Corp. All rights reserved.
*****************************************************************************/
#ifndef __NU_LCD_H__
#define __NU_LCD_H__
#ifdef __cplusplus
extern "C"
{
#endif
/** @addtogroup Standard_Driver Standard Driver
@{
*/
/** @addtogroup LCD_Driver LCD Driver
@{
*/
/** @addtogroup LCD_EXPORTED_CONSTANTS LCD Exported Constants
@{
*/
/*---------------------------------------------------------------------------------------------------------*/
/* LCD Bias Voltage Level Selection Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define LCD_BIAS_LV_1_2 (1ul << LCD_PCTL_BIAS_Pos) /*!< LCD bias voltage level selection - 1/2 Bias \hideinitializer */
#define LCD_BIAS_LV_1_3 (2ul << LCD_PCTL_BIAS_Pos) /*!< LCD bias voltage level selection - 1/3 Bias \hideinitializer */
#define LCD_BIAS_LV_1_4 (3ul << LCD_PCTL_BIAS_Pos) /*!< LCD bias voltage level selection - 1/4 Bias \hideinitializer */
/*---------------------------------------------------------------------------------------------------------*/
/* LCD COM Duty Ratio Selection Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define LCD_COM_DUTY_1_1 (0ul << LCD_PCTL_DUTY_Pos) /*!< LCD com duty ratio selection - 1/1 Duty \hideinitializer */
#define LCD_COM_DUTY_1_2 (1ul << LCD_PCTL_DUTY_Pos) /*!< LCD com duty ratio selection - 1/2 Duty \hideinitializer */
#define LCD_COM_DUTY_1_3 (2ul << LCD_PCTL_DUTY_Pos) /*!< LCD com duty ratio selection - 1/3 Duty \hideinitializer */
#define LCD_COM_DUTY_1_4 (3ul << LCD_PCTL_DUTY_Pos) /*!< LCD com duty ratio selection - 1/4 Duty \hideinitializer */
#define LCD_COM_DUTY_1_5 (4ul << LCD_PCTL_DUTY_Pos) /*!< LCD com duty ratio selection - 1/5 Duty \hideinitializer */
#define LCD_COM_DUTY_1_6 (5ul << LCD_PCTL_DUTY_Pos) /*!< LCD com duty ratio selection - 1/6 Duty \hideinitializer */
#define LCD_COM_DUTY_1_7 (6ul << LCD_PCTL_DUTY_Pos) /*!< LCD com duty ratio selection - 1/7 Duty \hideinitializer */
#define LCD_COM_DUTY_1_8 (7ul << LCD_PCTL_DUTY_Pos) /*!< LCD com duty ratio selection - 1/8 Duty \hideinitializer */
/*---------------------------------------------------------------------------------------------------------*/
/* LCD Waveform Attribute Selection Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define LCD_WAVEFORM_TYPE_A_NORMAL (0ul << LCD_PCTL_TYPE_Pos) /*!< LCD waveform Type-A, no inverse \hideinitializer */
#define LCD_WAVEFORM_TYPE_B_NORMAL (1ul << LCD_PCTL_TYPE_Pos) /*!< LCD waveform Type-B, no inverse \hideinitializer */
#define LCD_WAVEFORM_TYPE_A_INVERSE (2ul << LCD_PCTL_TYPE_Pos) /*!< LCD waveform Type-A and inverse \hideinitializer */
#define LCD_WAVEFORM_TYPE_B_INVERSE (3ul << LCD_PCTL_TYPE_Pos) /*!< LCD waveform Type-B and inverse \hideinitializer */
/*---------------------------------------------------------------------------------------------------------*/
/* LCD Charge Pump Voltage Selection Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define LCD_CP_VOLTAGE_LV_0 (0ul << LCD_PCTL_CPVSEL_Pos) /*!< Select LCD charge pump voltage 2.6 V \hideinitializer */
#define LCD_CP_VOLTAGE_LV_1 (1ul << LCD_PCTL_CPVSEL_Pos) /*!< Select LCD charge pump voltage 2.8 V \hideinitializer */
#define LCD_CP_VOLTAGE_LV_2 (2ul << LCD_PCTL_CPVSEL_Pos) /*!< Select LCD charge pump voltage 3.0 V \hideinitializer */
#define LCD_CP_VOLTAGE_LV_3 (3ul << LCD_PCTL_CPVSEL_Pos) /*!< Select LCD charge pump voltage 3.2 V \hideinitializer */
#define LCD_CP_VOLTAGE_LV_4 (4ul << LCD_PCTL_CPVSEL_Pos) /*!< Select LCD charge pump voltage 3.4 V \hideinitializer */
#define LCD_CP_VOLTAGE_LV_5 (5ul << LCD_PCTL_CPVSEL_Pos) /*!< Select LCD charge pump voltage 3.6 V \hideinitializer */
/*---------------------------------------------------------------------------------------------------------*/
/* LCD Interrupt Source Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define LCD_DISABLE_ALL_INT (0ul << LCD_INTEN_FCEIEN_Pos) /*!< Disable all LCD interrupt sources \hideinitializer */
#define LCD_FRAME_COUNTING_END_INT (1ul << LCD_INTEN_FCEIEN_Pos) /*!< Indicate frame count end interrupt \hideinitializer */
#define LCD_FRAME_END_INT (1ul << LCD_INTEN_FEIEN_Pos) /*!< Indicate frame end interrupt \hideinitializer */
#define LCD_CPTOUT_INT (1ul << LCD_INTEN_CTOIEN_Pos) /*!< Indicate charge pump charging timeout interrupt \hideinitializer */
#define LCD_ENABLE_ALL_INT (7ul << LCD_INTEN_FCEIEN_Pos) /*!< Enable all LCD interrupt sources \hideinitializer */
/*---------------------------------------------------------------------------------------------------------*/
/* LCD Operation Voltage Source Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define LCD_VOLTAGE_SOURCE_VLCD (0ul << LCD_DCTL_VSRC_Pos) /*!< LCD voltage source from external VLCD power \hideinitializer */
#define LCD_VOLTAGE_SOURCE_AVDD (1ul << LCD_DCTL_VSRC_Pos) /*!< LCD voltage source from internal VDD \hideinitializer */
#define LCD_VOLTAGE_SOURCE_CP (2ul << LCD_DCTL_VSRC_Pos) /*!< LCD voltage source from built-in charge pump \hideinitializer */
/*---------------------------------------------------------------------------------------------------------*/
/* LCD Driving Mode Selection Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define LCD_LOW_DRIVING_AND_BUF_OFF (0ul << LCD_DCTL_RESMODE_Pos) /*!< LCD operates with low-drive and voltage buffer disabled \hideinitializer */
#define LCD_HIGH_DRIVING_AND_BUF_OFF (1ul << LCD_DCTL_RESMODE_Pos) /*!< LCD operates with high-drive and voltage buffer disabled \hideinitializer */
#define LCD_LOW_DRIVING_AND_BUF_ON (2ul << LCD_DCTL_RESMODE_Pos) /*!< LCD operates with low-drive and voltage buffer enabled \hideinitializer */
#define LCD_HIGH_DRIVING_AND_BUF_OFF_AND_PWR_SAVING (5ul << LCD_DCTL_RESMODE_Pos) /*!< LCD operates with high-drive, voltage buffer disabled and power saving \hideinitializer */
#define LCD_LOW_DRIVING_AND_BUF_ON_AND_PWR_SAVING (6ul << LCD_DCTL_RESMODE_Pos) /*!< LCD operates with low-drive, voltage buffer enabled and power saving \hideinitializer */
/*---------------------------------------------------------------------------------------------------------*/
/* LCD Power Saving Mode Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define LCD_PWR_SAVING_NORMAL_MODE (0ul << LCD_DCTL_PSVREV_Pos) /*!< The timing of LCD power saving is normal \hideinitializer */
#define LCD_PWR_SAVING_REVERSE_MODE (1ul << LCD_DCTL_PSVREV_Pos) /*!< The timing of LCD power saving is reverse \hideinitializer */
/**@}*/ /* end of group LCD_EXPORTED_CONSTANTS */
/** @addtogroup LCD_EXPORTED_STRUCTS LCD Exported Structs
@{
*/
/**
* @details LCD Configuration Data Struct
*/
typedef struct
{
uint32_t u32SrcFreq; /*!< LCD clock source frequency */
uint32_t u32ComDuty; /*!< COM duty */
uint32_t u32BiasLevel; /*!< Bias level */
uint32_t u32Framerate; /*!< Operation frame rate */
uint32_t u32WaveformType; /*!< Waveform type */
uint32_t u32IntSrc; /*!< Interrupt source */
uint32_t u32DrivingMode; /*!< Driving mode */
uint32_t u32VSrc; /*!< Voltage source */
} S_LCD_CFG_T;
/**@}*/ /* end of group LCD_EXPORTED_STRUCTS */
/** @addtogroup LCD_EXPORTED_FUNCTIONS LCD Exported Functions
@{
*/
/**
* @brief Enable LCD Display
*
* @param None
*
* @return None
*
* @details This macro is used to enable LCD display.
*/
#define LCD_ENABLE_DISPLAY() do{ LCD->CTL |= LCD_CTL_EN_Msk; while(LCD->CTL & LCD_CTL_SYNC_Msk) {} }while(0)
/**
* @brief Disable LCD Display
*
* @param None
*
* @return None
*
* @details This macro is used to disable LCD display.
*/
#define LCD_DISABLE_DISPLAY() do{ LCD->CTL &= ~LCD_CTL_EN_Msk; while(LCD->CTL & LCD_CTL_SYNC_Msk) {} }while(0)
/**
* @brief Set LCD Waveform Type
*
* @param[in] type The LCD waveform type. It could be one of the following type
* - \ref LCD_WAVEFORM_TYPE_A_NORMAL
* - \ref LCD_WAVEFORM_TYPE_B_NORMAL
* - \ref LCD_WAVEFORM_TYPE_A_INVERSE
* - \ref LCD_WAVEFORM_TYPE_B_INVERSE
*
* @return None
*
* @details This macro is used to set the attribute of LCD output waveform.
*/
#define LCD_WAVEFORM_TYPE(type) (LCD->PCTL = (LCD->PCTL & ~LCD_PCTL_TYPE_Msk) | (type))
/**
* @brief Set LCD Source Clock Divider
*
* @param[in] div The frequency divider, valid value is between 1 to 1024.
*
* @return None
*
* @details This macro is used to set the LCD operarion frequency is (LCD source frequency / div).
*/
#define LCD_SET_FREQDIV(div) (LCD->PCTL = (LCD->PCTL & ~LCD_PCTL_FREQDIV_Msk) | (((div)-1) << LCD_PCTL_FREQDIV_Pos))
/**
* @brief Set Charge Pump Voltage
*
* @param[in] voltage The target charge pump voltage. It could be one of the following voltage level
* - \ref LCD_CP_VOLTAGE_LV_0, 2.6 V
* - \ref LCD_CP_VOLTAGE_LV_1, 2.8 V
* - \ref LCD_CP_VOLTAGE_LV_2, 3.0 V
* - \ref LCD_CP_VOLTAGE_LV_3, 3.2 V
* - \ref LCD_CP_VOLTAGE_LV_4, 3.4 V
* - \ref LCD_CP_VOLTAGE_LV_5, 3.6 V
*
* @return None
*
* @details This macro is used to set charge pump voltage for VLCD.
*/
#define LCD_SET_CP_VOLTAGE(voltage) (LCD->PCTL = (LCD->PCTL & ~LCD_PCTL_CPVSEL_Msk) | (voltage))
/**
* @brief Decrease Charge Pump Voltage
*
* @param[in] unit The tuning units, valid value is between 0 to 7.
* One unit of voltage is about 0.03V, and the charge pump voltage is decreased (unit * 0.03)V.
*
* @return None
*
* @details This macro is used to decrease charge pump voltage by specific units.
*/
#define LCD_CP_VOLTAGE_DECREASE(unit) (LCD->PCTL = (LCD->PCTL & ~LCD_PCTL_CPVTUNE_Msk) | ((unit) << LCD_PCTL_CPVTUNE_Pos))
/**
* @brief Increase Charge Pump Voltage
*
* @param[in] unit The tuning units, valid value is between 1 to 8.
* One unit of voltage is about 0.03V, and the charge pump voltage is increased (unit * 0.03)V.
*
* @return None
*
* @details This macro is used to increase charge pump voltage by specific units.
*/
#define LCD_CP_VOLTAGE_INCREASE(unit) (LCD->PCTL = (LCD->PCTL & ~LCD_PCTL_CPVTUNE_Msk) | ((16-(unit)) << LCD_PCTL_CPVTUNE_Pos))
/**
* @brief Set LCD Blinking ON
*
* @param None
*
* @return None
*
* @details This macro is used to enable LCD blinking.
*/
#define LCD_BLINKING_ON() (LCD->FCTL |= LCD_FCTL_BLINK_Msk)
/**
* @brief Set LCD Blinking OFF
*
* @param None
*
* @return None
*
* @details This macro is used to disable LCD blinking.
*/
#define LCD_BLINKING_OFF() (LCD->FCTL &= ~LCD_FCTL_BLINK_Msk)
/**
* @brief Set LCD Frame Counting Value
*
* @param[in] value Frame counting value. Valid value is between 1 to 1024.
*
* @return None
*
* @details This macro is used to set the LCD frame counting value to configure the blink interval.
* @note For type-B waveform, the frame counter increases at the end of odd frames, not even frames.
*/
#define LCD_SET_FRAME_COUNTING_VALUE(value) (LCD->FCTL = (LCD->FCTL & ~LCD_FCTL_FCV_Msk) | (((value)-1) << LCD_FCTL_FCV_Pos))
/**
* @brief Set Null Frame Time
*
* @param[in] unit The unit parameter is used to determine the null frame time, valid value is between 0 to 15.
* And one unit time is one LCD operation clock period.
*
* @return None
*
* @details This macro is used to set the one null frame time.
* @note All COM and SEG output voltages will keep at 0V during a null frame.
*/
#define LCD_SET_NULL_FRAME_TIME(unit) (LCD->FCTL = (LCD->FCTL & ~LCD_FCTL_NFTIME_Msk) | ((unit) << LCD_FCTL_NFTIME_Pos))
/**
* @brief Set Continuous Frames
*
* @param[in] frame The continuous frames, valid setting is between 1 to 16 frames.
*
* @return None
*
* @details This macro is used to specify the number of continuous frames reached to insert one null frame.
*/
#define LCD_SET_CONTINUOUS_FRAME(frame) (LCD->FCTL = (LCD->FCTL & ~LCD_FCTL_NFNUM_Msk) | (((frame)-1) << LCD_FCTL_NFNUM_Pos))
/**
* @brief Select LCD Voltage Source
*
* @param[in] mode The LCD operation voltage source. It could be one of the following source
* - \ref LCD_VOLTAGE_SOURCE_VLCD
* - \ref LCD_VOLTAGE_SOURCE_AVDD
* - \ref LCD_VOLTAGE_SOURCE_CP
*
* @return None
*
* @details This macro is used to select LCD operation voltage source.
*/
#define LCD_VOLTAGE_SOURCE(source) (LCD->DCTL = (LCD->DCTL & ~LCD_DCTL_VSRC_Msk) | (source))
/**
* @brief Set LCD Driving Mode
*
* @param[in] mode The LCD operation driving mode. It could be one of the following mode
* - \ref LCD_LOW_DRIVING_AND_BUF_OFF
* - \ref LCD_HIGH_DRIVING_AND_BUF_OFF
* - \ref LCD_LOW_DRIVING_AND_BUF_ON
* - \ref LCD_HIGH_DRIVING_AND_BUF_OFF_AND_PWR_SAVING
* - \ref LCD_LOW_DRIVING_AND_BUF_ON_AND_PWR_SAVING
*
* @return None
*
* @details This macro is used to set LCD operation drivig mode.
*/
#define LCD_DRIVING_MODE(mode) (LCD->DCTL = (LCD->DCTL & ~(LCD_DCTL_RESMODE_Msk | LCD_DCTL_BUFEN_Msk | LCD_DCTL_PSVEN_Msk)) | (mode))
/**
* @brief Select Power Saving Mode
*
* @param[in] mode The LCD power saving mode selection. It could be one of the following constant definition
* - \ref LCD_PWR_SAVING_NORMAL_MODE
* - \ref LCD_PWR_SAVING_REVERSE_MODE
*
* @return None
*
* @details This macro is used to set the LCD power saving mode.
* When the timing of power saving mode is reversed, the original power saving period becomes no power saving,
* and the original no power saving period becomes power saving.
*/
#define LCD_PWR_SAVING_MODE(mode) (LCD->DCTL = (LCD->DCTL & ~LCD_DCTL_PSVREV_Msk) | (mode))
/**
* @brief Set Power Saving T1 Period
*
* @param[in] t1 The number of t1 to determine T1 period, valid value is between 1 to 16.
* And one unit of t1 period is half of LCD operation clock period.
*
* @return None
*
* @details This macro is used to configure the T1 (Enable Time) period of power saving.
*/
#define LCD_PWR_SAVING_T1_PERIOD(t1) (LCD->DCTL = (LCD->DCTL & ~LCD_DCTL_PSVT1_Msk) | (((t1)-1) << LCD_DCTL_PSVT1_Pos))
/**
* @brief Set Power Saving T2 Period
*
* @param[in] t2 The number of t2 to determine T2 period, valid value is between 1 to 16.
* And one unit of t1 period is half of LCD operation clock period.
*
* @return None
*
* @details This macro is used to configure the T2 (On Time) period of power saving.
*/
#define LCD_PWR_SAVING_T2_PERIOD(t2) (LCD->DCTL = (LCD->DCTL & ~LCD_DCTL_PSVT2_Msk) | (((t2)-1) << LCD_DCTL_PSVT2_Pos))
/**
* @brief Set Charging Timeout Time
*
* @param[in] value The maximum timeout value, valid value is between 1 to 8192.
* And one unit of timeout value is one LCD operation clock period.
*
* @return None
*
* @details This macro is used to set maximum timeout time of charge pump charging timer.
*/
#define LCD_SET_CHARGE_TIMEOUT_TIME(value) (LCD->DCTL = (LCD->DCTL & ~LCD_DCTL_CTOTIME_Msk) | (((value)-1) << LCD_DCTL_CTOTIME_Pos))
/**
* @brief Select Device Package Type
*
* @param[in] pak Select device package type.
* 0 for 128-pin package, and 1 for 64-pin package.
*
* @return None
*
* @details This macro is used to select device output pins for LCD controller with different package type.
*/
#define LCD_SELECT_PACKAGE_TYPE(pkg) (LCD->PKGSEL = (LCD->PKGSEL & ~LCD_PKGSEL_PKG_Msk) | ((pkg) << LCD_PKGSEL_PKG_Pos))
/**
* @brief Enable LCD Frame Counting End Interrupt
*
* @param None
*
* @return None
*
* @details This macro is used to enable frame count end interrupt function.
*/
#define LCD_ENABLE_FRAME_COUNTING_END_INT() (LCD->INTEN |= LCD_INTEN_FCEIEN_Msk)
/**
* @brief Disable LCD Frame Counting End Interrupt
*
* @param None
*
* @return None
*
* @details This macro is used to disable frame count end interrupt function.
*/
#define LCD_DISABLE_FRAME_COUNTING_END_INT() (LCD->INTEN &= ~LCD_INTEN_FCEIEN_Msk)
/**
* @brief Enable LCD Frame End Interrupt
*
* @param None
*
* @return None
*
* @details This macro is used to enable frame end interrupt function.
*/
#define LCD_ENABLE_FRAME_END_INT() (LCD->INTEN |= LCD_INTEN_FEIEN_Msk)
/**
* @brief Disable LCD Frame End Interrupt
*
* @param None
*
* @return None
*
* @details This macro is used to disable frame end interrupt function.
*/
#define LCD_DISABLE_FRAME_END_INT() (LCD->INTEN &= ~LCD_INTEN_FEIEN_Msk)
/**
* @brief Enable Charging Timeout Interrupt
*
* @param None
*
* @return None
*
* @details This macro is used to enable charge pump charging timeout interrupt function.
*/
#define LCD_ENABLE_CHARGE_TIMEOUT_INT() (LCD->INTEN |= LCD_INTEN_CTOIEN_Msk)
/**
* @brief Disable Charging Timeout Interrupt
*
* @param None
*
* @return None
*
* @details This macro is used to disable charge pump charging timeout interrupt function.
*/
#define LCD_DISABLE_CHARGE_TIMEOUT_INT() (LCD->INTEN &= ~LCD_INTEN_CTOIEN_Msk)
/**
* @brief Get LCD Frame Counting End Flag
*
* @param None
*
* @retval 0 Frame count end flag did not occur
* @retval 1 Frame count end flag occurred
*
* @details This macro gets frame count end flag.
*/
#define LCD_GET_FRAME_COUNTING_END_FLAG() ((LCD->STS & LCD_STS_FCEF_Msk)? 1UL : 0UL)
/**
* @brief Clear LCD Frame Counting End Flag
*
* @param None
*
* @return None
*
* @details This macro clears frame count end flag.
*/
#define LCD_CLEAR_FRAME_COUNTING_END_FLAG() (LCD->STS = LCD_STS_FCEF_Msk)
/**
* @brief Get LCD Frame End Flag
*
* @param None
*
* @retval 0 Frame end flag did not occur
* @retval 1 Frame end flag occurred
*
* @details This macro gets frame end flag.
*/
#define LCD_GET_FRAME_END_FLAG() ((LCD->STS & LCD_STS_FEF_Msk)? 1UL : 0UL)
/**
* @brief Clear LCD Frame End Flag
*
* @param None
*
* @return None
*
* @details This macro clears frame end flag.
*/
#define LCD_CLEAR_FRAME_END_FLAG() (LCD->STS = LCD_STS_FEF_Msk)
/**
* @brief Get Charging Timeout Flag
*
* @param None
*
* @retval 0 Charge pump timer timeout flag did not occur
* @retval 1 Charge pump timer timeout flag occurred
*
* @details This macro gets charge pump charging timeout flag.
*/
#define LCD_GET_CHARGE_TIMEOUT_FLAG() ((LCD->STS & LCD_STS_CTOF_Msk)? 1UL : 0UL)
/**
* @brief Clear Charging Timeout Flag
*
* @param None
*
* @return None
*
* @details This macro clears charge pump charging timeout flag.
*/
#define LCD_CLEAR_CHARGE_TIMEOUT_FLAG() (LCD->STS = LCD_STS_CTOF_Msk)
/**
* @brief Get Charging Time
*
* @param None
*
* @return Current 13-bit charging timer value
*
* @details This macro gets charging timer value while stops charge pump charging.
*/
#define LCD_GET_CHARGE_TIME() ((LCD->STS & LCD_STS_CTIME_Msk) >> 16)
uint32_t LCD_Open(S_LCD_CFG_T *pLCDCfg);
void LCD_Close(void);
void LCD_SetPixel(uint32_t u32Com, uint32_t u32Seg, uint32_t u32OnFlag);
void LCD_SetAllPixels(uint32_t u32OnOff);
uint32_t LCD_EnableBlink(uint32_t u32ms);
void LCD_DisableBlink(void);
void LCD_EnableInt(uint32_t u32IntSrc);
void LCD_DisableInt(uint32_t u32IntSrc);
/**@}*/ /* end of group LCD_EXPORTED_FUNCTIONS */
/**@}*/ /* end of group LCD_Driver */
/**@}*/ /* end of group Standard_Driver */
#ifdef __cplusplus
}
#endif
#endif /* __NU_LCD_H__ */

View File

@ -0,0 +1,256 @@
/**************************************************************************//**
* @file nu_otg.h
* @version V3.00
* @brief M2354 series OTG driver header file
*
* @copyright SPDX-License-Identifier: Apache-2.0
* @copyright Copyright (C) 2020 Nuvoton Technology Corp. All rights reserved.
******************************************************************************/
#ifndef __NU_OTG_H__
#define __NU_OTG_H__
/*---------------------------------------------------------------------------------------------------------*/
/* Include related headers */
/*---------------------------------------------------------------------------------------------------------*/
#include "M2354.h"
#ifdef __cplusplus
extern "C"
{
#endif
/** @addtogroup Standard_Driver Standard Driver
@{
*/
/** @addtogroup OTG_Driver OTG Driver
@{
*/
/** @addtogroup OTG_EXPORTED_CONSTANTS OTG Exported Constants
@{
*/
/*---------------------------------------------------------------------------------------------------------*/
/* OTG constant definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define OTG_VBUS_EN_ACTIVE_HIGH (0UL) /*!< USB VBUS power switch enable signal is active high. */
#define OTG_VBUS_EN_ACTIVE_LOW (1UL) /*!< USB VBUS power switch enable signal is active low. */
#define OTG_VBUS_ST_VALID_HIGH (0UL) /*!< USB VBUS power switch valid status is high. */
#define OTG_VBUS_ST_VALID_LOW (1UL) /*!< USB VBUS power switch valid status is low. */
/**@}*/ /* end of group OTG_EXPORTED_CONSTANTS */
/** @addtogroup OTG_EXPORTED_FUNCTIONS OTG Exported Functions
@{
*/
/*---------------------------------------------------------------------------------------------------------*/
/* Define Macros and functions */
/*---------------------------------------------------------------------------------------------------------*/
/**
* @brief This macro is used to enable OTG function
* @param None
* @return None
* @details This macro will set OTGEN bit of OTG_CTL register to enable OTG function.
*/
#define OTG_ENABLE() (((__PC() & NS_OFFSET) == NS_OFFSET)? (OTG_NS->CTL |= OTG_CTL_OTGEN_Msk):(OTG->CTL |= OTG_CTL_OTGEN_Msk))
/**
* @brief This macro is used to disable OTG function
* @param None
* @return None
* @details This macro will clear OTGEN bit of OTG_CTL register to disable OTG function.
*/
#define OTG_DISABLE() (((__PC() & NS_OFFSET) == NS_OFFSET)? (OTG_NS->CTL &= ~OTG_CTL_OTGEN_Msk):(OTG->CTL &= ~OTG_CTL_OTGEN_Msk))
/**
* @brief This macro is used to enable USB PHY
* @param None
* @return None
* @details When the USB role is selected as OTG device, use this macro to enable USB PHY.
* This macro will set OTGPHYEN bit of OTG_PHYCTL register to enable USB PHY.
*/
#define OTG_ENABLE_PHY() (((__PC() & NS_OFFSET) == NS_OFFSET)? (OTG_NS->PHYCTL |= OTG_PHYCTL_OTGPHYEN_Msk):(OTG->PHYCTL |= OTG_PHYCTL_OTGPHYEN_Msk))
/**
* @brief This macro is used to disable USB PHY
* @param None
* @return None
* @details This macro will clear OTGPHYEN bit of OTG_PHYCTL register to disable USB PHY.
*/
#define OTG_DISABLE_PHY() (((__PC() & NS_OFFSET) == NS_OFFSET)? (OTG_NS->PHYCTL &= ~OTG_PHYCTL_OTGPHYEN_Msk):(OTG->PHYCTL &= ~OTG_PHYCTL_OTGPHYEN_Msk))
/**
* @brief This macro is used to enable ID detection function
* @param None
* @return None
* @details This macro will set IDDETEN bit of OTG_PHYCTL register to enable ID detection function.
*/
#define OTG_ENABLE_ID_DETECT() (((__PC() & NS_OFFSET) == NS_OFFSET)? (OTG_NS->PHYCTL |= OTG_PHYCTL_IDDETEN_Msk):(OTG->PHYCTL |= OTG_PHYCTL_IDDETEN_Msk))
/**
* @brief This macro is used to disable ID detection function
* @param None
* @return None
* @details This macro will clear IDDETEN bit of OTG_PHYCTL register to disable ID detection function.
*/
#define OTG_DISABLE_ID_DETECT() (((__PC() & NS_OFFSET) == NS_OFFSET)? (OTG_NS->PHYCTL &= ~OTG_PHYCTL_IDDETEN_Msk):(OTG->PHYCTL &= ~OTG_PHYCTL_IDDETEN_Msk))
/**
* @brief This macro is used to enable OTG wake-up function
* @param None
* @return None
* @details This macro will set WKEN bit of OTG_CTL register to enable OTG wake-up function.
*/
#define OTG_ENABLE_WAKEUP() (((__PC() & NS_OFFSET) == NS_OFFSET)? (OTG_NS->CTL |= OTG_CTL_WKEN_Msk):(OTG->CTL |= OTG_CTL_WKEN_Msk))
/**
* @brief This macro is used to disable OTG wake-up function
* @param None
* @return None
* @details This macro will clear WKEN bit of OTG_CTL register to disable OTG wake-up function.
*/
#define OTG_DISABLE_WAKEUP() (((__PC() & NS_OFFSET) == NS_OFFSET)? (OTG_NS->CTL &= ~OTG_CTL_WKEN_Msk):(OTG->CTL &= ~OTG_CTL_WKEN_Msk))
/**
* @brief This macro is used to set the polarity of USB_VBUS_EN pin
* @param[in] u32Pol The polarity selection. Valid values are listed below.
* - \ref OTG_VBUS_EN_ACTIVE_HIGH
* - \ref OTG_VBUS_EN_ACTIVE_LOW
* @return None
* @details This macro is used to set the polarity of external USB VBUS power switch enable signal.
*/
#define OTG_SET_VBUS_EN_POL(u32Pol) (((__PC() & NS_OFFSET) == NS_OFFSET)? (OTG_NS->PHYCTL = (OTG_NS->PHYCTL & (~OTG_PHYCTL_VBENPOL_Msk)) | ((u32Pol)<<OTG_PHYCTL_VBENPOL_Pos)):(OTG->PHYCTL = (OTG->PHYCTL & (~OTG_PHYCTL_VBENPOL_Msk)) | ((u32Pol)<<OTG_PHYCTL_VBENPOL_Pos)))
/**
* @brief This macro is used to set the polarity of USB_VBUS_ST pin
* @param[in] u32Pol The polarity selection. Valid values are listed below.
* - \ref OTG_VBUS_ST_VALID_HIGH
* - \ref OTG_VBUS_ST_VALID_LOW
* @return None
* @details This macro is used to set the polarity of external USB VBUS power switch status signal.
*/
#define OTG_SET_VBUS_STS_POL(u32Pol) (((__PC() & NS_OFFSET) == NS_OFFSET)? (OTG_NS->PHYCTL = (OTG_NS->PHYCTL & (~OTG_PHYCTL_VBSTSPOL_Msk)) | ((u32Pol)<<OTG_PHYCTL_VBSTSPOL_Pos)):(OTG->PHYCTL = (OTG->PHYCTL & (~OTG_PHYCTL_VBSTSPOL_Msk)) | ((u32Pol)<<OTG_PHYCTL_VBSTSPOL_Pos)))
/**
* @brief This macro is used to enable OTG related interrupts
* @param[in] u32Mask The combination of interrupt source. Each bit corresponds to a interrupt source. Valid values are listed below.
* - \ref OTG_INTEN_ROLECHGIEN_Msk
* - \ref OTG_INTEN_VBEIEN_Msk
* - \ref OTG_INTEN_SRPFIEN_Msk
* - \ref OTG_INTEN_HNPFIEN_Msk
* - \ref OTG_INTEN_GOIDLEIEN_Msk
* - \ref OTG_INTEN_IDCHGIEN_Msk
* - \ref OTG_INTEN_PDEVIEN_Msk
* - \ref OTG_INTEN_HOSTIEN_Msk
* - \ref OTG_INTEN_BVLDCHGIEN_Msk
* - \ref OTG_INTEN_AVLDCHGIEN_Msk
* - \ref OTG_INTEN_VBCHGIEN_Msk
* - \ref OTG_INTEN_SECHGIEN_Msk
* - \ref OTG_INTEN_SRPDETIEN_Msk
* @return None
* @details This macro will enable OTG related interrupts specified by u32Mask parameter.
*/
#define OTG_ENABLE_INT(u32Mask) (((__PC() & NS_OFFSET) == NS_OFFSET)? (OTG_NS->INTEN |= (u32Mask)):(OTG->INTEN |= (u32Mask)))
/**
* @brief This macro is used to disable OTG related interrupts
* @param[in] u32Mask The combination of interrupt source. Each bit corresponds to a interrupt source. Valid values are listed below.
* - \ref OTG_INTEN_ROLECHGIEN_Msk
* - \ref OTG_INTEN_VBEIEN_Msk
* - \ref OTG_INTEN_SRPFIEN_Msk
* - \ref OTG_INTEN_HNPFIEN_Msk
* - \ref OTG_INTEN_GOIDLEIEN_Msk
* - \ref OTG_INTEN_IDCHGIEN_Msk
* - \ref OTG_INTEN_PDEVIEN_Msk
* - \ref OTG_INTEN_HOSTIEN_Msk
* - \ref OTG_INTEN_BVLDCHGIEN_Msk
* - \ref OTG_INTEN_AVLDCHGIEN_Msk
* - \ref OTG_INTEN_VBCHGIEN_Msk
* - \ref OTG_INTEN_SECHGIEN_Msk
* - \ref OTG_INTEN_SRPDETIEN_Msk
* @return None
* @details This macro will disable OTG related interrupts specified by u32Mask parameter.
*/
#define OTG_DISABLE_INT(u32Mask) (((__PC() & NS_OFFSET) == NS_OFFSET)? (OTG_NS->INTEN &= ~(u32Mask)):(OTG->INTEN &= ~(u32Mask)))
/**
* @brief This macro is used to get OTG related interrupt flags
* @param[in] u32Mask The combination of interrupt source. Each bit corresponds to a interrupt source. Valid values are listed below.
* - \ref OTG_INTSTS_ROLECHGIF_Msk
* - \ref OTG_INTSTS_VBEIF_Msk
* - \ref OTG_INTSTS_SRPFIF_Msk
* - \ref OTG_INTSTS_HNPFIF_Msk
* - \ref OTG_INTSTS_GOIDLEIF_Msk
* - \ref OTG_INTSTS_IDCHGIF_Msk
* - \ref OTG_INTSTS_PDEVIF_Msk
* - \ref OTG_INTSTS_HOSTIF_Msk
* - \ref OTG_INTSTS_BVLDCHGIF_Msk
* - \ref OTG_INTSTS_AVLDCHGIF_Msk
* - \ref OTG_INTSTS_VBCHGIF_Msk
* - \ref OTG_INTSTS_SECHGIF_Msk
* - \ref OTG_INTSTS_SRPDETIF_Msk
* @return Interrupt flags of selected sources.
* @details This macro will return OTG related interrupt flags specified by u32Mask parameter.
*/
#define OTG_GET_INT_FLAG(u32Mask) (((__PC() & NS_OFFSET) == NS_OFFSET)? (OTG_NS->INTSTS & (u32Mask)):(OTG->INTSTS & (u32Mask)))
/**
* @brief This macro is used to clear OTG related interrupt flags
* @param[in] u32Mask The combination of interrupt source. Each bit corresponds to a interrupt source. Valid values are listed below.
* - \ref OTG_INTSTS_ROLECHGIF_Msk
* - \ref OTG_INTSTS_VBEIF_Msk
* - \ref OTG_INTSTS_SRPFIF_Msk
* - \ref OTG_INTSTS_HNPFIF_Msk
* - \ref OTG_INTSTS_GOIDLEIF_Msk
* - \ref OTG_INTSTS_IDCHGIF_Msk
* - \ref OTG_INTSTS_PDEVIF_Msk
* - \ref OTG_INTSTS_HOSTIF_Msk
* - \ref OTG_INTSTS_BVLDCHGIF_Msk
* - \ref OTG_INTSTS_AVLDCHGIF_Msk
* - \ref OTG_INTSTS_VBCHGIF_Msk
* - \ref OTG_INTSTS_SECHGIF_Msk
* - \ref OTG_INTSTS_SRPDETIF_Msk
* @return None
* @details This macro will clear OTG related interrupt flags specified by u32Mask parameter.
*/
#define OTG_CLR_INT_FLAG(u32Mask) (((__PC() & NS_OFFSET) == NS_OFFSET)? (OTG_NS->INTSTS = (u32Mask)):(OTG->INTSTS = (u32Mask)))
/**
* @brief This macro is used to get OTG related status
* @param[in] u32Mask The combination of user specified source. Valid values are listed below.
* - \ref OTG_STATUS_OVERCUR_Msk
* - \ref OTG_STATUS_IDSTS_Msk
* - \ref OTG_STATUS_SESSEND_Msk
* - \ref OTG_STATUS_BVLD_Msk
* - \ref OTG_STATUS_AVLD_Msk
* - \ref OTG_STATUS_VBUSVLD_Msk
* @return The user specified status.
* @details This macro will return OTG related status specified by u32Mask parameter.
*/
#define OTG_GET_STATUS(u32Mask) (((__PC() & NS_OFFSET) == NS_OFFSET)? (OTG_NS->STATUS & (u32Mask)):(OTG->STATUS & (u32Mask)))
/**@}*/ /* end of group OTG_EXPORTED_FUNCTIONS */
/**@}*/ /* end of group OTG_Driver */
/**@}*/ /* end of group Standard_Driver */
#ifdef __cplusplus
}
#endif
#endif /* __NU_OTG_H__ */

View File

@ -0,0 +1,697 @@
/**************************************************************************//**
* @file nu_partition_M2354.h
* @version V3.00
* @brief TrustZone partition file
*
* @copyright SPDX-License-Identifier: Apache-2.0
* @copyright Copyright (C) 2020 Nuvoton Technology Corp. All rights reserved.
******************************************************************************/
#ifndef PARTITION_M2354
#define PARTITION_M2354
#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U)
/*
Default M2354 pritition configuration file is for non-TrustZone sample code only.
If user wants to use TrurstZone, they should have their partition_m2354.h.
For TrustZone projects, path of local partition_m2354.h should be in the
front of the include path list to make sure local partition_m2354.h is used.
It also apply to non-secure project of the TrustZone projects.
*/
# error "Link to default nu_partition_M2354.h in secure mode. Please check your include path."
#endif
/*
//-------- <<< Use Configuration Wizard in Context Menu >>> -----------------
*/
/*
SRAMNSSET
*/
/*
// Bit 0..18
// <o.0..18> Secure SRAM Size <0=> 0 KB
// <0x4000=> 16KB
// <0x8000=> 32KB
// <0xc000=> 48KB
// <0x10000=> 64KB
// <0x14000=> 80KB
// <0x18000=> 96KB
// <0x1C000=> 112KB
// <0x20000=> 128KB
// <0x24000=> 144KB
// <0x28000=> 160KB
// <0x2C000=> 176KB
// <0x30000=> 192KB
// <0x34000=> 208KB
// <0x38000=> 224KB
// <0x3C000=> 240KB
// <0x40000=> 256KB
*/
#define SCU_SECURE_SRAM_SIZE 0x18000
#define NON_SECURE_SRAM_BASE (0x30000000 + SCU_SECURE_SRAM_SIZE)
/*--------------------------------------------------------------------------------------------------------*/
/*
NSBA
*/
#define FMC_INIT_NSBA 1
/*
// <o>Secure Flash ROM Size <0x800-0x80000:0x800>
*/
#define FMC_SECURE_ROM_SIZE 0x80000
#define FMC_NON_SECURE_BASE (0x10000000 + FMC_SECURE_ROM_SIZE)
/*--------------------------------------------------------------------------------------------------------*/
/*
// <h> Peripheral Secure Attribution Configuration
*/
/*
PNSSET0
*/
/*
// Module 0..31
// <o.9> USBH <0=> Secure <1=> Non-Secure
// <o.13> SD0 <0=> Secure <1=> Non-Secure
// <o.16> EBI <0=> Secure <1=> Non-Secure
// <o.24> PDMA1 <0=> Secure <1=> Non-Secure
*/
#define SCU_INIT_PNSSET0_VAL 0x0
/*
PNSSET1
*/
/*
// Module 0..31
// <o.17> CRC <0=> Secure <1=> Non-Secure
// <o.18> CRPT <0=> Secure <1=> Non-Secure
*/
#define SCU_INIT_PNSSET1_VAL 0x00000
/*
PNSSET2
*/
/*
// Module 0..31
// <o.2> EWDT <0=> Secure <1=> Non-Secure
// <o.3> EADC <0=> Secure <1=> Non-Secure
// <o.5> ACMP01 <0=> Secure <1=> Non-Secure
//
// <o.7> DAC <0=> Secure <1=> Non-Secure
// <o.8> I2S0 <0=> Secure <1=> Non-Secure
// <o.13> OTG <0=> Secure <1=> Non-Secure
// <h> TIMER
// <o.17> TMR23 <0=> Secure <1=> Non-Secure
// <o.18> TMR45 <0=> Secure <1=> Non-Secure
// <h> EPWM
// <o.24> EPWM0 <0=> Secure <1=> Non-Secure
// <o.25> EPWM1 <0=> Secure <1=> Non-Secure
// </h>
// <h> BPWM
// <o.26> BPWM0 <0=> Secure <1=> Non-Secure
// <o.27> BPWM1 <0=> Secure <1=> Non-Secure
// </h>
*/
#define SCU_INIT_PNSSET2_VAL 0x0
/*
PNSSET3
*/
/*
// Module 0..31
// <h> SPI
// <o.0> QSPI0 <0=> Secure <1=> Non-Secure
// <o.1> SPI0 <0=> Secure <1=> Non-Secure
// <o.2> SPI1 <0=> Secure <1=> Non-Secure
// <o.3> SPI2 <0=> Secure <1=> Non-Secure
// <o.4> SPI3 <0=> Secure <1=> Non-Secure
// </h>
// <h> UART
// <o.16> UART0 <0=> Secure <1=> Non-Secure
// <o.17> UART1 <0=> Secure <1=> Non-Secure
// <o.18> UART2 <0=> Secure <1=> Non-Secure
// <o.19> UART3 <0=> Secure <1=> Non-Secure
// <o.20> UART4 <0=> Secure <1=> Non-Secure
// <o.21> UART5 <0=> Secure <1=> Non-Secure
// </h>
*/
#define SCU_INIT_PNSSET3_VAL 0x00000
/*
PNSSET4
*/
/*
// Module 0..31
// <h> I2C
// <o.0> I2C0 <0=> Secure <1=> Non-Secure
// <o.1> I2C1 <0=> Secure <1=> Non-Secure
// <o.2> I2C2 <0=> Secure <1=> Non-Secure
// </h>
// <h> Smart Card
// <o.16> SC0 <0=> Secure <1=> Non-Secure
// <o.17> SC1 <0=> Secure <1=> Non-Secure
// <o.18> SC2 <0=> Secure <1=> Non-Secure
// </h>
*/
#define SCU_INIT_PNSSET4_VAL 0x0
/*
PNSSET5
*/
/*
// Module 0..31
// <o.0> CAN0 <0=> Secure <1=> Non-Secure
// <h> QEI
// <o.16> QEI0 <0=> Secure <1=> Non-Secure
// <o.17> QEI1 <0=> Secure <1=> Non-Secure
// </h>
// <h> ECAP
// <o.20> ECAP0 <0=> Secure <1=> Non-Secure
// <o.21> ECAP1 <0=> Secure <1=> Non-Secure
// </h>
// <o.25> TRNG <0=> Secure <1=> Non-Secure
// <o.27> LCD <0=> Secure <1=> Non-Secure
*/
#define SCU_INIT_PNSSET5_VAL 0x0
/*
PNSSET6
*/
/*
// Module 0..31
// <o.0> USBD <0=> Secure <1=> Non-Secure
// <h> USCI
// <o.16> USCI0 <0=> Secure <1=> Non-Secure
// <o.17> USCI1 <0=> Secure <1=> Non-Secure
// </h>
*/
#define SCU_INIT_PNSSET6_VAL 0x0
/*
// </h>
*/
/*
// <h> GPIO Secure Attribution Configuration
*/
/*
IONSSET
*/
/*
// Bit 0..31
// <h> PA
// <o.0> PA0 <0=> Secure <1=> Non-Secure
// <o.1> PA1 <0=> Secure <1=> Non-Secure
// <o.2> PA2 <0=> Secure <1=> Non-Secure
// <o.3> PA3 <0=> Secure <1=> Non-Secure
// <o.4> PA4 <0=> Secure <1=> Non-Secure
// <o.5> PA5 <0=> Secure <1=> Non-Secure
// <o.6> PA6 <0=> Secure <1=> Non-Secure
// <o.7> PA7 <0=> Secure <1=> Non-Secure
// <o.8> PA8 <0=> Secure <1=> Non-Secure
// <o.7> PA9 <0=> Secure <1=> Non-Secure
// <o.10> PA10 <0=> Secure <1=> Non-Secure
// <o.11> PA11 <0=> Secure <1=> Non-Secure
// <o.12> PA12 <0=> Secure <1=> Non-Secure
// <o.13> PA13 <0=> Secure <1=> Non-Secure
// <o.14> PA14 <0=> Secure <1=> Non-Secure
// <o.15> PA15 <0=> Secure <1=> Non-Secure
// </h>
*/
#define SCU_INIT_IONSSET0_VAL 0x00000000
/*
// Bit 0..31
// <h> PB
// <o.0> PB0 <0=> Secure <1=> Non-Secure
// <o.1> PB1 <0=> Secure <1=> Non-Secure
// <o.2> PB2 <0=> Secure <1=> Non-Secure
// <o.3> PB3 <0=> Secure <1=> Non-Secure
// <o.4> PB4 <0=> Secure <1=> Non-Secure
// <o.5> PB5 <0=> Secure <1=> Non-Secure
// <o.6> PB6 <0=> Secure <1=> Non-Secure
// <o.7> PB7 <0=> Secure <1=> Non-Secure
// <o.8> PB8 <0=> Secure <1=> Non-Secure
// <o.9> PB9 <0=> Secure <1=> Non-Secure
// <o.10> PB10 <0=> Secure <1=> Non-Secure
// <o.11> PB11 <0=> Secure <1=> Non-Secure
// <o.12> PB12 <0=> Secure <1=> Non-Secure
// <o.13> PB13 <0=> Secure <1=> Non-Secure
// <o.14> PB14 <0=> Secure <1=> Non-Secure
// <o.15> PB15 <0=> Secure <1=> Non-Secure
// </h>
*/
#define SCU_INIT_IONSSET1_VAL 0x00000000
/*
// Bit 0..31
// <h> PC
// <o.0> PC0 <0=> Secure <1=> Non-Secure
// <o.1> PC1 <0=> Secure <1=> Non-Secure
// <o.2> PC2 <0=> Secure <1=> Non-Secure
// <o.3> PC3 <0=> Secure <1=> Non-Secure
// <o.4> PC4 <0=> Secure <1=> Non-Secure
// <o.5> PC5 <0=> Secure <1=> Non-Secure
// <o.6> PC6 <0=> Secure <1=> Non-Secure
// <o.7> PC7 <0=> Secure <1=> Non-Secure
// <o.8> PC8 <0=> Secure <1=> Non-Secure
// <o.9> PC9 <0=> Secure <1=> Non-Secure
// <o.10> PC10 <0=> Secure <1=> Non-Secure
// <o.11> PC11 <0=> Secure <1=> Non-Secure
// <o.12> PC12 <0=> Secure <1=> Non-Secure
// <o.13> PC13 <0=> Secure <1=> Non-Secure
// </h>
*/
#define SCU_INIT_IONSSET2_VAL 0x00000000
/*
// Bit 0..31
// <h> PD
// <o.0> PD0 <0=> Secure <1=> Non-Secure
// <o.1> PD1 <0=> Secure <1=> Non-Secure
// <o.2> PD2 <0=> Secure <1=> Non-Secure
// <o.3> PD3 <0=> Secure <1=> Non-Secure
// <o.4> PD4 <0=> Secure <1=> Non-Secure
// <o.5> PD5 <0=> Secure <1=> Non-Secure
// <o.6> PD6 <0=> Secure <1=> Non-Secure
// <o.7> PD7 <0=> Secure <1=> Non-Secure
// <o.8> PD8 <0=> Secure <1=> Non-Secure
// <o.9> PD9 <0=> Secure <1=> Non-Secure
// <o.10> PD10 <0=> Secure <1=> Non-Secure
// <o.11> PD11 <0=> Secure <1=> Non-Secure
// <o.12> PD12 <0=> Secure <1=> Non-Secure
// <o.14> PD14 <0=> Secure <1=> Non-Secure
// </h>
*/
#define SCU_INIT_IONSSET3_VAL 0x00000000
/*
// Bit 0..31
// <h> PE
// <o.0> PE0 <0=> Secure <1=> Non-Secure
// <o.1> PE1 <0=> Secure <1=> Non-Secure
// <o.2> PE2 <0=> Secure <1=> Non-Secure
// <o.3> PE3 <0=> Secure <1=> Non-Secure
// <o.4> PE4 <0=> Secure <1=> Non-Secure
// <o.5> PE5 <0=> Secure <1=> Non-Secure
// <o.6> PE6 <0=> Secure <1=> Non-Secure
// <o.7> PE7 <0=> Secure <1=> Non-Secure
// <o.8> PE8 <0=> Secure <1=> Non-Secure
// <o.9> PE9 <0=> Secure <1=> Non-Secure
// <o.10> PE10 <0=> Secure <1=> Non-Secure
// <o.11> PE11 <0=> Secure <1=> Non-Secure
// <o.12> PE12 <0=> Secure <1=> Non-Secure
// <o.13> PE13 <0=> Secure <1=> Non-Secure
// <o.14> PE14 <0=> Secure <1=> Non-Secure
// <o.15> PE15 <0=> Secure <1=> Non-Secure
// </h>
*/
#define SCU_INIT_IONSSET4_VAL 0x00000000
/*
// Bit 0..31
// <h> PF
// <o.0> PF0 <0=> Secure <1=> Non-Secure
// <o.1> PF1 <0=> Secure <1=> Non-Secure
// <o.2> PF2 <0=> Secure <1=> Non-Secure
// <o.3> PF3 <0=> Secure <1=> Non-Secure
// <o.4> PF4 <0=> Secure <1=> Non-Secure
// <o.5> PF5 <0=> Secure <1=> Non-Secure
// <o.6> PF6 <0=> Secure <1=> Non-Secure
// <o.7> PF7 <0=> Secure <1=> Non-Secure
// <o.8> PF8 <0=> Secure <1=> Non-Secure
// <o.9> PF9 <0=> Secure <1=> Non-Secure
// <o.10> PF10 <0=> Secure <1=> Non-Secure
// <o.11> PF11 <0=> Secure <1=> Non-Secure
// </h>
*/
#define SCU_INIT_IONSSET5_VAL 0x00000000
/*
// Bit 0..31
// <h> PG
// <o.2> PG2 <0=> Secure <1=> Non-Secure
// <o.3> PG3 <0=> Secure <1=> Non-Secure
// <o.4> PG4 <0=> Secure <1=> Non-Secure
// <o.9> PG9 <0=> Secure <1=> Non-Secure
// <o.10> PG10 <0=> Secure <1=> Non-Secure
// <o.11> PG11 <0=> Secure <1=> Non-Secure
// <o.12> PG12 <0=> Secure <1=> Non-Secure
// <o.13> PG13 <0=> Secure <1=> Non-Secure
// <o.14> PG14 <0=> Secure <1=> Non-Secure
// <o.15> PG15 <0=> Secure <1=> Non-Secure
// </h>
*/
#define SCU_INIT_IONSSET6_VAL 0x00000000
/*
// Bit 0..31
// <h> PH
// <o.4> PH4 <0=> Secure <1=> Non-Secure
// <o.5> PH5 <0=> Secure <1=> Non-Secure
// <o.6> PH6 <0=> Secure <1=> Non-Secure
// <o.7> PH7 <0=> Secure <1=> Non-Secure
// <o.8> PH8 <0=> Secure <1=> Non-Secure
// <o.9> PH9 <0=> Secure <1=> Non-Secure
// <o.10> PH10 <0=> Secure <1=> Non-Secure
// <o.11> PH11 <0=> Secure <1=> Non-Secure
// </h>
*/
#define SCU_INIT_IONSSET7_VAL 0x00000000
/*
// </h>
*/
/*
// <h>Assign GPIO Interrupt to Secure or Non-secure Vector
*/
/*
Initialize GPIO ITNS (Interrupts 0..31)
*/
/*
// Bit 0..31
// <o.0> GPA <0=> Secure <1=> Non-Secure
// <o.1> GPB <0=> Secure <1=> Non-Secure
// <o.2> GPC <0=> Secure <1=> Non-Secure
// <o.3> GPD <0=> Secure <1=> Non-Secure
// <o.4> GPE <0=> Secure <1=> Non-Secure
// <o.5> GPF <0=> Secure <1=> Non-Secure
// <o.6> GPG <0=> Secure <1=> Non-Secure
// <o.7> GPH <0=> Secure <1=> Non-Secure
// <o.8> EINT0 <0=> Secure <1=> Non-Secure
// <o.9> EINT1 <0=> Secure <1=> Non-Secure
// <o.10> EINT2 <0=> Secure <1=> Non-Secure
// <o.11> EINT3 <0=> Secure <1=> Non-Secure
// <o.12> EINT4 <0=> Secure <1=> Non-Secure
// <o.13> EINT5 <0=> Secure <1=> Non-Secure
// <o.14> EINT6 <0=> Secure <1=> Non-Secure
// <o.15> EINT7 <0=> Secure <1=> Non-Secure
*/
#define SCU_INIT_IONSSET_VAL 0x0000
/*
// </h>
*/
/* ---------------------------------------------------------------------------------------------------- */
/*
// <e>Secure Attribute Unit (SAU) Control
*/
#define SAU_INIT_CTRL 0
/*
// <q> Enable SAU
// <i> To enable Secure Attribute Unit (SAU).
*/
#define SAU_INIT_CTRL_ENABLE 1
/*
// <o> All Memory Attribute When SAU is disabled
// <0=> All Memory is Secure
// <1=> All Memory is Non-Secure
// <i> To set the ALLNS bit in SAU CTRL.
// <i> When all Memory is Non-Secure (ALLNS is 1), IDAU can override memory map configuration.
*/
#define SAU_INIT_CTRL_ALLNS 0
/*
// </e>
*/
/*
// <h>Enable and Set Secure/Non-Secure region
*/
#define SAU_REGIONS_MAX 8 /* Max. number of SAU regions */
/*
// <e>SAU Region 0
// <i> Setup SAU Region 0
*/
#define SAU_INIT_REGION0 0
/*
// <o>Start Address <0-0xFFFFFFE0>
*/
#define SAU_INIT_START0 0x0003F000 /* start address of SAU region 0 */
/*
// <o>End Address <0x1F-0xFFFFFFFF>
*/
#define SAU_INIT_END0 0x0003FFFF /* end address of SAU region 0 */
/*
// <o>Region is
// <0=>Non-Secure
// <1=>Secure, Non-Secure Callable
*/
#define SAU_INIT_NSC0 1
/*
// </e>
*/
/*
// <e>SAU Region 1
// <i> Setup SAU Region 1
*/
#define SAU_INIT_REGION1 0
/*
// <o>Start Address <0-0xFFFFFFE0>
*/
#define SAU_INIT_START1 0x10040000
/*
// <o>End Address <0x1F-0xFFFFFFFF>
*/
#define SAU_INIT_END1 0x1007FFFF
/*
// <o>Region is
// <0=>Non-Secure
// <1=>Secure, Non-Secure Callable
*/
#define SAU_INIT_NSC1 0
/*
// </e>
*/
/*
// <e>SAU Region 2
// <i> Setup SAU Region 2
*/
#define SAU_INIT_REGION2 0
/*
// <o>Start Address <0-0xFFFFFFE0>
*/
#define SAU_INIT_START2 0x2000F000
/*
// <o>End Address <0x1F-0xFFFFFFFF>
*/
#define SAU_INIT_END2 0x2000FFFF
/*
// <o>Region is
// <0=>Non-Secure
// <1=>Secure, Non-Secure Callable
*/
#define SAU_INIT_NSC2 1
/*
// </e>
*/
/*
// <e>SAU Region 3
// <i> Setup SAU Region 3
*/
#define SAU_INIT_REGION3 0
/*
// <o>Start Address <0-0xFFFFFFE0>
*/
#define SAU_INIT_START3 0x3f000
/*
// <o>End Address <0x1F-0xFFFFFFFF>
*/
#define SAU_INIT_END3 0x3f7ff
/*
// <o>Region is
// <0=>Non-Secure
// <1=>Secure, Non-Secure Callable
*/
#define SAU_INIT_NSC3 1
/*
// </e>
*/
/*
<e>SAU Region 4
<i> Setup SAU Region 4
*/
#define SAU_INIT_REGION4 1
/*
<o>Start Address <0-0xFFFFFFE0>
*/
#define SAU_INIT_START4 FMC_NON_SECURE_BASE /* start address of SAU region 4 */
/*
<o>End Address <0x1F-0xFFFFFFFF>
*/
#define SAU_INIT_END4 0x1007FFFF /* end address of SAU region 4 */
/*
<o>Region is
<0=>Non-Secure
<1=>Secure, Non-Secure Callable
*/
#define SAU_INIT_NSC4 0
/*
</e>
*/
/*
<e>SAU Region 5
<i> Setup SAU Region 5
*/
#define SAU_INIT_REGION5 1
/*
<o>Start Address <0-0xFFFFFFE0>
*/
#define SAU_INIT_START5 0x00807E00
/*
<o>End Address <0x1F-0xFFFFFFFF>
*/
#define SAU_INIT_END5 0x00807FFF
/*
<o>Region is
<0=>Non-Secure
<1=>Secure, Non-Secure Callable
*/
#define SAU_INIT_NSC5 1
/*
</e>
*/
/*
<e>SAU Region 6
<i> Setup SAU Region 6
*/
#define SAU_INIT_REGION6 1
/*
<o>Start Address <0-0xFFFFFFE0>
*/
#define SAU_INIT_START6 NON_SECURE_SRAM_BASE
/*
<o>End Address <0x1F-0xFFFFFFFF>
*/
#define SAU_INIT_END6 0x30017FFF
/*
<o>Region is
<0=>Non-Secure
<1=>Secure, Non-Secure Callable
*/
#define SAU_INIT_NSC6 0
/*
</e>
*/
/*
<e>SAU Region 7
<i> Setup SAU Region 7
*/
#define SAU_INIT_REGION7 1
/*
<o>Start Address <0-0xFFFFFFE0>
*/
#define SAU_INIT_START7 0x50000000
/*
<o>End Address <0x1F-0xFFFFFFFF>
*/
#define SAU_INIT_END7 0x5FFFFFFF
/*
<o>Region is
<0=>Non-Secure
<1=>Secure, Non-Secure Callable
*/
#define SAU_INIT_NSC7 0
/*
</e>
*/
/*
// </h>
*/
/*
// <e>Setup behavior of Sleep and Exception Handling
*/
#define SCB_CSR_AIRCR_INIT 1
/*
// <o> Deep Sleep can be enabled by
// <0=>Secure and Non-Secure state
// <1=>Secure state only
// <i> Value for SCB->CSR register bit DEEPSLEEPS
*/
#define SCB_CSR_DEEPSLEEPS_VAL 0
/*
// <o>System reset request accessible from
// <0=> Secure and Non-Secure state
// <1=> Secure state only
// <i> Value for SCB->AIRCR register bit SYSRESETREQS
*/
#define SCB_AIRCR_SYSRESETREQS_VAL 0
/*
// <o>Priority of Non-Secure exceptions is
// <0=> Not altered
// <1=> Lowered to 0x80-0xFF
// <i> Value for SCB->AIRCR register bit PRIS
*/
#define SCB_AIRCR_PRIS_VAL 0
/* Assign HardFault to be always secure for safe */
#define SCB_AIRCR_BFHFNMINS_VAL 0
/*
// </e>
*/
/*
max 128 SAU regions.
SAU regions are defined in partition.h
*/
#define SAU_INIT_REGION(n) \
SAU->RNR = (n & SAU_RNR_REGION_Msk); \
SAU->RBAR = (SAU_INIT_START##n & SAU_RBAR_BADDR_Msk); \
SAU->RLAR = (SAU_INIT_END##n & SAU_RLAR_LADDR_Msk) | \
((SAU_INIT_NSC##n << SAU_RLAR_NSC_Pos) & SAU_RLAR_NSC_Msk) | 1U
#endif /* PARTITION_M2354 */

View File

@ -0,0 +1,380 @@
/**************************************************************************//**
* @file nu_pdma.h
* @version V3.00
* @brief M2354 series PDMA driver header file
*
* @copyright SPDX-License-Identifier: Apache-2.0
* @copyright Copyright (C) 2020 Nuvoton Technology Corp. All rights reserved.
*****************************************************************************/
#ifndef __NU_PDMA_H__
#define __NU_PDMA_H__
#ifdef __cplusplus
extern "C"
{
#endif
/** @addtogroup Standard_Driver Standard Driver
@{
*/
/** @addtogroup PDMA_Driver PDMA Driver
@{
*/
/** @addtogroup PDMA_EXPORTED_CONSTANTS PDMA Exported Constants
@{
*/
#define PDMA_CH_MAX 8UL /*!< Specify Maximum Channels of PDMA \hideinitializer */
/*---------------------------------------------------------------------------------------------------------*/
/* Operation Mode Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define PDMA_OP_STOP 0x00000000UL /*!<DMA Stop Mode \hideinitializer */
#define PDMA_OP_BASIC 0x00000001UL /*!<DMA Basic Mode \hideinitializer */
#define PDMA_OP_SCATTER 0x00000002UL /*!<DMA Scatter-gather Mode \hideinitializer */
/*---------------------------------------------------------------------------------------------------------*/
/* Data Width Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define PDMA_WIDTH_8 0x00000000UL /*!<DMA Transfer Width 8-bit \hideinitializer */
#define PDMA_WIDTH_16 0x00001000UL /*!<DMA Transfer Width 16-bit \hideinitializer */
#define PDMA_WIDTH_32 0x00002000UL /*!<DMA Transfer Width 32-bit \hideinitializer */
/*---------------------------------------------------------------------------------------------------------*/
/* Address Attribute Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define PDMA_SAR_INC 0x00000000UL /*!<DMA SAR increment \hideinitializer */
#define PDMA_SAR_FIX 0x00000300UL /*!<DMA SAR fix address \hideinitializer */
#define PDMA_DAR_INC 0x00000000UL /*!<DMA DAR increment \hideinitializer */
#define PDMA_DAR_FIX 0x00000C00UL /*!<DMA DAR fix address \hideinitializer */
/*---------------------------------------------------------------------------------------------------------*/
/* Burst Mode Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define PDMA_REQ_SINGLE 0x00000004UL /*!<DMA Single Request \hideinitializer */
#define PDMA_REQ_BURST 0x00000000UL /*!<DMA Burst Request \hideinitializer */
#define PDMA_BURST_128 0x00000000UL /*!<DMA Burst 128 Transfers \hideinitializer */
#define PDMA_BURST_64 0x00000010UL /*!<DMA Burst 64 Transfers \hideinitializer */
#define PDMA_BURST_32 0x00000020UL /*!<DMA Burst 32 Transfers \hideinitializer */
#define PDMA_BURST_16 0x00000030UL /*!<DMA Burst 16 Transfers \hideinitializer */
#define PDMA_BURST_8 0x00000040UL /*!<DMA Burst 8 Transfers \hideinitializer */
#define PDMA_BURST_4 0x00000050UL /*!<DMA Burst 4 Transfers \hideinitializer */
#define PDMA_BURST_2 0x00000060UL /*!<DMA Burst 2 Transfers \hideinitializer */
#define PDMA_BURST_1 0x00000070UL /*!<DMA Burst 1 Transfers \hideinitializer */
/*---------------------------------------------------------------------------------------------------------*/
/* Table Interrupt Disable Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define PDMA_TBINTDIS_ENABLE (0x0UL<<PDMA_DSCT_CTL_TBINTDIS_Pos) /*!<DMA Table Interrupt Enabled \hideinitializer */
#define PDMA_TBINTDIS_DISABLE (0x1UL<<PDMA_DSCT_CTL_TBINTDIS_Pos) /*!<DMA Table Interrupt Disabled \hideinitializer */
/*---------------------------------------------------------------------------------------------------------*/
/* Peripheral Transfer Mode Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define PDMA_MEM 0UL /*!<DMA Connect to Memory \hideinitializer */
#define PDMA_USB_TX 2UL /*!<DMA Connect to USB TX \hideinitializer */
#define PDMA_USB_RX 3UL /*!<DMA Connect to USB RX \hideinitializer */
#define PDMA_UART0_TX 4UL /*!<DMA Connect to UART0 TX \hideinitializer */
#define PDMA_UART0_RX 5UL /*!<DMA Connect to UART0 RX \hideinitializer */
#define PDMA_UART1_TX 6UL /*!<DMA Connect to UART1 TX \hideinitializer */
#define PDMA_UART1_RX 7UL /*!<DMA Connect to UART1 RX \hideinitializer */
#define PDMA_UART2_TX 8UL /*!<DMA Connect to UART2 TX \hideinitializer */
#define PDMA_UART2_RX 9UL /*!<DMA Connect to UART2 RX \hideinitializer */
#define PDMA_UART3_TX 10UL /*!<DMA Connect to UART3 TX \hideinitializer */
#define PDMA_UART3_RX 11UL /*!<DMA Connect to UART3 RX \hideinitializer */
#define PDMA_UART4_TX 12UL /*!<DMA Connect to UART4 TX \hideinitializer */
#define PDMA_UART4_RX 13UL /*!<DMA Connect to UART4 RX \hideinitializer */
#define PDMA_UART5_TX 14UL /*!<DMA Connect to UART5 TX \hideinitializer */
#define PDMA_UART5_RX 15UL /*!<DMA Connect to UART5 RX \hideinitializer */
#define PDMA_USCI0_TX 16UL /*!<DMA Connect to USCI0 TX \hideinitializer */
#define PDMA_USCI0_RX 17UL /*!<DMA Connect to USCI0 RX \hideinitializer */
#define PDMA_USCI1_TX 18UL /*!<DMA Connect to USCI1 TX \hideinitializer */
#define PDMA_USCI1_RX 19UL /*!<DMA Connect to USCI1 RX \hideinitializer */
#define PDMA_QSPI0_TX 20UL /*!<DMA Connect to QSPI0 TX \hideinitializer */
#define PDMA_QSPI0_RX 21UL /*!<DMA Connect to QSPI0 RX \hideinitializer */
#define PDMA_SPI0_TX 22UL /*!<DMA Connect to SPI0 TX \hideinitializer */
#define PDMA_SPI0_RX 23UL /*!<DMA Connect to SPI0 RX \hideinitializer */
#define PDMA_SPI1_TX 24UL /*!<DMA Connect to SPI1 TX \hideinitializer */
#define PDMA_SPI1_RX 25UL /*!<DMA Connect to SPI1 RX \hideinitializer */
#define PDMA_SPI2_TX 26UL /*!<DMA Connect to SPI2 TX \hideinitializer */
#define PDMA_SPI2_RX 27UL /*!<DMA Connect to SPI2 RX \hideinitializer */
#define PDMA_SPI3_TX 28UL /*!<DMA Connect to SPI3 TX \hideinitializer */
#define PDMA_SPI3_RX 29UL /*!<DMA Connect to SPI3 RX \hideinitializer */
#define PDMA_ADC_RX 30UL /*!<DMA Connect to ADC RX \hideinitializer */
#define PDMA_EPWM0_P1_RX 32UL /*!<DMA Connect to EPWM0 P1 RX \hideinitializer */
#define PDMA_EPWM0_P2_RX 33UL /*!<DMA Connect to EPWM0 P2 RX \hideinitializer */
#define PDMA_EPWM0_P3_RX 34UL /*!<DMA Connect to EPWM0 P3 RX \hideinitializer */
#define PDMA_EPWM1_P1_RX 35UL /*!<DMA Connect to EPWM1 P1 RX \hideinitializer */
#define PDMA_EPWM1_P2_RX 36UL /*!<DMA Connect to EPWM1 P2 RX \hideinitializer */
#define PDMA_EPWM1_P3_RX 37UL /*!<DMA Connect to EPWM1 P3 RX \hideinitializer */
#define PDMA_I2C0_TX 38UL /*!<DMA Connect to I2C0 TX \hideinitializer */
#define PDMA_I2C0_RX 39UL /*!<DMA Connect to I2C0 RX \hideinitializer */
#define PDMA_I2C1_TX 40UL /*!<DMA Connect to I2C1 TX \hideinitializer */
#define PDMA_I2C1_RX 41UL /*!<DMA Connect to I2C1 RX \hideinitializer */
#define PDMA_I2C2_TX 42UL /*!<DMA Connect to I2C2 TX \hideinitializer */
#define PDMA_I2C2_RX 43UL /*!<DMA Connect to I2C2 RX \hideinitializer */
#define PDMA_I2S0_TX 44UL /*!<DMA Connect to I2S0 TX \hideinitializer */
#define PDMA_I2S0_RX 45UL /*!<DMA Connect to I2S0 RX \hideinitializer */
#define PDMA_TMR0 46UL /*!<DMA Connect to TMR0 \hideinitializer */
#define PDMA_TMR1 47UL /*!<DMA Connect to TMR1 \hideinitializer */
#define PDMA_TMR2 48UL /*!<DMA Connect to TMR2 \hideinitializer */
#define PDMA_TMR3 49UL /*!<DMA Connect to TMR3 \hideinitializer */
#define PDMA_TMR4 50UL /*!<DMA Connect to TMR4 \hideinitializer */
#define PDMA_TMR5 51UL /*!<DMA Connect to TMR5 \hideinitializer */
#define PDMA_DAC0_TX 52UL /*!<DMA Connect to DAC0 TX \hideinitializer */
#define PDMA_DAC1_TX 53UL /*!<DMA Connect to DAC1 TX \hideinitializer */
#define PDMA_EPWM0_CH0_TX 54UL /*!<DMA Connect to EPWM0 CH0 TX \hideinitializer */
#define PDMA_EPWM0_CH1_TX 55UL /*!<DMA Connect to EPWM0 CH1 TX \hideinitializer */
#define PDMA_EPWM0_CH2_TX 56UL /*!<DMA Connect to EPWM0 CH2 TX \hideinitializer */
#define PDMA_EPWM0_CH3_TX 57UL /*!<DMA Connect to EPWM0 CH3 TX \hideinitializer */
#define PDMA_EPWM0_CH4_TX 58UL /*!<DMA Connect to EPWM0 CH4 TX \hideinitializer */
#define PDMA_EPWM0_CH5_TX 59UL /*!<DMA Connect to EPWM0 CH5 TX \hideinitializer */
#define PDMA_EPWM1_CH0_TX 60UL /*!<DMA Connect to EPWM1 CH0 TX \hideinitializer */
#define PDMA_EPWM1_CH1_TX 61UL /*!<DMA Connect to EPWM1 CH1 TX \hideinitializer */
#define PDMA_EPWM1_CH2_TX 62UL /*!<DMA Connect to EPWM1 CH2 TX \hideinitializer */
#define PDMA_EPWM1_CH3_TX 63UL /*!<DMA Connect to EPWM1 CH3 TX \hideinitializer */
#define PDMA_EPWM1_CH4_TX 64UL /*!<DMA Connect to EPWM1 CH4 TX \hideinitializer */
#define PDMA_EPWM1_CH5_TX 65UL /*!<DMA Connect to EPWM1 CH5 TX \hideinitializer */
/*---------------------------------------------------------------------------------------------------------*/
/* Interrupt Type Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define PDMA_INT_TRANS_DONE 0x00000000UL /*!<Transfer Done Interrupt \hideinitializer */
#define PDMA_INT_TABLE 0x00000001UL /*!<Table Interrupt \hideinitializer */
#define PDMA_INT_TIMEOUT 0x00000002UL /*!<Timeout Interrupt \hideinitializer */
#define PDMA_INT_ALIGN 0x00000003UL /*!<Transfer Alignment Interrupt \hideinitializer */
/**@}*/ /* end of group PDMA_EXPORTED_CONSTANTS */
/** @addtogroup PDMA_EXPORTED_FUNCTIONS PDMA Exported Functions
@{
*/
/**
* @brief Get PDMA Interrupt Status
*
* @param[in] pdma The pointer of the specified PDMA module
*
* @return None
*
* @details This macro gets the interrupt status.
*/
#define PDMA_GET_INT_STATUS(pdma) ((uint32_t)((pdma)->INTSTS))
/**
* @brief Get Transfer Done Interrupt Status
*
* @param[in] pdma The pointer of the specified PDMA module
*
* @return None
*
* @details Get the transfer done Interrupt status.
*/
#define PDMA_GET_TD_STS(pdma) ((uint32_t)((pdma)->TDSTS))
/**
* @brief Clear Transfer Done Interrupt Status
*
* @param[in] pdma The pointer of the specified PDMA module
* @param[in] u32Mask The channel mask
*
* @return None
*
* @details Clear the transfer done Interrupt status.
*/
#define PDMA_CLR_TD_FLAG(pdma, u32Mask) ((uint32_t)((pdma)->TDSTS = (u32Mask)))
/**
* @brief Get Target Abort Interrupt Status
*
* @param[in] pdma The pointer of the specified PDMA module
*
* @return None
*
* @details Get the target abort Interrupt status.
*/
#define PDMA_GET_ABORT_STS(pdma) ((uint32_t)((pdma)->ABTSTS))
/**
* @brief Clear Target Abort Interrupt Status
*
* @param[in] pdma The pointer of the specified PDMA module
* @param[in] u32Mask The channel mask
*
* @return None
*
* @details Clear the target abort Interrupt status.
*/
#define PDMA_CLR_ABORT_FLAG(pdma, u32Mask) ((uint32_t)((pdma)->ABTSTS = (u32Mask)))
/**
* @brief Get PDMA Transfer Alignment Status
*
* @param[in] pdma The pointer of the specified PDMA module
*
* @return None
*
* @details Get the PDMA transfer alignment status.
*/
#define PDMA_GET_ALIGN_STS(pdma) ((uint32_t)((pdma)->ALIGN))
/**
* @brief Clear PDMA Transfer Alignment Interrupt Status
*
* @param[in] pdma The pointer of the specified PDMA module
* @param[in] u32Mask The channel mask
*
* @return None
*
* @details Clear the PDMA transfer alignment Interrupt status.
*/
#define PDMA_CLR_ALIGN_FLAG(pdma, u32Mask) ((uint32_t)((pdma)->ALIGN = (u32Mask)))
/**
* @brief Clear Timeout Interrupt Status
*
* @param[in] pdma The pointer of the specified PDMA module
* @param[in] u32Ch The selected channel
*
* @return None
*
* @details Clear the selected channel timeout interrupt status.
* @note This function is only supported in channel 0 and channel 1.
*/
#define PDMA_CLR_TMOUT_FLAG(pdma, u32Ch) ((uint32_t)((pdma)->INTSTS = (1UL << ((u32Ch) + 8UL))))
/**
* @brief Check Channel Status
*
* @param[in] pdma The pointer of the specified PDMA module
* @param[in] u32Ch The selected channel
*
* @retval 0 Idle state
* @retval 1 Busy state
*
* @details Check the selected channel is busy or not.
*/
#define PDMA_IS_CH_BUSY(pdma, u32Ch) ((uint32_t)((pdma)->TRGSTS & (1UL << (u32Ch)))? 1 : 0)
/**
* @brief Set Source Address
*
* @param[in] pdma The pointer of the specified PDMA module
* @param[in] u32Ch The selected channel
* @param[in] u32Addr The selected address
*
* @return None
*
* @details This macro set the selected channel source address.
*/
#define PDMA_SET_SRC_ADDR(pdma, u32Ch, u32Addr) ((uint32_t)((pdma)->DSCT[(u32Ch)].SA = (u32Addr)))
/**
* @brief Set Destination Address
*
* @param[in] pdma The pointer of the specified PDMA module
* @param[in] u32Ch The selected channel
* @param[in] u32Addr The selected address
*
* @return None
*
* @details This macro set the selected channel destination address.
*/
#define PDMA_SET_DST_ADDR(pdma, u32Ch, u32Addr) ((uint32_t)((pdma)->DSCT[(u32Ch)].DA = (u32Addr)))
/**
* @brief Set Transfer Count
*
* @param[in] pdma The pointer of the specified PDMA module
* @param[in] u32Ch The selected channel
* @param[in] u32TransCount Transfer Count
*
* @return None
*
* @details This macro set the selected channel transfer count.
*/
#define PDMA_SET_TRANS_CNT(pdma, u32Ch, u32TransCount) ((uint32_t)((pdma)->DSCT[(u32Ch)].CTL=((pdma)->DSCT[(u32Ch)].CTL&~PDMA_DSCT_CTL_TXCNT_Msk)|(((u32TransCount)-1UL) << PDMA_DSCT_CTL_TXCNT_Pos)))
/**
* @brief Set Scatter-gather descriptor Address
*
* @param[in] pdma The pointer of the specified PDMA module
* @param[in] u32Ch The selected channel
* @param[in] u32Addr The descriptor address
*
* @return None
*
* @details This macro set the selected channel scatter-gather descriptor address.
*/
#define PDMA_SET_SCATTER_DESC(pdma, u32Ch, u32Addr) ((uint32_t)((pdma)->DSCT[(u32Ch)].NEXT = (u32Addr) - ((pdma)->SCATBA)))
/**
* @brief Stop the channel
*
* @param[in] pdma The pointer of the specified PDMA module
* @param[in] u32Ch The selected channel
*
* @return None
*
* @details This macro stop the selected channel.
*/
#define PDMA_STOP(pdma, u32Ch) ((uint32_t)((pdma)->PAUSE = (1UL << (u32Ch))))
/**
* @brief Pause the channel
*
* @param[in] pdma The pointer of the specified PDMA module
* @param[in] u32Ch The selected channel
*
* @return None
*
* @details This macro pause the selected channel.
*/
#define PDMA_PAUSE(pdma, u32Ch) ((uint32_t)((pdma)->PAUSE = (1UL << (u32Ch))))
/**
* @brief Reset the channel
*
* @param[in] pdma The pointer of the specified PDMA module
* @param[in] u32Ch The selected channel
*
* @return None
*
* @details This macro reset the selected channel.
*/
#define PDMA_RESET(pdma, u32Ch) ((uint32_t)((pdma)->CHRST = (1UL << (u32Ch))))
/*---------------------------------------------------------------------------------------------------------*/
/* Define PWM functions prototype */
/*---------------------------------------------------------------------------------------------------------*/
void PDMA_Open(PDMA_T *pdma, uint32_t u32Mask);
void PDMA_Close(PDMA_T *pdma);
void PDMA_SetTransferCnt(PDMA_T *pdma, uint32_t u32Ch, uint32_t u32Width, uint32_t u32TransCount);
void PDMA_SetStride(PDMA_T *pdma, uint32_t u32Ch, uint32_t u32DestLen, uint32_t u32SrcLen, uint32_t u32TransCount);
void PDMA_SetRepeat(PDMA_T * pdma, uint32_t u32Ch, uint32_t u32DestInterval, uint32_t u32SrcInterval, uint32_t u32RepeatCount);
void PDMA_SetTransferAddr(PDMA_T *pdma, uint32_t u32Ch, uint32_t u32SrcAddr, uint32_t u32SrcCtrl, uint32_t u32DstAddr, uint32_t u32DstCtrl);
void PDMA_SetTransferMode(PDMA_T *pdma, uint32_t u32Ch, uint32_t u32Peripheral, uint32_t u32ScatterEn, uint32_t u32DescAddr);
void PDMA_SetBurstType(PDMA_T *pdma, uint32_t u32Ch, uint32_t u32BurstType, uint32_t u32BurstSize);
void PDMA_EnableTimeout(PDMA_T *pdma, uint32_t u32Mask);
void PDMA_DisableTimeout(PDMA_T *pdma, uint32_t u32Mask);
void PDMA_SetTimeOut(PDMA_T *pdma, uint32_t u32Ch, uint32_t u32OnOff, uint32_t u32TimeOutCnt);
void PDMA_Trigger(PDMA_T *pdma, uint32_t u32Ch);
void PDMA_EnableInt(PDMA_T *pdma, uint32_t u32Ch, uint32_t u32Mask);
void PDMA_DisableInt(PDMA_T *pdma, uint32_t u32Ch, uint32_t u32Mask);
/**@}*/ /* end of group PDMA_EXPORTED_FUNCTIONS */
/**@}*/ /* end of group PDMA_Driver */
/**@}*/ /* end of group Standard_Driver */
#ifdef __cplusplus
}
#endif
#endif /* __NU_PDMA_H__ */

View File

@ -0,0 +1,95 @@
/**************************************************************************//**
* @file nu_plm.h
* @version V3.00
* @brief Product life cycle management
*
* @copyright SPDX-License-Identifier: Apache-2.0
* @copyright Copyright (C) 2020 Nuvoton Technology Corp. All rights reserved.
*****************************************************************************/
#ifndef __NU_PLM_H__
#define __NU_PLM_H__
#ifdef __cplusplus
extern "C"
{
#endif
/** @addtogroup Standard_Driver Standard Driver
@{
*/
/** @addtogroup PLM_Driver PLM Driver
@{
*/
/** @addtogroup PLM_EXPORTED_CONSTANTS PLM Exported Constants
@{
*/
typedef enum
{
PLM_VENDOR = 0,
PLM_OEM = 1,
PLM_DEPLOYED = 3,
PLM_RMA = 7
} PLM_STAGE_T;
#define PLM_VCODE (0x475A0000ul) /*!< The key code for PLM_CTL write. */
/**@}*/ /* end of group FVC_EXPORTED_CONSTANTS */
/** @addtogroup FVC_EXPORTED_FUNCTIONS FVC Exported Functions
@{
*/
/**
* @brief Get product life-cycle stage
* @return Current stage of PLM
* @details This function is used to Get PLM stage.
*/
#define PLM_GetStage() (PLM->STS & PLM_STS_STAGE_Msk)
/**
* @brief Set product life-cycle stage
* @param[in] stage Product life-cycle stage. It could be:
* \ref PLM_VENDOR
* \ref PLM_OEM
* \ref PLM_DEPLOYED
* \ref PLM_RMA
* @retval 0 Successful
* @retval -1 Failed
* @details This function is used to set PLM stage. It could be only be VENDOR, OEM, DEPLOYED and RMA.
* The setting of PLM cannot be rollback.
*/
__STATIC_INLINE int32_t PLM_SetStage(PLM_STAGE_T stage)
{
/* Do nothing when stage is not changed */
if(PLM_GetStage() == stage)
return 0;
PLM->CTL = PLM_VCODE | (stage);
/* The dirty flag should be set when PLM stage set successfully. */
if(PLM->STS & PLM_STS_DIRTY_Msk)
return -1;
return 0;
}
/**@}*/ /* end of group PLM_EXPORTED_FUNCTIONS */
/**@}*/ /* end of group PLM_Driver */
/**@}*/ /* end of group Standard_Driver */
#ifdef __cplusplus
}
#endif
#endif /* __NU_PLM_H__ */

View File

@ -0,0 +1,388 @@
/**************************************************************************//**
* @file nu_qei.h
* @version V3.00
* @brief Quadrature Encoder Interface (QEI) driver header file
*
* @copyright SPDX-License-Identifier: Apache-2.0
* @copyright Copyright (C) 2020 Nuvoton Technology Corp. All rights reserved.
*****************************************************************************/
#ifndef __NU_QEI_H__
#define __NU_QEI_H__
#ifdef __cplusplus
extern "C"
{
#endif
/** @addtogroup Standard_Driver Standard Driver
@{
*/
/** @addtogroup QEI_Driver QEI Driver
@{
*/
/** @addtogroup QEI_EXPORTED_CONSTANTS QEI Exported Constants
@{
*/
/*---------------------------------------------------------------------------------------------------------*/
/* QEI counting mode selection constants definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define QEI_CTL_X4_FREE_COUNTING_MODE (0x0<<QEI_CTL_MODE_Pos) /*!< QEI operate in X4 free-counting mode \hideinitializer */
#define QEI_CTL_X2_FREE_COUNTING_MODE (0x1<<QEI_CTL_MODE_Pos) /*!< QEI operate in X2 free-counting mode \hideinitializer */
#define QEI_CTL_X4_COMPARE_COUNTING_MODE (0x2<<QEI_CTL_MODE_Pos) /*!< QEI operate in X4 compare-counting mode \hideinitializer */
#define QEI_CTL_X2_COMPARE_COUNTING_MODE (0x3<<QEI_CTL_MODE_Pos) /*!< QEI operate in X2 compare-counting mode \hideinitializer */
/*---------------------------------------------------------------------------------------------------------*/
/* QEI noise filter clock pre-divide selection constants definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define QEI_CTL_NFCLKSEL_DIV1 (0x0<<QEI_CTL_NFCLKSEL_Pos) /*!< The sampling frequency of the noise filter is QEI_CLK \hideinitializer */
#define QEI_CTL_NFCLKSEL_DIV2 (0x1<<QEI_CTL_NFCLKSEL_Pos) /*!< The sampling frequency of the noise filter is QEI_CLK/2 \hideinitializer */
#define QEI_CTL_NFCLKSEL_DIV4 (0x2<<QEI_CTL_NFCLKSEL_Pos) /*!< The sampling frequency of the noise filter is QEI_CLK/4 \hideinitializer */
#define QEI_CTL_NFCLKSEL_DIV16 (0x3<<QEI_CTL_NFCLKSEL_Pos) /*!< The sampling frequency of the noise filter is QEI_CLK/16 \hideinitializer */
#define QEI_CTL_NFCLKSEL_DIV32 (0x4<<QEI_CTL_NFCLKSEL_Pos) /*!< The sampling frequency of the noise filter is QEI_CLK/32 \hideinitializer */
#define QEI_CTL_NFCLKSEL_DIV64 (0x5<<QEI_CTL_NFCLKSEL_Pos) /*!< The sampling frequency of the noise filter is QEI_CLK/64 \hideinitializer */
/**@}*/ /* end of group QEI_EXPORTED_CONSTANTS */
/** @addtogroup QEI_EXPORTED_FUNCTIONS QEI Exported Functions
@{
*/
/**
* @brief Disable QEI compare function
* @param[in] qei The pointer of the specified QEI module.
* @return None
* @details This macro disable QEI counter compare function.
* \hideinitializer
*/
#define QEI_DISABLE_CNT_CMP(qei) ((qei)->CTL &= (~QEI_CTL_CMPEN_Msk))
/**
* @brief Enable QEI compare function
* @param[in] qei The pointer of the specified QEI module.
* @return None
* @details This macro enable QEI counter compare function.
* \hideinitializer
*/
#define QEI_ENABLE_CNT_CMP(qei) ((qei)->CTL |= QEI_CTL_CMPEN_Msk)
/**
* @brief Disable QEI index latch function
* @param[in] qei The pointer of the specified QEI module.
* @return None
* @details This macro disable QEI index trigger counter latch function.
* \hideinitializer
*/
#define QEI_DISABLE_INDEX_LATCH(qei) ((qei)->CTL &= (~QEI_CTL_IDXLATEN_Msk))
/**
* @brief Enable QEI index latch function
* @param[in] qei The pointer of the specified QEI module.
* @return None
* @details This macro enable QEI index trigger counter latch function.
* \hideinitializer
*/
#define QEI_ENABLE_INDEX_LATCH(qei) ((qei)->CTL |= QEI_CTL_IDXLATEN_Msk)
/**
* @brief Disable QEI index reload function
* @param[in] qei The pointer of the specified QEI module.
* @return None
* @details This macro disable QEI index trigger counter reload function.
* \hideinitializer
*/
#define QEI_DISABLE_INDEX_RELOAD(qei) ((qei)->CTL &= (~QEI_CTL_IDXRLDEN_Msk))
/**
* @brief Enable QEI index reload function
* @param[in] qei The pointer of the specified QEI module.
* @return None
* @details This macro enable QEI index trigger counter reload function.
* \hideinitializer
*/
#define QEI_ENABLE_INDEX_RELOAD(qei) ((qei)->CTL |= QEI_CTL_IDXRLDEN_Msk)
/**
* @brief Disable QEI input
* @param[in] qei The pointer of the specified QEI module.
* @param[in] u32InputType Input signal type.
* - \ref QEI_CTL_CHAEN_Msk : QEA input
* - \ref QEI_CTL_CHAEN_Msk : QEB input
* - \ref QEI_CTL_IDXEN_Msk : IDX input
* @return None
* @details This macro disable specified QEI signal input.
* \hideinitializer
*/
#define QEI_DISABLE_INPUT(qei, u32InputType) ((qei)->CTL &= ~(u32InputType))
/**
* @brief Enable QEI input
* @param[in] qei The pointer of the specified QEI module.
* @param[in] u32InputType Input signal type .
* - \ref QEI_CTL_CHAEN_Msk : QEA input
* - \ref QEI_CTL_CHBEN_Msk : QEB input
* - \ref QEI_CTL_IDXEN_Msk : IDX input
* @return None
* @details This macro enable specified QEI signal input.
* \hideinitializer
*/
#define QEI_ENABLE_INPUT(qei, u32InputType) ((qei)->CTL |= (u32InputType))
/**
* @brief Disable inverted input polarity
* @param[in] qei The pointer of the specified QEI module.
* @param[in] u32InputType Input signal type .
* - \ref QEI_CTL_CHAINV_Msk : QEA Input
* - \ref QEI_CTL_CHBINV_Msk : QEB Input
* - \ref QEI_CTL_IDXINV_Msk : IDX Input
* @return None
* @details This macro disable specified QEI signal inverted input polarity.
* \hideinitializer
*/
#define QEI_DISABLE_INPUT_INV(qei, u32InputType) ((qei)->CTL &= ~(u32InputType))
/**
* @brief Enable inverted input polarity
* @param[in] qei The pointer of the specified QEI module.
* @param[in] u32InputType Input signal type.
* - \ref QEI_CTL_CHAINV_Msk : QEA Input
* - \ref QEI_CTL_CHBINV_Msk : QEB Input
* - \ref QEI_CTL_IDXINV_Msk : IDX Input
* @return None
* @details This macro inverse specified QEI signal input polarity.
* \hideinitializer
*/
#define QEI_ENABLE_INPUT_INV(qei, u32InputType) ((qei)->CTL |= (u32InputType))
/**
* @brief Disable QEI interrupt
* @param[in] qei The pointer of the specified QEI module.
* @param[in] u32IntSel Interrupt type selection.
* - \ref QEI_CTL_DIRIEN_Msk : Direction change interrupt
* - \ref QEI_CTL_OVUNIEN_Msk : Counter overflow or underflow interrupt
* - \ref QEI_CTL_CMPIEN_Msk : Compare-match interrupt
* - \ref QEI_CTL_IDXIEN_Msk : Index detected interrupt
* @return None
* @details This macro disable specified QEI interrupt.
* \hideinitializer
*/
#define QEI_DISABLE_INT(qei, u32IntSel) ((qei)->CTL &= ~(u32IntSel))
/**
* @brief Enable QEI interrupt
* @param[in] qei The pointer of the specified QEI module.
* @param[in] u32IntSel Interrupt type selection.
* - \ref QEI_CTL_DIRIEN_Msk : Direction change interrupt
* - \ref QEI_CTL_OVUNIEN_Msk : Counter overflow or underflow interrupt
* - \ref QEI_CTL_CMPIEN_Msk : Compare-match interrupt
* - \ref QEI_CTL_IDXIEN_Msk : Index detected interrupt
* @return None
* @details This macro enable specified QEI interrupt.
* \hideinitializer
*/
#define QEI_ENABLE_INT(qei, u32IntSel) ((qei)->CTL |= (u32IntSel))
/**
* @brief Disable QEI noise filter
* @param[in] qei The pointer of the specified QEI module.
* @return None
* @details This macro disable QEI noise filter function.
* \hideinitializer
*/
#define QEI_DISABLE_NOISE_FILTER(qei) ((qei)->CTL |= QEI_CTL_NFDIS_Msk)
/**
* @brief Enable QEI noise filter
* @param[in] qei The pointer of the specified QEI module.
* @param[in] u32ClkSel The sampling frequency of the noise filter clock.
* - \ref QEI_CTL_NFCLKSEL_DIV1
* - \ref QEI_CTL_NFCLKSEL_DIV2
* - \ref QEI_CTL_NFCLKSEL_DIV4
* - \ref QEI_CTL_NFCLKSEL_DIV16
* - \ref QEI_CTL_NFCLKSEL_DIV32
* - \ref QEI_CTL_NFCLKSEL_DIV64
* @return None
* @details This macro enable QEI noise filter function and select noise filter clock.
* \hideinitializer
*/
#define QEI_ENABLE_NOISE_FILTER(qei, u32ClkSel) ((qei)->CTL = ((qei)->CTL & (~(QEI_CTL_NFDIS_Msk|QEI_CTL_NFCLKSEL_Msk))) | (u32ClkSel))
/**
* @brief Get QEI counter value
* @param[in] qei The pointer of the specified QEI module.
* @return QEI pulse counter register value.
* @details This macro get QEI pulse counter value.
* \hideinitializer
*/
#define QEI_GET_CNT_VALUE(qei) ((qei)->CNT)
/**
* @brief Get QEI counting direction
* @param[in] qei The pointer of the specified QEI module.
* @retval 0 QEI counter is in down-counting.
* @retval 1 QEI counter is in up-counting.
* @details This macro get QEI counting direction.
* \hideinitializer
*/
#define QEI_GET_DIR(qei) (((qei)->STATUS & (QEI_STATUS_DIRF_Msk))?1:0)
/**
* @brief Get QEI counter hold value
* @param[in] qei The pointer of the specified QEI module.
* @return QEI pulse counter hold register value.
* @details This macro get QEI pulse counter hold value, which is updated with counter value in hold counter value control.
* \hideinitializer
*/
#define QEI_GET_HOLD_VALUE(qei) ((qei)->CNTHOLD)
/**
* @brief Get QEI counter index latch value
* @param[in] qei The pointer of the specified QEI module.
* @return QEI pulse counter index latch value
* @details This macro get QEI pulse counter index latch value, which is updated with counter value when the index is detected.
* \hideinitializer
*/
#define QEI_GET_INDEX_LATCH_VALUE(qei) ((qei)->CNTLATCH)
/**
* @brief Set QEI counter index latch value
* @param[in] qei The pointer of the specified QEI module.
* @param[in] u32Val The latch value.
* @return QEI pulse counter index latch value
* @details This macro set QEI pulse counter index latch value, which is updated with counter value when the index is detected.
* \hideinitializer
*/
#define QEI_SET_INDEX_LATCH_VALUE(qei,u32Val) ((qei)->CNTLATCH = (u32Val))
/**
* @brief Get QEI interrupt flag status
* @param[in] qei The pointer of the specified QEI module.
* @param[in] u32IntSel Interrupt type selection.
* - \ref QEI_STATUS_DIRF_Msk : Counting direction flag
* - \ref QEI_STATUS_DIRCHGF_Msk : Direction change flag
* - \ref QEI_STATUS_OVUNF_Msk : Counter overflow or underflow flag
* - \ref QEI_STATUS_CMPF_Msk : Compare-match flag
* - \ref QEI_STATUS_IDXF_Msk : Index detected flag
* @retval 0 QEI specified interrupt flag is not set.
* @retval 1 QEI specified interrupt flag is set.
* @details This macro get QEI specified interrupt flag status.
* \hideinitializer
*/
#define QEI_GET_INT_FLAG(qei, u32IntSel) (((qei)->STATUS & (u32IntSel))?1:0)
/**
* @brief Clear QEI interrupt flag
* @param[in] qei The pointer of the specified QEI module.
* @param[in] u32IntSel Interrupt type selection.
* - \ref QEI_STATUS_DIRCHGF_Msk : Direction change flag
* - \ref QEI_STATUS_OVUNF_Msk : Counter overflow or underflow flag
* - \ref QEI_STATUS_CMPF_Msk : Compare-match flag
* - \ref QEI_STATUS_IDXF_Msk : Index detected flag
* @return None
* @details This macro clear QEI specified interrupt flag.
* \hideinitializer
*/
#define QEI_CLR_INT_FLAG(qei, u32IntSel) ((qei)->STATUS = (u32IntSel))
/**
* @brief Set QEI counter compare value
* @param[in] qei The pointer of the specified QEI module.
* @param[in] u32Value The counter compare value.
* @return None
* @details This macro set QEI pulse counter compare value.
* \hideinitializer
*/
#define QEI_SET_CNT_CMP(qei, u32Value) ((qei)->CNTCMP = (u32Value))
/**
* @brief Set QEI counter value
* @param[in] qei The pointer of the specified QEI module.
* @param[in] u32Value The counter compare value.
* @return None
* @details This macro set QEI pulse counter value.
* \hideinitializer
*/
#define QEI_SET_CNT_VALUE(qei, u32Value) ((qei)->CNT = (u32Value))
/**
* @brief Enable QEI counter hold mode
* @param[in] qei The pointer of the specified QEI module.
* @param[in] u32Type The triggered type.
* - \ref QEI_CTL_HOLDCNT_Msk : Hold QEI_CNT control
* - \ref QEI_CTL_HOLDTMR0_Msk : Hold QEI_CNT by Timer0
* - \ref QEI_CTL_HOLDTMR1_Msk : Hold QEI_CNT by Timer1
* - \ref QEI_CTL_HOLDTMR2_Msk : Hold QEI_CNT by Timer2
* - \ref QEI_CTL_HOLDTMR3_Msk : Hold QEI_CNT by Timer3
* @return None
* @details This macro enable QEI counter hold mode.
* \hideinitializer
*/
#define QEI_ENABLE_HOLD_TRG_SRC(qei, u32Type) ((qei)->CTL |= (u32Type))
/**
* @brief Disable QEI counter hold mode
* @param[in] qei The pointer of the specified QEI module.
* @param[in] u32Type The triggered type.
* - \ref QEI_CTL_HOLDCNT_Msk : Hold QEI_CNT control
* - \ref QEI_CTL_HOLDTMR0_Msk : Hold QEI_CNT by Timer0
* - \ref QEI_CTL_HOLDTMR1_Msk : Hold QEI_CNT by Timer1
* - \ref QEI_CTL_HOLDTMR2_Msk : Hold QEI_CNT by Timer2
* - \ref QEI_CTL_HOLDTMR3_Msk : Hold QEI_CNT by Timer3
* @return None
* @details This macro disable QEI counter hold mode.
* \hideinitializer
*/
#define QEI_DISABLE_HOLD_TRG_SRC(qei, u32Type) ((qei)->CTL &= ~(u32Type))
/**
* @brief Set QEI maximum count value
* @param[in] qei The pointer of the specified QEI module.
* @param[in] u32Value The counter maximum value.
* @return QEI maximum count value
* @details This macro set QEI maximum count value.
* \hideinitializer
*/
#define QEI_SET_CNT_MAX(qei, u32Value) ((qei)->CNTMAX = (u32Value))
/**
* @brief Set QEI counting mode
* @param[in] qei The pointer of the specified QEI module.
* @param[in] u32Mode QEI counting mode.
* - \ref QEI_CTL_X4_FREE_COUNTING_MODE
* - \ref QEI_CTL_X2_FREE_COUNTING_MODE
* - \ref QEI_CTL_X4_COMPARE_COUNTING_MODE
* - \ref QEI_CTL_X2_COMPARE_COUNTING_MODE
* @return None
* @details This macro set QEI counting mode.
* \hideinitializer
*/
#define QEI_SET_CNT_MODE(qei, u32Mode) ((qei)->CTL = ((qei)->CTL & (~QEI_CTL_MODE_Msk)) | (u32Mode))
void QEI_Close(QEI_T* qei);
void QEI_DisableInt(QEI_T* qei, uint32_t u32IntSel);
void QEI_EnableInt(QEI_T* qei, uint32_t u32IntSel);
void QEI_Open(QEI_T* qei, uint32_t u32Mode, uint32_t u32Value);
void QEI_Start(QEI_T* qei);
void QEI_Stop(QEI_T* qei);
/**@}*/ /* end of group QEI_EXPORTED_FUNCTIONS */
/**@}*/ /* end of group QEI_Driver */
/**@}*/ /* end of group Standard_Driver */
#ifdef __cplusplus
}
#endif
#endif /*__NU_QEI_H__*/

View File

@ -0,0 +1,399 @@
/******************************************************************************
* @file nu_qspi.h
* @version V3.00
* @brief M2354 series QSPI driver header file
*
* @copyright SPDX-License-Identifier: Apache-2.0
* @copyright Copyright (C) 2020 Nuvoton Technology Corp. All rights reserved.
*****************************************************************************/
#ifndef __NU_QSPI_H__
#define __NU_QSPI_H__
#ifdef __cplusplus
extern "C"
{
#endif
/** @addtogroup Standard_Driver Standard Driver
@{
*/
/** @addtogroup QSPI_Driver QSPI Driver
@{
*/
/** @addtogroup QSPI_EXPORTED_CONSTANTS QSPI Exported Constants
@{
*/
#define QSPI_MODE_0 (QSPI_CTL_TXNEG_Msk) /*!< CLKPOL=0; RXNEG=0; TXNEG=1 */
#define QSPI_MODE_1 (QSPI_CTL_RXNEG_Msk) /*!< CLKPOL=0; RXNEG=1; TXNEG=0 */
#define QSPI_MODE_2 (QSPI_CTL_CLKPOL_Msk | QSPI_CTL_RXNEG_Msk) /*!< CLKPOL=1; RXNEG=1; TXNEG=0 */
#define QSPI_MODE_3 (QSPI_CTL_CLKPOL_Msk | QSPI_CTL_TXNEG_Msk) /*!< CLKPOL=1; RXNEG=0; TXNEG=1 */
#define QSPI_SLAVE (QSPI_CTL_SLAVE_Msk) /*!< Set as slave */
#define QSPI_MASTER (0x0UL) /*!< Set as master */
#define QSPI_SS (QSPI_SSCTL_SS_Msk) /*!< Set SS */
#define QSPI_SS_ACTIVE_HIGH (QSPI_SSCTL_SSACTPOL_Msk) /*!< SS active high */
#define QSPI_SS_ACTIVE_LOW (0x0UL) /*!< SS active low */
/* QSPI Interrupt Mask */
#define QSPI_UNIT_INT_MASK (0x001UL) /*!< Unit transfer interrupt mask */
#define QSPI_SSACT_INT_MASK (0x002UL) /*!< Slave selection signal active interrupt mask */
#define QSPI_SSINACT_INT_MASK (0x004UL) /*!< Slave selection signal inactive interrupt mask */
#define QSPI_SLVUR_INT_MASK (0x008UL) /*!< Slave under run interrupt mask */
#define QSPI_SLVBE_INT_MASK (0x010UL) /*!< Slave bit count error interrupt mask */
#define QSPI_SLVTO_INT_MASK (0x020UL) /*!< Slave Mode Time-out interrupt mask */
#define QSPI_TXUF_INT_MASK (0x040UL) /*!< Slave TX underflow interrupt mask */
#define QSPI_FIFO_TXTH_INT_MASK (0x080UL) /*!< FIFO TX threshold interrupt mask */
#define QSPI_FIFO_RXTH_INT_MASK (0x100UL) /*!< FIFO RX threshold interrupt mask */
#define QSPI_FIFO_RXOV_INT_MASK (0x200UL) /*!< FIFO RX overrun interrupt mask */
#define QSPI_FIFO_RXTO_INT_MASK (0x400UL) /*!< FIFO RX time-out interrupt mask */
/* QSPI Status Mask */
#define QSPI_BUSY_MASK (0x01UL) /*!< Busy status mask */
#define QSPI_RX_EMPTY_MASK (0x02UL) /*!< RX empty status mask */
#define QSPI_RX_FULL_MASK (0x04UL) /*!< RX full status mask */
#define QSPI_TX_EMPTY_MASK (0x08UL) /*!< TX empty status mask */
#define QSPI_TX_FULL_MASK (0x10UL) /*!< TX full status mask */
#define QSPI_TXRX_RESET_MASK (0x20UL) /*!< TX or RX reset status mask */
#define QSPI_SPIEN_STS_MASK (0x40UL) /*!< SPIEN status mask */
#define QSPI_SSLINE_STS_MASK (0x80UL) /*!< QSPIx_SS line status mask */
/* QSPI Status2 Mask */
#define QSPI_SLVBENUM_MASK (0x01UL) /*!< Effective bit number of uncompleted RX data status mask */
/**@}*/ /* end of group QSPI_EXPORTED_CONSTANTS */
/** @addtogroup QSPI_EXPORTED_FUNCTIONS QSPI Exported Functions
@{
*/
/**
* @brief Clear the unit transfer interrupt flag.
* @param[in] qspi The pointer of the specified QSPI module.
* @return None.
* @details Write 1 to UNITIF bit of QSPI_STATUS register to clear the unit transfer interrupt flag.
*/
#define QSPI_CLR_UNIT_TRANS_INT_FLAG(qspi) ( (qspi)->STATUS = QSPI_STATUS_UNITIF_Msk )
/**
* @brief Disable 2-bit Transfer mode.
* @param[in] qspi The pointer of the specified QSPI module.
* @return None.
* @details Clear TWOBIT bit of QSPI_CTL register to disable 2-bit Transfer mode.
*/
#define QSPI_DISABLE_2BIT_MODE(qspi) ( (qspi)->CTL &= ~QSPI_CTL_TWOBIT_Msk )
/**
* @brief Disable Slave 3-wire mode.
* @param[in] qspi The pointer of the specified QSPI module.
* @return None.
* @details Clear SLV3WIRE bit of QSPI_SSCTL register to disable Slave 3-wire mode.
*/
#define QSPI_DISABLE_3WIRE_MODE(qspi) ( (qspi)->SSCTL &= ~QSPI_SSCTL_SLV3WIRE_Msk )
/**
* @brief Disable Dual I/O mode.
* @param[in] qspi The pointer of the specified QSPI module.
* @return None.
* @details Clear DUALIOEN bit of QSPI_CTL register to disable Dual I/O mode.
*/
#define QSPI_DISABLE_DUAL_MODE(qspi) ( (qspi)->CTL &= ~QSPI_CTL_DUALIOEN_Msk )
/**
* @brief Disable Quad I/O mode.
* @param[in] qspi The pointer of the specified QSPI module.
* @return None.
* @details Clear QUADIOEN bit of QSPI_CTL register to disable Quad I/O mode.
*/
#define QSPI_DISABLE_QUAD_MODE(qspi) ( (qspi)->CTL &= ~QSPI_CTL_QUADIOEN_Msk )
/**
* @brief Disable TX DTR mode.
* @param[in] qspi The pointer of the specified QSPI module.
* @return None.
* @details Clear TXDTREN bit of QSPI_CTL register to disable TX DTR mode.
*/
#define QSPI_DISABLE_TXDTR_MODE(qspi) ( (qspi)->CTL &= ~QSPI_CTL_TXDTREN_Msk )
/**
* @brief Enable 2-bit Transfer mode.
* @param[in] qspi The pointer of the specified QSPI module.
* @return None.
* @details Set TWOBIT bit of QSPI_CTL register to enable 2-bit Transfer mode.
*/
#define QSPI_ENABLE_2BIT_MODE(qspi) ( (qspi)->CTL |= QSPI_CTL_TWOBIT_Msk )
/**
* @brief Enable Slave 3-wire mode.
* @param[in] qspi The pointer of the specified QSPI module.
* @return None.
* @details Set SLV3WIRE bit of QSPI_SSCTL register to enable Slave 3-wire mode.
*/
#define QSPI_ENABLE_3WIRE_MODE(qspi) ( (qspi)->SSCTL |= QSPI_SSCTL_SLV3WIRE_Msk )
/**
* @brief Enable Dual input mode.
* @param[in] qspi The pointer of the specified QSPI module.
* @return None.
* @details Clear DATDIR bit and set DUALIOEN bit of QSPI_CTL register to enable Dual input mode.
*/
#define QSPI_ENABLE_DUAL_INPUT_MODE(qspi) ( (qspi)->CTL = ((qspi)->CTL & (~QSPI_CTL_DATDIR_Msk)) | QSPI_CTL_DUALIOEN_Msk )
/**
* @brief Enable Dual output mode.
* @param[in] qspi The pointer of the specified QSPI module.
* @return None.
* @details Set DATDIR bit and DUALIOEN bit of QSPI_CTL register to enable Dual output mode.
*/
#define QSPI_ENABLE_DUAL_OUTPUT_MODE(qspi) ( (qspi)->CTL |= (QSPI_CTL_DATDIR_Msk | QSPI_CTL_DUALIOEN_Msk) )
/**
* @brief Enable Quad input mode.
* @param[in] qspi The pointer of the specified QSPI module.
* @return None.
* @details Clear DATDIR bit and set QUADIOEN bit of QSPI_CTL register to enable Quad input mode.
*/
#define QSPI_ENABLE_QUAD_INPUT_MODE(qspi) ( (qspi)->CTL = ((qspi)->CTL & (~QSPI_CTL_DATDIR_Msk)) | QSPI_CTL_QUADIOEN_Msk )
/**
* @brief Enable Quad output mode.
* @param[in] qspi The pointer of the specified QSPI module.
* @return None.
* @details Set DATDIR bit and QUADIOEN bit of QSPI_CTL register to enable Quad output mode.
*/
#define QSPI_ENABLE_QUAD_OUTPUT_MODE(qspi) ( (qspi)->CTL |= (QSPI_CTL_DATDIR_Msk | QSPI_CTL_QUADIOEN_Msk) )
/**
* @brief Enable TX DTR mode.
* @param[in] qspi The pointer of the specified QSPI module.
* @return None.
* @details Set TXDTREN bit of QSPI_CTL register to enable TX DTR mode.
*/
#define QSPI_ENABLE_TXDTR_MODE(qspi) ( (qspi)->CTL |= QSPI_CTL_TXDTREN_Msk )
/**
* @brief Trigger RX PDMA function.
* @param[in] qspi The pointer of the specified QSPI module.
* @return None.
* @details Set RXPDMAEN bit of QSPI_PDMACTL register to enable RX PDMA transfer function.
*/
#define QSPI_TRIGGER_RX_PDMA(qspi) ( (qspi)->PDMACTL |= QSPI_PDMACTL_RXPDMAEN_Msk )
/**
* @brief Trigger TX PDMA function.
* @param[in] qspi The pointer of the specified QSPI module.
* @return None.
* @details Set TXPDMAEN bit of QSPI_PDMACTL register to enable TX PDMA transfer function.
*/
#define QSPI_TRIGGER_TX_PDMA(qspi) ( (qspi)->PDMACTL |= QSPI_PDMACTL_TXPDMAEN_Msk )
/**
* @brief Trigger TX and RX PDMA function.
* @param[in] qspi The pointer of the specified QSPI module.
* @return None.
* @details Set TXPDMAEN bit and RXPDMAEN bit of QSPI_PDMACTL register to enable TX and RX PDMA transfer function.
*/
#define QSPI_TRIGGER_TX_RX_PDMA(qspi) ( (qspi)->PDMACTL |= (QSPI_PDMACTL_TXPDMAEN_Msk | QSPI_PDMACTL_RXPDMAEN_Msk) )
/**
* @brief Disable RX PDMA transfer.
* @param[in] qspi The pointer of the specified QSPI module.
* @return None.
* @details Clear RXPDMAEN bit of QSPI_PDMACTL register to disable RX PDMA transfer function.
*/
#define QSPI_DISABLE_RX_PDMA(qspi) ( (qspi)->PDMACTL &= ~QSPI_PDMACTL_RXPDMAEN_Msk )
/**
* @brief Disable TX PDMA transfer.
* @param[in] qspi The pointer of the specified QSPI module.
* @return None.
* @details Clear TXPDMAEN bit of QSPI_PDMACTL register to disable TX PDMA transfer function.
*/
#define QSPI_DISABLE_TX_PDMA(qspi) ( (qspi)->PDMACTL &= ~QSPI_PDMACTL_TXPDMAEN_Msk )
/**
* @brief Disable TX and RX PDMA transfer.
* @param[in] qspi The pointer of the specified QSPI module.
* @return None.
* @details Clear TXPDMAEN bit and RXPDMAEN bit of QSPI_PDMACTL register to disable TX and RX PDMA transfer function.
*/
#define QSPI_DISABLE_TX_RX_PDMA(qspi) ( (qspi)->PDMACTL &= ~(QSPI_PDMACTL_TXPDMAEN_Msk | QSPI_PDMACTL_RXPDMAEN_Msk) )
/**
* @brief Get the count of available data in RX FIFO.
* @param[in] qspi The pointer of the specified QSPI module.
* @return The count of available data in RX FIFO.
* @details Read RXCNT (QSPI_STATUS[27:24]) to get the count of available data in RX FIFO.
*/
#define QSPI_GET_RX_FIFO_COUNT(qspi) ( ((qspi)->STATUS & QSPI_STATUS_RXCNT_Msk) >> QSPI_STATUS_RXCNT_Pos )
/**
* @brief Get the RX FIFO empty flag.
* @param[in] qspi The pointer of the specified QSPI module.
* @retval 0 RX FIFO is not empty.
* @retval 1 RX FIFO is empty.
* @details Read RXEMPTY bit of QSPI_STATUS register to get the RX FIFO empty flag.
*/
#define QSPI_GET_RX_FIFO_EMPTY_FLAG(qspi) ( ((qspi)->STATUS & QSPI_STATUS_RXEMPTY_Msk) >> QSPI_STATUS_RXEMPTY_Pos )
/**
* @brief Get the TX FIFO empty flag.
* @param[in] qspi The pointer of the specified QSPI module.
* @retval 0 TX FIFO is not empty.
* @retval 1 TX FIFO is empty.
* @details Read TXEMPTY bit of QSPI_STATUS register to get the TX FIFO empty flag.
*/
#define QSPI_GET_TX_FIFO_EMPTY_FLAG(qspi) ( ((qspi)->STATUS & QSPI_STATUS_TXEMPTY_Msk) >> QSPI_STATUS_TXEMPTY_Pos )
/**
* @brief Get the TX FIFO full flag.
* @param[in] qspi The pointer of the specified QSPI module.
* @retval 0 TX FIFO is not full.
* @retval 1 TX FIFO is full.
* @details Read TXFULL bit of QSPI_STATUS register to get the TX FIFO full flag.
*/
#define QSPI_GET_TX_FIFO_FULL_FLAG(qspi) ( ((qspi)->STATUS & QSPI_STATUS_TXFULL_Msk) >> QSPI_STATUS_TXFULL_Pos )
/**
* @brief Get the datum read from RX register.
* @param[in] qspi The pointer of the specified QSPI module.
* @return Data in RX register.
* @details Read QSPI_RX register to get the received datum.
*/
#define QSPI_READ_RX(qspi) ( (qspi)->RX )
/**
* @brief Write datum to TX register.
* @param[in] qspi The pointer of the specified QSPI module.
* @param[in] u32TxData The datum which user attempt to transfer through QSPI bus.
* @return None.
* @details Write u32TxData to QSPI_TX register.
*/
#define QSPI_WRITE_TX(qspi, u32TxData) ( (qspi)->TX = (u32TxData) )
/**
* @brief Set QSPIx_SS pin to high state.
* @param[in] qspi The pointer of the specified QSPI module.
* @return None.
* @details Disable automatic slave selection function and set QSPIx_SS pin to high state.
*/
#define QSPI_SET_SS_HIGH(qspi) ( (qspi)->SSCTL = ((qspi)->SSCTL & (~QSPI_SSCTL_AUTOSS_Msk)) | (QSPI_SSCTL_SSACTPOL_Msk | QSPI_SSCTL_SS_Msk) )
/**
* @brief Set QSPIx_SS pin to low state.
* @param[in] qspi The pointer of the specified QSPI module.
* @return None.
* @details Disable automatic slave selection function and set QSPIx_SS pin to low state.
*/
#define QSPI_SET_SS_LOW(qspi) ( (qspi)->SSCTL = ((qspi)->SSCTL & (~(QSPI_SSCTL_AUTOSS_Msk | QSPI_SSCTL_SSACTPOL_Msk))) | QSPI_SSCTL_SS_Msk )
/**
* @brief Enable Byte Reorder function.
* @param[in] qspi The pointer of the specified QSPI module.
* @return None.
* @details Enable Byte Reorder function. The suspend interval depends on the setting of SUSPITV (QSPI_CTL[7:4]).
*/
#define QSPI_ENABLE_BYTE_REORDER(qspi) ( (qspi)->CTL |= QSPI_CTL_REORDER_Msk )
/**
* @brief Disable Byte Reorder function.
* @param[in] qspi The pointer of the specified QSPI module.
* @return None.
* @details Clear REORDER bit field of QSPI_CTL register to disable Byte Reorder function.
*/
#define QSPI_DISABLE_BYTE_REORDER(qspi) ( (qspi)->CTL &= ~QSPI_CTL_REORDER_Msk )
/**
* @brief Set the length of suspend interval.
* @param[in] qspi The pointer of the specified QSPI module.
* @param[in] u32SuspCycle Decides the length of suspend interval. It could be 0 ~ 15.
* @return None.
* @details Set the length of suspend interval according to u32SuspCycle.
* The length of suspend interval is ((u32SuspCycle + 0.5) * the length of one QSPI bus clock cycle).
*/
#define QSPI_SET_SUSPEND_CYCLE(qspi, u32SuspCycle) ( (qspi)->CTL = ((qspi)->CTL & ~QSPI_CTL_SUSPITV_Msk) | ((u32SuspCycle) << QSPI_CTL_SUSPITV_Pos) )
/**
* @brief Set the QSPI transfer sequence with LSB first.
* @param[in] qspi The pointer of the specified QSPI module.
* @return None.
* @details Set LSB bit of QSPI_CTL register to set the QSPI transfer sequence with LSB first.
*/
#define QSPI_SET_LSB_FIRST(qspi) ( (qspi)->CTL |= QSPI_CTL_LSB_Msk )
/**
* @brief Set the QSPI transfer sequence with MSB first.
* @param[in] qspi The pointer of the specified QSPI module.
* @return None.
* @details Clear LSB bit of QSPI_CTL register to set the QSPI transfer sequence with MSB first.
*/
#define QSPI_SET_MSB_FIRST(qspi) ( (qspi)->CTL &= ~QSPI_CTL_LSB_Msk )
/**
* @brief Set the data width of a QSPI transaction.
* @param[in] qspi The pointer of the specified QSPI module.
* @param[in] u32Width The bit width of one transaction.
* @return None.
* @details The data width can be 8 ~ 32 bits.
*/
#define QSPI_SET_DATA_WIDTH(qspi, u32Width) ( (qspi)->CTL = ((qspi)->CTL & ~QSPI_CTL_DWIDTH_Msk) | (((u32Width) & 0x1F) << QSPI_CTL_DWIDTH_Pos) )
/**
* @brief Get the QSPI busy state.
* @param[in] qspi The pointer of the specified QSPI module.
* @retval 0 QSPI controller is not busy.
* @retval 1 QSPI controller is busy.
* @details This macro will return the busy state of QSPI controller.
*/
#define QSPI_IS_BUSY(qspi) ( ((qspi)->STATUS & QSPI_STATUS_BUSY_Msk) >> QSPI_STATUS_BUSY_Pos )
/**
* @brief Enable QSPI controller.
* @param[in] qspi The pointer of the specified QSPI module.
* @return None.
* @details Set SPIEN (QSPI_CTL[0]) to enable QSPI controller.
*/
#define QSPI_ENABLE(qspi) ( (qspi)->CTL |= QSPI_CTL_SPIEN_Msk )
/**
* @brief Disable QSPI controller.
* @param[in] qspi The pointer of the specified QSPI module.
* @return None.
* @details Clear SPIEN (QSPI_CTL[0]) to disable QSPI controller.
*/
#define QSPI_DISABLE(qspi) ( (qspi)->CTL &= ~QSPI_CTL_SPIEN_Msk )
/* Function prototype declaration */
uint32_t QSPI_Open(QSPI_T *qspi, uint32_t u32MasterSlave, uint32_t u32QSPIMode, uint32_t u32DataWidth, uint32_t u32BusClock);
void QSPI_Close(QSPI_T *qspi);
void QSPI_ClearRxFIFO(QSPI_T *qspi);
void QSPI_ClearTxFIFO(QSPI_T *qspi);
void QSPI_DisableAutoSS(QSPI_T *qspi);
void QSPI_EnableAutoSS(QSPI_T *qspi, uint32_t u32SSPinMask, uint32_t u32ActiveLevel);
uint32_t QSPI_SetBusClock(QSPI_T *qspi, uint32_t u32BusClock);
void QSPI_SetFIFO(QSPI_T *qspi, uint32_t u32TxThreshold, uint32_t u32RxThreshold);
uint32_t QSPI_GetBusClock(QSPI_T *qspi);
void QSPI_EnableInt(QSPI_T *qspi, uint32_t u32Mask);
void QSPI_DisableInt(QSPI_T *qspi, uint32_t u32Mask);
uint32_t QSPI_GetIntFlag(QSPI_T *qspi, uint32_t u32Mask);
void QSPI_ClearIntFlag(QSPI_T *qspi, uint32_t u32Mask);
uint32_t QSPI_GetStatus(QSPI_T *qspi, uint32_t u32Mask);
uint32_t QSPI_GetStatus2(QSPI_T *qspi, uint32_t u32Mask);
/**@}*/ /* end of group QSPI_EXPORTED_FUNCTIONS */
/**@}*/ /* end of group QSPI_Driver */
/**@}*/ /* end of group Standard_Driver */
#ifdef __cplusplus
}
#endif
#endif /* __NU_QSPI_H__ */

View File

@ -0,0 +1,57 @@
/**************************************************************************//**
* @file nu_rng.h
* @version V3.00
* @brief Random Number Generator Interface Controller (rng) driver header file
*
* @copyright SPDX-License-Identifier: Apache-2.0
* @copyright Copyright (C) 2020 Nuvoton Technology Corp. All rights reserved.
*****************************************************************************/
#ifndef __NU_RNG_H__
#define __NU_RNG_H__
#ifdef __cplusplus
extern "C"
{
#endif
/** @addtogroup Standard_Driver Standard Driver
@{
*/
/** @addtogroup RNG_Driver RNG Driver
@{
*/
/** @addtogroup RNG_EXPORTED_CONSTANTS RNG Exported Constants
@{
*/
/**@}*/ /* end of group RNG_EXPORTED_CONSTANTS */
/** @addtogroup RNG_EXPORTED_FUNCTIONS RNG Exported Functions
@{
*/
int32_t RNG_Open(void);
int32_t RNG_Random(uint32_t *pu32Buf, int32_t nWords);
int32_t RNG_ECDSA_Init(uint32_t u32KeySize, uint32_t au32ECC_N[18]);
int32_t RNG_ECDSA(uint32_t u32KeySize);
int32_t RNG_ECDH_Init(uint32_t u32KeySize, uint32_t au32ECC_N[18]);
int32_t RNG_ECDH(uint32_t u32KeySize);
/**@}*/ /* end of group RNG_EXPORTED_FUNCTIONS */
/**@}*/ /* end of group RNG_Driver */
/**@}*/ /* end of group Standard_Driver */
#ifdef __cplusplus
}
#endif
#endif /* __NU_RNG_H__ */

View File

@ -0,0 +1,396 @@
/**************************************************************************//**
* @file nu_rtc.h
* @version V3.00
* @brief Real Time Clock(RTC) driver header file
*
* @copyright SPDX-License-Identifier: Apache-2.0
* @copyright Copyright (C) 2020 Nuvoton Technology Corp. All rights reserved.
*****************************************************************************/
#ifndef __NU_RTC_H__
#define __NU_RTC_H__
#ifdef __cplusplus
extern "C"
{
#endif
/** @addtogroup Standard_Driver Standard Driver
@{
*/
/** @addtogroup RTC_Driver RTC Driver
@{
*/
/** @addtogroup RTC_EXPORTED_CONSTANTS RTC Exported Constants
@{
*/
/*---------------------------------------------------------------------------------------------------------*/
/* RTC Initial Keyword Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define RTC_INIT_KEY 0xA5EB1357UL /*!< RTC Initiation Key to make RTC leaving reset state \hideinitializer */
/*---------------------------------------------------------------------------------------------------------*/
/* RTC Time Attribute Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define RTC_CLOCK_12 0UL /*!< RTC as 12-hour time scale with AM and PM indication \hideinitializer */
#define RTC_CLOCK_24 1UL /*!< RTC as 24-hour time scale \hideinitializer */
#define RTC_AM 1UL /*!< RTC as AM indication \hideinitializer */
#define RTC_PM 2UL /*!< RTC as PM indication \hideinitializer */
/*---------------------------------------------------------------------------------------------------------*/
/* RTC Tick Period Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define RTC_TICK_1_SEC 0x0UL /*!< RTC time tick period is 1 second \hideinitializer */
#define RTC_TICK_1_2_SEC 0x1UL /*!< RTC time tick period is 1/2 second \hideinitializer */
#define RTC_TICK_1_4_SEC 0x2UL /*!< RTC time tick period is 1/4 second \hideinitializer */
#define RTC_TICK_1_8_SEC 0x3UL /*!< RTC time tick period is 1/8 second \hideinitializer */
#define RTC_TICK_1_16_SEC 0x4UL /*!< RTC time tick period is 1/16 second \hideinitializer */
#define RTC_TICK_1_32_SEC 0x5UL /*!< RTC time tick period is 1/32 second \hideinitializer */
#define RTC_TICK_1_64_SEC 0x6UL /*!< RTC time tick period is 1/64 second \hideinitializer */
#define RTC_TICK_1_128_SEC 0x7UL /*!< RTC time tick period is 1/128 second \hideinitializer */
/*---------------------------------------------------------------------------------------------------------*/
/* RTC Day of Week Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define RTC_SUNDAY 0x0UL /*!< Day of the Week is Sunday \hideinitializer */
#define RTC_MONDAY 0x1UL /*!< Day of the Week is Monday \hideinitializer */
#define RTC_TUESDAY 0x2UL /*!< Day of the Week is Tuesday \hideinitializer */
#define RTC_WEDNESDAY 0x3UL /*!< Day of the Week is Wednesday \hideinitializer */
#define RTC_THURSDAY 0x4UL /*!< Day of the Week is Thursday \hideinitializer */
#define RTC_FRIDAY 0x5UL /*!< Day of the Week is Friday \hideinitializer */
#define RTC_SATURDAY 0x6UL /*!< Day of the Week is Saturday \hideinitializer */
/*---------------------------------------------------------------------------------------------------------*/
/* RTC Miscellaneous Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define RTC_YEAR2000 2000UL /*!< RTC Reference for compute year data \hideinitializer */
#define RTC_FCR_REFERENCE 32752 /*!< RTC Reference for frequency compensation */
/*---------------------------------------------------------------------------------------------------------*/
/* RTC Tamper Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define RTC_TAMPER0_SELECT (0x1UL << 0) /*!< Select Tamper 0 \hideinitializer */
#define RTC_TAMPER1_SELECT (0x1UL << 1) /*!< Select Tamper 1 \hideinitializer */
#define RTC_TAMPER2_SELECT (0x1UL << 2) /*!< Select Tamper 2 \hideinitializer */
#define RTC_TAMPER3_SELECT (0x1UL << 3) /*!< Select Tamper 3 \hideinitializer */
#define RTC_TAMPER4_SELECT (0x1UL << 4) /*!< Select Tamper 4 \hideinitializer */
#define RTC_TAMPER5_SELECT (0x1UL << 5) /*!< Select Tamper 5 \hideinitializer */
#define RTC_MAX_TAMPER_PIN_NUM 6UL /*!< Tamper Pin number \hideinitializer */
#define RTC_TAMPER_LOW_LEVEL_DETECT 0UL /*!< Tamper pin detect voltage level is low \hideinitializer */
#define RTC_TAMPER_HIGH_LEVEL_DETECT 1UL /*!< Tamper pin detect voltage level is high \hideinitializer */
#define RTC_TAMPER_DEBOUNCE_DISABLE 0UL /*!< Disable RTC tamper pin de-bounce function \hideinitializer */
#define RTC_TAMPER_DEBOUNCE_ENABLE 1UL /*!< Enable RTC tamper pin de-bounce function \hideinitializer */
#define RTC_PAIR0_SELECT (0x1UL << 0) /*!< Select Pair 0 \hideinitializer */
#define RTC_PAIR1_SELECT (0x1UL << 1) /*!< Select Pair 1 \hideinitializer */
#define RTC_PAIR2_SELECT (0x1UL << 2) /*!< Select Pair 2 \hideinitializer */
#define RTC_MAX_PAIR_NUM 3UL /*!< Pair number \hideinitializer */
#define RTC_2POW10_CLK (0x0UL << RTC_TAMPCTL_DYNRATE_Pos) /*!< 1024 RTC clock cycles \hideinitializer */
#define RTC_2POW11_CLK (0x1UL << RTC_TAMPCTL_DYNRATE_Pos) /*!< 1024 x 2 RTC clock cycles \hideinitializer */
#define RTC_2POW12_CLK (0x2UL << RTC_TAMPCTL_DYNRATE_Pos) /*!< 1024 x 4 RTC clock cycles \hideinitializer */
#define RTC_2POW13_CLK (0x3UL << RTC_TAMPCTL_DYNRATE_Pos) /*!< 1024 x 6 RTC clock cycles \hideinitializer */
#define RTC_2POW14_CLK (0x4UL << RTC_TAMPCTL_DYNRATE_Pos) /*!< 1024 x 8 RTC clock cycles \hideinitializer */
#define RTC_2POW15_CLK (0x5UL << RTC_TAMPCTL_DYNRATE_Pos) /*!< 1024 x 16 RTC clock cycles \hideinitializer */
#define RTC_2POW16_CLK (0x6UL << RTC_TAMPCTL_DYNRATE_Pos) /*!< 1024 x 32 RTC clock cycles \hideinitializer */
#define RTC_2POW17_CLK (0x7UL << RTC_TAMPCTL_DYNRATE_Pos) /*!< 1024 x 64 RTC clock cycles \hideinitializer */
#define RTC_REF_RANDOM_PATTERN 0x0UL /*!< The new reference pattern is generated by random number generator when the reference pattern run out \hideinitializer */
#define RTC_REF_SEED_VALUE 0x1UL /*!< The new reference pattern is repeated from SEED (RTC_TAMPSEED[31:0]) when the reference pattern run out \hideinitializer */
/*---------------------------------------------------------------------------------------------------------*/
/* RTC Clock Source Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define RTC_CLOCK_SOURCE_LXT 0UL /*!< Set RTC clock source as external LXT \hideinitializer */
#define RTC_CLOCK_SOURCE_LIRC 1UL /*!< Set RTC clock source as LIRC \hideinitializer */
#define RTC_CLOCK_SOURCE_LIRC32K 2UL /*!< Set RTC clock source as LIRC32K \hideinitializer */
/*---------------------------------------------------------------------------------------------------------*/
/* RTC GPIO_MODE Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define RTC_IO_MODE_INPUT 0x0UL /*!< Input Mode */
#define RTC_IO_MODE_OUTPUT 0x1UL /*!< Output Mode */
#define RTC_IO_MODE_OPEN_DRAIN 0x2UL /*!< Open-Drain Mode */
#define RTC_IO_MODE_QUASI 0x3UL /*!< Quasi-bidirectional Mode */
#define RTC_IO_DIGITAL_ENABLE 0UL /*!< I/O digital path is enabled */
#define RTC_IO_DIGITAL_DISABLE 1UL /*!< I/O digital path is disabled */
#define RTC_IO_PULL_UP_DOWN_DISABLE 0x0UL /*!< I/O pull-up and pull-down is disabled */
#define RTC_IO_PULL_UP_ENABLE 0x1UL /*!< I/O pull-up is enabled */
#define RTC_IO_PULL_DOWN_ENABLE 0x2UL /*!< I/O pull-down is enabled */
/**@}*/ /* end of group RTC_EXPORTED_CONSTANTS */
/** @addtogroup RTC_EXPORTED_STRUCTS RTC Exported Structs
@{
*/
/**
* @details RTC define Time Data Struct
*/
typedef struct
{
uint32_t u32Year; /*!< Year value */
uint32_t u32Month; /*!< Month value */
uint32_t u32Day; /*!< Day value */
uint32_t u32DayOfWeek; /*!< Day of week value */
uint32_t u32Hour; /*!< Hour value */
uint32_t u32Minute; /*!< Minute value */
uint32_t u32Second; /*!< Second value */
uint32_t u32TimeScale; /*!< 12-Hour, 24-Hour */
uint32_t u32AmPm; /*!< Only Time Scale select 12-hr used */
} S_RTC_TIME_DATA_T;
/**@}*/ /* end of group RTC_EXPORTED_STRUCTS */
/** @addtogroup RTC_EXPORTED_FUNCTIONS RTC Exported Functions
@{
*/
/**
* @brief Indicate is Leap Year or not
*
* @param[in] rtc The pointer of RTC module.
*
* @retval 0 This year is not a leap year
* @retval 1 This year is a leap year
*
* @details According to current date, return this year is leap year or not.
* \hideinitializer
*/
#define RTC_IS_LEAP_YEAR(rtc) (((rtc)->LEAPYEAR & RTC_LEAPYEAR_LEAPYEAR_Msk)? 1:0)
/**
* @brief Clear RTC Alarm Interrupt Flag
*
* @param[in] rtc The pointer of RTC module.
*
* @return None
*
* @details This macro is used to clear RTC alarm interrupt flag.
* \hideinitializer
*/
#define RTC_CLEAR_ALARM_INT_FLAG(rtc) ((rtc)->INTSTS = RTC_INTSTS_ALMIF_Msk)
/**
* @brief Clear RTC Tick Interrupt Flag
*
* @param[in] rtc The pointer of RTC module.
*
* @return None
*
* @details This macro is used to clear RTC tick interrupt flag.
* \hideinitializer
*/
#define RTC_CLEAR_TICK_INT_FLAG(rtc) ((rtc)->INTSTS = RTC_INTSTS_TICKIF_Msk)
/**
* @brief Clear RTC Tamper Interrupt Flag
*
* @param[in] rtc The pointer of RTC module.
* @param[in] u32TamperFlag Tamper interrupt flag. It consists of: \n
* - \ref RTC_INTSTS_TAMP0IF_Msk \n
* - \ref RTC_INTSTS_TAMP1IF_Msk \n
* - \ref RTC_INTSTS_TAMP2IF_Msk \n
* - \ref RTC_INTSTS_TAMP3IF_Msk \n
* - \ref RTC_INTSTS_TAMP4IF_Msk \n
* - \ref RTC_INTSTS_TAMP5IF_Msk
*
* @return None
*
* @details This macro is used to clear RTC tamper pin interrupt flag.
* \hideinitializer
*/
#define RTC_CLEAR_TAMPER_INT_FLAG(rtc, u32TamperFlag) ((rtc)->INTSTS = (u32TamperFlag))
/**
* @brief Get RTC Alarm Interrupt Flag
*
* @param[in] rtc The pointer of RTC module.
*
* @retval 0 RTC alarm interrupt did not occur
* @retval 1 RTC alarm interrupt occurred
*
* @details This macro indicates RTC alarm interrupt occurred or not.
* \hideinitializer
*/
#define RTC_GET_ALARM_INT_FLAG(rtc) (((rtc)->INTSTS & RTC_INTSTS_ALMIF_Msk)? 1:0)
/**
* @brief Get RTC Time Tick Interrupt Flag
*
* @param[in] rtc The pointer of RTC module.
*
* @retval 0 RTC time tick interrupt did not occur
* @retval 1 RTC time tick interrupt occurred
*
* @details This macro indicates RTC time tick interrupt occurred or not.
* \hideinitializer
*/
#define RTC_GET_TICK_INT_FLAG(rtc) (((rtc)->INTSTS & RTC_INTSTS_TICKIF_Msk)? 1:0)
/**
* @brief Set I/O Control By GPIO
*
* @param[in] rtc The pointer of RTC module.
*
* @return None
*
* @details This macro sets the PF.4~11 pin I/O is controlled by GPIO module.
* \hideinitializer
*/
#define RTC_SET_IOCTL_BY_GPIO(rtc) ((rtc)->LXTCTL &= ~RTC_LXTCTL_IOCTLSEL_Msk)
/**
* @brief Set I/O Control By RTC
*
* @param[in] rtc The pointer of RTC module.
*
* @return None
*
* @details This macro sets the PF.4~11 pin I/O is controlled by RTC module.
* \hideinitializer
*/
#define RTC_SET_IOCTL_BY_RTC(rtc) ((rtc)->LXTCTL |= RTC_LXTCTL_IOCTLSEL_Msk)
/**
* @brief Get I/O Control Property
*
* @param[in] rtc The pointer of RTC module.
*
* @retval 0 PF.4~11 pin I/O is controlled by GPIO module
* @retval 1 PF.4~11 pin I/O is controlled by RTC module
*
* @details This macro indicates the PF.4~11 pin I/O control property.
* \hideinitializer
*/
#define RTC_GET_IOCTL_PROPERTY(rtc) (((rtc)->LXTCTL & RTC_LXTCTL_IOCTLSEL_Msk)? 1:0)
/**
* @brief Get RTC Tamper Interrupt Flag
*
* @param[in] rtc The pointer of RTC module.
*
* @retval 0 RTC tamper event interrupt did not occur
* @retval 1 RTC tamper event interrupt occurred
*
* @details This macro indicates RTC tamper event occurred or not.
* \hideinitializer
*/
#define RTC_GET_TAMPER_INT_FLAG(rtc) (((rtc)->INTSTS & (0x3F00))? 1:0)
/**
* @brief Get RTC Tamper Interrupt Status
*
* @param[in] rtc The pointer of RTC module.
*
* @retval RTC_INTSTS_TAMP0IF_Msk Tamper 0 interrupt flag is generated
* @retval RTC_INTSTS_TAMP1IF_Msk Tamper 1 interrupt flag is generated
* @retval RTC_INTSTS_TAMP2IF_Msk Tamper 2 interrupt flag is generated
* @retval RTC_INTSTS_TAMP3IF_Msk Tamper 3 interrupt flag is generated
* @retval RTC_INTSTS_TAMP4IF_Msk Tamper 4 interrupt flag is generated
* @retval RTC_INTSTS_TAMP5IF_Msk Tamper 5 interrupt flag is generated
*
* @details This macro indicates RTC tamper interrupt status.
* \hideinitializer
*/
#define RTC_GET_TAMPER_INT_STATUS(rtc) (((rtc)->INTSTS & (0x3F00)))
/**
* @brief Enable RTC Tick Wake-up Function
*
* @param[in] rtc The pointer of RTC module.
*
* @return None
*
* @details This macro is used to enable RTC tick interrupt wake-up function.
* \hideinitializer
*/
#define RTC_ENABLE_TICK_WAKEUP(rtc) ((rtc)->INTEN |= RTC_INTEN_TICKIEN_Msk);
/**
* @brief Disable RTC Tick Wake-up Function
*
* @param[in] rtc The pointer of RTC module.
*
* @return None
*
* @details This macro is used to disable RTC tick interrupt wake-up function.
* \hideinitializer
*/
#define RTC_DISABLE_TICK_WAKEUP(rtc) ((rtc)->INTEN &= ~RTC_INTEN_TICKIEN_Msk);
/**
* @brief Read Spare Register
*
* @param[in] rtc The pointer of RTC module.
* @param[in] u32RegNum The spare register number, 0~19.
*
* @return Spare register content
*
* @details Read the specify spare register content.
* \hideinitializer
*/
#define RTC_READ_SPARE_REGISTER(rtc, u32RegNum) ((rtc)->SPR[(u32RegNum)])
/**
* @brief Write Spare Register
*
* @param[in] rtc The pointer of RTC module.
* @param[in] u32RegNum The spare register number, 0~19.
* @param[in] u32RegValue The spare register value.
*
* @return None
*
* @details Write specify data to spare register.
* \hideinitializer
*/
#define RTC_WRITE_SPARE_REGISTER(rtc, u32RegNum, u32RegValue) ((rtc)->SPR[(u32RegNum)] = (u32RegValue))
void RTC_Open(S_RTC_TIME_DATA_T *sPt);
void RTC_Close(void);
void RTC_32KCalibration(int32_t i32FrequencyX10000);
void RTC_GetDateAndTime(S_RTC_TIME_DATA_T *sPt);
void RTC_GetAlarmDateAndTime(S_RTC_TIME_DATA_T *sPt);
void RTC_SetDateAndTime(S_RTC_TIME_DATA_T *sPt);
void RTC_SetAlarmDateAndTime(S_RTC_TIME_DATA_T *sPt);
void RTC_SetDate(uint32_t u32Year, uint32_t u32Month, uint32_t u32Day, uint32_t u32DayOfWeek);
void RTC_SetTime(uint32_t u32Hour, uint32_t u32Minute, uint32_t u32Second, uint32_t u32TimeMode, uint32_t u32AmPm);
void RTC_SetAlarmDate(uint32_t u32Year, uint32_t u32Month, uint32_t u32Day);
void RTC_SetAlarmTime(uint32_t u32Hour, uint32_t u32Minute, uint32_t u32Second, uint32_t u32TimeMode, uint32_t u32AmPm);
void RTC_SetAlarmDateMask(uint8_t u8IsTenYMsk, uint8_t u8IsYMsk, uint8_t u8IsTenMMsk, uint8_t u8IsMMsk, uint8_t u8IsTenDMsk, uint8_t u8IsDMsk);
void RTC_SetAlarmTimeMask(uint8_t u8IsTenHMsk, uint8_t u8IsHMsk, uint8_t u8IsTenMMsk, uint8_t u8IsMMsk, uint8_t u8IsTenSMsk, uint8_t u8IsSMsk);
uint32_t RTC_GetDayOfWeek(void);
void RTC_SetTickPeriod(uint32_t u32TickSelection);
void RTC_EnableInt(uint32_t u32IntFlagMask);
void RTC_DisableInt(uint32_t u32IntFlagMask);
void RTC_EnableSpareAccess(void);
void RTC_DisableSpareRegister(void);
void RTC_StaticTamperEnable(uint32_t u32TamperSelect, uint32_t u32DetecLevel, uint32_t u32DebounceEn);
void RTC_StaticTamperDisable(uint32_t u32TamperSelect);
void RTC_DynamicTamperEnable(uint32_t u32PairSel, uint32_t u32DebounceEn, uint32_t u32Pair1Source, uint32_t u32Pair2Source);
void RTC_DynamicTamperDisable(uint32_t u32PairSel);
void RTC_DynamicTamperConfig(uint32_t u32ChangeRate, uint32_t u32SeedReload, uint32_t u32RefPattern, uint32_t u32Seed);
uint32_t RTC_SetClockSource(uint32_t u32ClkSrc);
void RTC_SetGPIOMode(uint32_t u32PFPin, uint32_t u32Mode, uint32_t u32DigitalCtl, uint32_t u32PullCtl, uint32_t u32OutputLevel);
void RTC_SetGPIOLevel(uint32_t u32PFPin, uint32_t u32OutputLevel);
/**@}*/ /* end of group RTC_EXPORTED_FUNCTIONS */
/**@}*/ /* end of group RTC_Driver */
/**@}*/ /* end of group Standard_Driver */
#ifdef __cplusplus
}
#endif
#endif /* __NU_RTC_H__ */

View File

@ -0,0 +1,305 @@
/**************************************************************************//**
* @file nu_sc.h
* @version V3.00
* @brief Smartcard(SC) driver header file
*
* @copyright SPDX-License-Identifier: Apache-2.0
* @copyright Copyright (C) 2020 Nuvoton Technology Corp. All rights reserved.
*****************************************************************************/
#ifndef __NU_SC_H__
#define __NU_SC_H__
#ifdef __cplusplus
extern "C"
{
#endif
/** @addtogroup Standard_Driver Standard Driver
@{
*/
/** @addtogroup SC_Driver SC Driver
@{
*/
/** @addtogroup SC_EXPORTED_CONSTANTS SC Exported Constants
@{
*/
#define SC_INTERFACE_NUM (3UL) /*!< Smartcard interface numbers \hideinitializer */
#define SC_PIN_STATE_HIGH (1UL) /*!< Smartcard pin status high \hideinitializer */
#define SC_PIN_STATE_LOW (0UL) /*!< Smartcard pin status low \hideinitializer */
#define SC_PIN_STATE_IGNORE (0xFFFFFFFFUL) /*!< Ignore pin status \hideinitializer */
#define SC_CLK_ON (1UL) /*!< Smartcard clock on \hideinitializer */
#define SC_CLK_OFF (0UL) /*!< Smartcard clock off \hideinitializer */
#define SC_TMR_MODE_0 (0UL << SC_TMRCTL0_OPMODE_Pos) /*!<Timer Operation Mode 0, down count \hideinitializer */
#define SC_TMR_MODE_1 (1UL << SC_TMRCTL0_OPMODE_Pos) /*!<Timer Operation Mode 1, down count, start after detect start bit \hideinitializer */
#define SC_TMR_MODE_2 (2UL << SC_TMRCTL0_OPMODE_Pos) /*!<Timer Operation Mode 2, down count, start after receive start bit \hideinitializer */
#define SC_TMR_MODE_3 (3UL << SC_TMRCTL0_OPMODE_Pos) /*!<Timer Operation Mode 3, down count, use for activation, only timer 0 support this mode \hideinitializer */
#define SC_TMR_MODE_4 (4UL << SC_TMRCTL0_OPMODE_Pos) /*!<Timer Operation Mode 4, down count with reload after timeout \hideinitializer */
#define SC_TMR_MODE_5 (5UL << SC_TMRCTL0_OPMODE_Pos) /*!<Timer Operation Mode 5, down count, start after detect start bit, reload after timeout \hideinitializer */
#define SC_TMR_MODE_6 (6UL << SC_TMRCTL0_OPMODE_Pos) /*!<Timer Operation Mode 6, down count, start after receive start bit, reload after timeout \hideinitializer */
#define SC_TMR_MODE_7 (7UL << SC_TMRCTL0_OPMODE_Pos) /*!<Timer Operation Mode 7, down count, start and reload after detect start bit \hideinitializer */
#define SC_TMR_MODE_8 (8UL << SC_TMRCTL0_OPMODE_Pos) /*!<Timer Operation Mode 8, up count \hideinitializer */
#define SC_TMR_MODE_F (0xFUL << SC_TMRCTL0_OPMODE_Pos) /*!<Timer Operation Mode 15, down count, reload after detect start bit \hideinitializer */
/**@}*/ /* end of group SC_EXPORTED_CONSTANTS */
/** @addtogroup SC_EXPORTED_FUNCTIONS SC Exported Functions
@{
*/
/**
* @brief This macro enable smartcard interrupt
*
* @param[in] sc The pointer of smartcard module.
* @param[in] u32Mask Interrupt mask to be enabled. A combination of
* - \ref SC_INTEN_ACERRIEN_Msk
* - \ref SC_INTEN_RXTOIEN_Msk
* - \ref SC_INTEN_INITIEN_Msk
* - \ref SC_INTEN_CDIEN_Msk
* - \ref SC_INTEN_BGTIEN_Msk
* - \ref SC_INTEN_TMR2IEN_Msk
* - \ref SC_INTEN_TMR1IEN_Msk
* - \ref SC_INTEN_TMR0IEN_Msk
* - \ref SC_INTEN_TERRIEN_Msk
* - \ref SC_INTEN_TBEIEN_Msk
* - \ref SC_INTEN_RDAIEN_Msk
*
* @return None
*
* @details The macro is used to enable Auto-convention error interrupt, Receiver buffer time-out interrupt, Initial end interrupt,
* Card detect interrupt, Block guard time interrupt, Timer2 interrupt, Timer1 interrupt, Timer0 interrupt,
* Transfer error interrupt, Transmit buffer empty interrupt or Receive data reach trigger level interrupt.
* \hideinitializer
*/
#define SC_ENABLE_INT(sc, u32Mask) ((sc)->INTEN |= (u32Mask))
/**
* @brief This macro disable smartcard interrupt
*
* @param[in] sc The pointer of smartcard module.
* @param[in] u32Mask Interrupt mask to be disabled. A combination of
* - \ref SC_INTEN_ACERRIEN_Msk
* - \ref SC_INTEN_RXTOIEN_Msk
* - \ref SC_INTEN_INITIEN_Msk
* - \ref SC_INTEN_CDIEN_Msk
* - \ref SC_INTEN_BGTIEN_Msk
* - \ref SC_INTEN_TMR2IEN_Msk
* - \ref SC_INTEN_TMR1IEN_Msk
* - \ref SC_INTEN_TMR0IEN_Msk
* - \ref SC_INTEN_TERRIEN_Msk
* - \ref SC_INTEN_TBEIEN_Msk
* - \ref SC_INTEN_RDAIEN_Msk
*
* @return None
*
* @details The macro is used to disable Auto-convention error interrupt, Receiver buffer time-out interrupt, Initial end interrupt,
* Card detect interrupt, Block guard time interrupt, Timer2 interrupt, Timer1 interrupt, Timer0 interrupt,
* Transfer error interrupt, Transmit buffer empty interrupt or Receive data reach trigger level interrupt.
* \hideinitializer
*/
#define SC_DISABLE_INT(sc, u32Mask) ((sc)->INTEN &= ~(u32Mask))
/**
* @brief This macro set VCC pin state of smartcard interface
*
* @param[in] sc The pointer of smartcard module.
* @param[in] u32State Pin state of VCC pin, valid parameters are \ref SC_PIN_STATE_HIGH and \ref SC_PIN_STATE_LOW.
*
* @return None
*
* @details User can set PWREN (SC_PINCTL[0]) and PWRINV (SC_PINCTL[11]) to decide SC_PWR pin is in high or low level.
* \hideinitializer
*/
#define SC_SET_VCC_PIN(sc, u32State) \
do {\
while(((sc)->PINCTL & SC_PINCTL_SYNC_Msk) == SC_PINCTL_SYNC_Msk);\
if(u32State)\
(sc)->PINCTL |= SC_PINCTL_PWREN_Msk;\
else\
(sc)->PINCTL &= ~SC_PINCTL_PWREN_Msk;\
}while(0)
/**
* @brief This macro turns CLK output on or off
*
* @param[in] sc The pointer of smartcard module.
* @param[in] u32OnOff Clock on or off for selected smartcard module, valid values are \ref SC_CLK_ON and \ref SC_CLK_OFF.
*
* @return None
*
* @details User can set CLKKEEP (SC_PINCTL[6]) to decide SC_CLK pin always keeps free running or not.
* \hideinitializer
*/
#define SC_SET_CLK_PIN(sc, u32OnOff)\
do {\
while(((sc)->PINCTL & SC_PINCTL_SYNC_Msk) == SC_PINCTL_SYNC_Msk);\
if(u32OnOff)\
(sc)->PINCTL |= SC_PINCTL_CLKKEEP_Msk;\
else\
(sc)->PINCTL &= ~(SC_PINCTL_CLKKEEP_Msk);\
}while(0)
/**
* @brief This macro set I/O pin state of smartcard interface
*
* @param[in] sc The pointer of smartcard module.
* @param[in] u32State Pin state of I/O pin, valid parameters are \ref SC_PIN_STATE_HIGH and \ref SC_PIN_STATE_LOW.
*
* @return None
*
* @details User can set SCDATA (SC_PINCTL[9]) to decide SC_DATA pin to high or low.
* \hideinitializer
*/
#define SC_SET_IO_PIN(sc, u32State)\
do {\
while(((sc)->PINCTL & SC_PINCTL_SYNC_Msk) == SC_PINCTL_SYNC_Msk);\
if(u32State)\
(sc)->PINCTL |= SC_PINCTL_SCDATA_Msk;\
else\
(sc)->PINCTL &= ~SC_PINCTL_SCDATA_Msk;\
}while(0)
/**
* @brief This macro set RST pin state of smartcard interface
*
* @param[in] sc The pointer of smartcard module.
* @param[in] u32State Pin state of RST pin, valid parameters are \ref SC_PIN_STATE_HIGH and \ref SC_PIN_STATE_LOW.
*
* @return None
*
* @details User can set SCRST (SC_PINCTL[1]) to decide SC_RST pin to high or low.
* \hideinitializer
*/
#define SC_SET_RST_PIN(sc, u32State)\
do {\
while(((sc)->PINCTL & SC_PINCTL_SYNC_Msk) == SC_PINCTL_SYNC_Msk);\
if(u32State)\
(sc)->PINCTL |= SC_PINCTL_RSTEN_Msk;\
else\
(sc)->PINCTL &= ~SC_PINCTL_RSTEN_Msk;\
}while(0)
/**
* @brief This macro read one byte from smartcard module receive FIFO
*
* @param[in] sc The pointer of smartcard module.
*
* @return One byte read from receive FIFO
*
* @details By reading DAT register, the SC will return an 8-bit received data.
* \hideinitializer
*/
#define SC_READ(sc) ((char)((sc)->DAT))
/**
* @brief This macro write one byte to smartcard module transmit FIFO
*
* @param[in] sc The pointer of smartcard module.
* @param[in] u8Data Data to write to transmit FIFO.
*
* @return None
*
* @details By writing data to DAT register, the SC will send out an 8-bit data.
* \hideinitializer
*/
#define SC_WRITE(sc, u8Data) ((sc)->DAT = (u8Data))
/**
* @brief This macro set smartcard stop bit length
*
* @param[in] sc The pointer of smartcard module.
* @param[in] u32Len Stop bit length, ether 1 or 2.
*
* @return None
*
* @details Stop bit length must be 1 for T = 1 protocol and 2 for T = 0 protocol.
* \hideinitializer
*/
#define SC_SET_STOP_BIT_LEN(sc, u32Len) ((sc)->CTL = ((sc)->CTL & ~SC_CTL_NSB_Msk) | (((u32Len) == 1)? SC_CTL_NSB_Msk : 0))
/*---------------------------------------------------------------------------------------------------------*/
/* static inline functions */
/*---------------------------------------------------------------------------------------------------------*/
/* Declare these inline functions here to avoid MISRA C 2004 rule 8.1 error */
__STATIC_INLINE void SC_SetTxRetry(SC_T *sc, uint32_t u32Count);
__STATIC_INLINE void SC_SetRxRetry(SC_T *sc, uint32_t u32Count);
/**
* @brief Enable/Disable Tx error retry, and set Tx error retry count
*
* @param[in] sc The pointer of smartcard module.
* @param[in] u32Count The number of times of Tx error retry count, between 0~8. 0 means disable Tx error retry.
*
* @return None
*
* @details This function is used to enable/disable transmitter retry function when parity error has occurred, and set error retry count.
*/
__STATIC_INLINE void SC_SetTxRetry(SC_T *sc, uint32_t u32Count)
{
while(((sc)->CTL & SC_CTL_SYNC_Msk) == SC_CTL_SYNC_Msk) {}
/* Retry count must set while enable bit disabled, so disable it first */
(sc)->CTL &= ~(SC_CTL_TXRTY_Msk | SC_CTL_TXRTYEN_Msk);
if((u32Count) != 0UL)
{
while(((sc)->CTL & SC_CTL_SYNC_Msk) == SC_CTL_SYNC_Msk) {}
(sc)->CTL |= (((u32Count) - 1UL) << SC_CTL_TXRTY_Pos) | SC_CTL_TXRTYEN_Msk;
}
}
/**
* @brief Enable/Disable Rx error retry, and set Rx error retry count
*
* @param[in] sc The pointer of smartcard module.
* @param[in] u32Count The number of times of Rx error retry count, between 0~8. 0 means disable Rx error retry.
*
* @return None
*
* @details This function is used to enable/disable receiver retry function when parity error has occurred, and set error retry count.
*/
__STATIC_INLINE void SC_SetRxRetry(SC_T *sc, uint32_t u32Count)
{
while(((sc)->CTL & SC_CTL_SYNC_Msk) == SC_CTL_SYNC_Msk) {}
/* Retry count must set while enable bit disabled, so disable it first */
(sc)->CTL &= ~(SC_CTL_RXRTY_Msk | SC_CTL_RXRTYEN_Msk);
if((u32Count) != 0UL)
{
while(((sc)->CTL & SC_CTL_SYNC_Msk) == SC_CTL_SYNC_Msk) {}
(sc)->CTL |= (((u32Count) - 1UL) << SC_CTL_RXRTY_Pos) | SC_CTL_RXRTYEN_Msk;
}
}
uint32_t SC_IsCardInserted(SC_T *sc);
void SC_ClearFIFO(SC_T *sc);
void SC_Close(SC_T *sc);
void SC_Open(SC_T *sc, uint32_t u32CardDet, uint32_t u32PWR);
void SC_ResetReader(SC_T *sc);
void SC_SetBlockGuardTime(SC_T *sc, uint32_t u32BGT);
void SC_SetCharGuardTime(SC_T *sc, uint32_t u32CGT);
void SC_StopAllTimer(SC_T *sc);
void SC_StartTimer(SC_T *sc, uint32_t u32TimerNum, uint32_t u32Mode, uint32_t u32ETUCount);
void SC_StopTimer(SC_T *sc, uint32_t u32TimerNum);
uint32_t SC_GetInterfaceClock(SC_T *sc);
/**@}*/ /* end of group SC_EXPORTED_FUNCTIONS */
/**@}*/ /* end of group SC_Driver */
/**@}*/ /* end of group Standard_Driver */
#ifdef __cplusplus
}
#endif
#endif /* __NU_SC_H__ */

View File

@ -0,0 +1,358 @@
/**************************************************************************//**
* @file nu_scu.h
* @version V3.00
* @brief Secure Configuration Unit Driver Header
*
* @copyright SPDX-License-Identifier: Apache-2.0
* @copyright Copyright (C) 2020 Nuvoton Technology Corp. All rights reserved.
*****************************************************************************/
#ifndef __NU_SCU_H__
#define __NU_SCU_H__
#ifdef __cplusplus
extern "C"
{
#endif
/** @addtogroup Standard_Driver Standard Driver
@{
*/
/** @addtogroup SCU_Driver SCU Driver
@{
*/
/** @addtogroup SCU_EXPORTED_CONSTANTS SCU Exported Constants
@{
*/
/**
* @details Non-secure Attribution Definition.
*/
typedef enum NSATTR
{
/****** PNNSET0 **********************************************************************************/
USBH_Attr = 9,
SDH0_Attr = 13,
EBI_Attr = 16,
PDMA1_Attr = 24,
/****** PNNSET1 **********************************************************************************/
CRC_Attr = 32 + 17,
CRPT_Attr = 32 + 18,
/****** PNNSET2 **********************************************************************************/
EWDT_Attr = 64 + 2,
EADC_Attr = 64 + 3,
ACMP01_Attr = 64 + 5,
DAC_Attr = 64 + 7,
I2S0_Attr = 64 + 8,
OTG_Attr = 64 + 13,
TMR23_Attr = 64 + 17,
TMR45_Attr = 64 + 18,
EPWM0_Attr = 64 + 24,
EPWM1_Attr = 64 + 25,
BPWM0_Attr = 64 + 26,
BPWM1_Attr = 64 + 27,
/****** PNNSET3 **********************************************************************************/
QSPI0_Attr = 96 + 0,
SPI0_Attr = 96 + 1,
SPI1_Attr = 96 + 2,
SPI2_Attr = 96 + 3,
SPI3_Attr = 96 + 4,
UART0_Attr = 96 + 16,
UART1_Attr = 96 + 17,
UART2_Attr = 96 + 18,
UART3_Attr = 96 + 19,
UART4_Attr = 96 + 20,
UART5_Attr = 96 + 21,
/****** PNNSET4 **********************************************************************************/
I2C0_Attr = 128 + 0,
I2C1_Attr = 128 + 1,
I2C2_Attr = 128 + 2,
SC0_Attr = 128 + 16,
SC1_Attr = 128 + 17,
SC2_Attr = 128 + 18,
/****** PNNSET5 **********************************************************************************/
CAN0_Attr = 160 + 0,
QEI0_Attr = 160 + 16,
QEI1_Attr = 160 + 17,
ECAP0_Attr = 160 + 20,
ECAP1_Attr = 160 + 21,
TRNG_Attr = 160 + 25,
LCD_Attr = 160 + 27,
/****** PNNSET6 **********************************************************************************/
USBD_Attr = 192 + 0,
USCI0_Attr = 192 + 16,
USCI1_Attr = 192 + 17
} NSATTR_T;
/**@}*/ /* end of group SCU_EXPORTED_CONSTANTS */
/** @addtogroup SCU_EXPORTED_FUNCTIONS SCU Exported Functions
@{
*/
/**
* @brief Set peripheral non-secure attribution
*
* @param[in] nsattr The secure/non-secure attribution of specified module.
The possible value could be refer to \ref NSATTR.
*
* @return None
*
* @details This macro is used to set a peripheral to be non-secure peripheral.
*
*/
#define SCU_SET_PNSSET(nsattr) { SCU->PNSSET[(nsattr)/32] |= (1 << ((nsattr) & 0x1ful)); }
/**
* @brief Get peripheral secure/non-secure attribution
*
* @param[in] nsattr The secure/non-secure attribution of specified module.
The possible value could be refer to \ref NSATTR.
*
* @return The secure/non-secure attribution of specified peripheral.
* @retval 0 The peripheral is secure
* @retval 1 The peripheral is non-secure
*
* @details This macro gets the peripheral secure/non-secure attribution.
*/
#define SCU_GET_PNSSET(nsattr) ((SCU->PNSSET[(nsattr)/32] >> ((nsattr) & 0x1ful)) & 1ul)
/**
* @brief Set secure/non-secure attribution of specified GPIO pin
*
* @param[in] port GPIO Port. It could be PA, PB, PC, PD, PE, PF, PG and PH.
* @param[in] bitmask Bit mask of each bit. 0 is secure. 1 is non-secure.
*
* @return None
*
* @details This macro sets GPIO pin secure/non-secure attribution.
*/
#define SCU_SET_IONSSET(port, mask) (SCU->IONSSET[((uint32_t)(port)-(GPIOA_BASE))/0x40] = (mask))
/**
* @brief Get secure/non-secure attribution of specified GPIO port
*
* @param[in] port GPIO Port. It could be PA, PB, PC, PD, PE, PF, PG and PH.
*
* @return The secure/non-secure attribution of the port.
* @retval 0 The relative bit of specified IO port is secure
* @retval 1 The relative bit of specified IO port is non-secure
*
* @details This macro gets IO secure/non-secure attribution of specified IO port.
*/
#define SCU_GET_IONSSET(port) (SCU->IONSSET[((uint32_t)(port) - (GPIOA_BASE))/0x40])
/**
* @brief Enable sercure violation interrupts
*
* @param[in] mask The mask of each secure violation interrupt source
* - \ref SCU_SVIOIEN_APB0IEN_Msk
* - \ref SCU_SVIOIEN_APB1IEN_Msk
* - \ref SCU_SVIOIEN_GPIOIEN_Msk
* - \ref SCU_SVIOIEN_EBIIEN_Msk
* - \ref SCU_SVIOIEN_USBHIEN_Msk
* - \ref SCU_SVIOIEN_CRCIEN_Msk
* - \ref SCU_SVIOIEN_SDH0IEN_Msk
* - \ref SCU_SVIOIEN_PDMA0IEN_Msk
* - \ref SCU_SVIOIEN_PDMA1IEN_Msk
* - \ref SCU_SVIOIEN_SRAM0IEN_Msk
* - \ref SCU_SVIOIEN_SRAM1IEN_Msk
* - \ref SCU_SVIOIEN_FMCIEN_Msk
* - \ref SCU_SVIOIEN_FLASHIEN_Msk
* - \ref SCU_SVIOIEN_SCUIEN_Msk
* - \ref SCU_SVIOIEN_SYSIEN_Msk
* - \ref SCU_SVIOIEN_CRPTIEN_Msk
*
* @return None
*
* @details This macro is used to enable secure violation interrupt of SCU.
* The secure violation interrupt could be used to detect attack of secure elements.
*/
#define SCU_ENABLE_INT(mask) (SCU->SVIOIEN |= (mask))
/**
* @brief Disable sercure violation interrupts
*
* @param[in] mask The mask of each secure violation interrupt source
* - \ref SCU_SVIOIEN_APB0IEN_Msk
* - \ref SCU_SVIOIEN_APB1IEN_Msk
* - \ref SCU_SVIOIEN_GPIOIEN_Msk
* - \ref SCU_SVIOIEN_EBIIEN_Msk
* - \ref SCU_SVIOIEN_USBHIEN_Msk
* - \ref SCU_SVIOIEN_CRCIEN_Msk
* - \ref SCU_SVIOIEN_SDH0IEN_Msk
* - \ref SCU_SVIOIEN_PDMA0IEN_Msk
* - \ref SCU_SVIOIEN_PDMA1IEN_Msk
* - \ref SCU_SVIOIEN_SRAM0IEN_Msk
* - \ref SCU_SVIOIEN_SRAM1IEN_Msk
* - \ref SCU_SVIOIEN_FMCIEN_Msk
* - \ref SCU_SVIOIEN_FLASHIEN_Msk
* - \ref SCU_SVIOIEN_SCUIEN_Msk
* - \ref SCU_SVIOIEN_SYSIEN_Msk
* - \ref SCU_SVIOIEN_CRPTIEN_Msk
*
* @return None
*
* @details This macro is used to disable secure violation interrupt of SCU.
*
*/
#define SCU_DISABLE_INT(mask) (SCU->SVIOIEN &= (~(mask)))
/**
* @brief Get secure violation interrupt status
*
* @param mask The interrupt flag mask bit
*
* @return The value of SCU_SVINTSTS register
*
* @details Return interrupt flag of SCU_SVINTSTS register.
*
*/
#define SCU_GET_INT_FLAG(mask) (SCU->SVINTSTS&(mask))
/**
* @brief Clear secure violation interrupt flag
*
* @param[in] flag The combination of the specified interrupt flags.
* Each bit corresponds to a interrupt source.
* This parameter decides which interrupt flags will be cleared.
* - \ref SCU_SVINTSTS_APB0IF_Msk
* - \ref SCU_SVINTSTS_APB1IF_Msk
* - \ref SCU_SVINTSTS_GPIOIF_Msk
* - \ref SCU_SVINTSTS_EBIIF_Msk
* - \ref SCU_SVINTSTS_USBHIF_Msk
* - \ref SCU_SVINTSTS_CRCIF_Msk
* - \ref SCU_SVINTSTS_SDH0IF_Msk
* - \ref SCU_SVINTSTS_PDMA0IF_Msk
* - \ref SCU_SVINTSTS_PDMA1IF_Msk
* - \ref SCU_SVINTSTS_SRAM0IF_Msk
* - \ref SCU_SVINTSTS_SRAM1IF_Msk
* - \ref SCU_SVINTSTS_FMCIF_Msk
* - \ref SCU_SVINTSTS_FLASHIF_Msk
* - \ref SCU_SVINTSTS_SCUIF_Msk
* - \ref SCU_SVINTSTS_SYSIF_Msk
* - \ref SCU_SVINTSTS_CRPTIF_Msk
*
* @return None
*
* @details Clear SCU related interrupt flags specified by flag parameter.
*
*/
#define SCU_CLR_INT_FLAG(flag) (SCU->SVINTSTS = (flag))
/**
* @brief Control the behavior of non-secure monitor when CPU is in idle state.
*
* @param[in] opt Option for behavior control of non-secure monitor when CPU in idle.
* - true The counter keeps counting when CPU is in idle.
- false The counter will stop when CPU is in idle.
*
* @return None
*
* @details To control non-secure monitor counter when CPU is in idle.
*
*/
#define SCU_NSM_IDLE_ON(opt) ((opt)?(SCU->NSMCTL |= SCU_NSMCTL_IDLEON_Msk):(SCU->NSMCTL &= ~SCU_NSMCTL_IDLEON_Msk))
/**
* @brief Control the behavior of non-secure monitor when CPU is in debug state.
*
* @param[in] opt Option for behavior control of non-secure monitor when CPU in debug.
* - true The counter keeps counting when CPU is in debug.
- false The counter will stop when CPU is in debug.
*
* @return None
*
* @details To control non-secure monitor counter when CPU is in debug.
*
*/
#define SCU_NSM_DBG_ON(opt) ((opt)?(SCU->NSMCTL |= SCU_NSMCTL_DBGON_Msk):(SCU->NSMCTL &= ~SCU_NSMCTL_DBGON_Msk))
/* Declare these inline functions here to avoid MISRA C 2004 rule 8.1 error */
__STATIC_INLINE void SCU_NSMConfig(uint32_t u32Ticks, uint32_t u32Prescale);
__STATIC_INLINE void SCU_TimerConfig(uint32_t u32Ticks, uint32_t u32Prescale);
/**
* @brief Config non-secure monitor to detect timeout in non-secure state.
*
* @param[in] u32Ticks A specified period for timeout in non-secure state
* @param[in] u32Prescale A pre-scale divider to non-secure monitor clock
*
* @return None
*
* @details This function is used to configure non-secure monitor. If the CPU state stay in non-secure state for
* a specified period. The non-secure monitor will timeout and assert an interrupt. Otherwise, the
* non-secure monitor will auto clear whenever returning to secure state. This could be used to avoid
* CPU state in non-secure state too long time for security purpose. User must enable SCU_IRQn if interrupt
* is necessary.
*
*/
__STATIC_INLINE void SCU_NSMConfig(uint32_t u32Ticks, uint32_t u32Prescale)
{
SCU->NSMLOAD = u32Ticks;
SCU->NSMVAL = 0ul;
SCU->NSMCTL = SCU_NSMCTL_AUTORLD_Msk | SCU_NSMCTL_NSMIEN_Msk | (u32Prescale & 0xfful);
}
/**
* @brief Config non-secure monitor to be a timer.
*
* @param[in] u32Ticks A specified period for timer interrupt.
* @param[in] u32Prescale A pre-scale divider to timer clock source.
*
* @return None
*
* @details This function is used to configure non-secure monitor as a timer. In other words, the timer counter
* keeps counting even CPU is in secure state.
*
*/
__STATIC_INLINE void SCU_TimerConfig(uint32_t u32Ticks, uint32_t u32Prescale)
{
SCU->NSMLOAD = u32Ticks;
SCU->NSMVAL = 0ul;
SCU->NSMCTL = SCU_NSMCTL_AUTORLD_Msk | SCU_NSMCTL_NSMIEN_Msk | SCU_NSMCTL_TMRMOD_Msk | (u32Prescale & 0xfful);
}
/**@}*/ /* end of group SCU_EXPORTED_FUNCTIONS */
/**@}*/ /* end of group SCU_Driver */
/**@}*/ /* end of group Standard_Driver */
#ifdef __cplusplus
}
#endif
#endif /* __NU_SCU_H__ */

View File

@ -0,0 +1,353 @@
/**************************************************************************//**
* @file nu_scuart.h
* @version V3.00
* @brief Smartcard UART mode (SCUART) driver header file
*
* @copyright SPDX-License-Identifier: Apache-2.0
* @copyright Copyright (C) 2020 Nuvoton Technology Corp. All rights reserved.
*****************************************************************************/
#ifndef __NU_SCUART_H__
#define __NU_SCUART_H__
#ifdef __cplusplus
extern "C"
{
#endif
/** @addtogroup Standard_Driver Standard Driver
@{
*/
/** @addtogroup SCUART_Driver SCUART Driver
@{
*/
/** @addtogroup SCUART_EXPORTED_CONSTANTS SCUART Exported Constants
@{
*/
#define SCUART_CHAR_LEN_5 (0x3UL << SC_UARTCTL_WLS_Pos) /*!< Set SCUART word length to 5 bits \hideinitializer */
#define SCUART_CHAR_LEN_6 (0x2UL << SC_UARTCTL_WLS_Pos) /*!< Set SCUART word length to 6 bits \hideinitializer */
#define SCUART_CHAR_LEN_7 (0x1UL << SC_UARTCTL_WLS_Pos) /*!< Set SCUART word length to 7 bits \hideinitializer */
#define SCUART_CHAR_LEN_8 (0UL) /*!< Set SCUART word length to 8 bits \hideinitializer */
#define SCUART_PARITY_NONE (SC_UARTCTL_PBOFF_Msk) /*!< Set SCUART transfer with no parity \hideinitializer */
#define SCUART_PARITY_ODD (SC_UARTCTL_OPE_Msk) /*!< Set SCUART transfer with odd parity \hideinitializer */
#define SCUART_PARITY_EVEN (0UL) /*!< Set SCUART transfer with even parity \hideinitializer */
#define SCUART_STOP_BIT_1 (SC_CTL_NSB_Msk) /*!< Set SCUART transfer with one stop bit \hideinitializer */
#define SCUART_STOP_BIT_2 (0UL) /*!< Set SCUART transfer with two stop bits \hideinitializer */
/**@}*/ /* end of group SCUART_EXPORTED_CONSTANTS */
/** @addtogroup SCUART_EXPORTED_FUNCTIONS SCUART Exported Functions
@{
*/
/* TX Macros */
/**
* @brief Write Data to Tx data register
*
* @param[in] sc The pointer of smartcard module.
* @param[in] u8Data Data byte to transmit.
*
* @return None
*
* @details By writing data to DAT register, the SC will send out an 8-bit data.
* \hideinitializer
*/
#define SCUART_WRITE(sc, u8Data) ((sc)->DAT = (u8Data))
/**
* @brief Get Tx FIFO empty flag status from register
*
* @param[in] sc The pointer of smartcard module.
*
* @return Transmit FIFO empty status
* @retval 0 Transmit FIFO is not empty
* @retval SC_STATUS_TXEMPTY_Msk Transmit FIFO is empty
*
* @details When the last byte of Tx buffer has been transferred to Transmitter Shift Register, hardware sets TXEMPTY (SC_STATUS[9]) high.
* It will be cleared when writing data into DAT (SC_DAT[7:0]).
* \hideinitializer
*/
#define SCUART_GET_TX_EMPTY(sc) ((sc)->STATUS & SC_STATUS_TXEMPTY_Msk)
/**
* @brief Get Tx FIFO full flag status from register
*
* @param[in] sc The pointer of smartcard module.
*
* @return Transmit FIFO full status
* @retval 0 Transmit FIFO is not full
* @retval SC_STATUS_TXFULL_Msk Transmit FIFO is full
*
* @details TXFULL (SC_STATUS[10]) is set when Tx buffer counts equals to 4, otherwise is cleared by hardware.
* \hideinitializer
*/
#define SCUART_GET_TX_FULL(sc) ((sc)->STATUS & SC_STATUS_TXFULL_Msk)
/**
* @brief Wait specified smartcard port transmission complete
*
* @param[in] sc The pointer of smartcard module.
*
* @return None
*
* @details TXACT (SC_STATUS[31]) is cleared automatically when Tx transfer is finished or the last byte transmission has completed.
*
* @note This macro blocks until transmit complete.
* \hideinitializer
*/
#define SCUART_WAIT_TX_EMPTY(sc) while(((sc)->STATUS & SC_STATUS_TXACT_Msk) == SC_STATUS_TXACT_Msk)
/**
* @brief Check specified smartcard port transmit FIFO is full or not
*
* @param[in] sc The pointer of smartcard module.
*
* @return Transmit FIFO full status
* @retval 0 Transmit FIFO is not full
* @retval 1 Transmit FIFO is full
*
* @details TXFULL (SC_STATUS[10]) indicates Tx buffer full or not.
* This bit is set when Tx buffer counts equals to 4, otherwise is cleared by hardware.
* \hideinitializer
*/
#define SCUART_IS_TX_FULL(sc) (((sc)->STATUS & SC_STATUS_TXFULL_Msk)? 1 : 0)
/**
* @brief Check specified smartcard port transmission is over
*
* @param[in] sc The pointer of smartcard module.
*
* @return Transmit complete status
* @retval 0 Transmit is not complete
* @retval 1 Transmit complete
*
* @details TXACT (SC_STATUS[31]) indicates Tx Transmit is complete or not.
* \hideinitializer
*/
#define SCUART_IS_TX_EMPTY(sc) (((sc)->STATUS & SC_STATUS_TXACT_Msk)? 0 : 1)
/**
* @brief Check specified smartcard port transmit FIFO empty status
*
* @param[in] sc The pointer of smartcard module.
*
* @return Transmit FIFO empty status
* @retval 0 Transmit FIFO is not empty
* @retval 1 Transmit FIFO is empty
*
* @details TXEMPTY (SC_STATUS[9]) is set by hardware when the last byte of Tx buffer has been transferred to Transmitter Shift Register.
* \hideinitializer
*/
#define SCUART_IS_TX_FIFO_EMPTY(sc) (((sc)->STATUS & SC_STATUS_TXEMPTY_Msk)? 1 : 0)
/**
* @brief Check specified Smartcard port Transmission Status
*
* @param[in] sc The pointer of smartcard module.
*
* @retval 0 Transmit is completed
* @retval 1 Transmit is active
*
* @details TXACT (SC_STATUS[31]) is set by hardware when Tx transfer is in active and the STOP bit of the last byte has been transmitted.
* \hideinitializer
*/
#define SCUART_IS_TX_ACTIVE(sc) (((sc)->STATUS & SC_STATUS_TXACT_Msk)? 1 : 0)
/* RX Macros */
/**
* @brief Read Rx data register
*
* @param[in] sc The pointer of smartcard module.
*
* @return The oldest data byte in RX FIFO
*
* @details By reading DAT register, the SC will return an 8-bit received data.
* \hideinitializer
*/
#define SCUART_READ(sc) ((sc)->DAT)
/**
* @brief Get Rx FIFO empty flag status from register
*
* @param[in] sc The pointer of smartcard module.
*
* @return Receive FIFO empty status
* @retval 0 Receive FIFO is not empty
* @retval SC_STATUS_RXEMPTY_Msk Receive FIFO is empty
*
* @details When the last byte of Rx buffer has been read by CPU, hardware sets RXEMPTY (SC_STATUS[1]) high.
* It will be cleared when SC receives any new data.
* \hideinitializer
*/
#define SCUART_GET_RX_EMPTY(sc) ((sc)->STATUS & SC_STATUS_RXEMPTY_Msk)
/**
* @brief Get Rx FIFO full flag status from register
*
* @param[in] sc The pointer of smartcard module.
*
* @return Receive FIFO full status
* @retval 0 Receive FIFO is not full
* @retval SC_STATUS_TXFULL_Msk Receive FIFO is full
*
* @details RXFULL (SC_STATUS[2]) is set when Rx buffer counts equals to 4, otherwise it is cleared by hardware.
* \hideinitializer
*/
#define SCUART_GET_RX_FULL(sc) ((sc)->STATUS & SC_STATUS_RXFULL_Msk)
/**
* @brief Check if receive data number in FIFO reach FIFO trigger level or not
*
* @param[in] sc The pointer of smartcard module.
*
* @return Receive FIFO data status
* @retval 0 The number of bytes in receive FIFO is less than trigger level
* @retval 1 The number of bytes in receive FIFO equals or larger than trigger level
*
* @details RDAIF (SC_INTSTS[0]) is used for received data reaching trigger level RXTRGLV (SC_CTL[7:6]) interrupt status flag.
*
* @note If receive trigger level is \b not 1 byte, this macro return 0 does not necessary indicates there is no data in FIFO.
* \hideinitializer
*/
#define SCUART_IS_RX_READY(sc) (((sc)->INTSTS & SC_INTSTS_RDAIF_Msk)? 1 : 0)
/**
* @brief Check specified smartcard port receive FIFO is full or not
*
* @param[in] sc The pointer of smartcard module.
*
* @return Receive FIFO full status
* @retval 0 Receive FIFO is not full
* @retval 1 Receive FIFO is full
*
* @details RXFULLF( SC_STATUS[2]) is set when Rx buffer counts equals to 4, otherwise it is cleared by hardware.
* \hideinitializer
*/
#define SCUART_IS_RX_FULL(sc) (((sc)->STATUS & SC_STATUS_RXFULL_Msk)? 1 : 0)
/* Interrupt Macros */
/**
* @brief Enable specified interrupts
*
* @param[in] sc The pointer of smartcard module.
* @param[in] u32Mask Interrupt masks to enable, a combination of following bits,
* - \ref SC_INTEN_RXTOIEN_Msk
* - \ref SC_INTEN_TERRIEN_Msk
* - \ref SC_INTEN_TBEIEN_Msk
* - \ref SC_INTEN_RDAIEN_Msk
*
* @return None
*
* @details The macro is used to enable receiver buffer time-out interrupt, transfer error interrupt,
* transmit buffer empty interrupt or receive data reach trigger level interrupt.
* \hideinitializer
*/
#define SCUART_ENABLE_INT(sc, u32Mask) ((sc)->INTEN |= (u32Mask))
/**
* @brief Disable specified interrupts
*
* @param[in] sc The pointer of smartcard module.
* @param[in] u32Mask Interrupt masks to disable, a combination of following bits,
* - \ref SC_INTEN_RXTOIEN_Msk
* - \ref SC_INTEN_TERRIEN_Msk
* - \ref SC_INTEN_TBEIEN_Msk
* - \ref SC_INTEN_RDAIEN_Msk
*
* @return None
*
* @details The macro is used to disable receiver buffer time-out interrupt, transfer error interrupt,
* transmit buffer empty interrupt or receive data reach trigger level interrupt.
* \hideinitializer
*/
#define SCUART_DISABLE_INT(sc, u32Mask) ((sc)->INTEN &= ~(u32Mask))
/**
* @brief Get specified interrupt flag/status
*
* @param[in] sc The pointer of smartcard module.
* @param[in] u32Type Interrupt flag/status to check, could be one of following value
* - \ref SC_INTSTS_RXTOIF_Msk
* - \ref SC_INTSTS_TERRIF_Msk
* - \ref SC_INTSTS_TBEIF_Msk
* - \ref SC_INTSTS_RDAIF_Msk
*
* @return The status of specified interrupt
* @retval 0 Specified interrupt does not happened
* @retval 1 Specified interrupt happened
*
* @details The macro is used to get receiver buffer time-out interrupt status, transfer error interrupt status,
* transmit buffer empty interrupt status or receive data reach interrupt status.
* \hideinitializer
*/
#define SCUART_GET_INT_FLAG(sc, u32Type) (((sc)->INTSTS & (u32Type))? 1 : 0)
/**
* @brief Clear specified interrupt flag/status
*
* @param[in] sc The pointer of smartcard module.
* @param[in] u32Type Interrupt flag/status to clear, only \ref SC_INTSTS_TERRIF_Msk valid for this macro.
*
* @return None
*
* @details The macro is used to clear transfer error interrupt flag.
* \hideinitializer
*/
#define SCUART_CLR_INT_FLAG(sc, u32Type) ((sc)->INTSTS = (u32Type))
/**
* @brief Get receive error flag/status
*
* @param[in] sc The pointer of smartcard module.
*
* @return Current receive error status, could one of following errors:
* @retval SC_STATUS_PEF_Msk Parity error
* @retval SC_STATUS_FEF_Msk Frame error
* @retval SC_STATUS_BEF_Msk Break error
*
* @details The macro is used to get receiver parity error status, frame error status or break error status.
* \hideinitializer
*/
#define SCUART_GET_ERR_FLAG(sc) ((sc)->STATUS & (SC_STATUS_PEF_Msk | SC_STATUS_FEF_Msk | SC_STATUS_BEF_Msk))
/**
* @brief Clear specified receive error flag/status
*
* @param[in] sc The pointer of smartcard module.
* @param[in] u32Mask Receive error flag/status to clear, combination following values
* - \ref SC_STATUS_PEF_Msk
* - \ref SC_STATUS_FEF_Msk
* - \ref SC_STATUS_BEF_Msk
*
* @return None
*
* @details The macro is used to clear receiver parity error flag, frame error flag or break error flag.
* \hideinitializer
*/
#define SCUART_CLR_ERR_FLAG(sc, u32Mask) ((sc)->STATUS = (u32Mask))
void SCUART_Close(SC_T* sc);
uint32_t SCUART_Open(SC_T* sc, uint32_t u32Baudrate);
uint32_t SCUART_Read(SC_T* sc, uint8_t pu8RxBuf[], uint32_t u32ReadBytes);
uint32_t SCUART_SetLineConfig(SC_T* sc, uint32_t u32Baudrate, uint32_t u32DataWidth, uint32_t u32Parity, uint32_t u32StopBits);
void SCUART_SetTimeoutCnt(SC_T* sc, uint32_t u32TOC);
void SCUART_Write(SC_T* sc, uint8_t pu8TxBuf[], uint32_t u32WriteBytes);
/**@}*/ /* end of group SCUART_EXPORTED_FUNCTIONS */
/**@}*/ /* end of group SCUART_Driver */
/**@}*/ /* end of group Standard_Driver */
#ifdef __cplusplus
}
#endif
#endif /* __NU_SCUART_H__ */

View File

@ -0,0 +1,203 @@
/**************************************************************************//**
* @file nu_sdh.h
* @version V1.00
* @brief M2354 SDH driver header file
*
* @copyright SPDX-License-Identifier: Apache-2.0
* @copyright Copyright (C) 2020 Nuvoton Technology Corp. All rights reserved.
*****************************************************************************/
#ifndef __NU_SDH_H__
#define __NU_SDH_H__
#ifdef __cplusplus
extern "C"
{
#endif
#include <stdio.h>
/** @addtogroup Standard_Driver Standard Driver
@{
*/
/** @addtogroup SDH_Driver SDH Driver
@{
*/
/** @addtogroup SDH_EXPORTED_CONSTANTS SDH Exported Constants
@{
*/
#define SDH_ERR_ID 0xFFFF0100UL /*!< SDH error ID \hideinitializer */
#define SDH_TIMEOUT (SDH_ERR_ID|0x01UL) /*!< Timeout \hideinitializer */
#define SDH_NO_MEMORY (SDH_ERR_ID|0x02UL) /*!< OOM \hideinitializer */
/* -- function return value */
#define Successful 0U /*!< Success \hideinitializer */
#define Fail 1U /*!< Failed \hideinitializer */
/* --- define type of SD card or MMC */
#define SDH_TYPE_UNKNOWN 0UL /*!< Unknown card type \hideinitializer */
#define SDH_TYPE_SD_HIGH 1UL /*!< SDHC card \hideinitializer */
#define SDH_TYPE_SD_LOW 2UL /*!< SD card \hideinitializer */
#define SDH_TYPE_MMC 3UL /*!< MMC card \hideinitializer */
#define SDH_TYPE_EMMC 4UL /*!< eMMC card \hideinitializer */
/* SD error */
#define SDH_NO_SD_CARD (SDH_ERR_ID|0x10UL) /*!< Card removed \hideinitializer */
#define SDH_ERR_DEVICE (SDH_ERR_ID|0x11UL) /*!< Device error \hideinitializer */
#define SDH_INIT_TIMEOUT (SDH_ERR_ID|0x12UL) /*!< Card init timeout \hideinitializer */
#define SDH_SELECT_ERROR (SDH_ERR_ID|0x13UL) /*!< Card select error \hideinitializer */
#define SDH_WRITE_PROTECT (SDH_ERR_ID|0x14UL) /*!< Card write protect \hideinitializer */
#define SDH_INIT_ERROR (SDH_ERR_ID|0x15UL) /*!< Card init error \hideinitializer */
#define SDH_CRC7_ERROR (SDH_ERR_ID|0x16UL) /*!< CRC 7 error \hideinitializer */
#define SDH_CRC16_ERROR (SDH_ERR_ID|0x17UL) /*!< CRC 16 error \hideinitializer */
#define SDH_CRC_ERROR (SDH_ERR_ID|0x18UL) /*!< CRC error \hideinitializer */
#define SDH_CMD8_ERROR (SDH_ERR_ID|0x19UL) /*!< Command 8 error \hideinitializer */
#define MMC_FREQ 20000UL /*!< output 20MHz to MMC \hideinitializer */
#define SD_FREQ 25000UL /*!< output 25MHz to SD \hideinitializer */
#define SDHC_FREQ 50000UL /*!< output 50MHz to SDH \hideinitializer */
#define CardDetect_From_GPIO (1UL << 8) /*!< Card detection pin is GPIO \hideinitializer */
#define CardDetect_From_DAT3 (1UL << 9) /*!< Card detection pin is DAT3 \hideinitializer */
/**@}*/ /* end of group SDH_EXPORTED_CONSTANTS */
/** @addtogroup SDH_EXPORTED_TYPEDEF SDH Exported Type Defines
@{
*/
#if defined ( __ARMCC_VERSION )
#pragma pack(push)
#pragma pack(1)
#endif
typedef struct SDH_info_t
{
unsigned int CardType; /*!< SDHC, SD, or MMC */
unsigned int RCA; /*!< Relative card address */
unsigned char IsCardInsert; /*!< Card insert state */
unsigned int totalSectorN; /*!< Total sector number */
unsigned int diskSize; /*!< Disk size in K bytes */
int sectorSize; /*!< Sector size in bytes */
} SDH_INFO_T; /*!< Structure holds SD card info */
#if defined ( __ARMCC_VERSION )
#pragma pack(pop)
#endif
/**@}*/ /* end of group SDH_EXPORTED_TYPEDEF */
/** @cond HIDDEN_SYMBOLS */
extern SDH_INFO_T SD0;
extern uint8_t volatile g_u8SDDataReadyFlag;
extern uint8_t g_u8R3Flag;
/** @endcond HIDDEN_SYMBOLS */
/** @addtogroup SDH_EXPORTED_FUNCTIONS SDH Exported Functions
@{
*/
/**
* @brief Enable specified interrupt.
*
* @param[in] sdh The pointer of the specified SDH module.
* @param[in] u32IntMask Interrupt type mask:
* \ref SDH_INTEN_BLKDIEN_Msk / \ref SDH_INTEN_CRCIEN_Msk / \ref SDH_INTEN_CDIEN_Msk /
* \ref SDH_INTEN_CDSRC_Msk / \ref SDH_INTEN_RTOIEN_Msk / \ref SDH_INTEN_DITOIEN_Msk /
* \ref SDH_INTEN_WKIEN_Msk
*
* @return None.
* \hideinitializer
*/
#define SDH_ENABLE_INT(sdh, u32IntMask) ((sdh)->INTEN |= (u32IntMask))
/**
* @brief Disable specified interrupt.
*
* @param[in] sdh The pointer of the specified SDH module.
* @param[in] u32IntMask Interrupt type mask:
* \ref SDH_INTEN_BLKDIEN_Msk / \ref SDH_INTEN_CRCIEN_Msk / \ref SDH_INTEN_CDIEN_Msk /
* \ref SDH_INTEN_RTOIEN_Msk / \ref SDH_INTEN_DITOIEN_Msk / \ref SDH_INTEN_WKIEN_Msk / \ref SDH_INTEN_CDSRC_Msk /
*
* @return None.
* \hideinitializer
*/
#define SDH_DISABLE_INT(sdh, u32IntMask) ((sdh)->INTEN &= ~(u32IntMask))
/**
* @brief Get specified interrupt flag/status.
*
* @param[in] sdh The pointer of the specified SDH module.
* @param[in] u32IntMask Interrupt type mask:
* \ref SDH_INTSTS_BLKDIF_Msk / \ref SDH_INTSTS_CRCIF_Msk / \ref SDH_INTSTS_CRC7_Msk /
* \ref SDH_INTSTS_CRC16_Msk / \ref SDH_INTSTS_CRCSTS_Msk / \ref SDH_INTSTS_DAT0STS_Msk /
* \ref SDH_INTSTS_CDIF_Msk / \ref SDH_INTSTS_RTOIF_Msk /
* \ref SDH_INTSTS_DITOIF_Msk / \ref SDH_INTSTS_CDSTS_Msk /
* \ref SDH_INTSTS_DAT1STS_Msk
*
*
* @return 0 = The specified interrupt is not happened.
* 1 = The specified interrupt is happened.
* \hideinitializer
*/
#define SDH_GET_INT_FLAG(sdh, u32IntMask) (((sdh)->INTSTS & (u32IntMask))?1:0)
/**
* @brief Clear specified interrupt flag/status.
*
* @param[in] sdh The pointer of the specified SDH module.
* @param[in] u32IntMask Interrupt type mask:
* \ref SDH_INTSTS_BLKDIF_Msk / \ref SDH_INTSTS_CRCIF_Msk / \ref SDH_INTSTS_CDIF_Msk /
* \ref SDH_INTSTS_RTOIF_Msk / \ref SDH_INTSTS_DITOIF_Msk
*
*
* @return None.
* \hideinitializer
*/
#define SDH_CLR_INT_FLAG(sdh, u32IntMask) ((sdh)->INTSTS = (u32IntMask))
/**
* @brief Check SD Card inserted or removed.
*
* @param[in] sdh The pointer of the specified SDH module.
*
* @return 1: Card inserted.
* 0: Card removed.
* \hideinitializer
*/
#define SDH_IS_CARD_PRESENT(sdh) ((((sdh) == SDH0)||((sdh) == SDH0_NS))? SD0.IsCardInsert : 0)
/**
* @brief Get SD Card capacity.
*
* @param[in] sdh The pointer of the specified SDH module.
*
* @return SD Card capacity. (unit: KByte)
* \hideinitializer
*/
#define SDH_GET_CARD_CAPACITY(sdh) ((((sdh) == SDH0)||((sdh) == SDH0_NS))? SD0.diskSize : 0)
void SDH_Open(SDH_T *sdh, uint32_t u32CardDetSrc);
uint32_t SDH_Probe(SDH_T *sdh);
uint32_t SDH_Read(SDH_T *sdh, uint8_t *pu8BufAddr, uint32_t u32StartSec, uint32_t u32SecCount);
uint32_t SDH_Write(SDH_T *sdh, uint8_t *pu8BufAddr, uint32_t u32StartSec, uint32_t u32SecCount);
uint32_t SDH_CardDetection(SDH_T *sdh);
void SDH_Open_Disk(SDH_T *sdh, uint32_t u32CardDetSrc);
void SDH_Close_Disk(SDH_T *sdh);
/**@}*/ /* end of group SDH_EXPORTED_FUNCTIONS */
/**@}*/ /* end of group SDH_Driver */
/**@}*/ /* end of group Standard_Driver */
#ifdef __cplusplus
}
#endif
#endif /* end of __NU_SDH_H__ */

View File

@ -0,0 +1,582 @@
/******************************************************************************
* @file nu_spi.h
* @version V3.00
* @brief M2354 series SPI driver header file
*
* @copyright SPDX-License-Identifier: Apache-2.0
* @copyright Copyright (C) 2020 Nuvoton Technology Corp. All rights reserved.
*****************************************************************************/
#ifndef __NU_SPI_H__
#define __NU_SPI_H__
#ifdef __cplusplus
extern "C"
{
#endif
/** @addtogroup Standard_Driver Standard Driver
@{
*/
/** @addtogroup SPI_Driver SPI Driver
@{
*/
/** @addtogroup SPI_EXPORTED_CONSTANTS SPI Exported Constants
@{
*/
#define SPI_MODE_0 (SPI_CTL_TXNEG_Msk) /*!< CLKPOL=0; RXNEG=0; TXNEG=1 */
#define SPI_MODE_1 (SPI_CTL_RXNEG_Msk) /*!< CLKPOL=0; RXNEG=1; TXNEG=0 */
#define SPI_MODE_2 (SPI_CTL_CLKPOL_Msk | SPI_CTL_RXNEG_Msk) /*!< CLKPOL=1; RXNEG=1; TXNEG=0 */
#define SPI_MODE_3 (SPI_CTL_CLKPOL_Msk | SPI_CTL_TXNEG_Msk) /*!< CLKPOL=1; RXNEG=0; TXNEG=1 */
#define SPI_SLAVE (SPI_CTL_SLAVE_Msk) /*!< Set as slave */
#define SPI_MASTER (0x0UL) /*!< Set as master */
#define SPI_SS (SPI_SSCTL_SS_Msk) /*!< Set SS */
#define SPI_SS_ACTIVE_HIGH (SPI_SSCTL_SSACTPOL_Msk) /*!< SS active high */
#define SPI_SS_ACTIVE_LOW (0x0UL) /*!< SS active low */
/* SPI Interrupt Mask */
#define SPI_UNIT_INT_MASK (0x001UL) /*!< Unit transfer interrupt mask */
#define SPI_SSACT_INT_MASK (0x002UL) /*!< Slave selection signal active interrupt mask */
#define SPI_SSINACT_INT_MASK (0x004UL) /*!< Slave selection signal inactive interrupt mask */
#define SPI_SLVUR_INT_MASK (0x008UL) /*!< Slave under run interrupt mask */
#define SPI_SLVBE_INT_MASK (0x010UL) /*!< Slave bit count error interrupt mask */
#define SPI_TXUF_INT_MASK (0x040UL) /*!< Slave TX underflow interrupt mask */
#define SPI_FIFO_TXTH_INT_MASK (0x080UL) /*!< FIFO TX threshold interrupt mask */
#define SPI_FIFO_RXTH_INT_MASK (0x100UL) /*!< FIFO RX threshold interrupt mask */
#define SPI_FIFO_RXOV_INT_MASK (0x200UL) /*!< FIFO RX overrun interrupt mask */
#define SPI_FIFO_RXTO_INT_MASK (0x400UL) /*!< FIFO RX time-out interrupt mask */
/* SPI Status Mask */
#define SPI_BUSY_MASK (0x01UL) /*!< Busy status mask */
#define SPI_RX_EMPTY_MASK (0x02UL) /*!< RX empty status mask */
#define SPI_RX_FULL_MASK (0x04UL) /*!< RX full status mask */
#define SPI_TX_EMPTY_MASK (0x08UL) /*!< TX empty status mask */
#define SPI_TX_FULL_MASK (0x10UL) /*!< TX full status mask */
#define SPI_TXRX_RESET_MASK (0x20UL) /*!< TX or RX reset status mask */
#define SPI_SPIEN_STS_MASK (0x40UL) /*!< SPIEN status mask */
#define SPI_SSLINE_STS_MASK (0x80UL) /*!< SPIx_SS line status mask */
/* SPI Status2 Mask */
#define SPI_SLVBENUM_MASK (0x01UL) /*!< Effective bit number of uncompleted RX data status mask */
/* I2S Data Width */
#define SPII2S_DATABIT_8 (0UL << SPI_I2SCTL_WDWIDTH_Pos) /*!< I2S data width is 8-bit */
#define SPII2S_DATABIT_16 (1UL << SPI_I2SCTL_WDWIDTH_Pos) /*!< I2S data width is 16-bit */
#define SPII2S_DATABIT_24 (2UL << SPI_I2SCTL_WDWIDTH_Pos) /*!< I2S data width is 24-bit */
#define SPII2S_DATABIT_32 (3UL << SPI_I2SCTL_WDWIDTH_Pos) /*!< I2S data width is 32-bit */
/* I2S Audio Format */
#define SPII2S_MONO SPI_I2SCTL_MONO_Msk /*!< Monaural channel */
#define SPII2S_STEREO (0UL) /*!< Stereo channel */
/* I2S Data Format */
#define SPII2S_FORMAT_I2S (0UL << SPI_I2SCTL_FORMAT_Pos) /*!< I2S data format */
#define SPII2S_FORMAT_MSB (1UL << SPI_I2SCTL_FORMAT_Pos) /*!< MSB justified data format */
#define SPII2S_FORMAT_PCMA (2UL << SPI_I2SCTL_FORMAT_Pos) /*!< PCM mode A data format */
#define SPII2S_FORMAT_PCMB (3UL << SPI_I2SCTL_FORMAT_Pos) /*!< PCM mode B data format */
/* I2S Operation mode */
#define SPII2S_MODE_SLAVE SPI_I2SCTL_SLAVE_Msk /*!< As slave mode */
#define SPII2S_MODE_MASTER (0UL) /*!< As master mode */
/* I2S TX FIFO Threshold */
#define SPII2S_FIFO_TX_LEVEL_WORD_0 (0UL) /*!< TX threshold is 0 word */
#define SPII2S_FIFO_TX_LEVEL_WORD_1 (1UL << SPI_FIFOCTL_TXTH_Pos) /*!< TX threshold is 1 word */
#define SPII2S_FIFO_TX_LEVEL_WORD_2 (2UL << SPI_FIFOCTL_TXTH_Pos) /*!< TX threshold is 2 words */
#define SPII2S_FIFO_TX_LEVEL_WORD_3 (3UL << SPI_FIFOCTL_TXTH_Pos) /*!< TX threshold is 3 words */
/* I2S RX FIFO Threshold */
#define SPII2S_FIFO_RX_LEVEL_WORD_1 (0UL) /*!< RX threshold is 1 word */
#define SPII2S_FIFO_RX_LEVEL_WORD_2 (1UL << SPI_FIFOCTL_RXTH_Pos) /*!< RX threshold is 2 words */
#define SPII2S_FIFO_RX_LEVEL_WORD_3 (2UL << SPI_FIFOCTL_RXTH_Pos) /*!< RX threshold is 3 words */
#define SPII2S_FIFO_RX_LEVEL_WORD_4 (3UL << SPI_FIFOCTL_RXTH_Pos) /*!< RX threshold is 4 words */
/* I2S Record Channel */
#define SPII2S_MONO_RIGHT (0UL) /*!< Record mono right channel */
#define SPII2S_MONO_LEFT SPI_I2SCTL_RXLCH_Msk /*!< Record mono left channel */
/* I2S Channel */
#define SPII2S_RIGHT (0UL) /*!< Select right channel */
#define SPII2S_LEFT (1UL) /*!< Select left channel */
/* I2S Interrupt Mask */
#define SPII2S_FIFO_TXTH_INT_MASK (0x01UL) /*!< TX FIFO threshold interrupt mask */
#define SPII2S_FIFO_RXTH_INT_MASK (0x02UL) /*!< RX FIFO threshold interrupt mask */
#define SPII2S_FIFO_RXOV_INT_MASK (0x04UL) /*!< RX FIFO overrun interrupt mask */
#define SPII2S_FIFO_RXTO_INT_MASK (0x08UL) /*!< RX FIFO time-out interrupt mask */
#define SPII2S_TXUF_INT_MASK (0x10UL) /*!< TX FIFO underflow interrupt mask */
#define SPII2S_RIGHT_ZC_INT_MASK (0x20UL) /*!< Right channel zero cross interrupt mask */
#define SPII2S_LEFT_ZC_INT_MASK (0x40UL) /*!< Left channel zero cross interrupt mask */
#define SPII2S_SLAVE_ERR_INT_MASK (0x80UL) /*!< Bit clock loss interrupt mask */
/**@}*/ /* end of group SPI_EXPORTED_CONSTANTS */
/** @addtogroup SPI_EXPORTED_FUNCTIONS SPI Exported Functions
@{
*/
/**
* @brief Clear the unit transfer interrupt flag.
* @param[in] spi The pointer of the specified SPI module.
* @return None.
* @details Write 1 to UNITIF bit of SPI_STATUS register to clear the unit transfer interrupt flag.
*/
#define SPI_CLR_UNIT_TRANS_INT_FLAG(spi) ( (spi)->STATUS = SPI_STATUS_UNITIF_Msk )
/**
* @brief Disable Slave 3-wire mode.
* @param[in] spi The pointer of the specified SPI module.
* @return None.
* @details Clear SLV3WIRE bit of SPI_SSCTL register to disable Slave 3-wire mode.
*/
#define SPI_DISABLE_3WIRE_MODE(spi) ( (spi)->SSCTL &= ~SPI_SSCTL_SLV3WIRE_Msk )
/**
* @brief Enable Slave 3-wire mode.
* @param[in] spi The pointer of the specified SPI module.
* @return None.
* @details Set SLV3WIRE bit of SPI_SSCTL register to enable Slave 3-wire mode.
*/
#define SPI_ENABLE_3WIRE_MODE(spi) ( (spi)->SSCTL |= SPI_SSCTL_SLV3WIRE_Msk )
/**
* @brief Trigger RX PDMA function.
* @param[in] spi The pointer of the specified SPI module.
* @return None.
* @details Set RXPDMAEN bit of SPI_PDMACTL register to enable RX PDMA transfer function.
*/
#define SPI_TRIGGER_RX_PDMA(spi) ( (spi)->PDMACTL |= SPI_PDMACTL_RXPDMAEN_Msk )
/**
* @brief Trigger TX PDMA function.
* @param[in] spi The pointer of the specified SPI module.
* @return None.
* @details Set TXPDMAEN bit of SPI_PDMACTL register to enable TX PDMA transfer function.
*/
#define SPI_TRIGGER_TX_PDMA(spi) ( (spi)->PDMACTL |= SPI_PDMACTL_TXPDMAEN_Msk )
/**
* @brief Trigger TX and RX PDMA function.
* @param[in] spi The pointer of the specified SPI module.
* @return None.
* @details Set TXPDMAEN bit and RXPDMAEN bit of SPI_PDMACTL register to enable TX and RX PDMA transfer function.
*/
#define SPI_TRIGGER_TX_RX_PDMA(spi) ( (spi)->PDMACTL |= (SPI_PDMACTL_TXPDMAEN_Msk | SPI_PDMACTL_RXPDMAEN_Msk) )
/**
* @brief Disable RX PDMA transfer.
* @param[in] spi The pointer of the specified SPI module.
* @return None.
* @details Clear RXPDMAEN bit of SPI_PDMACTL register to disable RX PDMA transfer function.
*/
#define SPI_DISABLE_RX_PDMA(spi) ( (spi)->PDMACTL &= ~SPI_PDMACTL_RXPDMAEN_Msk )
/**
* @brief Disable TX PDMA transfer.
* @param[in] spi The pointer of the specified SPI module.
* @return None.
* @details Clear TXPDMAEN bit of SPI_PDMACTL register to disable TX PDMA transfer function.
*/
#define SPI_DISABLE_TX_PDMA(spi) ( (spi)->PDMACTL &= ~SPI_PDMACTL_TXPDMAEN_Msk )
/**
* @brief Disable TX and RX PDMA transfer.
* @param[in] spi The pointer of the specified SPI module.
* @return None.
* @details Clear TXPDMAEN bit and RXPDMAEN bit of SPI_PDMACTL register to disable TX and RX PDMA transfer function.
*/
#define SPI_DISABLE_TX_RX_PDMA(spi) ( (spi)->PDMACTL &= ~(SPI_PDMACTL_TXPDMAEN_Msk | SPI_PDMACTL_RXPDMAEN_Msk) )
/**
* @brief Get the count of available data in RX FIFO.
* @param[in] spi The pointer of the specified SPI module.
* @return The count of available data in RX FIFO.
* @details Read RXCNT (SPI_STATUS[27:24]) to get the count of available data in RX FIFO.
*/
#define SPI_GET_RX_FIFO_COUNT(spi) ( ((spi)->STATUS & SPI_STATUS_RXCNT_Msk) >> SPI_STATUS_RXCNT_Pos )
/**
* @brief Get the RX FIFO empty flag.
* @param[in] spi The pointer of the specified SPI module.
* @retval 0 RX FIFO is not empty.
* @retval 1 RX FIFO is empty.
* @details Read RXEMPTY bit of SPI_STATUS register to get the RX FIFO empty flag.
*/
#define SPI_GET_RX_FIFO_EMPTY_FLAG(spi) ( ((spi)->STATUS & SPI_STATUS_RXEMPTY_Msk) >> SPI_STATUS_RXEMPTY_Pos )
/**
* @brief Get the TX FIFO empty flag.
* @param[in] spi The pointer of the specified SPI module.
* @retval 0 TX FIFO is not empty.
* @retval 1 TX FIFO is empty.
* @details Read TXEMPTY bit of SPI_STATUS register to get the TX FIFO empty flag.
*/
#define SPI_GET_TX_FIFO_EMPTY_FLAG(spi) ( ((spi)->STATUS & SPI_STATUS_TXEMPTY_Msk) >> SPI_STATUS_TXEMPTY_Pos )
/**
* @brief Get the TX FIFO full flag.
* @param[in] spi The pointer of the specified SPI module.
* @retval 0 TX FIFO is not full.
* @retval 1 TX FIFO is full.
* @details Read TXFULL bit of SPI_STATUS register to get the TX FIFO full flag.
*/
#define SPI_GET_TX_FIFO_FULL_FLAG(spi) ( ((spi)->STATUS & SPI_STATUS_TXFULL_Msk) >> SPI_STATUS_TXFULL_Pos )
/**
* @brief Get the datum read from RX register.
* @param[in] spi The pointer of the specified SPI module.
* @return Data in RX register.
* @details Read SPI_RX register to get the received datum.
*/
#define SPI_READ_RX(spi) ( (spi)->RX )
/**
* @brief Write datum to TX register.
* @param[in] spi The pointer of the specified SPI module.
* @param[in] u32TxData The datum which user attempt to transfer through SPI bus.
* @return None.
* @details Write u32TxData to SPI_TX register.
*/
#define SPI_WRITE_TX(spi, u32TxData) ( (spi)->TX = (u32TxData) )
/**
* @brief Set SPIx_SS pin to high state.
* @param[in] spi The pointer of the specified SPI module.
* @return None.
* @details Disable automatic slave selection function and set SPIx_SS pin to high state.
*/
#define SPI_SET_SS_HIGH(spi) ( (spi)->SSCTL = ((spi)->SSCTL & (~SPI_SSCTL_AUTOSS_Msk)) | (SPI_SSCTL_SSACTPOL_Msk | SPI_SSCTL_SS_Msk) )
/**
* @brief Set SPIx_SS pin to low state.
* @param[in] spi The pointer of the specified SPI module.
* @return None.
* @details Disable automatic slave selection function and set SPIx_SS pin to low state.
*/
#define SPI_SET_SS_LOW(spi) ( (spi)->SSCTL = ((spi)->SSCTL & (~(SPI_SSCTL_AUTOSS_Msk | SPI_SSCTL_SSACTPOL_Msk))) | SPI_SSCTL_SS_Msk )
/**
* @brief Enable Byte Reorder function.
* @param[in] spi The pointer of the specified SPI module.
* @return None.
* @details Enable Byte Reorder function. The suspend interval depends on the setting of SUSPITV (SPI_CTL[7:4]).
*/
#define SPI_ENABLE_BYTE_REORDER(spi) ( (spi)->CTL |= SPI_CTL_REORDER_Msk )
/**
* @brief Disable Byte Reorder function.
* @param[in] spi The pointer of the specified SPI module.
* @return None.
* @details Clear REORDER bit field of SPI_CTL register to disable Byte Reorder function.
*/
#define SPI_DISABLE_BYTE_REORDER(spi) ( (spi)->CTL &= ~SPI_CTL_REORDER_Msk )
/**
* @brief Set the length of suspend interval.
* @param[in] spi The pointer of the specified SPI module.
* @param[in] u32SuspCycle Decides the length of suspend interval. It could be 0 ~ 15.
* @return None.
* @details Set the length of suspend interval according to u32SuspCycle.
* The length of suspend interval is ((u32SuspCycle + 0.5) * the length of one SPI bus clock cycle).
*/
#define SPI_SET_SUSPEND_CYCLE(spi, u32SuspCycle) ( (spi)->CTL = ((spi)->CTL & ~SPI_CTL_SUSPITV_Msk) | ((u32SuspCycle) << SPI_CTL_SUSPITV_Pos) )
/**
* @brief Set the SPI transfer sequence with LSB first.
* @param[in] spi The pointer of the specified SPI module.
* @return None.
* @details Set LSB bit of SPI_CTL register to set the SPI transfer sequence with LSB first.
*/
#define SPI_SET_LSB_FIRST(spi) ( (spi)->CTL |= SPI_CTL_LSB_Msk )
/**
* @brief Set the SPI transfer sequence with MSB first.
* @param[in] spi The pointer of the specified SPI module.
* @return None.
* @details Clear LSB bit of SPI_CTL register to set the SPI transfer sequence with MSB first.
*/
#define SPI_SET_MSB_FIRST(spi) ( (spi)->CTL &= ~SPI_CTL_LSB_Msk )
/**
* @brief Set the data width of a SPI transaction.
* @param[in] spi The pointer of the specified SPI module.
* @param[in] u32Width The bit width of one transaction.
* @return None.
* @details The data width can be 8 ~ 32 bits.
*/
#define SPI_SET_DATA_WIDTH(spi, u32Width) ( (spi)->CTL = ((spi)->CTL & ~SPI_CTL_DWIDTH_Msk) | (((u32Width) & 0x1F) << SPI_CTL_DWIDTH_Pos) )
/**
* @brief Get the SPI busy state.
* @param[in] spi The pointer of the specified SPI module.
* @retval 0 SPI controller is not busy.
* @retval 1 SPI controller is busy.
* @details This macro will return the busy state of SPI controller.
*/
#define SPI_IS_BUSY(spi) ( ((spi)->STATUS & SPI_STATUS_BUSY_Msk) >> SPI_STATUS_BUSY_Pos )
/**
* @brief Enable SPI controller.
* @param[in] spi The pointer of the specified SPI module.
* @return None.
* @details Set SPIEN (SPI_CTL[0]) to enable SPI controller.
*/
#define SPI_ENABLE(spi) ( (spi)->CTL |= SPI_CTL_SPIEN_Msk )
/**
* @brief Disable SPI controller.
* @param[in] spi The pointer of the specified SPI module.
* @return None.
* @details Clear SPIEN (SPI_CTL[0]) to disable SPI controller.
*/
#define SPI_DISABLE(spi) ( (spi)->CTL &= ~SPI_CTL_SPIEN_Msk )
/**
* @brief Enable zero cross detection function.
* @param[in] i2s The pointer of the specified I2S module.
* @param[in] u32ChMask The mask for left or right channel. Valid values are:
* - \ref SPII2S_RIGHT
* - \ref SPII2S_LEFT
* @return None
* @details This function will set RZCEN or LZCEN bit of SPI_I2SCTL register to enable zero cross detection function.
*/
__STATIC_INLINE void SPII2S_ENABLE_TX_ZCD(SPI_T *i2s, uint32_t u32ChMask)
{
if(u32ChMask == SPII2S_RIGHT)
{
i2s->I2SCTL |= SPI_I2SCTL_RZCEN_Msk;
}
else
{
i2s->I2SCTL |= SPI_I2SCTL_LZCEN_Msk;
}
}
/**
* @brief Disable zero cross detection function.
* @param[in] i2s The pointer of the specified I2S module.
* @param[in] u32ChMask The mask for left or right channel. Valid values are:
* - \ref SPII2S_RIGHT
* - \ref SPII2S_LEFT
* @return None
* @details This function will clear RZCEN or LZCEN bit of SPI_I2SCTL register to disable zero cross detection function.
*/
__STATIC_INLINE void SPII2S_DISABLE_TX_ZCD(SPI_T *i2s, uint32_t u32ChMask)
{
if(u32ChMask == SPII2S_RIGHT)
{
i2s->I2SCTL &= ~SPI_I2SCTL_RZCEN_Msk;
}
else
{
i2s->I2SCTL &= ~SPI_I2SCTL_LZCEN_Msk;
}
}
/**
* @brief Enable I2S TX DMA function.
* @param[in] i2s The pointer of the specified I2S module.
* @return None
* @details This macro will set TXPDMAEN bit of SPI_PDMACTL register to transmit data with PDMA.
*/
#define SPII2S_ENABLE_TXDMA(i2s) ( (i2s)->PDMACTL |= SPI_PDMACTL_TXPDMAEN_Msk )
/**
* @brief Disable I2S TX DMA function.
* @param[in] i2s The pointer of the specified I2S module.
* @return None
* @details This macro will clear TXPDMAEN bit of SPI_PDMACTL register to disable TX DMA function.
*/
#define SPII2S_DISABLE_TXDMA(i2s) ( (i2s)->PDMACTL &= ~SPI_PDMACTL_TXPDMAEN_Msk )
/**
* @brief Enable I2S RX DMA function.
* @param[in] i2s The pointer of the specified I2S module.
* @return None
* @details This macro will set RXPDMAEN bit of SPI_PDMACTL register to receive data with PDMA.
*/
#define SPII2S_ENABLE_RXDMA(i2s) ( (i2s)->PDMACTL |= SPI_PDMACTL_RXPDMAEN_Msk )
/**
* @brief Disable I2S RX DMA function.
* @param[in] i2s The pointer of the specified I2S module.
* @return None
* @details This macro will clear RXPDMAEN bit of SPI_PDMACTL register to disable RX DMA function.
*/
#define SPII2S_DISABLE_RXDMA(i2s) ( (i2s)->PDMACTL &= ~SPI_PDMACTL_RXPDMAEN_Msk )
/**
* @brief Enable I2S TX function.
* @param[in] i2s The pointer of the specified I2S module.
* @return None
* @details This macro will set TXEN bit of SPI_I2SCTL register to enable I2S TX function.
*/
#define SPII2S_ENABLE_TX(i2s) ( (i2s)->I2SCTL |= SPI_I2SCTL_TXEN_Msk )
/**
* @brief Disable I2S TX function.
* @param[in] i2s The pointer of the specified I2S module.
* @return None
* @details This macro will clear TXEN bit of SPI_I2SCTL register to disable I2S TX function.
*/
#define SPII2S_DISABLE_TX(i2s) ( (i2s)->I2SCTL &= ~SPI_I2SCTL_TXEN_Msk )
/**
* @brief Enable I2S RX function.
* @param[in] i2s The pointer of the specified I2S module.
* @return None
* @details This macro will set RXEN bit of SPI_I2SCTL register to enable I2S RX function.
*/
#define SPII2S_ENABLE_RX(i2s) ( (i2s)->I2SCTL |= SPI_I2SCTL_RXEN_Msk )
/**
* @brief Disable I2S RX function.
* @param[in] i2s The pointer of the specified I2S module.
* @return None
* @details This macro will clear RXEN bit of SPI_I2SCTL register to disable I2S RX function.
*/
#define SPII2S_DISABLE_RX(i2s) ( (i2s)->I2SCTL &= ~SPI_I2SCTL_RXEN_Msk )
/**
* @brief Enable TX Mute function.
* @param[in] i2s The pointer of the specified I2S module.
* @return None
* @details This macro will set MUTE bit of SPI_I2SCTL register to enable I2S TX mute function.
*/
#define SPII2S_ENABLE_TX_MUTE(i2s) ( (i2s)->I2SCTL |= SPI_I2SCTL_MUTE_Msk )
/**
* @brief Disable TX Mute function.
* @param[in] i2s The pointer of the specified I2S module.
* @return None
* @details This macro will clear MUTE bit of SPI_I2SCTL register to disable I2S TX mute function.
*/
#define SPII2S_DISABLE_TX_MUTE(i2s) ( (i2s)->I2SCTL &= ~SPI_I2SCTL_MUTE_Msk )
/**
* @brief Clear TX FIFO.
* @param[in] i2s The pointer of the specified I2S module.
* @return None
* @details This macro will clear TX FIFO. The internal TX FIFO pointer will be reset to FIFO start point.
*/
#define SPII2S_CLR_TX_FIFO(i2s) ( (i2s)->FIFOCTL |= SPI_FIFOCTL_TXFBCLR_Msk )
/**
* @brief Clear RX FIFO.
* @param[in] i2s The pointer of the specified I2S module.
* @return None
* @details This macro will clear RX FIFO. The internal RX FIFO pointer will be reset to FIFO start point.
*/
#define SPII2S_CLR_RX_FIFO(i2s) ( (i2s)->FIFOCTL |= SPI_FIFOCTL_RXFBCLR_Msk )
/**
* @brief This function sets the recording source channel when mono mode is used.
* @param[in] i2s The pointer of the specified I2S module.
* @param[in] u32Ch left or right channel. Valid values are:
* - \ref SPII2S_MONO_LEFT
* - \ref SPII2S_MONO_RIGHT
* @return None
* @details This function selects the recording source channel of monaural mode.
*/
__STATIC_INLINE void SPII2S_SET_MONO_RX_CHANNEL(SPI_T *i2s, uint32_t u32Ch)
{
u32Ch == SPII2S_MONO_LEFT ?
(i2s->I2SCTL |= SPI_I2SCTL_RXLCH_Msk) :
(i2s->I2SCTL &= ~SPI_I2SCTL_RXLCH_Msk);
}
/**
* @brief Write data to I2S TX FIFO.
* @param[in] i2s The pointer of the specified I2S module.
* @param[in] u32Data The value written to TX FIFO.
* @return None
* @details This macro will write a value to TX FIFO.
*/
#define SPII2S_WRITE_TX_FIFO(i2s, u32Data) ( (i2s)->TX = (u32Data) )
/**
* @brief Read RX FIFO.
* @param[in] i2s The pointer of the specified I2S module.
* @return The value read from RX FIFO.
* @details This function will return a value read from RX FIFO.
*/
#define SPII2S_READ_RX_FIFO(i2s) ( (i2s)->RX )
/**
* @brief Get the interrupt flag.
* @param[in] i2s The pointer of the specified I2S module.
* @param[in] u32Mask The mask value for all interrupt flags.
* @return The interrupt flags specified by the u32mask parameter.
* @details This macro will return the combination interrupt flags of SPI_I2SSTS register. The flags are specified by the u32mask parameter.
*/
#define SPII2S_GET_INT_FLAG(i2s, u32Mask) ( (i2s)->I2SSTS & (u32Mask) )
/**
* @brief Clear the interrupt flag.
* @param[in] i2s The pointer of the specified I2S module.
* @param[in] u32Mask The mask value for all interrupt flags.
* @return None
* @details This macro will clear the interrupt flags specified by the u32mask parameter.
* @note Except TX and RX FIFO threshold interrupt flags, the other interrupt flags can be cleared by writing 1 to itself.
*/
#define SPII2S_CLR_INT_FLAG(i2s, u32Mask) ( (i2s)->I2SSTS = (u32Mask) )
/**
* @brief Get transmit FIFO level
* @param[in] i2s The pointer of the specified I2S module.
* @return TX FIFO level
* @details This macro will return the number of available words in TX FIFO.
*/
#define SPII2S_GET_TX_FIFO_LEVEL(i2s) ( ((i2s)->I2SSTS & SPI_I2SSTS_TXCNT_Msk) >> SPI_I2SSTS_TXCNT_Pos )
/**
* @brief Get receive FIFO level
* @param[in] i2s The pointer of the specified I2S module.
* @return RX FIFO level
* @details This macro will return the number of available words in RX FIFO.
*/
#define SPII2S_GET_RX_FIFO_LEVEL(i2s) ( ((i2s)->I2SSTS & SPI_I2SSTS_RXCNT_Msk) >> SPI_I2SSTS_RXCNT_Pos )
/* Function prototype declaration */
uint32_t SPI_Open(SPI_T *spi, uint32_t u32MasterSlave, uint32_t u32SPIMode, uint32_t u32DataWidth, uint32_t u32BusClock);
void SPI_Close(SPI_T *spi);
void SPI_ClearRxFIFO(SPI_T *spi);
void SPI_ClearTxFIFO(SPI_T *spi);
void SPI_DisableAutoSS(SPI_T *spi);
void SPI_EnableAutoSS(SPI_T *spi, uint32_t u32SSPinMask, uint32_t u32ActiveLevel);
uint32_t SPI_SetBusClock(SPI_T *spi, uint32_t u32BusClock);
void SPI_SetFIFO(SPI_T *spi, uint32_t u32TxThreshold, uint32_t u32RxThreshold);
uint32_t SPI_GetBusClock(SPI_T *spi);
void SPI_EnableInt(SPI_T *spi, uint32_t u32Mask);
void SPI_DisableInt(SPI_T *spi, uint32_t u32Mask);
uint32_t SPI_GetIntFlag(SPI_T *spi, uint32_t u32Mask);
void SPI_ClearIntFlag(SPI_T *spi, uint32_t u32Mask);
uint32_t SPI_GetStatus(SPI_T *spi, uint32_t u32Mask);
uint32_t SPI_GetStatus2(SPI_T *spi, uint32_t u32Mask);
uint32_t SPII2S_Open(SPI_T *i2s, uint32_t u32MasterSlave, uint32_t u32SampleRate, uint32_t u32WordWidth, uint32_t u32Channels, uint32_t u32DataFormat);
void SPII2S_Close(SPI_T *i2s);
void SPII2S_EnableInt(SPI_T *i2s, uint32_t u32Mask);
void SPII2S_DisableInt(SPI_T *i2s, uint32_t u32Mask);
uint32_t SPII2S_EnableMCLK(SPI_T *i2s, uint32_t u32BusClock);
void SPII2S_DisableMCLK(SPI_T *i2s);
void SPII2S_SetFIFO(SPI_T *i2s, uint32_t u32TxThreshold, uint32_t u32RxThreshold);
/**@}*/ /* end of group SPI_EXPORTED_FUNCTIONS */
/**@}*/ /* end of group SPI_Driver */
/**@}*/ /* end of group Standard_Driver */
#ifdef __cplusplus
}
#endif
#endif /* __NU_SPI_H__ */

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,464 @@
/**************************************************************************//**
* @file nu_tamper.h
* @version V3.00
* @brief M2354 series TAMPER driver header file
*
* @copyright SPDX-License-Identifier: Apache-2.0
* @copyright Copyright (C) 2020 Nuvoton Technology Corp. All rights reserved.
*****************************************************************************/
#ifndef __NU_TAMPER_H__
#define __NU_TAMPER_H__
#ifdef __cplusplus
extern "C"
{
#endif
/** @addtogroup Standard_Driver Standard Driver
@{
*/
/** @addtogroup TAMPER_Driver Tamper Driver
@{
*/
/** @addtogroup TAMPER_EXPORTED_CONSTANTS Tamper Exported Constants
@{
*/
#define TAMPER_TAMPER0_SELECT (0x1UL << 0) /*!< Select Tamper 0 */
#define TAMPER_TAMPER1_SELECT (0x1UL << 1) /*!< Select Tamper 1 */
#define TAMPER_TAMPER2_SELECT (0x1UL << 2) /*!< Select Tamper 2 */
#define TAMPER_TAMPER3_SELECT (0x1UL << 3) /*!< Select Tamper 3 */
#define TAMPER_TAMPER4_SELECT (0x1UL << 4) /*!< Select Tamper 4 */
#define TAMPER_TAMPER5_SELECT (0x1UL << 5) /*!< Select Tamper 5 */
#define TAMPER_MAX_TAMPER_PIN_NUM 6UL /*!< Tamper Pin number */
#define TAMPER_TAMPER_HIGH_LEVEL_DETECT 1UL /*!< Tamper pin detect voltage level is high */
#define TAMPER_TAMPER_LOW_LEVEL_DETECT 0UL /*!< Tamper pin detect voltage level is low */
#define TAMPER_TAMPER_DEBOUNCE_ENABLE 1UL /*!< Enable tamper pin de-bounce function */
#define TAMPER_TAMPER_DEBOUNCE_DISABLE 0UL /*!< Disable tamper pin de-bounce function */
#define TAMPER_PAIR0_SELECT (0x1UL << 0) /*!< Select Pair 0 */
#define TAMPER_PAIR1_SELECT (0x1UL << 1) /*!< Select Pair 1 */
#define TAMPER_PAIR2_SELECT (0x1UL << 2) /*!< Select Pair 2 */
#define TAMPER_MAX_PAIR_NUM 3UL /*!< Pair number */
#define TAMPER_2POW6_CLK (0x0UL << TAMPER_TIOCTL_DYNRATE_Pos) /*!< 64 RTC clock cycles */
#define TAMPER_2POW7_CLK (0x1UL << TAMPER_TIOCTL_DYNRATE_Pos) /*!< 64 x 2 RTC clock cycles */
#define TAMPER_2POW8_CLK (0x2UL << TAMPER_TIOCTL_DYNRATE_Pos) /*!< 64 x 4 RTC clock cycles */
#define TAMPER_2POW9_CLK (0x3UL << TAMPER_TIOCTL_DYNRATE_Pos) /*!< 64 x 6 RTC clock cycles */
#define TAMPER_2POW10_CLK (0x4UL << TAMPER_TIOCTL_DYNRATE_Pos) /*!< 64 x 8 RTC clock cycles */
#define TAMPER_2POW11_CLK (0x5UL << TAMPER_TIOCTL_DYNRATE_Pos) /*!< 64 x 10 RTC clock cycles */
#define TAMPER_2POW12_CLK (0x6UL << TAMPER_TIOCTL_DYNRATE_Pos) /*!< 64 x 12 RTC clock cycles */
#define TAMPER_2POW13_CLK (0x7UL << TAMPER_TIOCTL_DYNRATE_Pos) /*!< 64 x 14 RTC clock cycles */
#define TAMPER_ACTS_2POW10_CLK (0x0UL << 5) /*!< 1024 LIRC32K clock cycles */
#define TAMPER_ACTS_2POW11_CLK (0x1UL << 5) /*!< 1024 x 2 LIRC32K clock cycles */
#define TAMPER_ACTS_2POW12_CLK (0x2UL << 5) /*!< 1024 x 4 LIRC32K clock cycles */
#define TAMPER_ACTS_2POW13_CLK (0x3UL << 5) /*!< 1024 x 6 LIRC32K clock cycles */
#define TAMPER_ACTS_2POW14_CLK (0x4UL << 5) /*!< 1024 x 8 LIRC32K clock cycles */
#define TAMPER_ACTS_2POW15_CLK (0x5UL << 5) /*!< 1024 x 16 LIRC32K clock cycles */
#define TAMPER_ACTS_2POW16_CLK (0x6UL << 5) /*!< 1024 x 32 LIRC32K clock cycles */
#define TAMPER_ACTS_2POW17_CLK (0x7UL << 5) /*!< 1024 x 64 LIRC32K clock cycles */
#define TAMPER_REF_RANDOM_PATTERN 0x0UL /*!< The new reference pattern is generated by random number generator when the reference pattern run out */
#define TAMPER_REF_SEED 0x1UL /*!< The new reference pattern is repeated from SEED (TAMPER_SEED[31:0]) when the reference pattern run out */
#define TAMPER_VG_192M_SAMPLE 0x0UL /*!< Select voltage glitch 192M sampleing rate */
/**@}*/ /* end of group TAMPER_EXPORTED_CONSTANTS */
/** @addtogroup TAMPER_EXPORTED_FUNCTIONS Tamper Exported Functions
@{
*/
/**
* @brief Reset Tamper Coreblock
*
* @param None
*
* @return None
*
* @details To set TAMPER INIT control register to reset the tamper coreblock.
*
*/
#define TAMPER_CORE_RESET() ((uint32_t)(TAMPER->INIT = 0x55AA))
/**
* @brief Release Tamper Coreblock
*
* @param None
*
* @return None
*
* @details To set TAMPER INIT control register to release the tamper coreblock.
*
*/
#define TAMPER_CORE_RELEASE() ((uint32_t)(TAMPER->INIT = 0x5500))
/**
* @brief Get the Voltage Regulator Power Ready Status
*
* @param None
*
* @retval 0 The power status of voltage regulator is not ready.
* @retval 1 The power status of voltage regulator is ready.
*
* @details This macro will return the power status of voltage regulator.
*
*/
#define TAMPER_TLDO_IS_READY() (TAMPER->INIT & TAMPER_INIT_TLDORDY_Msk ? 1:0)
/**
* @brief Enable LXT Clock Detection
*
* @param None
*
* @return None
*
* @details To set TAMPER FUNEN control register to enable LXT clock detection.
*
*/
#define TAMPER_ENABLE_LXTDET() ((uint32_t)(TAMPER->FUNEN = (TAMPER->FUNEN & ~0xFFUL) | 0x44))
/**
* @brief Disable LXT Clock Detection
*
* @param None
*
* @return None
*
* @details To set TAMPER FUNEN control register to disable LXT clock detection.
*
*/
#define TAMPER_DISABLE_LXTDET() ((uint32_t)(TAMPER->FUNEN = (TAMPER->FUNEN & ~0xFFUL) | 0x40))
/**
* @brief Tamper I/O TAMPER Block Detection Selection
*
* @param[in] u32TamperSelect Tamper pin select. Possible options are
* - \ref TAMPER_TAMPER0_SELECT
* - \ref TAMPER_TAMPER1_SELECT
* - \ref TAMPER_TAMPER2_SELECT
* - \ref TAMPER_TAMPER3_SELECT
* - \ref TAMPER_TAMPER4_SELECT
* - \ref TAMPER_TAMPER5_SELECT
*
* @return None
*
* @details To set TAMPER FUNEN control register to select tamper I/O 0~5 and its function is detected through TAMPER block.
*
*/
__STATIC_INLINE void TAMPER_IOSEL_TAMPER(uint32_t u32TamperSelect)
{
uint32_t i;
for(i = 0UL; i < (uint32_t)TAMPER_MAX_TAMPER_PIN_NUM; i++)
{
if(u32TamperSelect & (0x1UL << i))
{
TAMPER->FUNEN = (TAMPER->FUNEN & ~0xFFUL) | (0x94 + i * 0x10UL);
}
}
}
/**
* @brief Tamper I/O RTC Block Detection Selection
*
* @param[in] u32TamperSelect Tamper pin select. Possible options are
* - \ref TAMPER_TAMPER0_SELECT
* - \ref TAMPER_TAMPER1_SELECT
* - \ref TAMPER_TAMPER2_SELECT
* - \ref TAMPER_TAMPER3_SELECT
* - \ref TAMPER_TAMPER4_SELECT
* - \ref TAMPER_TAMPER5_SELECT
*
* @return None
*
* @details To set TAMPER FUNEN control register to select tamper I/O 0~5 and its function is detected through RTC block.
*
*/
__STATIC_INLINE void TAMPER_IOSEL_RTC(uint32_t u32TamperSelect)
{
uint32_t i;
for(i = 0UL; i < (uint32_t)TAMPER_MAX_TAMPER_PIN_NUM; i++)
{
if(u32TamperSelect & (0x1UL << i))
{
TAMPER->FUNEN = (TAMPER->FUNEN & ~0xFFUL) | (0x90 + i * 0x10UL);
}
}
}
/**
* @brief Enable HIRC48M
*
* @param None
*
* @return None
*
* @details To set TAMPER FUNEN control register to enable HIRC48M.
*
*/
#define TAMPER_ENABLE_HIRC48M() ((uint32_t)(TAMPER->FUNEN &= (~TAMPER_FUNEN_HIRC48MEN_Msk)))
/**
* @brief Disable HIRC48M
*
* @param None
*
* @return None
*
* @details To set TAMPER FUNEN control register to disable HIRC48M.
*
*/
#define TAMPER_DISABLE_HIRC48M() ((uint32_t)(TAMPER->FUNEN = (TAMPER->FUNEN & (~TAMPER_FUNEN_HIRC48MEN_Msk)) | (0x5A << TAMPER_FUNEN_HIRC48MEN_Pos)))
/**
* @brief Voltage Glitch Sampling Rate Selection
*
* @param[in] u32VGSampleRate Voltage Glitch sampling rate select. Possible option is
* - \ref TAMPER_VG_192M_SAMPLE
*
* @return None
*
* @details To set TAMPER FUNEN control register to enable voltage glitch channel 0~3 to select voltage glitch sampling rate.
*
*/
__STATIC_INLINE void TAMPER_VG_SAMPLE_SEL(uint32_t u32VGSampleRate)
{
TAMPER->FUNEN &= ~0xF000000UL;
if(u32VGSampleRate == TAMPER_VG_192M_SAMPLE)
{
TAMPER->FUNEN |= TAMPER_FUNEN_VGCHEN0_Msk | TAMPER_FUNEN_VGCHEN1_Msk | TAMPER_FUNEN_VGCHEN2_Msk | TAMPER_FUNEN_VGCHEN3_Msk;
}
}
/**
* @brief Enable to Trigger Key Store
*
* @param None
*
* @return None
*
* @details Set KSTRIGEN bit of TAMPER TRIEN control register to trigger Key Store when Tamper event is detected.
*
*/
#define TAMPER_ENABLE_KS_TRIG() ((uint32_t)(TAMPER->TRIEN |= TAMPER_TRIEN_KSTRIGEN_Msk))
/**
* @brief Disable to Trigger Key Store
*
* @param None
*
* @return None
*
* @details Clear KSTRIGEN bit of TAMPER TRIEN control register to not trigger Key Store when Tamper event is detected.
*
*/
#define TAMPER_DISABLE_KS_TRIG() ((uint32_t)(TAMPER->TRIEN &= (~TAMPER_TRIEN_KSTRIGEN_Msk)))
/**
* @brief Enable Wake-up Function
*
* @param None
*
* @return None
*
* @details Set WAKEUPEN bit of TAMPER TRIEN control register to wake-up the system when Tamper event is detected.
*
*/
#define TAMPER_ENABLE_WAKEUP() ((uint32_t)(TAMPER->TRIEN |= TAMPER_TRIEN_WAKEUPEN_Msk))
/**
* @brief Disable Wake-up Function
*
* @param None
*
* @return None
*
* @details Clear WAKEUPEN bit of TAMPER TRIEN control register to not wake-up the system when Tamper event is detected.
*
*/
#define TAMPER_DISABLE_WAKEUP() ((uint32_t)(TAMPER->TRIEN &= (~TAMPER_TRIEN_WAKEUPEN_Msk)))
/**
* @brief Enable to Clear Crypto Function
*
* @param None
*
* @return None
*
* @details Set CRYPTOEN bit of TAMPER TRIEN control register to reset Crypto when Tamper event is detected.
*
*/
#define TAMPER_ENABLE_CRYPTO() ((uint32_t)(TAMPER->TRIEN |= TAMPER_TRIEN_CRYPTOEN_Msk))
/**
* @brief Disable to Clear Crypto Function
*
* @param None
*
* @return None
*
* @details Clear CRYPTOEN bit of TAMPER TRIEN control register to not reset Crypto when Tamper event is detected.
*
*/
#define TAMPER_DISABLE_CRYPTO() ((uint32_t)(TAMPER->TRIEN &= (~TAMPER_TRIEN_CRYPTOEN_Msk)))
/**
* @brief Enable to Trigger Chip Reset
*
* @param None
*
* @return None
*
* @details Set CHIPRSTEN bit of TAMPER TRIEN control register to reset the system when Tamper event is detected.
*
*/
#define TAMPER_ENABLE_CHIPRST() ((uint32_t)(TAMPER->TRIEN |= TAMPER_TRIEN_CHIPRSTEN_Msk))
/**
* @brief Disable to Trigger Chip Reset
*
* @param None
*
* @return None
*
* @details Clear CHIPRSTEN bit of TAMPER TRIEN control register to not reset the system when Tamper event is detected.
*
*/
#define TAMPER_DISABLE_CHIPRST() ((uint32_t)(TAMPER->TRIEN &= (~TAMPER_TRIEN_CHIPRSTEN_Msk)))
/**
* @brief Enable to Clear RTC Spare Register
*
* @param None
*
* @return None
*
* @details Set RTCSPCLREN bit of TAMPER TRIEN control register to reset RTC spare register when Tamper event is detected.
*
*/
#define TAMPER_ENABLE_RTCSPCLR() ((uint32_t)(TAMPER->TRIEN |= TAMPER_TRIEN_RTCSPCLREN_Msk))
/**
* @brief Disable to Clear RTC Spare Register
*
* @param None
*
* @return None
*
* @details Clear RTCSPCLREN bit of TAMPER TRIEN control register to not reset RTC spare register when Tamper event is detected.
*
*/
#define TAMPER_DISABLE_RTCSPCLR() ((uint32_t)(TAMPER->TRIEN &= (~TAMPER_TRIEN_RTCSPCLREN_Msk)))
/**
* @brief Get Tamper Interrupt Flag
*
* @param None
*
* @retval 0 Tamper event Interrupt did not occur
* @retval 1 Tamper event Interrupt occurred
*
* @details This macro indicates Tamper event intertupt occurred or not.
*
*/
#define TAMPER_GET_INT_FLAG() ((TAMPER->INTSTS & (0xAA7FAFFF))? 1:0)
/**
* @brief Clear Tamper Interrupt Status
*
* @param[in] u32TamperFlag Tamper event interrupt flag. It consists of:
* - \ref TAMPER_INTSTS_TAMP0IF_Msk
* - \ref TAMPER_INTSTS_TAMP1IF_Msk
* - \ref TAMPER_INTSTS_TAMP2IF_Msk
* - \ref TAMPER_INTSTS_TAMP3IF_Msk
* - \ref TAMPER_INTSTS_TAMP4IF_Msk
* - \ref TAMPER_INTSTS_TAMP5IF_Msk
* - \ref TAMPER_INTSTS_CLKFAILIF_Msk
* - \ref TAMPER_INTSTS_CLKSTOPIF_Msk
* - \ref TAMPER_INTSTS_OVPOUTIF_Msk
* - \ref TAMPER_INTSTS_VGPEVIF_Msk
* - \ref TAMPER_INTSTS_VGNEVIF_Msk
* - \ref TAMPER_INTSTS_ACTSEIF_Msk
* - \ref TAMPER_INTSTS_ACTST5IF_Msk
* - \ref TAMPER_INTSTS_ACTST25IF_Msk
* - \ref TAMPER_INTSTS_BODIF_Msk
* - \ref TAMPER_INTSTS_ACTST1IF_Msk
* - \ref TAMPER_INTSTS_ACTST3IF_Msk
* - \ref TAMPER_INTSTS_ACTST21IF_Msk
* - \ref TAMPER_INTSTS_ACTST23IF_Msk
*
* @return None
*
* @details This macro is used to clear Tamper event flag.
*
*/
#define TAMPER_CLR_INT_STATUS(u32TamperFlag) (TAMPER->INTSTS = (u32TamperFlag))
/**
* @brief Get Tamper Interrupt Status
*
* @param None
*
* @retval TAMPER_INTSTS_TAMP0IF_Msk
* @retval TAMPER_INTSTS_TAMP1IF_Msk
* @retval TAMPER_INTSTS_TAMP2IF_Msk
* @retval TAMPER_INTSTS_TAMP3IF_Msk
* @retval TAMPER_INTSTS_TAMP4IF_Msk
* @retval TAMPER_INTSTS_TAMP5IF_Msk
* @retval TAMPER_INTSTS_CLKFAILIF_Msk
* @retval TAMPER_INTSTS_CLKSTOPIF_Msk
* @retval TAMPER_INTSTS_OVPOUTIF_Msk
* @retval TAMPER_INTSTS_VGPEVIF_Msk
* @retval TAMPER_INTSTS_VGNEVIF_Msk
* @retval TAMPER_INTSTS_ACTSEFIF_Msk
* @retval TAMPER_INTSTS_ACTST5IF_Msk
* @retval TAMPER_INTSTS_ACTST25IF_Msk
* @retval TAMPER_INTSTS_RTCLVRIF_Msk
* @retval TAMPER_INTSTS_RIOTRIGIF_Msk
* @retval TAMPER_INTSTS_RCLKTRIGIF_Msk
* @retval TAMPER_INTSTS_BODIF_Msk
* @retval TAMPER_INTSTS_ACTST1IF_Msk
* @retval TAMPER_INTSTS_ACTST3IF_Msk
* @retval TAMPER_INTSTS_ACTST21IF_Msk
* @retval TAMPER_INTSTS_ACTST23IF_Msk
*
* @details This macro indicates Tamper event status.
*
*/
#define TAMPER_GET_INT_STATUS() ((TAMPER->INTSTS & (0xAA7FAFFF)))
void TAMPER_EnableInt(uint32_t u32IntFlagMask);
void TAMPER_DisableInt(uint32_t u32IntFlagMask);
void TAMPER_StaticTamperEnable(uint32_t u32TamperSelect, uint32_t u32DetecLevel, uint32_t u32DebounceEn);
void TAMPER_StaticTamperDisable(uint32_t u32TamperSelect);
void TAMPER_DynamicTamperEnable(uint32_t u32PairSel, uint32_t u32DebounceEn, uint32_t u32Pair1Source, uint32_t u32Pair2Source);
void TAMPER_DynamicTamperDisable(uint32_t u32PairSel);
void TAMPER_DynamicTamperConfig(uint32_t u32ChangeRate, uint32_t u32SeedReload, uint32_t u32RefPattern, uint32_t u32Seed);
void TAMPER_ActiveShieldDynamicTamperEnable(uint32_t u32PairSel1, uint32_t u32Pair1Source1, uint32_t u32PairSel2, uint32_t u32Pair1Source2);
void TAMPER_ActiveShieldDynamicTamperDisable(uint32_t u32PairSel1, uint32_t u32PairSe2);
void TAMPER_ActiveShieldDynamicTamperConfig(uint32_t u32ChangeRate1, uint32_t u32SeedReload1, uint32_t u32RefPattern1, uint32_t u32Seed,
uint32_t u32ChangeRate2, uint32_t u32SeedReload2, uint32_t u32RefPattern2, uint32_t u32Seed2);
/**@}*/ /* end of group TAMPER_EXPORTED_FUNCTIONS */
/**@}*/ /* end of group TAMPER_Driver */
/**@}*/ /* end of group Standard_Driver */
#ifdef __cplusplus
}
#endif
#endif /* __NU_TAMPER_H__ */

View File

@ -0,0 +1,541 @@
/**************************************************************************//**
* @file nu_timer.h
* @version V3.00
* @brief Timer Controller(Timer) driver header file
*
* @copyright SPDX-License-Identifier: Apache-2.0
* @copyright Copyright (C) 2020 Nuvoton Technology Corp. All rights reserved.
*****************************************************************************/
#ifndef __NU_TIMER_H__
#define __NU_TIMER_H__
#ifdef __cplusplus
extern "C"
{
#endif
/** @addtogroup Standard_Driver Standard Driver
@{
*/
/** @addtogroup TIMER_Driver TIMER Driver
@{
*/
/** @addtogroup TIMER_EXPORTED_CONSTANTS TIMER Exported Constants
@{
*/
/*---------------------------------------------------------------------------------------------------------*/
/* TIMER Operation Mode, External Counter and Capture Mode Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define TIMER_ONESHOT_MODE (0UL << TIMER_CTL_OPMODE_Pos) /*!< Timer working in one-shot mode \hideinitializer */
#define TIMER_PERIODIC_MODE (1UL << TIMER_CTL_OPMODE_Pos) /*!< Timer working in periodic mode \hideinitializer */
#define TIMER_TOGGLE_MODE (2UL << TIMER_CTL_OPMODE_Pos) /*!< Timer working in toggle-output mode \hideinitializer */
#define TIMER_CONTINUOUS_MODE (3UL << TIMER_CTL_OPMODE_Pos) /*!< Timer working in continuous counting mode \hideinitializer */
#define TIMER_TOUT_PIN_FROM_TMX (0UL << TIMER_CTL_TGLPINSEL_Pos) /*!< Timer toggle-output pin is from TMx pin \hideinitializer */
#define TIMER_TOUT_PIN_FROM_TMX_EXT (1UL << TIMER_CTL_TGLPINSEL_Pos) /*!< Timer toggle-output pin is from TMx_EXT pin \hideinitializer */
#define TIMER_COUNTER_EVENT_FALLING (0UL << TIMER_EXTCTL_CNTPHASE_Pos) /*!< Counter increase on falling edge detection \hideinitializer */
#define TIMER_COUNTER_EVENT_RISING (1UL << TIMER_EXTCTL_CNTPHASE_Pos) /*!< Counter increase on rising edge detection \hideinitializer */
#define TIMER_CAPTURE_FREE_COUNTING_MODE (0UL << TIMER_EXTCTL_CAPFUNCS_Pos) /*!< Timer capture event to get timer counter value \hideinitializer */
#define TIMER_CAPTURE_COUNTER_RESET_MODE (1UL << TIMER_EXTCTL_CAPFUNCS_Pos) /*!< Timer capture event to reset timer counter \hideinitializer */
#define TIMER_CAPTURE_EVENT_FALLING (0UL << TIMER_EXTCTL_CAPEDGE_Pos) /*!< Falling edge detection to trigger capture event \hideinitializer */
#define TIMER_CAPTURE_EVENT_RISING (1UL << TIMER_EXTCTL_CAPEDGE_Pos) /*!< Rising edge detection to trigger capture event \hideinitializer */
#define TIMER_CAPTURE_EVENT_FALLING_RISING (2UL << TIMER_EXTCTL_CAPEDGE_Pos) /*!< Both falling and rising edge detection to trigger capture event, and first event at falling edge \hideinitializer */
#define TIMER_CAPTURE_EVENT_RISING_FALLING (3UL << TIMER_EXTCTL_CAPEDGE_Pos) /*!< Both rising and falling edge detection to trigger capture event, and first event at rising edge \hideinitializer */
#define TIMER_CAPTURE_EVENT_GET_LOW_PERIOD (6UL << TIMER_EXTCTL_CAPEDGE_Pos) /*!< First capture event is at falling edge, follows are at at rising edge \hideinitializer */
#define TIMER_CAPTURE_EVENT_GET_HIGH_PERIOD (7UL << TIMER_EXTCTL_CAPEDGE_Pos) /*!< First capture event is at rising edge, follows are at at falling edge \hideinitializer */
#define TIMER_CAPTURE_SOURCE_FROM_PIN (0UL << TIMER_CTL_CAPSRC_Pos) /*!< The capture source is from TMx_EXT pin \hideinitializer */
#define TIMER_CAPTURE_SOURCE_FROM_INTERNAL (1UL << TIMER_CTL_CAPSRC_Pos) /*!< The capture source is from internal ACMPx signal or clock source \hideinitializer */
#define TIMER_CAPTURE_SOURCE_DIV_1 (0UL << TIMER_EXTCTL_CAPDIVSCL_Pos) /*!< Input capture source divide 1 \hideinitializer */
#define TIMER_CAPTURE_SOURCE_DIV_2 (1UL << TIMER_EXTCTL_CAPDIVSCL_Pos) /*!< Input capture source divide 2 \hideinitializer */
#define TIMER_CAPTURE_SOURCE_DIV_4 (2UL << TIMER_EXTCTL_CAPDIVSCL_Pos) /*!< Input capture source divide 4 \hideinitializer */
#define TIMER_CAPTURE_SOURCE_DIV_8 (3UL << TIMER_EXTCTL_CAPDIVSCL_Pos) /*!< Input capture source divide 8 \hideinitializer */
#define TIMER_CAPTURE_SOURCE_DIV_16 (4UL << TIMER_EXTCTL_CAPDIVSCL_Pos) /*!< Input capture source divide 16 \hideinitializer */
#define TIMER_CAPTURE_SOURCE_DIV_32 (5UL << TIMER_EXTCTL_CAPDIVSCL_Pos) /*!< Input capture source divide 32 \hideinitializer */
#define TIMER_CAPTURE_SOURCE_DIV_64 (6UL << TIMER_EXTCTL_CAPDIVSCL_Pos) /*!< Input capture source divide 64 \hideinitializer */
#define TIMER_CAPTURE_SOURCE_DIV_128 (7UL << TIMER_EXTCTL_CAPDIVSCL_Pos) /*!< Input capture source divide 128 \hideinitializer */
#define TIMER_CAPTURE_SOURCE_DIV_256 (8UL << TIMER_EXTCTL_CAPDIVSCL_Pos) /*!< Input capture source divide 256 \hideinitializer */
#define TIMER_INTER_CAPTURE_SOURCE_ACMP0 (0UL << TIMER_EXTCTL_INTERCAPSEL_Pos) /*!< Capture source from internal ACMP0 output signal \hideinitializer */
#define TIMER_INTER_CAPTURE_SOURCE_ACMP1 (1UL << TIMER_EXTCTL_INTERCAPSEL_Pos) /*!< Capture source from internal ACMP1 output signal \hideinitializer */
#define TIMER_INTER_CAPTURE_SOURCE_HXT (2UL << TIMER_EXTCTL_INTERCAPSEL_Pos) /*!< Capture source from HXT \hideinitializer */
#define TIMER_INTER_CAPTURE_SOURCE_LXT (3UL << TIMER_EXTCTL_INTERCAPSEL_Pos) /*!< Capture source from LXT \hideinitializer */
#define TIMER_INTER_CAPTURE_SOURCE_HIRC (4UL << TIMER_EXTCTL_INTERCAPSEL_Pos) /*!< Capture source from HIRC \hideinitializer */
#define TIMER_INTER_CAPTURE_SOURCE_LIRC (5UL << TIMER_EXTCTL_INTERCAPSEL_Pos) /*!< Capture source from LIRC \hideinitializer */
#define TIMER_INTER_CAPTURE_SOURCE_MIRC (6UL << TIMER_EXTCTL_INTERCAPSEL_Pos) /*!< Capture source from MIRC. Only available on TIMER4 and TIMER5 \hideinitializer */
#define TIMER_TRGSRC_TIMEOUT_EVENT (0UL << TIMER_TRGCTL_TRGSSEL_Pos) /*!< Select internal trigger source from timer time-out event \hideinitializer */
#define TIMER_TRGSRC_CAPTURE_EVENT (1UL << TIMER_TRGCTL_TRGSSEL_Pos) /*!< Select internal trigger source from timer capture event \hideinitializer */
#define TIMER_TRG_TO_PWM (TIMER_TRGCTL_TRGPWM_Msk) /*!< Each timer event as EPWM and BPWM counter clock source. NOT supported on TIMER4 and TIMER5 \hideinitializer */
#define TIMER_TRG_TO_EADC (TIMER_TRGCTL_TRGEADC_Msk) /*!< Each timer event to start ADC conversion \hideinitializer */
#define TIMER_TRG_TO_DAC (TIMER_TRGCTL_TRGDAC_Msk) /*!< Each timer event to start DAC conversion. NOT supported on TIMER4 and TIMER5 \hideinitializer */
#define TIMER_TRG_TO_PDMA (TIMER_TRGCTL_TRGPDMA_Msk) /*!< Each timer event to trigger PDMA transfer \hideinitializer */
/**@}*/ /* end of group TIMER_EXPORTED_CONSTANTS */
/** @addtogroup TIMER_EXPORTED_FUNCTIONS TIMER Exported Functions
@{
*/
/**
* @brief Set Timer Compared Value
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER0 ~ TIMER5.
* @param[in] u32Value Timer compare value. Valid values are between 2 to 0xFFFFFF.
*
* @return None
*
* @details This macro is used to set timer compared value to adjust timer time-out interval.
* @note 1. Never write 0x0 or 0x1 in this field, or the core will run into unknown state. \n
* 2. If update timer compared value in continuous counting mode, timer counter value will keep counting continuously. \n
* But if timer is operating at other modes, the timer up counter will restart counting and start from 0.
* \hideinitializer
*/
#define TIMER_SET_CMP_VALUE(timer, u32Value) ((timer)->CMP = (u32Value))
/**
* @brief Set Timer Prescale Value
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER0 ~ TIMER5.
* @param[in] u32Value Timer prescale value. Valid values are between 0 to 0xFF.
*
* @return None
*
* @details This macro is used to set timer prescale value and timer source clock will be divided by (prescale + 1) \n
* before it is fed into timer.
* \hideinitializer
*/
#define TIMER_SET_PRESCALE_VALUE(timer, u32Value) ((timer)->CTL = ((timer)->CTL & ~TIMER_CTL_PSC_Msk) | (u32Value))
/**
* @brief Check specify Timer Status
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER0 ~ TIMER5.
*
* @retval 0 Timer 24-bit up counter is inactive
* @retval 1 Timer 24-bit up counter is active
*
* @details This macro is used to check if specify Timer counter is inactive or active.
* \hideinitializer
*/
#define TIMER_IS_ACTIVE(timer) ((((timer)->CTL & TIMER_CTL_ACTSTS_Msk) == TIMER_CTL_ACTSTS_Msk)? 1 : 0)
/**
* @brief Select Toggle-output Pin
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER0 ~ TIMER5.
* @param[in] u32ToutSel Toggle-output pin selection, valid values are:
* - \ref TIMER_TOUT_PIN_FROM_TMX
* - \ref TIMER_TOUT_PIN_FROM_TMX_EXT
*
* @return None
*
* @details This macro is used to select timer toggle-output pin is output on TMx or TMx_EXT pin.
* \hideinitializer
*/
#define TIMER_SELECT_TOUT_PIN(timer, u32ToutSel) ((timer)->CTL = ((timer)->CTL & ~TIMER_CTL_TGLPINSEL_Msk) | (u32ToutSel))
/**
* @brief Set Timer Operating Mode
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER0 ~ TIMER5.
* @param[in] u32OpMode Operation mode. Possible options are
* - \ref TIMER_ONESHOT_MODE
* - \ref TIMER_PERIODIC_MODE
* - \ref TIMER_TOGGLE_MODE
* - \ref TIMER_CONTINUOUS_MODE
*
* @return None
* \hideinitializer
*/
#define TIMER_SET_OPMODE(timer, u32OpMode) ((timer)->CTL = ((timer)->CTL & ~TIMER_CTL_OPMODE_Msk) | (u32OpMode))
/*---------------------------------------------------------------------------------------------------------*/
/* static inline functions */
/*---------------------------------------------------------------------------------------------------------*/
/* Declare these inline functions here to avoid MISRA C 2004 rule 8.1 error */
__STATIC_INLINE void TIMER_Start(TIMER_T *timer);
__STATIC_INLINE void TIMER_Stop(TIMER_T *timer);
__STATIC_INLINE void TIMER_EnableWakeup(TIMER_T *timer);
__STATIC_INLINE void TIMER_DisableWakeup(TIMER_T *timer);
__STATIC_INLINE void TIMER_StartCapture(TIMER_T *timer);
__STATIC_INLINE void TIMER_StopCapture(TIMER_T *timer);
__STATIC_INLINE void TIMER_EnableCaptureDebounce(TIMER_T *timer);
__STATIC_INLINE void TIMER_DisableCaptureDebounce(TIMER_T *timer);
__STATIC_INLINE void TIMER_EnableEventCounterDebounce(TIMER_T *timer);
__STATIC_INLINE void TIMER_DisableEventCounterDebounce(TIMER_T *timer);
__STATIC_INLINE void TIMER_EnableInt(TIMER_T *timer);
__STATIC_INLINE void TIMER_DisableInt(TIMER_T *timer);
__STATIC_INLINE void TIMER_EnableCaptureInt(TIMER_T *timer);
__STATIC_INLINE void TIMER_DisableCaptureInt(TIMER_T *timer);
__STATIC_INLINE uint32_t TIMER_GetIntFlag(TIMER_T *timer);
__STATIC_INLINE void TIMER_ClearIntFlag(TIMER_T *timer);
__STATIC_INLINE uint32_t TIMER_GetCaptureIntFlag(TIMER_T *timer);
__STATIC_INLINE void TIMER_ClearCaptureIntFlag(TIMER_T *timer);
__STATIC_INLINE uint32_t TIMER_GetWakeupFlag(TIMER_T *timer);
__STATIC_INLINE void TIMER_ClearWakeupFlag(TIMER_T *timer);
__STATIC_INLINE uint32_t TIMER_GetCaptureData(TIMER_T *timer);
__STATIC_INLINE uint32_t TIMER_GetCounter(TIMER_T *timer);
__STATIC_INLINE void TIMER_ResetCounter(TIMER_T *timer);
/**
* @brief Start Timer Counting
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER0 ~ TIMER5.
*
* @return None
*
* @details This function is used to start Timer counting.
*/
__STATIC_INLINE void TIMER_Start(TIMER_T *timer)
{
timer->CTL |= TIMER_CTL_CNTEN_Msk;
}
/**
* @brief Stop Timer Counting
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER0 ~ TIMER5.
*
* @return None
*
* @details This function is used to stop/suspend Timer counting.
*/
__STATIC_INLINE void TIMER_Stop(TIMER_T *timer)
{
timer->CTL &= ~TIMER_CTL_CNTEN_Msk;
}
/**
* @brief Enable Timer Interrupt Wake-up Function
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER0 ~ TIMER5.
*
* @return None
*
* @details This function is used to enable the timer interrupt wake-up function and interrupt source could be time-out interrupt, \n
* counter event interrupt or capture trigger interrupt.
* @note To wake the system from Power-down mode, timer clock source must be ether LXT or LIRC.
*/
__STATIC_INLINE void TIMER_EnableWakeup(TIMER_T *timer)
{
timer->CTL |= TIMER_CTL_WKEN_Msk;
}
/**
* @brief Disable Timer Wake-up Function
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER0 ~ TIMER5.
*
* @return None
*
* @details This function is used to disable the timer interrupt wake-up function.
*/
__STATIC_INLINE void TIMER_DisableWakeup(TIMER_T *timer)
{
timer->CTL &= ~TIMER_CTL_WKEN_Msk;
}
/**
* @brief Start Timer Capture Function
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER0 ~ TIMER5.
*
* @return None
*
* @details This function is used to start Timer capture function.
*/
__STATIC_INLINE void TIMER_StartCapture(TIMER_T *timer)
{
timer->EXTCTL |= TIMER_EXTCTL_CAPEN_Msk;
}
/**
* @brief Stop Timer Capture Function
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER0 ~ TIMER5.
*
* @return None
*
* @details This function is used to stop Timer capture function.
*/
__STATIC_INLINE void TIMER_StopCapture(TIMER_T *timer)
{
timer->EXTCTL &= ~TIMER_EXTCTL_CAPEN_Msk;
}
/**
* @brief Enable Capture Pin De-bounce
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER0 ~ TIMER5.
*
* @return None
*
* @details This function is used to enable the detect de-bounce function of capture pin.
*/
__STATIC_INLINE void TIMER_EnableCaptureDebounce(TIMER_T *timer)
{
timer->EXTCTL |= TIMER_EXTCTL_CAPDBEN_Msk;
}
/**
* @brief Disable Capture Pin De-bounce
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER0 ~ TIMER5.
*
* @return None
*
* @details This function is used to disable the detect de-bounce function of capture pin.
*/
__STATIC_INLINE void TIMER_DisableCaptureDebounce(TIMER_T *timer)
{
timer->EXTCTL &= ~TIMER_EXTCTL_CAPDBEN_Msk;
}
/**
* @brief Enable Counter Pin De-bounce
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER0 ~ TIMER5.
*
* @return None
*
* @details This function is used to enable the detect de-bounce function of counter pin.
*/
__STATIC_INLINE void TIMER_EnableEventCounterDebounce(TIMER_T *timer)
{
timer->EXTCTL |= TIMER_EXTCTL_CNTDBEN_Msk;
}
/**
* @brief Disable Counter Pin De-bounce
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER0 ~ TIMER5.
*
* @return None
*
* @details This function is used to disable the detect de-bounce function of counter pin.
*/
__STATIC_INLINE void TIMER_DisableEventCounterDebounce(TIMER_T *timer)
{
timer->EXTCTL &= ~TIMER_EXTCTL_CNTDBEN_Msk;
}
/**
* @brief Enable Timer Time-out Interrupt
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER0 ~ TIMER5.
*
* @return None
*
* @details This function is used to enable the timer time-out interrupt function.
*/
__STATIC_INLINE void TIMER_EnableInt(TIMER_T *timer)
{
timer->CTL |= TIMER_CTL_INTEN_Msk;
}
/**
* @brief Disable Timer Time-out Interrupt
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER0 ~ TIMER5.
*
* @return None
*
* @details This function is used to disable the timer time-out interrupt function.
*/
__STATIC_INLINE void TIMER_DisableInt(TIMER_T *timer)
{
timer->CTL &= ~TIMER_CTL_INTEN_Msk;
}
/**
* @brief Enable Capture Trigger Interrupt
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER0 ~ TIMER5.
*
* @return None
*
* @details This function is used to enable the timer capture trigger interrupt function.
*/
__STATIC_INLINE void TIMER_EnableCaptureInt(TIMER_T *timer)
{
timer->EXTCTL |= TIMER_EXTCTL_CAPIEN_Msk;
}
/**
* @brief Disable Capture Trigger Interrupt
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER0 ~ TIMER5.
*
* @return None
*
* @details This function is used to disable the timer capture trigger interrupt function.
*/
__STATIC_INLINE void TIMER_DisableCaptureInt(TIMER_T *timer)
{
timer->EXTCTL &= ~TIMER_EXTCTL_CAPIEN_Msk;
}
/**
* @brief Get Timer Time-out Interrupt Flag
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER0 ~ TIMER5.
*
* @retval 0 Timer time-out interrupt did not occur
* @retval 1 Timer time-out interrupt occurred
*
* @details This function indicates timer time-out interrupt occurred or not.
*/
__STATIC_INLINE uint32_t TIMER_GetIntFlag(TIMER_T *timer)
{
return (((timer->INTSTS & TIMER_INTSTS_TIF_Msk) == TIMER_INTSTS_TIF_Msk) ? 1UL : 0UL);
}
/**
* @brief Clear Timer Time-out Interrupt Flag
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER0 ~ TIMER5.
*
* @return None
*
* @details This function clears timer time-out interrupt flag to 0.
*/
__STATIC_INLINE void TIMER_ClearIntFlag(TIMER_T *timer)
{
timer->INTSTS = TIMER_INTSTS_TIF_Msk;
}
/**
* @brief Get Timer Capture Interrupt Flag
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER0 ~ TIMER5.
*
* @retval 0 Timer capture interrupt did not occur
* @retval 1 Timer capture interrupt occurred
*
* @details This function indicates timer capture trigger interrupt occurred or not.
*/
__STATIC_INLINE uint32_t TIMER_GetCaptureIntFlag(TIMER_T *timer)
{
return timer->EINTSTS;
}
/**
* @brief Clear Timer Capture Interrupt Flag
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER0 ~ TIMER5.
*
* @return None
*
* @details This function clears timer capture trigger interrupt flag to 0.
*/
__STATIC_INLINE void TIMER_ClearCaptureIntFlag(TIMER_T *timer)
{
timer->EINTSTS = TIMER_EINTSTS_CAPIF_Msk;
}
/**
* @brief Get Timer Wake-up Flag
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER0 ~ TIMER5.
*
* @retval 0 Timer does not cause CPU wake-up
* @retval 1 Timer interrupt event cause CPU wake-up
*
* @details This function indicates timer interrupt event has waked up system or not.
*/
__STATIC_INLINE uint32_t TIMER_GetWakeupFlag(TIMER_T *timer)
{
return (((timer->INTSTS & TIMER_INTSTS_TWKF_Msk) == TIMER_INTSTS_TWKF_Msk) ? 1UL : 0UL);
}
/**
* @brief Clear Timer Wake-up Flag
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER0 ~ TIMER5.
*
* @return None
*
* @details This function clears the timer wake-up system flag to 0.
*/
__STATIC_INLINE void TIMER_ClearWakeupFlag(TIMER_T *timer)
{
timer->INTSTS = TIMER_INTSTS_TWKF_Msk;
}
/**
* @brief Get Capture value
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER0 ~ TIMER5.
*
* @return 24-bit Capture Value
*
* @details This function reports the current 24-bit timer capture value.
*/
__STATIC_INLINE uint32_t TIMER_GetCaptureData(TIMER_T *timer)
{
return timer->CAP;
}
/**
* @brief Get Counter value
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER0 ~ TIMER5.
*
* @return 24-bit Counter Value
*
* @details This function reports the current 24-bit timer counter value.
*/
__STATIC_INLINE uint32_t TIMER_GetCounter(TIMER_T *timer)
{
return timer->CNT;
}
/**
* @brief Reset Counter
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER0 ~ TIMER5.
*
* @return None
*
* @details This function is used to reset current counter value and internal prescale counter value.
*/
__STATIC_INLINE void TIMER_ResetCounter(TIMER_T *timer)
{
timer->CNT = 0UL;
while((timer->CNT & TIMER_CNT_RSTACT_Msk) == TIMER_CNT_RSTACT_Msk) {}
}
uint32_t TIMER_Open(TIMER_T *timer, uint32_t u32Mode, uint32_t u32Freq);
void TIMER_Close(TIMER_T *timer);
void TIMER_Delay(TIMER_T *timer, uint32_t u32Usec);
void TIMER_EnableCapture(TIMER_T *timer, uint32_t u32CapMode, uint32_t u32Edge);
void TIMER_DisableCapture(TIMER_T *timer);
void TIMER_EnableEventCounter(TIMER_T *timer, uint32_t u32Edge);
void TIMER_DisableEventCounter(TIMER_T *timer);
uint32_t TIMER_GetModuleClock(TIMER_T *timer);
void TIMER_EnableFreqCounter(TIMER_T *timer, uint32_t u32DropCount, uint32_t u32Timeout, uint32_t u32EnableInt);
void TIMER_DisableFreqCounter(TIMER_T *timer);
void TIMER_SetTriggerSource(TIMER_T *timer, uint32_t u32Src);
void TIMER_SetTriggerTarget(TIMER_T *timer, uint32_t u32Mask);
/**@}*/ /* end of group TIMER_EXPORTED_FUNCTIONS */
/**@}*/ /* end of group TIMER_Driver */
/**@}*/ /* end of group Standard_Driver */
#ifdef __cplusplus
}
#endif
#endif /* __NU_TIMER_H__ */

View File

@ -0,0 +1,877 @@
/**************************************************************************//**
* @file timer.h
* @version V3.00
* @brief Timer PWM Controller(Timer PWM) driver header file
*
* @copyright SPDX-License-Identifier: Apache-2.0
* @copyright Copyright (C) 2020 Nuvoton Technology Corp. All rights reserved.
*****************************************************************************/
#ifndef __NU_TIMER_PWM_H__
#define __NU_TIMER_PWM_H__
#ifdef __cplusplus
extern "C"
{
#endif
/** @addtogroup Standard_Driver Standard Driver
@{
*/
/** @addtogroup TIMER_PWM_Driver TIMER PWM Driver
@{
*/
/** @addtogroup TIMER_PWM_EXPORTED_CONSTANTS TIMER PWM Exported Constants
@{
*/
/*---------------------------------------------------------------------------------------------------------*/
/* Output Channel Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define TPWM_CH0 (BIT0) /*!< Indicate PWMx_CH0 \hideinitializer */
#define TPWM_CH1 (BIT1) /*!< Indicate PWMx_CH1 \hideinitializer */
/*---------------------------------------------------------------------------------------------------------*/
/* Counter Type Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define TPWM_UP_COUNT (0UL << TIMER_PWMCTL_CNTTYPE_Pos) /*!< Up count type \hideinitializer */
#define TPWM_DOWN_COUNT (1UL << TIMER_PWMCTL_CNTTYPE_Pos) /*!< Down count type \hideinitializer */
#define TPWM_UP_DOWN_COUNT (2UL << TIMER_PWMCTL_CNTTYPE_Pos) /*!< Up-Down count type \hideinitializer */
/*---------------------------------------------------------------------------------------------------------*/
/* Counter Mode Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define TPWM_AUTO_RELOAD_MODE (0UL) /*!< Auto-reload mode \hideinitializer */
#define TPWM_ONE_SHOT_MODE (TIMER_PWMCTL_CNTMODE_Msk) /*!< One-shot mode \hideinitializer */
/*---------------------------------------------------------------------------------------------------------*/
/* Output Level Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define TPWM_OUTPUT_TOGGLE (0UL) /*!< Timer PWM output toggle \hideinitializer */
#define TPWM_OUTPUT_NOTHING (1UL) /*!< Timer PWM output nothing \hideinitializer */
#define TPWM_OUTPUT_LOW (2UL) /*!< Timer PWM output low \hideinitializer */
#define TPWM_OUTPUT_HIGH (3UL) /*!< Timer PWM output high \hideinitializer */
/*---------------------------------------------------------------------------------------------------------*/
/* Trigger Event Source Select Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define TPWM_TRIGGER_EVENT_AT_ZERO_POINT (0UL << TIMER_PWMTRGCTL_TRGSEL_Pos) /*!< Timer PWM trigger event while counter zero point event occurred \hideinitializer */
#define TPWM_TRIGGER_EVENT_AT_PERIOD_POINT (1UL << TIMER_PWMTRGCTL_TRGSEL_Pos) /*!< Timer PWM trigger event while counter period point event occurred \hideinitializer */
#define TPWM_TRIGGER_EVENT_AT_ZERO_OR_PERIOD_POINT (2UL << TIMER_PWMTRGCTL_TRGSEL_Pos) /*!< Timer PWM trigger event while counter zero or period point event occurred \hideinitializer */
#define TPWM_TRIGGER_EVENT_AT_COMPARE_UP_POINT (3UL << TIMER_PWMTRGCTL_TRGSEL_Pos) /*!< Timer PWM trigger event while counter up count compare point event occurred \hideinitializer */
#define TPWM_TRIGGER_EVENT_AT_COMPARE_DOWN_POINT (4UL << TIMER_PWMTRGCTL_TRGSEL_Pos) /*!< Timer PWM trigger event while counter down count compare point event occurred \hideinitializer */
#define TPWM_TRIGGER_EVENT_AT_PERIOD_OR_COMPARE_UP_POINT (5UL << TIMER_PWMTRGCTL_TRGSEL_Pos) /*!< Timer PWM trigger event while counter period or up count compare point event occurred \hideinitializer */
/*---------------------------------------------------------------------------------------------------------*/
/* Brake Control Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define TPWM_BRAKE_SOURCE_EDGE_ACMP0 (TIMER_PWMBRKCTL_CPO0EBEN_Msk) /*!< Comparator 0 as edge-detect fault brake source \hideinitializer */
#define TPWM_BRAKE_SOURCE_EDGE_ACMP1 (TIMER_PWMBRKCTL_CPO1EBEN_Msk) /*!< Comparator 1 as edge-detect fault brake source \hideinitializer */
#define TPWM_BRAKE_SOURCE_EDGE_BKPIN (TIMER_PWMBRKCTL_BRKPEEN_Msk) /*!< Brake pin as edge-detect fault brake source \hideinitializer */
#define TPWM_BRAKE_SOURCE_EDGE_SYS_CSS (TIMER_PWMBRKCTL_SYSEBEN_Msk | (TIMER_PWMFAILBRK_CSSBRKEN_Msk << 16)) /*!< System fail condition: clock security system detection as edge-detect fault brake source \hideinitializer */
#define TPWM_BRAKE_SOURCE_EDGE_SYS_BOD (TIMER_PWMBRKCTL_SYSEBEN_Msk | (TIMER_PWMFAILBRK_BODBRKEN_Msk << 16)) /*!< System fail condition: brown-out detection as edge-detect fault brake source \hideinitializer */
#define TPWM_BRAKE_SOURCE_EDGE_SYS_COR (TIMER_PWMBRKCTL_SYSEBEN_Msk | (TIMER_PWMFAILBRK_CORBRKEN_Msk << 16)) /*!< System fail condition: core lockup detection as edge-detect fault brake source \hideinitializer */
#define TPWM_BRAKE_SOURCE_EDGE_SYS_RAM (TIMER_PWMBRKCTL_SYSEBEN_Msk | (TIMER_PWMFAILBRK_RAMBRKEN_Msk << 16)) /*!< System fail condition: SRAM parity error detection as edge-detect fault brake source \hideinitializer */
#define TPWM_BRAKE_SOURCE_LEVEL_ACMP0 (TIMER_PWMBRKCTL_CPO0LBEN_Msk) /*!< Comparator 0 as level-detect fault brake source \hideinitializer */
#define TPWM_BRAKE_SOURCE_LEVEL_ACMP1 (TIMER_PWMBRKCTL_CPO1LBEN_Msk) /*!< Comparator 1 as level-detect fault brake source \hideinitializer */
#define TPWM_BRAKE_SOURCE_LEVEL_BKPIN (TIMER_PWMBRKCTL_BRKPLEN_Msk) /*!< Brake pin as level-detect fault brake source \hideinitializer */
#define TPWM_BRAKE_SOURCE_LEVEL_SYS_CSS (TIMER_PWMBRKCTL_SYSLBEN_Msk | (TIMER_PWMFAILBRK_CSSBRKEN_Msk << 16)) /*!< System fail condition: clock security system detection as level-detect fault brake source \hideinitializer */
#define TPWM_BRAKE_SOURCE_LEVEL_SYS_BOD (TIMER_PWMBRKCTL_SYSLBEN_Msk | (TIMER_PWMFAILBRK_BODBRKEN_Msk << 16)) /*!< System fail condition: brown-out detection as level-detect fault brake source \hideinitializer */
#define TPWM_BRAKE_SOURCE_LEVEL_SYS_COR (TIMER_PWMBRKCTL_SYSLBEN_Msk | (TIMER_PWMFAILBRK_CORBRKEN_Msk << 16)) /*!< System fail condition: core lockup detection as level-detect fault brake source \hideinitializer */
#define TPWM_BRAKE_SOURCE_LEVEL_SYS_RAM (TIMER_PWMBRKCTL_SYSLBEN_Msk | (TIMER_PWMFAILBRK_RAMBRKEN_Msk << 16)) /*!< System fail condition: SRAM parity error detection as level-detect fault brake source \hideinitializer */
#define TPWM_BRAKE_EDGE (TIMER_PWMSWBRK_BRKETRG_Msk) /*!< Edge-detect fault brake \hideinitializer */
#define TPWM_BRAKE_LEVEL (TIMER_PWMSWBRK_BRKLTRG_Msk) /*!< Level-detect fault brake \hideinitializer */
/*---------------------------------------------------------------------------------------------------------*/
/* Load Mode Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define TPWM_LOAD_MODE_PERIOD (0UL) /*!< Timer PWM period load mode \hideinitializer */
#define TPWM_LOAD_MODE_IMMEDIATE (TIMER_PWMCTL_IMMLDEN_Msk) /*!< Timer PWM immediately load mode \hideinitializer */
#define TPWM_LOAD_MODE_CENTER (TIMER_PWMCTL_CTRLD_Msk) /*!< Timer PWM center load mode \hideinitializer */
/*---------------------------------------------------------------------------------------------------------*/
/* Brake Pin De-bounce Clock Source Select Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define TPWM_BKP_DBCLK_PCLK_DIV_1 (0UL) /*!< De-bounce clock is PCLK divide by 1 \hideinitializer */
#define TPWM_BKP_DBCLK_PCLK_DIV_2 (1UL) /*!< De-bounce clock is PCLK divide by 2 \hideinitializer */
#define TPWM_BKP_DBCLK_PCLK_DIV_4 (2UL) /*!< De-bounce clock is PCLK divide by 4 \hideinitializer */
#define TPWM_BKP_DBCLK_PCLK_DIV_8 (3UL) /*!< De-bounce clock is PCLK divide by 8 \hideinitializer */
#define TPWM_BKP_DBCLK_PCLK_DIV_16 (4UL) /*!< De-bounce clock is PCLK divide by 16 \hideinitializer */
#define TPWM_BKP_DBCLK_PCLK_DIV_32 (5UL) /*!< De-bounce clock is PCLK divide by 32 \hideinitializer */
#define TPWM_BKP_DBCLK_PCLK_DIV_64 (6UL) /*!< De-bounce clock is PCLK divide by 64 \hideinitializer */
#define TPWM_BKP_DBCLK_PCLK_DIV_128 (7UL) /*!< De-bounce clock is PCLK divide by 128 \hideinitializer */
/*---------------------------------------------------------------------------------------------------------*/
/* Brake Pin Source Select Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define TPWM_TM_BRAKE0 (0UL) /*!< Brake pin source comes from TM_BRAKE0 \hideinitializer */
#define TPWM_TM_BRAKE1 (1UL) /*!< Brake pin source comes from TM_BRAKE1 \hideinitializer */
#define TPWM_TM_BRAKE2 (2UL) /*!< Brake pin source comes from TM_BRAKE2 \hideinitializer */
#define TPWM_TM_BRAKE3 (3UL) /*!< Brake pin source comes from TM_BRAKE3 \hideinitializer */
/*---------------------------------------------------------------------------------------------------------*/
/* Counter Clock Source Select Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define TPWM_CNTR_CLKSRC_TMR_CLK (0UL) /*!< Timer PWM Clock source selects to TMR_CLK \hideinitializer */
#define TPWM_CNTR_CLKSRC_TIMER0_INT (1UL) /*!< Timer PWM Clock source selects to TIMER0 interrupt event \hideinitializer */
#define TPWM_CNTR_CLKSRC_TIMER1_INT (2UL) /*!< Timer PWM Clock source selects to TIMER1 interrupt event \hideinitializer */
#define TPWM_CNTR_CLKSRC_TIMER2_INT (3UL) /*!< Timer PWM Clock source selects to TIMER2 interrupt event \hideinitializer */
#define TPWM_CNTR_CLKSRC_TIMER3_INT (4UL) /*!< Timer PWM Clock source selects to TIMER3 interrupt event \hideinitializer */
/*---------------------------------------------------------------------------------------------------------*/
/* Counter Synchronous Mode Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define TPWM_CNTR_SYNC_DISABLE (0UL) /*!< Disable TIMER PWM synchronous function \hideinitializer */
#define TPWM_CNTR_SYNC_START_BY_TIMER0 ((0<<TIMER_PWMSCTL_SYNCSRC_Pos) | (1<<TIMER_PWMSCTL_SYNCMODE_Pos)) /*!< PWM counter synchronous start by TIMER0 PWM \hideinitializer */
#define TPWM_CNTR_SYNC_CLEAR_BY_TIMER0 ((0<<TIMER_PWMSCTL_SYNCSRC_Pos) | (3<<TIMER_PWMSCTL_SYNCMODE_Pos)) /*!< PWM counter synchronous clear by TIMER0 PWM \hideinitializer */
#define TPWM_CNTR_SYNC_START_BY_TIMER2 ((1<<TIMER_PWMSCTL_SYNCSRC_Pos) | (1<<TIMER_PWMSCTL_SYNCMODE_Pos)) /*!< PWM counter synchronous start by TIMER2 PWM \hideinitializer */
#define TPWM_CNTR_SYNC_CLEAR_BY_TIMER2 ((1<<TIMER_PWMSCTL_SYNCSRC_Pos) | (3<<TIMER_PWMSCTL_SYNCMODE_Pos)) /*!< PWM counter synchronous clear by TIMER2 PWM \hideinitializer */
/**@}*/ /* end of group TIMER_PWM_EXPORTED_CONSTANTS */
/** @addtogroup TIMER_PWM_EXPORTED_FUNCTIONS TIMER PWM Exported Functions
@{
*/
/**
* @brief Enable PWM Counter Mode
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER0 ~ TIMER5.
*
* @return None
*
* @details This macro is used to enable specified Timer channel as PWM counter mode, then timer counter mode is invalid.
* @note All registers about time counter function will be cleared to 0 and timer clock source will be changed to PCLKx automatically after executing this macro.
* \hideinitializer
*/
#define TPWM_ENABLE_PWM_MODE(timer) \
do{ \
if(((uint32_t)&((timer)->PWMCTL) & TMR45_BASE) == TMR45_BASE) { \
(timer)->CTL |= TIMER_CTL_FUNCSEL_Msk; \
while(((timer)->CTL & TIMER_CTL_FUNCSEL_Msk) == 0) {} \
} else { \
(timer)->ALTCTL = TIMER_ALTCTL_FUNCSEL_Msk; \
while(((timer)->ALTCTL & TIMER_ALTCTL_FUNCSEL_Msk) == 0) {} \
} \
}while(0)
/**
* @brief Disable PWM Counter Mode
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER0 ~ TIMER5.
*
* @return None
*
* @details This macro is used to disable specified Timer channel as PWM counter mode, then timer counter mode is available.
* @note All registers about PWM counter function will be cleared to 0 after executing this macro.
* \hideinitializer
*/
#define TPWM_DISABLE_PWM_MODE(timer) \
do{ \
if(((uint32_t)&((timer)->PWMCTL) & TMR45_BASE) == TMR45_BASE) { \
(timer)->CTL &= ~TIMER_CTL_FUNCSEL_Msk; \
while(((timer)->CTL & TIMER_CTL_FUNCSEL_Msk) == TIMER_CTL_FUNCSEL_Msk) {} \
} else { \
(timer)->ALTCTL &= ~TIMER_ALTCTL_FUNCSEL_Msk; \
while(((timer)->ALTCTL & TIMER_ALTCTL_FUNCSEL_Msk) == TIMER_ALTCTL_FUNCSEL_Msk) {} \
} \
}while(0)
/**
* @brief Enable Independent Mode
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER0, TIMER1, TIMER2, TIMER3.
*
* @return None
*
* @details This macro is used to enable independent mode of TIMER PWM module and complementary mode will be disabled.
* @note NOT available on TIMER4 and TIMER5.
* \hideinitializer
*/
#define TPWM_ENABLE_INDEPENDENT_MODE(timer) ((timer)->PWMCTL &= ~(1ul << TIMER_PWMCTL_OUTMODE_Pos))
/**
* @brief Enable Complementary Mode
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER0, TIMER1, TIMER2, TIMER3.
*
* @return None
*
* @details This macro is used to enable complementary mode of Timer PWM module and independent mode will be disabled.
* @note NOT available on TIMER4 and TIMER5.
* \hideinitializer
*/
#define TPWM_ENABLE_COMPLEMENTARY_MODE(timer) ((timer)->PWMCTL |= (1 << TIMER_PWMCTL_OUTMODE_Pos))
/**
* @brief Set Counter Type
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER0, TIMER1, TIMER2, TIMER3.
* @param[in] type Timer PWM count type, could be one of the following type
* - \ref TPWM_UP_COUNT
* - \ref TPWM_DOWN_COUNT
* - \ref TPWM_UP_DOWN_COUNT
*
* @return None
*
* @details This macro is used to set Timer PWM counter type.
* @note NOT available on TIMER4 and TIMER5. Both TIMER4 and TIMER5 are only support count up.
* \hideinitializer
*/
#define TPWM_SET_COUNTER_TYPE(timer, type) ((timer)->PWMCTL = ((timer)->PWMCTL & ~TIMER_PWMCTL_CNTTYPE_Msk) | (type))
/**
* @brief Start PWM Counter
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER0 ~ TIMER5.
*
* @return None
*
* @details This macro is used to enable PWM generator and start counter counting.
* \hideinitializer
*/
#define TPWM_START_COUNTER(timer) ((timer)->PWMCTL |= TIMER_PWMCTL_CNTEN_Msk)
/**
* @brief Stop PWM Counter
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER0 ~ TIMER5.
*
* @return None
*
* @details This macro is used to stop PWM counter after current period is completed.
* \hideinitializer
*/
#define TPWM_STOP_COUNTER(timer) ((timer)->PWMPERIOD = 0x0)
/**
* @brief Set Counter Clock Prescaler
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER0 ~ TIMER5.
*
* @param[in] prescaler Clock prescaler of specified channel.
* Valid values are between 0x0~0xFFF for TIMER0, TIMER1, TIMER2, TIMER3, and
* valid values are between 0x0~0xFF for TIMER4 and TIMER5.
*
* @return None
*
* @details This macro is used to set the prescaler of specified TIMER PWM.
* @note If prescaler is 0, then there is no scaling in counter clock source.
* \hideinitializer
*/
#define TPWM_SET_PRESCALER(timer, prescaler) ((timer)->PWMCLKPSC = (prescaler))
/**
* @brief Get Counter Clock Prescaler
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER0 ~ TIMER5.
*
* @return Target prescaler setting, CLKPSC (TIMERx_PWMCLKPSC[11:0])
*
* @details Get the prescaler setting, the target counter clock divider is (CLKPSC + 1).
* \hideinitializer
*/
#define TPWM_GET_PRESCALER(timer) ((timer)->PWMCLKPSC)
/**
* @brief Set Couner Period
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER0 ~ TIMER5.
*
* @param[in] period Period of specified channel. Valid values are between 0x0~0xFFFF.
*
* @return None
*
* @details This macro is used to set the period of specified TIMER PWM.
* \hideinitializer
*/
#define TPWM_SET_PERIOD(timer, period) ((timer)->PWMPERIOD = (period))
/**
* @brief Get Couner Period
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER0 ~ TIMER5.
*
* @return Target period setting, PERIOD (TIMERx_PWMPERIOD[15:0])
*
* @details This macro is used to get the period of specified TIMER PWM.
* \hideinitializer
*/
#define TPWM_GET_PERIOD(timer) ((timer)->PWMPERIOD)
/**
* @brief Set Comparator Value
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER0 ~ TIMER5.
*
* @param[in] cmp Comparator of specified channel. Valid values are between 0x0~0xFFFF.
*
* @return None
*
* @details This macro is used to set the comparator value of specified TIMER PWM.
* \hideinitializer
*/
#define TPWM_SET_CMPDAT(timer, cmp) ((timer)->PWMCMPDAT = (cmp))
/**
* @brief Get Comparator Value
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER0 ~ TIMER5.
*
* @return Target comparator setting, CMPDAT (TIMERx_PWMCMPDAT[15:0])
*
* @details This macro is used to get the comparator value of specified TIMER PWM.
* \hideinitializer
*/
#define TPWM_GET_CMPDAT(timer) ((timer)->PWMCMPDAT)
/**
* @brief Clear Counter
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER0 ~ TIMER5.
*
* @return None
*
* @details This macro is used to clear counter of specified TIMER PWM.
* \hideinitializer
*/
#define TPWM_CLEAR_COUNTER(timer) ((timer)->PWMCNTCLR = TIMER_PWMCNTCLR_CNTCLR_Msk)
/**
* @brief Software Trigger Brake Event
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER0, TIMER1, TIMER2, TIMER3.
*
* @param[in] type Type of brake trigger. Valid values are:
* - \ref TPWM_BRAKE_EDGE
* - \ref TPWM_BRAKE_LEVEL
*
* @return None
*
* @details This macro is used to trigger brake event by writing PWMSWBRK register.
* @note NOT available on TIMER4 and TIMER5.
* \hideinitializer
*/
#define TPWM_SW_TRIGGER_BRAKE(timer, type) ((timer)->PWMSWBRK = (type))
/**
* @brief Enable Output Function
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER0 ~ TIMER5.
*
* @param[in] ch Enable specified channel output function. Valid values are:
* For TIMER0 ~ TIMER3, the valid value could be a combination of \ref TPWM_CH0 and \ref TPWM_CH1.
* For TIMER4, TIMER5, the valid value could be \ref TPWM_CH0 or \ref TPWM_CH1.
*
* @return None
*
* @details This macro is used to enable output function of specified output pins.
* \hideinitializer
*/
#define TPWM_ENABLE_OUTPUT(timer, ch) \
do{ \
if(((uint32_t)&((timer)->PWMCTL) & TMR45_BASE) == TMR45_BASE) { \
if((ch) == BIT0) \
(timer)->PWMPOEN = BIT0; \
else \
(timer)->PWMPOEN = (BIT0 | BIT8); \
} else { \
(timer)->PWMPOEN = (ch); \
} \
}while(0)
/**
* @brief Set Output Inverse
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER0 ~ TIMER5.
*
* @param[in] ch Set specified channel output is inversed or not.
* For TIMER0 ~ TIMER3, the valid value could be a combination of \ref TPWM_CH0 and \ref TPWM_CH1.
* But this parameter is no effect on TIMER4 and TIMER5.
*
* @return None
*
* @details This macro is used to enable output inverse of specified output pins.
* \hideinitializer
*/
#define TPWM_SET_OUTPUT_INVERSE(timer, ch) \
do{ \
if(((uint32_t)&((timer)->PWMCTL) & TMR45_BASE) == TMR45_BASE) { \
(timer)->PWMPOLCTL = BIT0; \
} else { \
(timer)->PWMPOLCTL = (ch); \
} \
}while(0)
/**
* @brief Enable Output Mask Function
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER0, TIMER1, TIMER2, TIMER3.
*
* @param[in] ch Enable specified channel output mask function. Valid value could be a combination of \ref TPWM_CH0 and \ref TPWM_CH1.
*
* @param[in] level Output to high or low on specified mask channel.
*
* @return None
*
* @details This macro is used to enable output mask function of specified output pins.
* @note NOT available on TIMER4 and TIMER5.
* \hideinitializer
*/
#define TPWM_SET_MASK_OUTPUT(timer, ch, level) do {(timer)->PWMMSKEN = (ch); (timer)->PWMMSK = (level); }while(0)
/**
* @brief Set Counter Synchronous Mode
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER0, TIMER1, TIMER2, TIMER3.
*
* @param[in] mode Synchronous mode. Possible options are:
* - \ref TPWM_CNTR_SYNC_DISABLE
* - \ref TPWM_CNTR_SYNC_START_BY_TIMER0
* - \ref TPWM_CNTR_SYNC_CLEAR_BY_TIMER0
* - \ref TPWM_CNTR_SYNC_START_BY_TIMER2
* - \ref TPWM_CNTR_SYNC_CLEAR_BY_TIMER2
*
* @return None
*
* @details This macro is used to set counter synchronous mode of specified Timer PWM module.
* @note Only support all PWM counters are synchronous by TIMER0 PWM or TIMER0~1 PWM counter synchronous by TIMER0 PWM and
* TIMER2~3 PWM counter synchronous by TIMER2 PWM.
* @note NOT available on TIMER4 and TIMER5.
* \hideinitializer
*/
#define TPWM_SET_COUNTER_SYNC_MODE(timer, mode) ((timer)->PWMSCTL = (mode))
/**
* @brief Trigger Counter Synchronous
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER0, TIMER1, TIMER2, TIMER3.
*
* @return None
*
* @details This macro is used to trigger synchronous event by specified TIMER PWM.
* @note 1. This macro is only available for TIMER0 PWM and TIMER2 PWM. \n
* 2. STRGEN (PWMSTRG[0]) is write only and always read as 0.
* @note NOT available on TIMER4 and TIMER5.
* \hideinitializer
*/
#define TPWM_TRIGGER_COUNTER_SYNC(timer) ((timer)->PWMSTRG = TIMER_PWMSTRG_STRGEN_Msk)
/**
* @brief Enable Timer PWM Interrupt Wake-up Function
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER4 or TIMER5.
*
* @return None
*
* @details This macro is used to enable the timer pwm interrupt wake-up function.
* @note Only available on TIMER4 and TIMER5.
* \hideinitializer
*/
#define TPWM_ENABLE_PWMINT_WAKEUP(timer) ((timer)->PWMCTL |= TIMER_PWMCTL_WKEN_Msk)
/**
* @brief Disable Timer PWM Interrupt Wake-up Function
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER4 or TIMER5.
*
* @return None
*
* @details This macro is used to disable the timer pwm interrupt wake-up function.
* @note Only available on TIMER4 and TIMER5.
* \hideinitializer
*/
#define TPWM_DISABLE_PWMINT_WAKEUP(timer) ((timer)->PWMCTL &= ~TIMER_PWMCTL_WKEN_Msk)
/**
* @brief Enable Zero Event Interrupt
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER0, TIMER1, TIMER2, TIMER3.
*
* @return None
*
* @details This macro is used to enable the zero event interrupt function.
* @note NOT available on TIMER4 and TIMER5.
* \hideinitializer
*/
#define TPWM_ENABLE_ZERO_INT(timer) ((timer)->PWMINTEN0 |= TIMER_PWMINTEN0_ZIEN_Msk)
/**
* @brief Disable Zero Event Interrupt
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER0, TIMER1, TIMER2, TIMER3.
*
* @return None
*
* @details This macro is used to disable the zero event interrupt function.
* @note NOT available on TIMER4 and TIMER5.
* \hideinitializer
*/
#define TPWM_DISABLE_ZERO_INT(timer) ((timer)->PWMINTEN0 &= ~TIMER_PWMINTEN0_ZIEN_Msk)
/**
* @brief Get Zero Event Interrupt Flag
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER0, TIMER1, TIMER2, TIMER3.
*
* @retval 0 Zero event interrupt did not occur
* @retval 1 Zero event interrupt occurred
*
* @details This macro indicates zero event occurred or not.
* @note NOT available on TIMER4 and TIMER5.
* \hideinitializer
*/
#define TPWM_GET_ZERO_INT_FLAG(timer) (((timer)->PWMINTSTS0 & TIMER_PWMINTSTS0_ZIF_Msk)? 1 : 0)
/**
* @brief Clear Zero Event Interrupt Flag
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER0, TIMER1, TIMER2, TIMER3.
*
* @return None
*
* @details This macro clears zero event interrupt flag.
* @note NOT available on TIMER4 and TIMER5.
* \hideinitializer
*/
#define TPWM_CLEAR_ZERO_INT_FLAG(timer) ((timer)->PWMINTSTS0 = TIMER_PWMINTSTS0_ZIF_Msk)
/**
* @brief Enable Period Event Interrupt
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER0 ~ TIMER5.
*
* @return None
*
* @details This macro is used to enable the period event interrupt function.
* \hideinitializer
*/
#define TPWM_ENABLE_PERIOD_INT(timer) ((timer)->PWMINTEN0 |= TIMER_PWMINTEN0_PIEN_Msk)
/**
* @brief Disable Period Event Interrupt
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER0 ~ TIMER5.
*
* @return None
*
* @details This macro is used to disable the period event interrupt function.
* \hideinitializer
*/
#define TPWM_DISABLE_PERIOD_INT(timer) ((timer)->PWMINTEN0 &= ~TIMER_PWMINTEN0_PIEN_Msk)
/**
* @brief Get Period Event Interrupt Flag
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER0 ~ TIMER5.
*
* @retval 0 Period event interrupt did not occur
* @retval 1 Period event interrupt occurred
*
* @details This macro indicates period event occurred or not.
* \hideinitializer
*/
#define TPWM_GET_PERIOD_INT_FLAG(timer) (((timer)->PWMINTSTS0 & TIMER_PWMINTSTS0_PIF_Msk)? 1 : 0)
/**
* @brief Clear Period Event Interrupt Flag
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER0 ~ TIMER5.
*
* @return None
*
* @details This macro clears period event interrupt flag.
* \hideinitializer
*/
#define TPWM_CLEAR_PERIOD_INT_FLAG(timer) ((timer)->PWMINTSTS0 = TIMER_PWMINTSTS0_PIF_Msk)
/**
* @brief Enable Compare Up Event Interrupt
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER0 ~ TIMER5.
*
* @return None
*
* @details This macro is used to enable the compare up event interrupt function.
* \hideinitializer
*/
#define TPWM_ENABLE_CMP_UP_INT(timer) ((timer)->PWMINTEN0 |= TIMER_PWMINTEN0_CMPUIEN_Msk)
/**
* @brief Disable Compare Up Event Interrupt
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER0 ~ TIMER5.
*
* @return None
*
* @details This macro is used to disable the compare up event interrupt function.
* \hideinitializer
*/
#define TPWM_DISABLE_CMP_UP_INT(timer) ((timer)->PWMINTEN0 &= ~TIMER_PWMINTEN0_CMPUIEN_Msk)
/**
* @brief Get Compare Up Event Interrupt Flag
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER0 ~ TIMER5.
*
* @retval 0 Compare up event interrupt did not occur
* @retval 1 Compare up event interrupt occurred
*
* @details This macro indicates compare up event occurred or not.
* \hideinitializer
*/
#define TPWM_GET_CMP_UP_INT_FLAG(timer) (((timer)->PWMINTSTS0 & TIMER_PWMINTSTS0_CMPUIF_Msk)? 1 : 0)
/**
* @brief Clear Compare Up Event Interrupt Flag
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER0 ~ TIMER5.
*
* @return None
*
* @details This macro clears compare up event interrupt flag.
* \hideinitializer
*/
#define TPWM_CLEAR_CMP_UP_INT_FLAG(timer) ((timer)->PWMINTSTS0 = TIMER_PWMINTSTS0_CMPUIF_Msk)
/**
* @brief Enable Compare Down Event Interrupt
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER0, TIMER1, TIMER2, TIMER3.
*
* @return None
*
* @details This macro is used to enable the compare down event interrupt function.
* @note NOT available on TIMER4 and TIMER5.
* \hideinitializer
*/
#define TPWM_ENABLE_CMP_DOWN_INT(timer) ((timer)->PWMINTEN0 |= TIMER_PWMINTEN0_CMPDIEN_Msk)
/**
* @brief Disable Compare Down Event Interrupt
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER0, TIMER1, TIMER2, TIMER3.
*
* @return None
*
* @details This macro is used to disable the compare down event interrupt function.
* @note NOT available on TIMER4 and TIMER5.
* \hideinitializer
*/
#define TPWM_DISABLE_CMP_DOWN_INT(timer) ((timer)->PWMINTEN0 &= ~TIMER_PWMINTEN0_CMPDIEN_Msk)
/**
* @brief Get Compare Down Event Interrupt Flag
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER0, TIMER1, TIMER2, TIMER3.
*
* @retval 0 Compare down event interrupt did not occur
* @retval 1 Compare down event interrupt occurred
*
* @details This macro indicates compare down event occurred or not.
* @note NOT available on TIMER4 and TIMER5.
* \hideinitializer
*/
#define TPWM_GET_CMP_DOWN_INT_FLAG(timer) (((timer)->PWMINTSTS0 & TIMER_PWMINTSTS0_CMPDIF_Msk)? 1 : 0)
/**
* @brief Clear Compare Down Event Interrupt Flag
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER0, TIMER1, TIMER2, TIMER3.
*
* @return None
*
* @details This macro clears compare down event interrupt flag.
* @note NOT available on TIMER4 and TIMER5.
* \hideinitializer
*/
#define TPWM_CLEAR_CMP_DOWN_INT_FLAG(timer) ((timer)->PWMINTSTS0 = TIMER_PWMINTSTS0_CMPDIF_Msk)
/**
* @brief Get Counter Reach Maximum Count Status
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER0 ~ TIMER5.
*
* @retval 0 Timer PWM counter never counts to maximum value
* @retval 1 Timer PWM counter counts to maximum value, 0xFFFF
*
* @details This macro indicates Timer PWM counter has count to 0xFFFF or not.
* \hideinitializer
*/
#define TPWM_GET_REACH_MAX_CNT_STATUS(timer) (((timer)->PWMSTATUS & TIMER_PWMSTATUS_CNTMAXF_Msk)? 1 : 0)
/**
* @brief Clear Counter Reach Maximum Count Status
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER0 ~ TIMER5.
*
* @return None
*
* @details This macro clears reach maximum count status.
* \hideinitializer
*/
#define TPWM_CLEAR_REACH_MAX_CNT_STATUS(timer) ((timer)->PWMSTATUS = TIMER_PWMSTATUS_CNTMAXF_Msk)
/**
* @brief Get Trigger ADC Status
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER0 ~ TIMER5.
*
* @retval 0 Trigger ADC start conversion is not occur
* @retval 1 Specified counter compare event has trigger ADC start conversion
*
* @details This macro is used to indicate PWM counter compare event has triggered ADC start conversion.
* \hideinitializer
*/
#define TPWM_GET_TRG_ADC_STATUS(timer) (((timer)->PWMSTATUS & TIMER_PWMSTATUS_EADCTRGF_Msk)? 1 : 0)
/**
* @brief Clear Trigger ADC Status
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER0 ~ TIMER5.
*
* @return None
*
* @details This macro is used to clear PWM counter compare event trigger ADC status.
* \hideinitializer
*/
#define TPWM_CLEAR_TRG_ADC_STATUS(timer) ((timer)->PWMSTATUS = TIMER_PWMSTATUS_EADCTRGF_Msk)
/**
* @brief Get Trigger PDMA Status
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER4 ~ TIMER5.
*
* @retval 0 Trigger PDMA transfer data is not occur
* @retval 1 Specified counter compare event has trigger PDMA transfer data
*
* @details This macro is used to indicate PWM counter compare event has triggered PDMA start transfer data.
* @note Only available on TIMER4 and TIMER5.
* \hideinitializer
*/
#define TPWM_GET_TRG_PDMA_STATUS(timer) (((timer)->PWMSTATUS & TIMER_PWMSTATUS_PDMATRGF_Msk)? 1 : 0)
/**
* @brief Clear Trigger PDMA Status
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER4 ~ TIMER5.
*
* @return None
*
* @details This macro is used to clear PWM counter compare event trigger PDMA status.
* @note Only available on TIMER4 and TIMER5.
* \hideinitializer
*/
#define TPWM_CLEAR_TRG_PDMA_STATUS(timer) ((timer)->PWMSTATUS = TIMER_PWMSTATUS_PDMATRGF_Msk)
/**
* @brief Get PWM Interrupt Wake-up Flag
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER4 ~ TIMER5.
*
* @retval 0 PWM does not cause CPU wake-up
* @retval 1 PWM interrupt event cause CPU wake-up
*
* @details This function indicates PWM interrupt event has waked up system or not.
* @note Only available on TIMER4 and TIMER5.
*/
#define TPWM_GET_PWMINT_WAKEUP_STATUS(timer) (((timer)->PWMSTATUS & TIMER_PWMSTATUS_WKF_Msk)? 1 : 0)
/**
* @brief Clear PWM Interrupt Wake-up Flag
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER4 ~ TIMER5.
*
* @return None
*
* @details This macro is used to clear PWM interrupt wakeup status.
* @note Only available on TIMER4 and TIMER5.
* \hideinitializer
*/
#define TPWM_CLEAR_PWMINT_WAKEUP_STATUS(timer) ((timer)->PWMSTATUS = TIMER_PWMSTATUS_WKF_Msk)
/**
* @brief Set Brake Event at Brake Pin High or Low-to-High
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER0, TIMER1, TIMER2, TIMER3.
*
* @return None
*
* @details This macro is used to set detect brake event when external brake pin at high level or transfer from low to high.
* @note The default brake pin detection is high level or from low to high.
* @note NOT available on TIMER4 and TIMER5.
* \hideinitializer
*/
#define TPWM_SET_BRAKE_PIN_HIGH_DETECT(timer) ((timer)->PWMBNF &= ~TIMER_PWMBNF_BRKPINV_Msk)
/**
* @brief Set Brake Event at Brake Pin Low or High-to-Low
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER0, TIMER1, TIMER2, TIMER3.
*
* @return None
*
* @details This macro is used to set detect brake event when external brake pin at low level or transfer from high to low.
* @note NOT available on TIMER4 and TIMER5.
* \hideinitializer
*/
#define TPWM_SET_BRAKE_PIN_LOW_DETECT(timer) ((timer)->PWMBNF |= TIMER_PWMBNF_BRKPINV_Msk)
/**
* @brief Set External Brake Pin Source
*
* @param[in] timer The pointer of the specified Timer module. It could be TIMER0, TIMER1, TIMER2, TIMER3.
* @param[in] pin The external brake pin source, could be one of following source
* - \ref TPWM_TM_BRAKE0
* - \ref TPWM_TM_BRAKE1
* - \ref TPWM_TM_BRAKE2
* - \ref TPWM_TM_BRAKE3
*
* @return None
*
* @details This macro is used to set detect brake event when external brake pin at high level or transfer from low to high.
* @note NOT available on TIMER4 and TIMER5.
* \hideinitializer
*/
#define TPWM_SET_BRAKE_PIN_SOURCE(timer, pin) ((timer)->PWMBNF = ((timer)->PWMBNF & ~TIMER_PWMBNF_BKPINSRC_Msk) | ((pin)<<TIMER_PWMBNF_BKPINSRC_Pos))
void TPWM_SetCounterClockSource(TIMER_T *timer, uint32_t u32CntClkSrc);
uint32_t TPWM_ConfigOutputFreqAndDuty(TIMER_T *timer, uint32_t u32Frequency, uint32_t u32DutyCycle);
void TPWM_EnableDeadTime(TIMER_T *timer, uint32_t u32DTCount);
void TPWM_EnableDeadTimeWithPrescale(TIMER_T *timer, uint32_t u32DTCount);
void TPWM_DisableDeadTime(TIMER_T *timer);
void TPWM_EnableCounter(TIMER_T *timer);
void TPWM_DisableCounter(TIMER_T *timer);
void TPWM_EnableTriggerADC(TIMER_T *timer, uint32_t u32Condition);
void TPWM_DisableTriggerADC(TIMER_T *timer);
void TPWM_EnableTriggerPDMA(TIMER_T *timer, uint32_t u32Condition);
void TPWM_DisableTriggerPDMA(TIMER_T *timer);
void TPWM_EnableFaultBrake(TIMER_T *timer, uint32_t u32CH0Level, uint32_t u32CH1Level, uint32_t u32BrakeSource);
void TPWM_EnableFaultBrakeInt(TIMER_T *timer, uint32_t u32IntSource);
void TPWM_DisableFaultBrakeInt(TIMER_T *timer, uint32_t u32IntSource);
uint32_t TPWM_GetFaultBrakeIntFlag(TIMER_T *timer, uint32_t u32IntSource);
void TPWM_ClearFaultBrakeIntFlag(TIMER_T *timer, uint32_t u32IntSource);
void TPWM_SetLoadMode(TIMER_T *timer, uint32_t u32LoadMode);
void TPWM_EnableBrakePinDebounce(TIMER_T *timer, uint32_t u32BrakePinSrc, uint32_t u32DebounceCnt, uint32_t u32ClkSrcSel);
void TPWM_DisableBrakePinDebounce(TIMER_T *timer);
void TPWM_EnableBrakePinInverse(TIMER_T *timer);
void TPWM_DisableBrakePinInverse(TIMER_T *timer);
void TPWM_SetBrakePinSource(TIMER_T *timer, uint32_t u32BrakePinNum);
/**@}*/ /* end of group TIMER_PWM_EXPORTED_FUNCTIONS */
/**@}*/ /* end of group TIMER_PWM_Driver */
/**@}*/ /* end of group Standard_Driver */
#ifdef __cplusplus
}
#endif
#endif /* __NU_TIMER_PWM_H__ */

View File

@ -0,0 +1,516 @@
/**************************************************************************//**
* @file nu_uart.h
* @version V3.00
* @brief M2354 series UART Interface Controller (UART) driver header file
*
* @copyright SPDX-License-Identifier: Apache-2.0
* @copyright Copyright (C) 2020 Nuvoton Technology Corp. All rights reserved.
*****************************************************************************/
#ifndef __NU_UART_H__
#define __NU_UART_H__
#include <M2354.h>
#ifdef __cplusplus
extern "C"
{
#endif
/** @addtogroup Standard_Driver Standard Driver
@{
*/
/** @addtogroup UART_Driver UART Driver
@{
*/
/** @addtogroup UART_EXPORTED_CONSTANTS UART Exported Constants
@{
*/
/*---------------------------------------------------------------------------------------------------------*/
/* UART FIFO size constants definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define UART0_FIFO_SIZE 16UL /*!< UART0 supports separated receive/transmit 16/16 bytes entry FIFO */
#define UART1_FIFO_SIZE 16UL /*!< UART1 supports separated receive/transmit 16/16 bytes entry FIFO */
#define UART2_FIFO_SIZE 16UL /*!< UART2 supports separated receive/transmit 16/16 bytes entry FIFO */
#define UART3_FIFO_SIZE 16UL /*!< UART3 supports separated receive/transmit 16/16 bytes entry FIFO */
#define UART4_FIFO_SIZE 16UL /*!< UART4 supports separated receive/transmit 16/16 bytes entry FIFO */
#define UART5_FIFO_SIZE 16UL /*!< UART5 supports separated receive/transmit 16/16 bytes entry FIFO */
/*---------------------------------------------------------------------------------------------------------*/
/* UART_FIFO constants definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define UART_FIFO_RFITL_1BYTE (0x0UL << UART_FIFO_RFITL_Pos) /*!< UART_FIFO setting to set RX FIFO Trigger Level to 1 byte */
#define UART_FIFO_RFITL_4BYTES (0x1UL << UART_FIFO_RFITL_Pos) /*!< UART_FIFO setting to set RX FIFO Trigger Level to 4 bytes */
#define UART_FIFO_RFITL_8BYTES (0x2UL << UART_FIFO_RFITL_Pos) /*!< UART_FIFO setting to set RX FIFO Trigger Level to 8 bytes */
#define UART_FIFO_RFITL_14BYTES (0x3UL << UART_FIFO_RFITL_Pos) /*!< UART_FIFO setting to set RX FIFO Trigger Level to 14 bytes */
#define UART_FIFO_RTSTRGLV_1BYTE (0x0UL << UART_FIFO_RTSTRGLV_Pos) /*!< UART_FIFO setting to set RTS Trigger Level to 1 byte */
#define UART_FIFO_RTSTRGLV_4BYTES (0x1UL << UART_FIFO_RTSTRGLV_Pos) /*!< UART_FIFO setting to set RTS Trigger Level to 4 bytes */
#define UART_FIFO_RTSTRGLV_8BYTES (0x2UL << UART_FIFO_RTSTRGLV_Pos) /*!< UART_FIFO setting to set RTS Trigger Level to 8 bytes */
#define UART_FIFO_RTSTRGLV_14BYTES (0x3UL << UART_FIFO_RTSTRGLV_Pos) /*!< UART_FIFO setting to set RTS Trigger Level to 14 bytes */
/*---------------------------------------------------------------------------------------------------------*/
/* UART_LINE constants definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define UART_WORD_LEN_5 (0UL) /*!< UART_LINE setting to set UART word length to 5 bits */
#define UART_WORD_LEN_6 (1UL) /*!< UART_LINE setting to set UART word length to 6 bits */
#define UART_WORD_LEN_7 (2UL) /*!< UART_LINE setting to set UART word length to 7 bits */
#define UART_WORD_LEN_8 (3UL) /*!< UART_LINE setting to set UART word length to 8 bits */
#define UART_PARITY_NONE (0x0UL << UART_LINE_PBE_Pos) /*!< UART_LINE setting to set UART as no parity */
#define UART_PARITY_ODD (0x1UL << UART_LINE_PBE_Pos) /*!< UART_LINE setting to set UART as odd parity */
#define UART_PARITY_EVEN (0x3UL << UART_LINE_PBE_Pos) /*!< UART_LINE setting to set UART as even parity */
#define UART_PARITY_MARK (0x5UL << UART_LINE_PBE_Pos) /*!< UART_LINE setting to keep parity bit as '1' */
#define UART_PARITY_SPACE (0x7UL << UART_LINE_PBE_Pos) /*!< UART_LINE setting to keep parity bit as '0' */
#define UART_STOP_BIT_1 (0x0UL << UART_LINE_NSB_Pos) /*!< UART_LINE setting for one stop bit */
#define UART_STOP_BIT_1_5 (0x1UL << UART_LINE_NSB_Pos) /*!< UART_LINE setting for 1.5 stop bit when 5-bit word length */
#define UART_STOP_BIT_2 (0x1UL << UART_LINE_NSB_Pos) /*!< UART_LINE setting for two stop bit when 6, 7, 8-bit word length */
/*---------------------------------------------------------------------------------------------------------*/
/* UART RTS ACTIVE LEVEL constants definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define UART_RTS_IS_LOW_LEV_ACTIVE (0x1UL << UART_MODEM_RTSACTLV_Pos) /*!< Set RTS is Low Level Active */
#define UART_RTS_IS_HIGH_LEV_ACTIVE (0x0UL << UART_MODEM_RTSACTLV_Pos) /*!< Set RTS is High Level Active */
/*---------------------------------------------------------------------------------------------------------*/
/* UART_IRDA constants definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define UART_IRDA_TXEN (0x1UL << UART_IRDA_TXEN_Pos) /*!< Set IrDA function Tx mode */
#define UART_IRDA_RXEN (0x0UL << UART_IRDA_TXEN_Pos) /*!< Set IrDA function Rx mode */
/*---------------------------------------------------------------------------------------------------------*/
/* UART_FUNCSEL constants definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define UART_FUNCSEL_UART (0x0UL << UART_FUNCSEL_FUNCSEL_Pos) /*!< UART_FUNCSEL setting to set UART Function (Default) */
#define UART_FUNCSEL_LIN (0x1UL << UART_FUNCSEL_FUNCSEL_Pos) /*!< UART_FUNCSEL setting to set LIN Function */
#define UART_FUNCSEL_IrDA (0x2UL << UART_FUNCSEL_FUNCSEL_Pos) /*!< UART_FUNCSEL setting to set IrDA Function */
#define UART_FUNCSEL_RS485 (0x3UL << UART_FUNCSEL_FUNCSEL_Pos) /*!< UART_FUNCSEL setting to set RS485 Function */
#define UART_FUNCSEL_SINGLE_WIRE (0x4ul << UART_FUNCSEL_FUNCSEL_Pos) /*!< UART_FUNCSEL setting to set Single Wire Function */
/*---------------------------------------------------------------------------------------------------------*/
/* UART_LINCTL constants definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define UART_LINCTL_BRKFL(x) (((x)-1UL) << UART_LINCTL_BRKFL_Pos) /*!< UART_LINCTL setting to set LIN Break Field Length, x = 10 ~ 15, default value is 12 */
#define UART_LINCTL_BSL(x) (((x)-1UL) << UART_LINCTL_BSL_Pos) /*!< UART_LINCTL setting to set LIN Break/Sync Delimiter Length, x = 1 ~ 4 */
#define UART_LINCTL_HSEL_BREAK (0x0UL << UART_LINCTL_HSEL_Pos) /*!< UART_LINCTL setting to set LIN Header Select to break field */
#define UART_LINCTL_HSEL_BREAK_SYNC (0x1UL << UART_LINCTL_HSEL_Pos) /*!< UART_LINCTL setting to set LIN Header Select to break field and sync field */
#define UART_LINCTL_HSEL_BREAK_SYNC_ID (0x2UL << UART_LINCTL_HSEL_Pos) /*!< UART_LINCTL setting to set LIN Header Select to break field, sync field and ID field*/
#define UART_LINCTL_PID(x) ((x) << UART_LINCTL_PID_Pos) /*!< UART_LINCTL setting to set LIN PID value */
/*---------------------------------------------------------------------------------------------------------*/
/* UART BAUDRATE MODE constants definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define UART_BAUD_MODE0 (0UL) /*!< Set UART Baudrate Mode is Mode0 */
#define UART_BAUD_MODE2 (UART_BAUD_BAUDM1_Msk | UART_BAUD_BAUDM0_Msk) /*!< Set UART Baudrate Mode is Mode2 */
/**@}*/ /* end of group UART_EXPORTED_CONSTANTS */
/** @addtogroup UART_EXPORTED_FUNCTIONS UART Exported Functions
@{
*/
/**
* @brief Calculate UART baudrate mode0 divider
*
* @param[in] u32SrcFreq UART clock frequency
* @param[in] u32BaudRate Baudrate of UART module
*
* @return UART baudrate mode0 divider
*
* @details This macro calculate UART baudrate mode0 divider.
*/
#define UART_BAUD_MODE0_DIVIDER(u32SrcFreq, u32BaudRate) ((((u32SrcFreq) + ((u32BaudRate)*8ul)) / (u32BaudRate) >> 4ul)-2ul)
/**
* @brief Calculate UART baudrate mode2 divider
*
* @param[in] u32SrcFreq UART clock frequency
* @param[in] u32BaudRate Baudrate of UART module
*
* @return UART baudrate mode2 divider
*
* @details This macro calculate UART baudrate mode2 divider.
*/
#define UART_BAUD_MODE2_DIVIDER(u32SrcFreq, u32BaudRate) ((((u32SrcFreq) + ((u32BaudRate)/2ul)) / (u32BaudRate))-2ul)
/**
* @brief Write UART data
*
* @param[in] uart The pointer of the specified UART module
* @param[in] u8Data Data byte to transmit.
*
* @return None
*
* @details This macro write Data to Tx data register.
*/
#define UART_WRITE(uart, u8Data) ((uart)->DAT = (u8Data))
/**
* @brief Read UART data
*
* @param[in] uart The pointer of the specified UART module
*
* @return The oldest data byte in RX FIFO.
*
* @details This macro read Rx data register.
*/
#define UART_READ(uart) ((uart)->DAT)
/**
* @brief Get Tx empty
*
* @param[in] uart The pointer of the specified UART module
*
* @retval 0 Tx FIFO is not empty
* @retval >=1 Tx FIFO is empty
*
* @details This macro get Transmitter FIFO empty register value.
*/
#define UART_GET_TX_EMPTY(uart) ((uart)->FIFOSTS & UART_FIFOSTS_TXEMPTY_Msk)
/**
* @brief Get Rx empty
*
* @param[in] uart The pointer of the specified UART module
*
* @retval 0 Rx FIFO is not empty
* @retval >=1 Rx FIFO is empty
*
* @details This macro get Receiver FIFO empty register value.
*/
#define UART_GET_RX_EMPTY(uart) ((uart)->FIFOSTS & UART_FIFOSTS_RXEMPTY_Msk)
/**
* @brief Check specified uart port transmission is over.
*
* @param[in] uart The pointer of the specified UART module
*
* @retval 0 Tx transmission is not over
* @retval 1 Tx transmission is over
*
* @details This macro return Transmitter Empty Flag register bit value.
* It indicates if specified uart port transmission is over nor not.
*/
#define UART_IS_TX_EMPTY(uart) (((uart)->FIFOSTS & UART_FIFOSTS_TXEMPTYF_Msk) >> UART_FIFOSTS_TXEMPTYF_Pos)
/**
* @brief Wait specified uart port transmission is over
*
* @param[in] uart The pointer of the specified UART module
*
* @return None
*
* @details This macro wait specified uart port transmission is over.
*/
#define UART_WAIT_TX_EMPTY(uart) while(!((((uart)->FIFOSTS) & UART_FIFOSTS_TXEMPTYF_Msk) >> UART_FIFOSTS_TXEMPTYF_Pos))
/**
* @brief Check RX is ready or not
*
* @param[in] uart The pointer of the specified UART module
*
* @retval 0 The number of bytes in the RX FIFO is less than the RFITL
* @retval 1 The number of bytes in the RX FIFO equals or larger than RFITL
*
* @details This macro check receive data available interrupt flag is set or not.
*/
#define UART_IS_RX_READY(uart) (((uart)->INTSTS & UART_INTSTS_RDAIF_Msk)>>UART_INTSTS_RDAIF_Pos)
/**
* @brief Check TX FIFO is full or not
*
* @param[in] uart The pointer of the specified UART module
*
* @retval 1 TX FIFO is full
* @retval 0 TX FIFO is not full
*
* @details This macro check TX FIFO is full or not.
*/
#define UART_IS_TX_FULL(uart) (((uart)->FIFOSTS & UART_FIFOSTS_TXFULL_Msk)>>UART_FIFOSTS_TXFULL_Pos)
/**
* @brief Check RX FIFO is full or not
*
* @param[in] uart The pointer of the specified UART module
*
* @retval 1 RX FIFO is full
* @retval 0 RX FIFO is not full
*
* @details This macro check RX FIFO is full or not.
*/
#define UART_IS_RX_FULL(uart) (((uart)->FIFOSTS & UART_FIFOSTS_RXFULL_Msk)>>UART_FIFOSTS_RXFULL_Pos)
/**
* @brief Get Tx full register value
*
* @param[in] uart The pointer of the specified UART module
*
* @retval 0 Tx FIFO is not full.
* @retval >=1 Tx FIFO is full.
*
* @details This macro get Tx full register value.
*/
#define UART_GET_TX_FULL(uart) ((uart)->FIFOSTS & UART_FIFOSTS_TXFULL_Msk)
/**
* @brief Get Rx full register value
*
* @param[in] uart The pointer of the specified UART module
*
* @retval 0 Rx FIFO is not full.
* @retval >=1 Rx FIFO is full.
*
* @details This macro get Rx full register value.
*/
#define UART_GET_RX_FULL(uart) ((uart)->FIFOSTS & UART_FIFOSTS_RXFULL_Msk)
/**
* @brief Rx Idle Status register value
*
* @param[in] uart The pointer of the specified UART module
*
* @retval 0 Rx is busy.
* @retval 1 Rx is Idle(Default)
*
* @details This macro get Rx Idle Status register value.
* \hideinitializer
*/
#define UART_RX_IDLE(uart) (((uart)->FIFOSTS & UART_FIFOSTS_RXIDLE_Msk )>> UART_FIFOSTS_RXIDLE_Pos)
/**
* @brief Enable specified UART interrupt
*
* @param[in] uart The pointer of the specified UART module
* @param[in] u32eIntSel Interrupt type select
* - \ref UART_INTEN_TXENDIEN_Msk : Transmitter empty interrupt
* - \ref UART_INTEN_ABRIEN_Msk : Auto baud rate interrupt
* - \ref UART_INTEN_LINIEN_Msk : Lin bus interrupt
* - \ref UART_INTEN_WKIEN_Msk : Wake-up interrupt
* - \ref UART_INTEN_BUFERRIEN_Msk : Buffer Error interrupt
* - \ref UART_INTEN_RXTOIEN_Msk : Rx time-out interrupt
* - \ref UART_INTEN_MODEMIEN_Msk : Modem interrupt
* - \ref UART_INTEN_RLSIEN_Msk : Rx Line status interrupt
* - \ref UART_INTEN_THREIEN_Msk : Tx empty interrupt
* - \ref UART_INTEN_RDAIEN_Msk : Rx ready interrupt
*
* @return None
*
* @details This macro enable specified UART interrupt.
*/
#define UART_ENABLE_INT(uart, u32eIntSel) ((uart)->INTEN |= (u32eIntSel))
/**
* @brief Disable specified UART interrupt
*
* @param[in] uart The pointer of the specified UART module
* @param[in] u32eIntSel Interrupt type select
* - \ref UART_INTEN_TXENDIEN_Msk : Transmitter Empty Interrupt
* - \ref UART_INTEN_ABRIEN_Msk : Auto-baud Rate Interrupt
* - \ref UART_INTEN_LINIEN_Msk : Lin Bus interrupt
* - \ref UART_INTEN_WKIEN_Msk : Wake-up interrupt
* - \ref UART_INTEN_BUFERRIEN_Msk : Buffer Error interrupt
* - \ref UART_INTEN_RXTOIEN_Msk : Rx Time-out Interrupt
* - \ref UART_INTEN_MODEMIEN_Msk : MODEM Status Interrupt
* - \ref UART_INTEN_RLSIEN_Msk : Receive Line Status Interrupt
* - \ref UART_INTEN_THREIEN_Msk : Transmit Holding Register Empty Interrupt
* - \ref UART_INTEN_RDAIEN_Msk : Receive Data Available Interrupt
*
* @return None
*
* @details This macro enable specified UART interrupt.
*/
#define UART_DISABLE_INT(uart, u32eIntSel) ((uart)->INTEN &= ~ (u32eIntSel))
/**
* @brief Get specified interrupt flag/status
*
* @param[in] uart The pointer of the specified UART module
* @param[in] u32eIntTypeFlag Interrupt Type Flag, should be
* - \ref UART_INTSTS_ABRINT_Msk : Auto-baud Rate Interrupt Indicator
* - \ref UART_INTSTS_HWBUFEINT_Msk : PDMA Mode Buffer Error Interrupt Indicator
* - \ref UART_INTSTS_HWTOINT_Msk : PDMA Mode Rx Time-out Interrupt Indicator
* - \ref UART_INTSTS_HWMODINT_Msk : PDMA Mode MODEM Status Interrupt Indicator
* - \ref UART_INTSTS_HWRLSINT_Msk : PDMA Mode Receive Line Status Interrupt Indicator
* - \ref UART_INTSTS_SWBEINT_Msk : Single-wire Bit Error Detect Interrupt Indicator
* - \ref UART_INTSTS_HWBUFEIF_Msk : PDMA Mode Buffer Error Interrupt Flag
* - \ref UART_INTSTS_HWTOIF_Msk : PDMA Mode Time-out Interrupt Flag
* - \ref UART_INTSTS_HWMODIF_Msk : PDMA Mode MODEM Status Interrupt Flag
* - \ref UART_INTSTS_HWRLSIF_Msk : PDMA Mode Receive Line Status Flag
* - \ref UART_INTSTS_SWBEIF_Msk : Single-wire Bit Error Detect Interrupt Flag
* - \ref UART_INTSTS_TXENDINT_Msk : Transmitter Empty Interrupt Indicator
* - \ref UART_INTSTS_LININT_Msk : LIN Bus Interrupt Indicator
* - \ref UART_INTSTS_WKINT_Msk : Wake-up Interrupt Indicator
* - \ref UART_INTSTS_BUFERRINT_Msk : Buffer Error Interrupt Indicator
* - \ref UART_INTSTS_RXTOINT_Msk : Rx Time-out Interrupt Indicator
* - \ref UART_INTSTS_MODEMINT_Msk : Modem Status Interrupt Indicator
* - \ref UART_INTSTS_RLSINT_Msk : Receive Line Status Interrupt Indicator
* - \ref UART_INTSTS_THREINT_Msk : Transmit Holding Register Empty Interrupt Indicator
* - \ref UART_INTSTS_RDAINT_Msk : Receive Data Available Interrupt Indicator
* - \ref UART_INTSTS_TXENDIF_Msk : Transmitter Empty Interrupt Flag
* - \ref UART_INTSTS_LINIF_Msk : LIN Bus Interrupt Flag
* - \ref UART_INTSTS_WKIF_Msk : Wake-up Interrupt Flag
* - \ref UART_INTSTS_BUFERRIF_Msk : Buffer Error Interrupt Flag
* - \ref UART_INTSTS_RXTOIF_Msk : Rx Time-out Interrupt Flag
* - \ref UART_INTSTS_MODEMIF_Msk : MODEM Status Interrupt Flag
* - \ref UART_INTSTS_RLSIF_Msk : Receive Line Status Interrupt Flag
* - \ref UART_INTSTS_THREIF_Msk : Transmit Holding Register Empty Interrupt Flag
* - \ref UART_INTSTS_RDAIF_Msk : Receive Data Available Interrupt Flag
*
* @retval 0 The specified interrupt is not happened.
* 1 The specified interrupt is happened.
*
* @details This macro get specified interrupt flag or interrupt indicator status.
*/
#define UART_GET_INT_FLAG(uart,u32eIntTypeFlag) (((uart)->INTSTS & (u32eIntTypeFlag))?1:0)
/*---------------------------------------------------------------------------------------------------------*/
/* static inline functions */
/*---------------------------------------------------------------------------------------------------------*/
/* Declare these inline functions here to avoid MISRA C 2004 rule 8.1 error */
static __INLINE void UART_CLEAR_RTS(UART_T* uart);
static __INLINE void UART_SET_RTS(UART_T* uart);
/**
* @brief Set RTS pin to low
*
* @param[in] uart The pointer of the specified UART module
*
* @return None
*
* @details This macro set RTS pin to low.
*/
__STATIC_INLINE void UART_CLEAR_RTS(UART_T* uart)
{
uart->MODEM |= UART_MODEM_RTSACTLV_Msk;
uart->MODEM &= ~UART_MODEM_RTS_Msk;
}
/**
* @brief Set RTS pin to high
*
* @param[in] uart The pointer of the specified UART module
*
* @return None
*
* @details This macro set RTS pin to high.
*/
__STATIC_INLINE void UART_SET_RTS(UART_T* uart)
{
uart->MODEM |= UART_MODEM_RTSACTLV_Msk | UART_MODEM_RTS_Msk;
}
/**
* @brief Clear RS-485 Address Byte Detection Flag
*
* @param[in] uart The pointer of the specified UART module
*
* @return None
*
* @details This macro clear RS-485 address byte detection flag.
*/
#define UART_RS485_CLEAR_ADDR_FLAG(uart) ((uart)->FIFOSTS = UART_FIFOSTS_ADDRDETF_Msk)
/**
* @brief Get RS-485 Address Byte Detection Flag
*
* @param[in] uart The pointer of the specified UART module
*
* @retval 0 Receiver detects a data that is not an address bit.
* @retval 1 Receiver detects a data that is an address bit.
*
* @details This macro get RS-485 address byte detection flag.
*/
#define UART_RS485_GET_ADDR_FLAG(uart) (((uart)->FIFOSTS & UART_FIFOSTS_ADDRDETF_Msk) >> UART_FIFOSTS_ADDRDETF_Pos)
/**
* @brief Enable specified UART PDMA function
*
* @param[in] uart The pointer of the specified UART module
* @param[in] u32FuncSel Combination of following functions
* - \ref UART_INTEN_TXPDMAEN_Msk
* - \ref UART_INTEN_RXPDMAEN_Msk
*
* @return None
*
* @details This macro enable specified UART PDMA function.
*/
#define UART_PDMA_ENABLE(uart, u32FuncSel) ((uart)->INTEN |= (u32FuncSel))
/**
* @brief Disable specified UART PDMA function
*
* @param[in] uart The pointer of the specified UART module
* @param[in] u32FuncSel Combination of following functions
* - \ref UART_INTEN_TXPDMAEN_Msk
* - \ref UART_INTEN_RXPDMAEN_Msk
*
* @return None
*
* @details This macro disable specified UART PDMA function.
*/
#define UART_PDMA_DISABLE(uart, u32FuncSel) ((uart)->INTEN &= ~(u32FuncSel))
void UART_ClearIntFlag(UART_T* uart, uint32_t u32InterruptFlag);
void UART_Close(UART_T* uart);
void UART_DisableFlowCtrl(UART_T* uart);
void UART_DisableInt(UART_T* uart, uint32_t u32InterruptFlag);
void UART_EnableFlowCtrl(UART_T* uart);
void UART_EnableInt(UART_T* uart, uint32_t u32InterruptFlag);
void UART_Open(UART_T* uart, uint32_t u32baudrate);
uint32_t UART_Read(UART_T* uart, uint8_t pu8RxBuf[], uint32_t u32ReadBytes);
void UART_SetLineConfig(UART_T* uart, uint32_t u32baudrate, uint32_t u32data_width, uint32_t u32parity, uint32_t u32stop_bits);
void UART_SetTimeoutCnt(UART_T* uart, uint32_t u32TOC);
void UART_SelectIrDAMode(UART_T* uart, uint32_t u32Buadrate, uint32_t u32Direction);
void UART_SelectRS485Mode(UART_T* uart, uint32_t u32Mode, uint32_t u32Addr);
void UART_SelectLINMode(UART_T* uart, uint32_t u32Mode, uint32_t u32BreakLength);
uint32_t UART_Write(UART_T* uart, uint8_t pu8TxBuf[], uint32_t u32WriteBytes);
void UART_SelectSingleWireMode(UART_T *uart);
/**@}*/ /* end of group UART_EXPORTED_FUNCTIONS */
/**@}*/ /* end of group UART_Driver */
/**@}*/ /* end of group Standard_Driver */
#ifdef __cplusplus
}
#endif
#endif /* __NU_UART_H__ */

View File

@ -0,0 +1,796 @@
/******************************************************************************
* @file nu_usbd.h
* @version V3.00
* @brief M2354 series USBD driver header file
*
* @copyright SPDX-License-Identifier: Apache-2.0
* @copyright Copyright (C) 2020 Nuvoton Technology Corp. All rights reserved.
******************************************************************************/
#ifndef __NU_USBD_H__
#define __NU_USBD_H__
#define SUPPORT_LPM // define to support LPM
#ifdef __cplusplus
extern "C"
{
#endif
/** @addtogroup Standard_Driver Standard Driver
@{
*/
/** @addtogroup USBD_Driver USBD Driver
@{
*/
/** @addtogroup USBD_EXPORTED_STRUCTS USBD Exported Structs
@{
*/
typedef struct s_usbd_info
{
uint8_t *gu8DevDesc; /*!< Pointer for USB Device Descriptor */
uint8_t *gu8ConfigDesc; /*!< Pointer for USB Configuration Descriptor */
uint8_t **gu8StringDesc; /*!< Pointer for USB String Descriptor pointers */
uint8_t **gu8HidReportDesc; /*!< Pointer for USB HID Report Descriptor */
uint8_t *gu8BosDesc; /*!< Pointer for USB BOS Descriptor */
uint32_t *gu32HidReportSize; /*!< Pointer for HID Report descriptor Size */
uint32_t *gu32ConfigHidDescIdx; /*!< Pointer for HID Descriptor start index */
} S_USBD_INFO_T; /*!< Device description structure */
extern const S_USBD_INFO_T gsInfo;
/**@}*/ /* end of group USBD_EXPORTED_STRUCTS */
/** @addtogroup USBD_EXPORTED_CONSTANTS USBD Exported Constants
@{
*/
#define USBD_BUF_BASE (uint32_t)(((__PC() & NS_OFFSET) == NS_OFFSET)? (USBD_BASE+NS_OFFSET+0x100UL):(USBD_BASE+0x100UL)) /*!< USBD buffer base address */
#define USBD_MAX_EP 12UL /*!< Total EP number */
#define EP0 0UL /*!< Endpoint 0 */
#define EP1 1UL /*!< Endpoint 1 */
#define EP2 2UL /*!< Endpoint 2 */
#define EP3 3UL /*!< Endpoint 3 */
#define EP4 4UL /*!< Endpoint 4 */
#define EP5 5UL /*!< Endpoint 5 */
#define EP6 6UL /*!< Endpoint 6 */
#define EP7 7UL /*!< Endpoint 7 */
#define EP8 8UL /*!< Endpoint 8 */
#define EP9 9UL /*!< Endpoint 9 */
#define EP10 10UL /*!< Endpoint 10 */
#define EP11 11UL /*!< Endpoint 11 */
/** @cond HIDDEN_SYMBOLS */
/* USB Request Type */
#define REQ_STANDARD 0x00UL
#define REQ_CLASS 0x20UL
#define REQ_VENDOR 0x40UL
/* USB Standard Request */
#define GET_STATUS 0x00UL
#define CLEAR_FEATURE 0x01UL
#define SET_FEATURE 0x03UL
#define SET_ADDRESS 0x05UL
#define GET_DESCRIPTOR 0x06UL
#define SET_DESCRIPTOR 0x07UL
#define GET_CONFIGURATION 0x08UL
#define SET_CONFIGURATION 0x09UL
#define GET_INTERFACE 0x0AUL
#define SET_INTERFACE 0x0BUL
#define SYNC_FRAME 0x0CUL
/* USB Descriptor Type */
#define DESC_DEVICE 0x01UL
#define DESC_CONFIG 0x02UL
#define DESC_STRING 0x03UL
#define DESC_INTERFACE 0x04UL
#define DESC_ENDPOINT 0x05UL
#define DESC_QUALIFIER 0x06UL
#define DESC_OTHERSPEED 0x07UL
#define DESC_IFPOWER 0x08UL
#define DESC_OTG 0x09UL
#define DESC_BOS 0x0FUL
#define DESC_CAPABILITY 0x10UL
/* USB Device Capability Type */
#define CAP_WIRELESS 0x01UL
#define CAP_USB20_EXT 0x02UL
/*!<USB HID Descriptor Type */
#define DESC_HID 0x21UL
#define DESC_HID_RPT 0x22UL
/* USB Descriptor Length */
#define LEN_DEVICE 18UL
#define LEN_QUALIFIER 10UL
#define LEN_CONFIG 9UL
#define LEN_INTERFACE 9UL
#define LEN_ENDPOINT 7UL
#define LEN_OTG 5UL
#define LEN_BOS 5UL
#define LEN_HID 9UL
#define LEN_CCID 0x36UL
#define LEN_BOSCAP 7UL
/* USB Endpoint Type */
#define EP_ISO 0x01
#define EP_BULK 0x02
#define EP_INT 0x03
#define EP_INPUT 0x80
#define EP_OUTPUT 0x00
/* USB Feature Selector */
#define FEATURE_DEVICE_REMOTE_WAKEUP 0x01UL
#define FEATURE_ENDPOINT_HALT 0x00UL
/** @endcond HIDDEN_SYMBOLS */
/******************************************************************************/
/* USB Specific Macros */
/******************************************************************************/
#define USBD_WAKEUP_EN USBD_INTEN_WKEN_Msk /*!< USB Wake-up Enable */
#define USBD_DRVSE0 USBD_SE0_SE0_Msk /*!< Drive SE0 */
#define USBD_LPMACK USBD_ATTR_LPMACK_Msk /*!< LPM Enable */
#define USBD_BYTEM USBD_ATTR_BYTEM_Msk /*!< Access Size Mode Selection */
#define USBD_DPPU_EN USBD_ATTR_DPPUEN_Msk /*!< USB D+ Pull-up Enable */
#define USBD_USB_EN USBD_ATTR_USBEN_Msk /*!< USB Enable */
#define USBD_RWAKEUP USBD_ATTR_RWAKEUP_Msk /*!< Remote Wake-Up */
#define USBD_PHY_EN USBD_ATTR_PHYEN_Msk /*!< PHY Enable */
#define USBD_INT_BUS USBD_INTEN_BUSIEN_Msk /*!< USB Bus Event Interrupt */
#define USBD_INT_USB USBD_INTEN_USBIEN_Msk /*!< USB Event Interrupt */
#define USBD_INT_FLDET USBD_INTEN_VBDETIEN_Msk /*!< USB VBUS Detection Interrupt */
#define USBD_INT_WAKEUP (USBD_INTEN_NEVWKIEN_Msk | USBD_INTEN_WKEN_Msk) /*!< USB No-Event-Wake-Up Interrupt */
#define USBD_INTSTS_WAKEUP USBD_INTSTS_NEVWKIF_Msk /*!< USB No-Event-Wake-Up Interrupt Status */
#define USBD_INTSTS_FLDET USBD_INTSTS_VBDETIF_Msk /*!< USB Float Detect Interrupt Status */
#define USBD_INTSTS_BUS USBD_INTSTS_BUSIF_Msk /*!< USB Bus Event Interrupt Status */
#define USBD_INTSTS_USB USBD_INTSTS_USBIF_Msk /*!< USB Event Interrupt Status */
#define USBD_INTSTS_SETUP USBD_INTSTS_SETUP_Msk /*!< USB Setup Event */
#define USBD_INTSTS_EP0 USBD_INTSTS_EPEVT0_Msk /*!< USB Endpoint 0 Event */
#define USBD_INTSTS_EP1 USBD_INTSTS_EPEVT1_Msk /*!< USB Endpoint 1 Event */
#define USBD_INTSTS_EP2 USBD_INTSTS_EPEVT2_Msk /*!< USB Endpoint 2 Event */
#define USBD_INTSTS_EP3 USBD_INTSTS_EPEVT3_Msk /*!< USB Endpoint 3 Event */
#define USBD_INTSTS_EP4 USBD_INTSTS_EPEVT4_Msk /*!< USB Endpoint 4 Event */
#define USBD_INTSTS_EP5 USBD_INTSTS_EPEVT5_Msk /*!< USB Endpoint 5 Event */
#define USBD_INTSTS_EP6 USBD_INTSTS_EPEVT6_Msk /*!< USB Endpoint 6 Event */
#define USBD_INTSTS_EP7 USBD_INTSTS_EPEVT7_Msk /*!< USB Endpoint 7 Event */
#define USBD_INTSTS_EP8 USBD_INTSTS_EPEVT8_Msk /*!< USB Endpoint 8 Event */
#define USBD_INTSTS_EP9 USBD_INTSTS_EPEVT9_Msk /*!< USB Endpoint 9 Event */
#define USBD_INTSTS_EP10 USBD_INTSTS_EPEVT10_Msk /*!< USB Endpoint 10 Event */
#define USBD_INTSTS_EP11 USBD_INTSTS_EPEVT11_Msk /*!< USB Endpoint 11 Event */
#define USBD_STATE_USBRST USBD_ATTR_USBRST_Msk /*!< USB Bus Reset */
#define USBD_STATE_SUSPEND USBD_ATTR_SUSPEND_Msk /*!< USB Bus Suspend */
#define USBD_STATE_RESUME USBD_ATTR_RESUME_Msk /*!< USB Bus Resume */
#define USBD_STATE_TIMEOUT USBD_ATTR_TOUT_Msk /*!< USB Bus Timeout */
#define USBD_STATE_L1SUSPEND USBD_ATTR_L1SUSPEND_Msk /*!< USB Bus L1SUSPEND */
#define USBD_STATE_L1RESUME USBD_ATTR_L1RESUME_Msk /*!< USB Bus L1RESUME */
#define USBD_CFG_DB_EN USBD_CFG_DBEN_Msk /*!< Double Buffer Enable */
#define USBD_CFG_DBTGACTIVE USBD_CFG_DBTGACTIVE_Msk /*!< Double Buffer Toggle Active */
#define USBD_CFGP_SSTALL USBD_CFGP_SSTALL_Msk /*!< Set Stall */
#define USBD_CFG_CSTALL USBD_CFG_CSTALL_Msk /*!< Clear Stall */
#define USBD_CFG_EPMODE_DISABLE (0UL << USBD_CFG_STATE_Pos)/*!< Endpoint Disable */
#define USBD_CFG_EPMODE_OUT (1UL << USBD_CFG_STATE_Pos)/*!< Out Endpoint */
#define USBD_CFG_EPMODE_IN (2UL << USBD_CFG_STATE_Pos)/*!< In Endpoint */
#define USBD_CFG_TYPE_ISO (1UL << USBD_CFG_ISOCH_Pos)/*!< Isochronous */
/**@}*/ /* end of group USBD_EXPORTED_CONSTANTS */
/** @addtogroup USBD_EXPORTED_FUNCTIONS USBD Exported Functions
@{
*/
/**
* @brief Compare two input numbers and return maximum one.
*
* @param[in] a First number to be compared.
* @param[in] b Second number to be compared.
*
* @return Maximum value between a and b.
*
* @details If a > b, then return a. Otherwise, return b.
*/
#define USBD_Maximum(a,b) ((a)>(b) ? (a) : (b))
/**
* @brief Compare two input numbers and return minimum one
*
* @param[in] a First number to be compared
* @param[in] b Second number to be compared
*
* @return Minimum value between a and b
*
* @details If a < b, then return a. Otherwise, return b.
*/
#define USBD_Minimum(a,b) ((a)<(b) ? (a) : (b))
/**
* @brief Enable USB
*
* @param None
*
* @return None
*
* @details To set USB ATTR control register to enable USB and PHY.
*
*/
#define USBD_ENABLE_USB() (((__PC() & NS_OFFSET) == NS_OFFSET)? ((uint32_t)(USBD_NS->ATTR |= 0x7D0)):((uint32_t)(USBD->ATTR |= 0x7D0)))
/**
* @brief Disable USB
*
* @param None
*
* @return None
*
* @details To set USB ATTR control register to disable USB.
*
*/
#define USBD_DISABLE_USB() (((__PC() & NS_OFFSET) == NS_OFFSET)? ((uint32_t)(USBD_NS->ATTR &= ~USBD_USB_EN)):((uint32_t)(USBD->ATTR &= ~USBD_USB_EN)))
/**
* @brief Enable USB PHY
*
* @param None
*
* @return None
*
* @details To set USB ATTR control register to enable USB PHY.
*
*/
#define USBD_ENABLE_PHY() (((__PC() & NS_OFFSET) == NS_OFFSET)? ((uint32_t)(USBD_NS->ATTR |= USBD_PHY_EN)):((uint32_t)(USBD->ATTR |= USBD_PHY_EN)))
/**
* @brief Disable USB PHY
*
* @param None
*
* @return None
*
* @details To set USB ATTR control register to disable USB PHY.
*
*/
#define USBD_DISABLE_PHY() (((__PC() & NS_OFFSET) == NS_OFFSET)? ((uint32_t)(USBD_NS->ATTR &= ~USBD_PHY_EN)):((uint32_t)(USBD->ATTR &= ~USBD_PHY_EN)))
/**
* @brief Enable SE0. Force USB PHY transceiver to drive SE0.
*
* @param None
*
* @return None
*
* @details Set DRVSE0 bit of USB_DRVSE0 register to enable software-disconnect function. Force USB PHY transceiver to drive SE0 to bus.
*
*/
#define USBD_SET_SE0() (((__PC() & NS_OFFSET) == NS_OFFSET)? ((uint32_t)(USBD_NS->SE0 |= USBD_DRVSE0)):((uint32_t)(USBD->SE0 |= USBD_DRVSE0)))
/**
* @brief Disable SE0
*
* @param None
*
* @return None
*
* @details Clear DRVSE0 bit of USB_DRVSE0 register to disable software-disconnect function.
*
*/
#define USBD_CLR_SE0() (((__PC() & NS_OFFSET) == NS_OFFSET)? ((uint32_t)(USBD_NS->SE0 &= ~USBD_DRVSE0)):((uint32_t)(USBD->SE0 &= ~USBD_DRVSE0)))
/**
* @brief Set USB device address
*
* @param[in] addr The USB device address.
*
* @return None
*
* @details Write USB device address to USB_FADDR register.
*
*/
#define USBD_SET_ADDR(addr) (((__PC() & NS_OFFSET) == NS_OFFSET)? (USBD_NS->FADDR = (addr)):(USBD->FADDR = (addr)))
/**
* @brief Get USB device address
*
* @param None
*
* @return USB device address
*
* @details Read USB_FADDR register to get USB device address.
*
*/
#define USBD_GET_ADDR() (((__PC() & NS_OFFSET) == NS_OFFSET)? ((uint32_t)(USBD_NS->FADDR)):((uint32_t)(USBD->FADDR)))
/**
* @brief Enable USB interrupt function
*
* @param[in] intr The combination of the specified interrupt enable bits.
* Each bit corresponds to a interrupt enable bit.
* This parameter decides which interrupts will be enabled.
* (USBD_INT_WAKEUP, USBD_INT_FLDET, USBD_INT_USB, USBD_INT_BUS)
*
* @return None
*
* @details Enable USB related interrupt functions specified by intr parameter.
*
*/
#define USBD_ENABLE_INT(intr) (((__PC() & NS_OFFSET) == NS_OFFSET)? (USBD_NS->INTEN |= (intr)):(USBD->INTEN |= (intr)))
/**
* @brief Get interrupt status
*
* @param None
*
* @return The value of USB_INTSTS register
*
* @details Return all interrupt flags of USB_INTSTS register.
*
*/
#define USBD_GET_INT_FLAG() (((__PC() & NS_OFFSET) == NS_OFFSET)? ((uint32_t)(USBD_NS->INTSTS)):((uint32_t)(USBD->INTSTS)))
/**
* @brief Clear USB interrupt flag
*
* @param[in] flag The combination of the specified interrupt flags.
* Each bit corresponds to a interrupt source.
* This parameter decides which interrupt flags will be cleared.
* (USBD_INTSTS_WAKEUP, USBD_INTSTS_FLDET, USBD_INTSTS_BUS, USBD_INTSTS_USB)
*
* @return None
*
* @details Clear USB related interrupt flags specified by flag parameter.
*
*/
#define USBD_CLR_INT_FLAG(flag) (((__PC() & NS_OFFSET) == NS_OFFSET)? (USBD_NS->INTSTS = (flag)):(USBD->INTSTS = (flag)))
/**
* @brief Get endpoint status
*
* @param None
*
* @return The value of USB_EPSTS register.
*
* @details Return all endpoint status.
*
*/
#define USBD_GET_EP_FLAG() (((__PC() & NS_OFFSET) == NS_OFFSET)? ((uint32_t)(USBD_NS->EPSTS)):((uint32_t)(USBD->EPSTS)))
/**
* @brief Get USB bus state
*
* @param None
*
* @return The value of USB_ATTR[13:12] and USB_ATTR[3:0].
* Bit 0 indicates USB bus reset status.
* Bit 1 indicates USB bus suspend status.
* Bit 2 indicates USB bus resume status.
* Bit 3 indicates USB bus time-out status.
* Bit 12 indicates USB bus LPM L1 suspend status.
* Bit 13 indicates USB bus LPM L1 resume status.
*
* @details Return USB_ATTR[13:12] and USB_ATTR[3:0] for USB bus events.
*
*/
#define USBD_GET_BUS_STATE() (((__PC() & NS_OFFSET) == NS_OFFSET)? ((uint32_t)(USBD_NS->ATTR & 0x300F)):((uint32_t)(USBD->ATTR & 0x300F)))
/**
* @brief Check cable connection state
*
* @param None
*
* @retval 0 USB cable is not attached.
* @retval 1 USB cable is attached.
*
* @details Check the connection state by FLDET bit of USB_FLDET register.
*
*/
#define USBD_IS_ATTACHED() (((__PC() & NS_OFFSET) == NS_OFFSET)? ((uint32_t)(USBD_NS->VBUSDET & USBD_VBUSDET_VBUSDET_Msk)):((uint32_t)(USBD->VBUSDET & USBD_VBUSDET_VBUSDET_Msk)))
/**
* @brief Stop USB transaction of the specified endpoint ID
*
* @param[in] ep The USB endpoint ID. M2354 Series supports 12 hardware endpoint ID. This parameter could be 0 ~ 11.
*
* @return None
*
* @details Write 1 to CLRRDY bit of USB_CFGPx register to stop USB transaction of the specified endpoint ID.
*
*/
#define USBD_STOP_TRANSACTION(ep) (((__PC() & NS_OFFSET) == NS_OFFSET)? (*((__IO uint32_t *) ((uint32_t)&USBD_NS->EP[0].CFGP + (uint32_t)((ep) << 4))) |= USBD_CFGP_CLRRDY_Msk):(*((__IO uint32_t *) ((uint32_t)&USBD->EP[0].CFGP + (uint32_t)((ep) << 4))) |= USBD_CFGP_CLRRDY_Msk))
/**
* @brief Set USB DATA1 PID for the specified endpoint ID
*
* @param[in] ep The USB endpoint ID. M2354 Series supports 12 hardware endpoint ID. This parameter could be 0 ~ 11.
*
* @return None
*
* @details Set DSQ_SYNC bit of USB_CFGx register to specify the DATA1 PID for the following IN token transaction.
* Base on this setting, hardware will toggle PID between DATA0 and DATA1 automatically for IN token transactions in single buffer mode.
*
*/
#define USBD_SET_DATA1(ep) (((__PC() & NS_OFFSET) == NS_OFFSET)? (*((__IO uint32_t *) ((uint32_t)&USBD_NS->EP[0].CFG + (uint32_t)((ep) << 4))) |= USBD_CFG_DSQSYNC_Msk):(*((__IO uint32_t *) ((uint32_t)&USBD->EP[0].CFG + (uint32_t)((ep) << 4))) |= USBD_CFG_DSQSYNC_Msk))
/**
* @brief Set USB DATA0 PID for the specified endpoint ID
*
* @param[in] ep The USB endpoint ID. M2354 Series supports 12 hardware endpoint ID. This parameter could be 0 ~ 11.
*
* @return None
*
* @details Clear DSQ_SYNC bit of USB_CFGx register to specify the DATA0 PID for the following IN token transaction.
* Base on this setting, hardware will toggle PID between DATA0 and DATA1 automatically for IN token transactions in single buffer mode.
*
*/
#define USBD_SET_DATA0(ep) (((__PC() & NS_OFFSET) == NS_OFFSET)? (*((__IO uint32_t *) ((uint32_t)&USBD_NS->EP[0].CFG + (uint32_t)((ep) << 4))) &= (~USBD_CFG_DSQSYNC_Msk)):(*((__IO uint32_t *) ((uint32_t)&USBD->EP[0].CFG + (uint32_t)((ep) << 4))) &= (~USBD_CFG_DSQSYNC_Msk)))
/**
* @brief Set USB payload size (IN data)
*
* @param[in] ep The USB endpoint ID. M2354 Series supports 12 hardware endpoint ID. This parameter could be 0 ~ 11.
*
* @param[in] size The transfer length.
*
* @return None
*
* @details This macro will write the transfer length to USB_MXPLDx register for IN data transaction.
*
*/
#define USBD_SET_PAYLOAD_LEN(ep, size) (((__PC() & NS_OFFSET) == NS_OFFSET)? (*((__IO uint32_t *) ((uint32_t)&USBD_NS->EP[0].MXPLD + (uint32_t)((ep) << 4))) = (size)):(*((__IO uint32_t *) ((uint32_t)&USBD->EP[0].MXPLD + (uint32_t)((ep) << 4))) = (size)))
/**
* @brief Get USB payload size (OUT data)
*
* @param[in] ep The USB endpoint ID. M2354 Series supports 12 hardware endpoint ID. This parameter could be 0 ~ 11.
*
* @return The value of USB_MXPLDx register.
*
* @details Get the data length of OUT data transaction by reading USB_MXPLDx register.
*
*/
#define USBD_GET_PAYLOAD_LEN(ep) (((__PC() & NS_OFFSET) == NS_OFFSET)? ((uint32_t)*((__IO uint32_t *) ((uint32_t)&USBD_NS->EP[0].MXPLD + (uint32_t)((ep) << 4)))):((uint32_t)*((__IO uint32_t *) ((uint32_t)&USBD->EP[0].MXPLD + (uint32_t)((ep) << 4)))))
/**
* @brief Configure endpoint
*
* @param[in] ep The USB endpoint ID. M2354 Series supports 12 hardware endpoint ID. This parameter could be 0 ~ 11.
*
* @param[in] config The USB configuration.
*
* @return None
*
* @details This macro will write config parameter to USB_CFGx register of specified endpoint ID.
*
*/
#define USBD_CONFIG_EP(ep, config) (((__PC() & NS_OFFSET) == NS_OFFSET)? (*((__IO uint32_t *) ((uint32_t)&USBD_NS->EP[0].CFG + (uint32_t)((ep) << 4))) = (config)):(*((__IO uint32_t *) ((uint32_t)&USBD->EP[0].CFG + (uint32_t)((ep) << 4))) = (config)))
/**
* @brief Set USB endpoint buffer
*
* @param[in] ep The USB endpoint ID. M2354 Series supports 12 hardware endpoint ID. This parameter could be 0 ~ 11.
*
* @param[in] offset The SRAM offset.
*
* @return None
*
* @details This macro will set the SRAM offset for the specified endpoint ID.
*
*/
#define USBD_SET_EP_BUF_ADDR(ep, offset) (((__PC() & NS_OFFSET) == NS_OFFSET)? (*((__IO uint32_t *) ((uint32_t)&USBD_NS->EP[0].BUFSEG + (uint32_t)((ep) << 4))) = (offset)):(*((__IO uint32_t *) ((uint32_t)&USBD->EP[0].BUFSEG + (uint32_t)((ep) << 4))) = (offset)))
/**
* @brief Get the offset of the specified USB endpoint buffer
*
* @param[in] ep The USB endpoint ID. M2354 Series supports 12 hardware endpoint ID. This parameter could be 0 ~ 11.
*
* @return The offset of the specified endpoint buffer.
*
* @details This macro will return the SRAM offset of the specified endpoint ID.
*
*/
#define USBD_GET_EP_BUF_ADDR(ep) (((__PC() & NS_OFFSET) == NS_OFFSET)? ((uint32_t)*((__IO uint32_t *) ((uint32_t)&USBD_NS->EP[0].BUFSEG + (uint32_t)((ep) << 4)))):((uint32_t)*((__IO uint32_t *) ((uint32_t)&USBD->EP[0].BUFSEG + (uint32_t)((ep) << 4)))))
/**
* @brief Set USB endpoint stall state
*
* @param[in] ep The USB endpoint ID. M2354 Series supports 12 hardware endpoint ID. This parameter could be 0 ~ 11.
*
* @return None
*
* @details Set USB endpoint stall state for the specified endpoint ID. Endpoint will respond STALL token automatically.
*
*/
#define USBD_SET_EP_STALL(ep) (((__PC() & NS_OFFSET) == NS_OFFSET)? (*((__IO uint32_t *) ((uint32_t)&USBD_NS->EP[0].CFGP + (uint32_t)((ep) << 4))) |= USBD_CFGP_SSTALL_Msk):(*((__IO uint32_t *) ((uint32_t)&USBD->EP[0].CFGP + (uint32_t)((ep) << 4))) |= USBD_CFGP_SSTALL_Msk))
/**
* @brief Clear USB endpoint stall state
*
* @param[in] ep The USB endpoint ID. M2354 Series supports 12 hardware endpoint ID. This parameter could be 0 ~ 11.
*
* @return None
*
* @details Clear USB endpoint stall state for the specified endpoint ID. Endpoint will respond ACK/NAK token.
*
*/
#define USBD_CLR_EP_STALL(ep) (((__PC() & NS_OFFSET) == NS_OFFSET)? (*((__IO uint32_t *) ((uint32_t)&USBD_NS->EP[0].CFGP + (uint32_t)((ep) << 4))) &= ~USBD_CFGP_SSTALL_Msk):(*((__IO uint32_t *) ((uint32_t)&USBD->EP[0].CFGP + (uint32_t)((ep) << 4))) &= ~USBD_CFGP_SSTALL_Msk))
/**
* @brief Get USB endpoint stall state
*
* @param[in] ep The USB endpoint ID. M2354 Series supports 12 hardware endpoint ID. This parameter could be 0 ~ 11.
*
* @retval 0 USB endpoint is not stalled.
* @retval Others USB endpoint is stalled.
*
* @details Get USB endpoint stall state of the specified endpoint ID.
*
*/
#define USBD_GET_EP_STALL(ep) (((__PC() & NS_OFFSET) == NS_OFFSET)? (*((__IO uint32_t *) ((uint32_t)&USBD_NS->EP[0].CFGP + (uint32_t)((ep) << 4))) & USBD_CFGP_SSTALL_Msk):(*((__IO uint32_t *) ((uint32_t)&USBD->EP[0].CFGP + (uint32_t)((ep) << 4))) & USBD_CFGP_SSTALL_Msk))
/**
* @brief Set USB double buffer mode for the specified endpoint ID
*
* @param[in] ep The USB endpoint ID. M2354 Series supports 12 hardware endpoint ID. This parameter could be 0 ~ 11.
*
* @return None
*
* @details Set DBEN bit of USB_CFGx register to enable the double buffer mode of the specified endpoint ID.
*
*/
#define USBD_SET_DB_MODE(ep) (((__PC() & NS_OFFSET) == NS_OFFSET)? (*((__IO uint32_t *) ((uint32_t)&USBD_NS->EP[0].CFG + (uint32_t)((ep) << 4))) |= USBD_CFG_DBEN_Msk):(*((__IO uint32_t *) ((uint32_t)&USBD->EP[0].CFG + (uint32_t)((ep) << 4))) |= USBD_CFG_DBEN_Msk))
/**
* @brief Set USB single buffer mode for the specified endpoint ID
*
* @param[in] ep The USB endpoint ID. M2354 Series supports 12 hardware endpoint ID. This parameter could be 0 ~ 11.
*
* @return None
*
* @details Clear DBEN bit of USB_CFGx register to enable the single buffer mode of the specified endpoint ID.
*
*/
#define USBD_SET_SB_MODE(ep) (((__PC() & NS_OFFSET) == NS_OFFSET)? (*((__IO uint32_t *) ((uint32_t)&USBD_NS->EP[0].CFG + (uint32_t)((ep) << 4))) &= (~USBD_CFG_DBEN_Msk)):(*((__IO uint32_t *) ((uint32_t)&USBD->EP[0].CFG + (uint32_t)((ep) << 4))) &= (~USBD_CFG_DBEN_Msk)))
/**
* @brief Get the buffer mode of the specified USB endpoint buffer
*
* @param[in] ep The USB endpoint ID. M2354 Series supports 12 hardware endpoint ID. This parameter could be 0 ~ 11.
*
* @retval 0 USB is single buffer mode.
* @retval 1 USB is double buffer mode.
*
* @details This macro will return the buffer mode of the specified endpoint ID.
*
*/
#define USBD_IS_DB_MODE(ep) (((__PC() & NS_OFFSET) == NS_OFFSET)? (*((__IO uint32_t *) ((uint32_t)&USBD_NS->EP[0].CFG + (uint32_t)((ep) << 4))) & USBD_CFG_DBEN_Msk):(*((__IO uint32_t *) ((uint32_t)&USBD->EP[0].CFG + (uint32_t)((ep) << 4))) & USBD_CFG_DBEN_Msk))
/**
* @brief Set to active in USB double buffer mode for the specified endpoint ID
*
* @param[in] ep The USB endpoint ID. M2354 Series supports 12 hardware endpoint ID. This parameter could be 0 ~ 11.
*
* @return None
*
* @details Set DBTGACTIVE bit of USB_CFGx register for toggle active in the double buffer mode of the specified endpoint ID.
*
*/
#define USBD_SET_DB_ACTIVE(ep) (((__PC() & NS_OFFSET) == NS_OFFSET)? (*((__IO uint32_t *) ((uint32_t)&USBD_NS->EP[0].CFG + (uint32_t)((ep) << 4))) |= USBD_CFG_DBTGACTIVE_Msk):(*((__IO uint32_t *) ((uint32_t)&USBD->EP[0].CFG + (uint32_t)((ep) << 4))) |= USBD_CFG_DBTGACTIVE_Msk))
/**
* @brief Set to inactive in USB double buffer mode for the specified endpoint ID
*
* @param[in] ep The USB endpoint ID. M2354 Series supports 12 hardware endpoint ID. This parameter could be 0 ~ 11.
*
* @return None
*
* @details Clear DBTGACTIVE bit of USB_CFGx register for toggle inactive in the double buffer mode of the specified endpoint ID.
*
*/
#define USBD_SET_DB_INACTIVE(ep) (((__PC() & NS_OFFSET) == NS_OFFSET)? (*((__IO uint32_t *) ((uint32_t)&USBD_NS->EP[0].CFG + (uint32_t)((ep) << 4))) &= (~USBD_CFG_DBTGACTIVE_Msk)):(*((__IO uint32_t *) ((uint32_t)&USBD->EP[0].CFG + (uint32_t)((ep) << 4))) &= (~USBD_CFG_DBTGACTIVE_Msk)))
/**
* @brief To support byte access between USB SRAM and system SRAM
*
* @param[in] dest Destination pointer.
*
* @param[in] src Source pointer.
*
* @param[in] size Byte count.
*
* @return None
*
* @details This function will copy the number of data specified by size and src parameters to the address specified by dest parameter.
*
*/
__STATIC_INLINE void USBD_MemCopy(uint8_t dest[], uint8_t src[], uint32_t size)
{
uint32_t volatile i = 0UL;
while(size--)
{
dest[i] = src[i];
i++;
}
}
/**
* @brief Set USB endpoint stall state
*
* @param[in] epnum USB endpoint number
*
* @return None
*
* @details Set USB endpoint stall state. Endpoint will respond STALL token automatically.
*
*/
__STATIC_INLINE void USBD_SetStall(uint8_t epnum)
{
uint32_t u32CfgAddr;
uint32_t u32Cfg;
uint32_t i;
USBD_T *pUSBD;
if((__PC() & NS_OFFSET) == NS_OFFSET)
{
pUSBD = USBD_NS;
}
else
{
pUSBD = USBD;
}
for(i = 0UL; i < USBD_MAX_EP; i++)
{
u32CfgAddr = (uint32_t)(i << 4) + (uint32_t)&pUSBD->EP[0].CFG; /* USBD_CFG0 */
u32Cfg = *((__IO uint32_t *)(u32CfgAddr));
if((u32Cfg & 0xFUL) == epnum)
{
u32CfgAddr = (uint32_t)(i << 4) + (uint32_t)&pUSBD->EP[0].CFGP; /* USBD_CFGP0 */
u32Cfg = *((__IO uint32_t *)(u32CfgAddr));
*((__IO uint32_t *)(u32CfgAddr)) = (u32Cfg | USBD_CFGP_SSTALL);
break;
}
}
}
/**
* @brief Clear USB endpoint stall state
*
* @param[in] epnum USB endpoint number
*
* @return None
*
* @details Clear USB endpoint stall state. Endpoint will respond ACK/NAK token.
*/
__STATIC_INLINE void USBD_ClearStall(uint8_t epnum)
{
uint32_t u32CfgAddr;
uint32_t u32Cfg;
uint32_t i;
USBD_T *pUSBD;
if((__PC() & NS_OFFSET) == NS_OFFSET)
{
pUSBD = USBD_NS;
}
else
{
pUSBD = USBD;
}
for(i = 0UL; i < USBD_MAX_EP; i++)
{
u32CfgAddr = (uint32_t)(i << 4) + (uint32_t)&pUSBD->EP[0].CFG; /* USBD_CFG0 */
u32Cfg = *((__IO uint32_t *)(u32CfgAddr));
if((u32Cfg & 0xFUL) == epnum)
{
u32CfgAddr = (uint32_t)(i << 4) + (uint32_t)&pUSBD->EP[0].CFGP; /* USBD_CFGP0 */
u32Cfg = *((__IO uint32_t *)(u32CfgAddr));
*((__IO uint32_t *)(u32CfgAddr)) = (u32Cfg & ~USBD_CFGP_SSTALL);
break;
}
}
}
/**
* @brief Get USB endpoint stall state
*
* @param[in] epnum USB endpoint number
*
* @retval 0 USB endpoint is not stalled.
* @retval Others USB endpoint is stalled.
*
* @details Get USB endpoint stall state.
*
*/
__STATIC_INLINE uint32_t USBD_GetStall(uint8_t epnum)
{
uint32_t u32CfgAddr = 0UL;
uint32_t u32Cfg;
uint32_t i;
USBD_T *pUSBD;
if((__PC() & NS_OFFSET) == NS_OFFSET)
{
pUSBD = USBD_NS;
}
else
{
pUSBD = USBD;
}
for(i = 0UL; i < USBD_MAX_EP; i++)
{
u32CfgAddr = (uint32_t)(i << 4) + (uint32_t)&pUSBD->EP[0].CFG; /* USBD_CFG0 */
u32Cfg = *((__IO uint32_t *)(u32CfgAddr));
if((u32Cfg & 0xFUL) == epnum)
{
u32CfgAddr = (uint32_t)(i << 4) + (uint32_t)&pUSBD->EP[0].CFGP; /* USBD_CFGP0 */
break;
}
}
return ((*((__IO uint32_t *)(u32CfgAddr))) & USBD_CFGP_SSTALL);
}
extern uint8_t g_USBD_au8SetupPacket[8];
extern volatile uint8_t g_USBD_u8RemoteWakeupEn;
typedef void (*VENDOR_REQ)(void); /*!< Functional pointer type definition for Vendor class */
typedef void (*CLASS_REQ)(void); /*!< Functional pointer type declaration for USB class request callback handler */
typedef void (*SET_INTERFACE_REQ)(uint32_t u32AltInterface); /*!< Functional pointer type declaration for USB set interface request callback handler */
typedef void (*SET_CONFIG_CB)(void); /*!< Functional pointer type declaration for USB set configuration request callback handler */
extern const S_USBD_INFO_T *g_USBD_sInfo;
extern VENDOR_REQ g_USBD_pfnVendorRequest;
extern CLASS_REQ g_USBD_pfnClassRequest;
extern SET_INTERFACE_REQ g_USBD_pfnSetInterface;
extern SET_CONFIG_CB g_USBD_pfnSetConfigCallback;
extern uint32_t g_USBD_u32EpStallLock;
/*--------------------------------------------------------------------*/
void USBD_Open(const S_USBD_INFO_T *param, CLASS_REQ pfnClassReq, SET_INTERFACE_REQ pfnSetInterface);
void USBD_Start(void);
void USBD_GetSetupPacket(uint8_t *buf);
void USBD_ProcessSetupPacket(void);
void USBD_GetDescriptor(void);
void USBD_StandardRequest(void);
void USBD_PrepareCtrlIn(uint8_t pu8Buf[], uint32_t u32Size);
void USBD_CtrlIn(void);
void USBD_PrepareCtrlOut(uint8_t *pu8Buf, uint32_t u32Size);
void USBD_CtrlOut(void);
void USBD_SwReset(void);
void USBD_SetVendorRequest(VENDOR_REQ pfnVendorReq);
void USBD_SetConfigCallback(SET_CONFIG_CB pfnSetConfigCallback);
void USBD_LockEpStall(uint32_t u32EpBitmap);
/**@}*/ /* end of group USBD_EXPORTED_FUNCTIONS */
/**@}*/ /* end of group USBD_Driver */
/**@}*/ /* end of group Standard_Driver */
#ifdef __cplusplus
}
#endif
#endif /* __NU_USBD_H__ */

View File

@ -0,0 +1,318 @@
/**************************************************************************//**
* @file nu_usci_i2c.h
* @version V3.0
* $Revision: 1 $
* $Date: 16/07/07 7:50p $
* @brief M2355 series USCI I2C(UI2C) driver header file
*
* @copyright SPDX-License-Identifier: Apache-2.0
* @copyright Copyright (C) 2020 Nuvoton Technology Corp. All rights reserved.
******************************************************************************/
#ifndef __NU_USCI_I2C_H__
#define __NU_USCI_I2C_H__
#ifdef __cplusplus
extern "C"
{
#endif
/** @addtogroup Standard_Driver Standard Driver
@{
*/
/** @addtogroup USCI_I2C_Driver USCI_I2C Driver
@{
*/
/** @addtogroup USCI_I2C_EXPORTED_CONSTANTS USCI_I2C Exported Constants
@{
*/
/*---------------------------------------------------------------------------------------------------------*/
/* USCI_I2C master event definitions */
/*---------------------------------------------------------------------------------------------------------*/
enum UI2C_MASTER_EVENT
{
MASTER_SEND_ADDRESS = 10u, /*!< Master send address to Slave */
MASTER_SEND_H_WR_ADDRESS, /*!< Master send High address to Slave */
MASTER_SEND_H_RD_ADDRESS, /*!< Master send address to Slave (Read ADDR) */
MASTER_SEND_L_ADDRESS, /*!< Master send Low address to Slave */
MASTER_SEND_DATA, /*!< Master Send Data to Slave */
MASTER_SEND_REPEAT_START, /*!< Master send repeat start to Slave */
MASTER_READ_DATA, /*!< Master Get Data from Slave */
MASTER_STOP, /*!< Master send stop to Slave */
MASTER_SEND_START /*!< Master send start to Slave */
};
/*---------------------------------------------------------------------------------------------------------*/
/* USCI_I2C slave event definitions */
/*---------------------------------------------------------------------------------------------------------*/
enum UI2C_SLAVE_EVENT
{
SLAVE_ADDRESS_ACK = 100u, /*!< Slave send address ACK */
SLAVE_H_WR_ADDRESS_ACK, /*!< Slave send High address ACK */
SLAVE_L_WR_ADDRESS_ACK, /*!< Slave send Low address ACK */
SLAVE_GET_DATA, /*!< Slave Get Data from Master (Write CMD) */
SLAVE_SEND_DATA, /*!< Slave Send Data to Master (Read CMD) */
SLAVE_H_RD_ADDRESS_ACK, /*!< Slave send High address ACK */
SLAVE_L_RD_ADDRESS_ACK /*!< Slave send Low address ACK */
};
/*---------------------------------------------------------------------------------------------------------*/
/* USCI_CTL constant definitions. */
/*---------------------------------------------------------------------------------------------------------*/
#define UI2C_CTL_PTRG (0x20U) /*!< USCI_CTL setting for I2C control bits. It would set PTRG bit */
#define UI2C_CTL_STA (0x08U) /*!< USCI_CTL setting for I2C control bits. It would set STA bit */
#define UI2C_CTL_STO (0x04U) /*!< USCI_CTL setting for I2C control bits. It would set STO bit */
#define UI2C_CTL_AA (0x02U) /*!< USCI_CTL setting for I2C control bits. It would set AA bit */
/*---------------------------------------------------------------------------------------------------------*/
/* USCI_I2C GCMode constant definitions. */
/*---------------------------------------------------------------------------------------------------------*/
#define UI2C_GCMODE_ENABLE (1U) /*!< Enable USCI_I2C GC Mode */
#define UI2C_GCMODE_DISABLE (0U) /*!< Disable USCI_I2C GC Mode */
/*---------------------------------------------------------------------------------------------------------*/
/* USCI_I2C Wakeup Mode constant definitions. */
/*---------------------------------------------------------------------------------------------------------*/
#define UI2C_DATA_TOGGLE_WK (0x0U << UI2C_WKCTL_WKADDREN_Pos) /*!< Wakeup according data toggle */
#define UI2C_ADDR_MATCH_WK (0x1U << UI2C_WKCTL_WKADDREN_Pos) /*!< Wakeup according address match */
/*---------------------------------------------------------------------------------------------------------*/
/* USCI_I2C interrupt mask definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define UI2C_TO_INT_MASK (0x001U) /*!< Time-out interrupt mask */
#define UI2C_STAR_INT_MASK (0x002U) /*!< Start condition received interrupt mask */
#define UI2C_STOR_INT_MASK (0x004U) /*!< Stop condition received interrupt mask */
#define UI2C_NACK_INT_MASK (0x008U) /*!< Non-acknowledge interrupt mask */
#define UI2C_ARBLO_INT_MASK (0x010U) /*!< Arbitration lost interrupt mask */
#define UI2C_ERR_INT_MASK (0x020U) /*!< Error interrupt mask */
#define UI2C_ACK_INT_MASK (0x040U) /*!< Acknowledge interrupt mask */
/**@}*/ /* end of group USCI_I2C_EXPORTED_CONSTANTS */
/** @addtogroup USCI_I2C_EXPORTED_FUNCTIONS USCI_I2C Exported Functions
@{
*/
/**
* @brief This macro sets the USCI_I2C protocol control register at one time
*
* @param[in] ui2c The pointer of the specified USCI_I2C module.
* @param[in] u8Ctrl Set the register value of USCI_I2C control register.
*
* @return None
*
* @details Set UI2C_PROTCTL register to control USCI_I2C bus conditions of START, STOP, PTRG, ACK.
*/
#define UI2C_SET_CONTROL_REG(ui2c, u8Ctrl) ((ui2c)->PROTCTL = ((ui2c)->PROTCTL & ~0x2EU) | (u8Ctrl))
/**
* @brief This macro only set START bit to protocol control register of USCI_I2C module.
*
* @param[in] ui2c The pointer of the specified USCI_I2C module.
*
* @return None
*
* @details Set the USCI_I2C bus START condition in UI2C_PROTCTL register.
*/
#define UI2C_START(ui2c) ((ui2c)->PROTCTL = ((ui2c)->PROTCTL & ~UI2C_PROTCTL_PTRG_Msk) | UI2C_PROTCTL_STA_Msk)
/**
* @brief This macro only set STOP bit to the control register of USCI_I2C module
*
* @param[in] ui2c The pointer of the specified USCI_I2C module.
*
* @return None
*
* @details Set the USCI_I2C bus STOP condition in UI2C_PROTCTL register.
*/
#define UI2C_STOP(ui2c) ((ui2c)->PROTCTL = ((ui2c)->PROTCTL & ~0x2E) | (UI2C_PROTCTL_PTRG_Msk | UI2C_PROTCTL_STO_Msk))
/**
* @brief This macro returns the data stored in data register of USCI_I2C module
*
* @param[in] ui2c The pointer of the specified USCI_I2C module.
*
* @return Data
*
* @details Read a byte data value of UI2C_RXDAT register from USCI_I2C bus
*/
#define UI2C_GET_DATA(ui2c) ((ui2c)->RXDAT)
/**
* @brief This macro writes the data to data register of USCI_I2C module
*
* @param[in] ui2c The pointer of the specified USCI_I2C module.
* @param[in] u8Data The data which will be written to data register of USCI_I2C module.
*
* @return None
*
* @details Write a byte data value of UI2C_TXDAT register, then sends address or data to USCI I2C bus
*/
#define UI2C_SET_DATA(ui2c, u8Data) ((ui2c)->TXDAT = (u8Data))
/**
* @brief This macro returns time-out flag
*
* @param[in] ui2c The pointer of the specified USCI_I2C module.
*
* @retval 0 USCI_I2C bus time-out is not happened
* @retval 1 USCI_I2C bus time-out is happened
*
* @details USCI_I2C bus occurs time-out event, the time-out flag will be set. If not occurs time-out event, this bit is cleared.
*/
#define UI2C_GET_TIMEOUT_FLAG(ui2c) (((ui2c)->PROTSTS & UI2C_PROTSTS_TOIF_Msk) == UI2C_PROTSTS_TOIF_Msk ? 1:0)
/**
* @brief This macro returns wake-up flag
*
* @param[in] ui2c The pointer of the specified USCI_I2C module.
*
* @retval 0 Chip is not woken-up from power-down mode
* @retval 1 Chip is woken-up from power-down mode
*
* @details USCI_I2C controller wake-up flag will be set when USCI_I2C bus occurs wake-up from deep-sleep.
*/
#define UI2C_GET_WAKEUP_FLAG(ui2c) (((ui2c)->WKSTS & UI2C_WKSTS_WKF_Msk) == UI2C_WKSTS_WKF_Msk ? 1:0)
/**
* @brief This macro is used to clear USCI_I2C wake-up flag
*
* @param[in] ui2c The pointer of the specified USCI_I2C module.
*
* @return None
*
* @details If USCI_I2C wake-up flag is set, use this macro to clear it.
*/
#define UI2C_CLR_WAKEUP_FLAG(ui2c) ((ui2c)->WKSTS = UI2C_WKSTS_WKF_Msk)
/**
* @brief This macro disables the USCI_I2C 10-bit address mode
*
* @param[in] ui2c The pointer of the specified USCI_I2C module.
*
* @return None
*
* @details The UI2C_I2C is 7-bit address mode, when disable USCI_I2C 10-bit address match function.
*/
#define UI2C_DISABLE_10BIT_ADDR_MODE(ui2c) ((ui2c)->PROTCTL &= ~(UI2C_PROTCTL_ADDR10EN_Msk))
/**
* @brief This macro enables the 10-bit address mode
*
* @param[in] ui2c The pointer of the specified USCI_I2C module.
*
* @return None
*
* @details To enable USCI_I2C 10-bit address match function.
*/
#define UI2C_ENABLE_10BIT_ADDR_MODE(ui2c) ((ui2c)->PROTCTL |= UI2C_PROTCTL_ADDR10EN_Msk)
/**
* @brief This macro gets USCI_I2C protocol interrupt flag or bus status
*
* @param[in] ui2c The pointer of the specified USCI_I2C module.
*
* @return A word data of USCI_I2C_PROTSTS register
*
* @details Read a word data of USCI_I2C PROTSTS register to get USCI_I2C bus Interrupt flags or status.
*/
#define UI2C_GET_PROT_STATUS(ui2c) ((ui2c)->PROTSTS)
/**
* @brief This macro clears specified protocol interrupt flag
* @param[in] ui2c The pointer of the specified USCI_I2C module.
* @param[in] u32IntTypeFlag Interrupt Type Flag, should be
* - \ref UI2C_PROTSTS_ACKIF_Msk
* - \ref UI2C_PROTSTS_ERRIF_Msk
* - \ref UI2C_PROTSTS_ARBLOIF_Msk
* - \ref UI2C_PROTSTS_NACKIF_Msk
* - \ref UI2C_PROTSTS_STORIF_Msk
* - \ref UI2C_PROTSTS_STARIF_Msk
* - \ref UI2C_PROTSTS_TOIF_Msk
* @return None
*
* @details To clear interrupt flag when USCI_I2C occurs interrupt and set interrupt flag.
*/
#define UI2C_CLR_PROT_INT_FLAG(ui2c,u32IntTypeFlag) ((ui2c)->PROTSTS = (u32IntTypeFlag))
/**
* @brief This macro enables specified protocol interrupt
* @param[in] ui2c The pointer of the specified USCI_I2C module.
* @param[in] u32IntSel Interrupt Type, should be
* - \ref UI2C_PROTIEN_ACKIEN_Msk
* - \ref UI2C_PROTIEN_ERRIEN_Msk
* - \ref UI2C_PROTIEN_ARBLOIEN_Msk
* - \ref UI2C_PROTIEN_NACKIEN_Msk
* - \ref UI2C_PROTIEN_STORIEN_Msk
* - \ref UI2C_PROTIEN_STARIEN_Msk
* - \ref UI2C_PROTIEN_TOIEN_Msk
* @return None
*
* @details Set specified USCI_I2C protocol interrupt bits to enable interrupt function.
*/
#define UI2C_ENABLE_PROT_INT(ui2c, u32IntSel) ((ui2c)->PROTIEN |= (u32IntSel))
/**
* @brief This macro disables specified protocol interrupt
* @param[in] ui2c The pointer of the specified USCI_I2C module.
* @param[in] u32IntSel Interrupt Type, should be
* - \ref UI2C_PROTIEN_ACKIEN_Msk
* - \ref UI2C_PROTIEN_ERRIEN_Msk
* - \ref UI2C_PROTIEN_ARBLOIEN_Msk
* - \ref UI2C_PROTIEN_NACKIEN_Msk
* - \ref UI2C_PROTIEN_STORIEN_Msk
* - \ref UI2C_PROTIEN_STARIEN_Msk
* - \ref UI2C_PROTIEN_TOIEN_Msk
* @return None
*
* @details Clear specified USCI_I2C protocol interrupt bits to disable interrupt funtion.
*/
#define UI2C_DISABLE_PROT_INT(ui2c, u32IntSel) ((ui2c)->PROTIEN &= ~ (u32IntSel))
uint32_t UI2C_Open(UI2C_T *ui2c, uint32_t u32BusClock);
void UI2C_Close(UI2C_T *ui2c);
void UI2C_ClearTimeoutFlag(UI2C_T *ui2c);
void UI2C_Trigger(UI2C_T *ui2c, uint8_t u8Start, uint8_t u8Stop, uint8_t u8Ptrg, uint8_t u8Ack);
void UI2C_DisableInt(UI2C_T *ui2c, uint32_t u32Mask);
void UI2C_EnableInt(UI2C_T *ui2c, uint32_t u32Mask);
uint32_t UI2C_GetBusClockFreq(UI2C_T *ui2c);
uint32_t UI2C_SetBusClockFreq(UI2C_T *ui2c, uint32_t u32BusClock);
uint32_t UI2C_GetIntFlag(UI2C_T *ui2c, uint32_t u32Mask);
void UI2C_ClearIntFlag(UI2C_T* ui2c, uint32_t u32Mask);
uint32_t UI2C_GetData(UI2C_T *ui2c);
void UI2C_SetData(UI2C_T *ui2c, uint8_t u8Data);
void UI2C_SetSlaveAddr(UI2C_T *ui2c, uint8_t u8SlaveNo, uint16_t u16SlaveAddr, uint8_t u8GCMode);
void UI2C_SetSlaveAddrMask(UI2C_T *ui2c, uint8_t u8SlaveNo, uint16_t u16SlaveAddrMask);
void UI2C_EnableTimeout(UI2C_T *ui2c, uint32_t u32TimeoutCnt);
void UI2C_DisableTimeout(UI2C_T *ui2c);
void UI2C_EnableWakeup(UI2C_T *ui2c, uint8_t u8WakeupMode);
void UI2C_DisableWakeup(UI2C_T *ui2c);
uint8_t UI2C_WriteByte(UI2C_T *ui2c, uint8_t u8SlaveAddr, uint8_t data);
uint32_t UI2C_WriteMultiBytes(UI2C_T *ui2c, uint8_t u8SlaveAddr, uint8_t data[], uint32_t u32wLen);
uint8_t UI2C_WriteByteOneReg(UI2C_T *ui2c, uint8_t u8SlaveAddr, uint8_t u8DataAddr, uint8_t data);
uint32_t UI2C_WriteMultiBytesOneReg(UI2C_T *ui2c, uint8_t u8SlaveAddr, uint8_t u8DataAddr, uint8_t data[], uint32_t u32wLen);
uint8_t UI2C_WriteByteTwoRegs(UI2C_T *ui2c, uint8_t u8SlaveAddr, uint16_t u16DataAddr, uint8_t data);
uint32_t UI2C_WriteMultiBytesTwoRegs(UI2C_T *ui2c, uint8_t u8SlaveAddr, uint16_t u16DataAddr, uint8_t data[], uint32_t u32wLen);
uint8_t UI2C_ReadByte(UI2C_T *ui2c, uint8_t u8SlaveAddr);
uint32_t UI2C_ReadMultiBytes(UI2C_T *ui2c, uint8_t u8SlaveAddr, uint8_t rdata[], uint32_t u32rLen);
uint8_t UI2C_ReadByteOneReg(UI2C_T *ui2c, uint8_t u8SlaveAddr, uint8_t u8DataAddr);
uint32_t UI2C_ReadMultiBytesOneReg(UI2C_T *ui2c, uint8_t u8SlaveAddr, uint8_t u8DataAddr, uint8_t rdata[], uint32_t u32rLen);
uint8_t UI2C_ReadByteTwoRegs(UI2C_T *ui2c, uint8_t u8SlaveAddr, uint16_t u16DataAddr);
uint32_t UI2C_ReadMultiBytesTwoRegs(UI2C_T *ui2c, uint8_t u8SlaveAddr, uint16_t u16DataAddr, uint8_t rdata[], uint32_t u32rLen);
/**@}*/ /* end of group USCI_I2C_EXPORTED_FUNCTIONS */
/**@}*/ /* end of group USCI_I2C_Driver */
/**@}*/ /* end of group Standard_Driver */
#ifdef __cplusplus
}
#endif
#endif

View File

@ -0,0 +1,420 @@
/****************************************************************************//**
* @file nu_usci_spi.h
* @version V3.00
* @brief M2354 series USCI_SPI driver header file
*
* @copyright SPDX-License-Identifier: Apache-2.0
* @copyright Copyright (C) 2020 Nuvoton Technology Corp. All rights reserved.
*****************************************************************************/
#ifndef __NU_USCI_SPI_H__
#define __NU_USCI_SPI_H__
#ifdef __cplusplus
extern "C"
{
#endif
/** @addtogroup Standard_Driver Standard Driver
@{
*/
/** @addtogroup USCI_SPI_Driver USCI_SPI Driver
@{
*/
/** @addtogroup USCI_SPI_EXPORTED_CONSTANTS USCI_SPI Exported Constants
@{
*/
#define USPI_MODE_0 (0x0UL << USPI_PROTCTL_SCLKMODE_Pos) /*!< SCLK idle low; data transmit with falling edge and receive with rising edge */
#define USPI_MODE_1 (0x1UL << USPI_PROTCTL_SCLKMODE_Pos) /*!< SCLK idle low; data transmit with rising edge and receive with falling edge */
#define USPI_MODE_2 (0x2UL << USPI_PROTCTL_SCLKMODE_Pos) /*!< SCLK idle high; data transmit with rising edge and receive with falling edge */
#define USPI_MODE_3 (0x3UL << USPI_PROTCTL_SCLKMODE_Pos) /*!< SCLK idle high; data transmit with falling edge and receive with rising edge */
#define USPI_SLAVE (USPI_PROTCTL_SLAVE_Msk) /*!< Set as slave */
#define USPI_MASTER (0x0UL) /*!< Set as master */
#define USPI_SS (USPI_PROTCTL_SS_Msk) /*!< Set SS */
#define USPI_SS_ACTIVE_HIGH (0x0UL) /*!< SS active high */
#define USPI_SS_ACTIVE_LOW (USPI_LINECTL_CTLOINV_Msk) /*!< SS active low */
/* USCI_SPI Interrupt Mask */
#define USPI_SSINACT_INT_MASK (0x001UL) /*!< Slave Slave Inactive interrupt mask */
#define USPI_SSACT_INT_MASK (0x002UL) /*!< Slave Slave Active interrupt mask */
#define USPI_SLVTO_INT_MASK (0x004UL) /*!< Slave Mode Time-out interrupt mask */
#define USPI_SLVBE_INT_MASK (0x008UL) /*!< Slave Mode Bit Count Error interrupt mask */
#define USPI_TXUDR_INT_MASK (0x010UL) /*!< Slave Transmit Under Run interrupt mask */
#define USPI_RXOV_INT_MASK (0x020UL) /*!< Receive Buffer Overrun interrupt mask */
#define USPI_TXST_INT_MASK (0x040UL) /*!< Transmit Start interrupt mask */
#define USPI_TXEND_INT_MASK (0x080UL) /*!< Transmit End interrupt mask */
#define USPI_RXST_INT_MASK (0x100UL) /*!< Receive Start interrupt mask */
#define USPI_RXEND_INT_MASK (0x200UL) /*!< Receive End interrupt mask */
/* USCI_SPI Status Mask */
#define USPI_BUSY_MASK (0x01UL) /*!< Busy status mask */
#define USPI_RX_EMPTY_MASK (0x02UL) /*!< RX empty status mask */
#define USPI_RX_FULL_MASK (0x04UL) /*!< RX full status mask */
#define USPI_TX_EMPTY_MASK (0x08UL) /*!< TX empty status mask */
#define USPI_TX_FULL_MASK (0x10UL) /*!< TX full status mask */
#define USPI_SSLINE_STS_MASK (0x20UL) /*!< USCI_SPI_SS line status mask */
/**@}*/ /* end of group USCI_SPI_EXPORTED_CONSTANTS */
/** @addtogroup USCI_SPI_EXPORTED_FUNCTIONS USCI_SPI Exported Functions
@{
*/
/**
* @brief Disable slave 3-wire mode.
* @param[in] uspi The pointer of the specified USCI_SPI module.
* @return None
* \hideinitializer
*/
#define USPI_DISABLE_3WIRE_MODE(uspi) ( (uspi)->PROTCTL &= ~USPI_PROTCTL_SLV3WIRE_Msk )
/**
* @brief Enable slave 3-wire mode.
* @param[in] uspi The pointer of the specified USCI_SPI module.
* @return None
* \hideinitializer
*/
#define USPI_ENABLE_3WIRE_MODE(uspi) ( (uspi)->PROTCTL |= USPI_PROTCTL_SLV3WIRE_Msk )
/**
* @brief Get the Rx buffer empty flag.
* @param[in] uspi The pointer of the specified USCI_SPI module.
* @return Rx buffer flag
* @retval 0: Rx buffer is not empty
* @retval 1: Rx buffer is empty
* \hideinitializer
*/
#define USPI_GET_RX_EMPTY_FLAG(uspi) ( ((uspi)->BUFSTS & USPI_BUFSTS_RXEMPTY_Msk) == USPI_BUFSTS_RXEMPTY_Msk ? 1:0 )
/**
* @brief Get the Tx buffer empty flag.
* @param[in] uspi The pointer of the specified USCI_SPI module.
* @return Tx buffer flag
* @retval 0: Tx buffer is not empty
* @retval 1: Tx buffer is empty
* \hideinitializer
*/
#define USPI_GET_TX_EMPTY_FLAG(uspi) ( ((uspi)->BUFSTS & USPI_BUFSTS_TXEMPTY_Msk) == USPI_BUFSTS_TXEMPTY_Msk ? 1:0 )
/**
* @brief Get the Tx buffer full flag.
* @param[in] uspi The pointer of the specified USCI_SPI module.
* @return Tx buffer flag
* @retval 0: Tx buffer is not full
* @retval 1: Tx buffer is full
* \hideinitializer
*/
#define USPI_GET_TX_FULL_FLAG(uspi) ( ((uspi)->BUFSTS & USPI_BUFSTS_TXFULL_Msk) == USPI_BUFSTS_TXFULL_Msk ? 1:0 )
/**
* @brief Get the datum read from RX register.
* @param[in] uspi The pointer of the specified USCI_SPI module.
* @return data in Rx register
* \hideinitializer
*/
#define USPI_READ_RX(uspi) ( (uspi)->RXDAT )
/**
* @brief Write datum to TX register.
* @param[in] uspi The pointer of the specified USCI_SPI module.
* @param[in] u32TxData The datum which user attempt to transfer through USCI_SPI bus.
* @return None
* \hideinitializer
*/
#define USPI_WRITE_TX(uspi, u32TxData) ( (uspi)->TXDAT = (u32TxData) )
/**
* @brief Set USCI_SPI_SS pin to high state.
* @param[in] uspi The pointer of the specified USCI_SPI module.
* @return None.
* @details Disable automatic slave selection function and set USCI_SPI_SS pin to high state. Only available in Master mode.
* \hideinitializer
*/
#define USPI_SET_SS_HIGH(uspi) \
do{ \
(uspi)->LINECTL &= ~USPI_LINECTL_CTLOINV_Msk; \
(uspi)->PROTCTL = (((uspi)->PROTCTL & ~USPI_PROTCTL_AUTOSS_Msk) | USPI_PROTCTL_SS_Msk); \
}while(0)
/**
* @brief Set USCI_SPI_SS pin to low state.
* @param[in] uspi The pointer of the specified USCI_SPI module.
* @return None.
* @details Disable automatic slave selection function and set USCI_SPI_SS pin to low state. Only available in Master mode.
* \hideinitializer
*/
#define USPI_SET_SS_LOW(uspi) \
do{ \
(uspi)->LINECTL |= USPI_LINECTL_CTLOINV_Msk; \
(uspi)->PROTCTL = (((uspi)->PROTCTL & ~USPI_PROTCTL_AUTOSS_Msk) | USPI_PROTCTL_SS_Msk); \
}while(0)
/**
* @brief Set the length of suspend interval.
* @param[in] uspi The pointer of the specified USCI_SPI module.
* @param[in] u32SuspCycle Decide the length of suspend interval.
* @return None
* \hideinitializer
*/
#define USPI_SET_SUSPEND_CYCLE(uspi, u32SuspCycle) ( (uspi)->PROTCTL = ((uspi)->PROTCTL & ~USPI_PROTCTL_SUSPITV_Msk) | ((u32SuspCycle) << USPI_PROTCTL_SUSPITV_Pos) )
/**
* @brief Set the USCI_SPI transfer sequence with LSB first.
* @param[in] uspi The pointer of the specified USCI_SPI module.
* @return None
* \hideinitializer
*/
#define USPI_SET_LSB_FIRST(uspi) ( (uspi)->LINECTL |= USPI_LINECTL_LSB_Msk )
/**
* @brief Set the USCI_SPI transfer sequence with MSB first.
* @param[in] uspi The pointer of the specified USCI_SPI module.
* @return None
* \hideinitializer
*/
#define USPI_SET_MSB_FIRST(uspi) ( (uspi)->LINECTL &= ~USPI_LINECTL_LSB_Msk )
/**
* @brief Set the data width of a USCI_SPI transaction.
* @param[in] uspi The pointer of the specified USCI_SPI module.
* @param[in] u32Width The data width
* @return None
* \hideinitializer
*/
#define USPI_SET_DATA_WIDTH(uspi, u32Width) \
do{ \
if((u32Width) == 16ul){ \
(uspi)->LINECTL = ((uspi)->LINECTL & ~USPI_LINECTL_DWIDTH_Msk) | (0 << USPI_LINECTL_DWIDTH_Pos); \
}else { \
(uspi)->LINECTL = ((uspi)->LINECTL & ~USPI_LINECTL_DWIDTH_Msk) | ((u32Width) << USPI_LINECTL_DWIDTH_Pos); \
} \
}while(0)
/**
* @brief Get the USCI_SPI busy state.
* @param[in] uspi The pointer of the specified USCI_SPI module.
* @return USCI_SPI busy status
* @retval 0: USCI_SPI module is not busy
* @retval 1: USCI_SPI module is busy
* \hideinitializer
*/
#define USPI_IS_BUSY(uspi) ( ((uspi)->PROTSTS & USPI_PROTSTS_BUSY_Msk) == USPI_PROTSTS_BUSY_Msk ? 1:0 )
/**
* @brief Get the USCI_SPI wakeup flag.
* @param[in] uspi The pointer of the specified USCI_SPI module.
* @return Wakeup status.
* @retval 0 Flag is not set.
* @retval 1 Flag is set.
* \hideinitializer
*/
#define USPI_GET_WAKEUP_FLAG(uspi) ( ((uspi)->WKSTS & USPI_WKSTS_WKF_Msk) == USPI_WKSTS_WKF_Msk ? 1:0 )
/**
* @brief Clear the USCI_SPI wakeup flag.
* @param[in] uspi The pointer of the specified USCI_SPI module.
* @return None
* \hideinitializer
*/
#define USPI_CLR_WAKEUP_FLAG(uspi) ( (uspi)->WKSTS |= USPI_WKSTS_WKF_Msk )
/**
* @brief Get protocol interrupt flag/status.
* @param[in] uspi The pointer of the specified USCI_SPI module.
* @return The interrupt flag/status of protocol status register.
* \hideinitializer
*/
#define USPI_GET_PROT_STATUS(uspi) ( (uspi)->PROTSTS )
/**
* @brief Clear specified protocol interrupt flag.
* @param[in] uspi The pointer of the specified USCI_SPI module.
* @param[in] u32IntTypeFlag Interrupt Type Flag, should be
* - \ref USPI_PROTSTS_SSACTIF_Msk
* - \ref USPI_PROTSTS_SSINAIF_Msk
* - \ref USPI_PROTSTS_SLVBEIF_Msk
* - \ref USPI_PROTSTS_SLVTOIF_Msk
* - \ref USPI_PROTSTS_RXENDIF_Msk
* - \ref USPI_PROTSTS_RXSTIF_Msk
* - \ref USPI_PROTSTS_TXENDIF_Msk
* - \ref USPI_PROTSTS_TXSTIF_Msk
* @return None
* \hideinitializer
*/
#define USPI_CLR_PROT_INT_FLAG(uspi, u32IntTypeFlag) ( (uspi)->PROTSTS = (u32IntTypeFlag) )
/**
* @brief Get buffer interrupt flag/status.
* @param[in] uspi The pointer of the specified USCI_SPI module.
* @return The interrupt flag/status of buffer status register.
* \hideinitializer
*/
#define USPI_GET_BUF_STATUS(uspi) ( (uspi)->BUFSTS )
/**
* @brief Clear specified buffer interrupt flag.
* @param[in] uspi The pointer of the specified USCI_SPI module.
* @param[in] u32IntTypeFlag Interrupt Type Flag, should be
* - \ref USPI_BUFSTS_TXUDRIF_Msk
* - \ref USPI_BUFSTS_RXOVIF_Msk
* @return None
* \hideinitializer
*/
#define USPI_CLR_BUF_INT_FLAG(uspi, u32IntTypeFlag) ( (uspi)->BUFSTS = (u32IntTypeFlag) )
/**
* @brief Enable specified protocol interrupt.
* @param[in] uspi The pointer of the specified USCI_SPI module.
* @param[in] u32IntSel Interrupt Type, should be
* - \ref USPI_PROTIEN_SLVBEIEN_Msk
* - \ref USPI_PROTIEN_SLVTOIEN_Msk
* - \ref USPI_PROTIEN_SSACTIEN_Msk
* - \ref USPI_PROTIEN_SSINAIEN_Msk
* @return None
* \hideinitializer
*/
#define USPI_ENABLE_PROT_INT(uspi, u32IntSel) ( (uspi)->PROTIEN |= (u32IntSel) )
/**
* @brief Disable specified protocol interrupt.
* @param[in] uspi The pointer of the specified USCI_SPI module.
* @param[in] u32IntSel Interrupt Type, should be
* - \ref USPI_PROTIEN_SLVBEIEN_Msk
* - \ref USPI_PROTIEN_SLVTOIEN_Msk
* - \ref USPI_PROTIEN_SSACTIEN_Msk
* - \ref USPI_PROTIEN_SSINAIEN_Msk
* @return None
* \hideinitializer
*/
#define USPI_DISABLE_PROT_INT(uspi, u32IntSel) ( (uspi)->PROTIEN &= ~ (u32IntSel) )
/**
* @brief Enable specified buffer interrupt.
* @param[in] uspi The pointer of the specified USCI_SPI module.
* @param[in] u32IntSel Interrupt Type, should be
* - \ref USPI_BUFCTL_RXOVIEN_Msk
* - \ref USPI_BUFCTL_TXUDRIEN_Msk
* @return None
* \hideinitializer
*/
#define USPI_ENABLE_BUF_INT(uspi, u32IntSel) ( (uspi)->BUFCTL |= (u32IntSel) )
/**
* @brief Disable specified buffer interrupt.
* @param[in] uspi The pointer of the specified USCI_SPI module.
* @param[in] u32IntSel Interrupt Type, should be
* - \ref USPI_BUFCTL_RXOVIEN_Msk
* - \ref USPI_BUFCTL_TXUDRIEN_Msk
* @return None
* \hideinitializer
*/
#define USPI_DISABLE_BUF_INT(uspi, u32IntSel) ( (uspi)->BUFCTL &= ~ (u32IntSel) )
/**
* @brief Enable specified transfer interrupt.
* @param[in] uspi The pointer of the specified USCI_SPI module.
* @param[in] u32IntSel Interrupt Type, should be
* - \ref USPI_INTEN_RXENDIEN_Msk
* - \ref USPI_INTEN_RXSTIEN_Msk
* - \ref USPI_INTEN_TXENDIEN_Msk
* - \ref USPI_INTEN_TXSTIEN_Msk
* @return None
* \hideinitializer
*/
#define USPI_ENABLE_TRANS_INT(uspi, u32IntSel) ( (uspi)->INTEN |= (u32IntSel) )
/**
* @brief Disable specified transfer interrupt.
* @param[in] uspi The pointer of the specified USCI_SPI module.
* @param[in] u32IntSel Interrupt Type, should be
* - \ref USPI_INTEN_RXENDIEN_Msk
* - \ref USPI_INTEN_RXSTIEN_Msk
* - \ref USPI_INTEN_TXENDIEN_Msk
* - \ref USPI_INTEN_TXSTIEN_Msk
* @return None
* \hideinitializer
*/
#define USPI_DISABLE_TRANS_INT(uspi, u32IntSel) ( (uspi)->INTEN &= ~ (u32IntSel) )
/**
* @brief Trigger RX PDMA function.
* @param[in] uspi The pointer of the specified USCI_SPI module.
* @return None.
* @details Set RXPDMAEN bit of USPI_PDMACTL register to enable RX PDMA transfer function.
*/
#define USPI_TRIGGER_RX_PDMA(uspi) ( (uspi)->PDMACTL |= USPI_PDMACTL_RXPDMAEN_Msk | USPI_PDMACTL_PDMAEN_Msk )
/**
* @brief Trigger TX PDMA function.
* @param[in] uspi The pointer of the specified USCI_SPI module.
* @return None.
* @details Set TXPDMAEN bit of USPI_PDMACTL register to enable TX PDMA transfer function.
*/
#define USPI_TRIGGER_TX_PDMA(uspi) ( (uspi)->PDMACTL |= USPI_PDMACTL_TXPDMAEN_Msk | USPI_PDMACTL_PDMAEN_Msk )
/**
* @brief Trigger TX and RX PDMA function.
* @param[in] uspi The pointer of the specified USCI_SPI module.
* @return None.
* @details Set TXPDMAEN bit and RXPDMAEN bit of USPI_PDMACTL register to enable TX and RX PDMA transfer function.
*/
#define USPI_TRIGGER_TX_RX_PDMA(uspi) ( (uspi)->PDMACTL |= USPI_PDMACTL_TXPDMAEN_Msk | USPI_PDMACTL_RXPDMAEN_Msk | USPI_PDMACTL_PDMAEN_Msk )
/**
* @brief Disable RX PDMA transfer.
* @param[in] uspi The pointer of the specified USCI_SPI module.
* @return None.
* @details Clear RXPDMAEN bit of USPI_PDMACTL register to disable RX PDMA transfer function.
*/
#define USPI_DISABLE_RX_PDMA(uspi) ( (uspi)->PDMACTL &= ~USPI_PDMACTL_RXPDMAEN_Msk )
/**
* @brief Disable TX PDMA transfer.
* @param[in] uspi The pointer of the specified USCI_SPI module.
* @return None.
* @details Clear TXPDMAEN bit of USPI_PDMACTL register to disable TX PDMA transfer function.
*/
#define USPI_DISABLE_TX_PDMA(uspi) ( (uspi)->PDMACTL &= ~USPI_PDMACTL_TXPDMAEN_Msk )
/**
* @brief Disable TX and RX PDMA transfer.
* @param[in] uspi The pointer of the specified USCI_SPI module.
* @return None.
* @details Clear TXPDMAEN bit and RXPDMAEN bit of USPI_PDMACTL register to disable TX and RX PDMA transfer function.
*/
#define USPI_DISABLE_TX_RX_PDMA(uspi) ( (uspi)->PDMACTL &= ~(USPI_PDMACTL_TXPDMAEN_Msk | USPI_PDMACTL_RXPDMAEN_Msk) )
uint32_t USPI_Open(USPI_T *uspi, uint32_t u32MasterSlave, uint32_t u32SPIMode, uint32_t u32DataWidth, uint32_t u32BusClock);
void USPI_Close(USPI_T *uspi);
void USPI_ClearRxBuf(USPI_T *uspi);
void USPI_ClearTxBuf(USPI_T *uspi);
void USPI_DisableAutoSS(USPI_T *uspi);
void USPI_EnableAutoSS(USPI_T *uspi, uint32_t u32SSPinMask, uint32_t u32ActiveLevel);
uint32_t USPI_SetBusClock(USPI_T *uspi, uint32_t u32BusClock);
uint32_t USPI_GetBusClock(USPI_T *uspi);
void USPI_EnableInt(USPI_T *uspi, uint32_t u32Mask);
void USPI_DisableInt(USPI_T *uspi, uint32_t u32Mask);
uint32_t USPI_GetIntFlag(USPI_T *uspi, uint32_t u32Mask);
void USPI_ClearIntFlag(USPI_T *uspi, uint32_t u32Mask);
uint32_t USPI_GetStatus(USPI_T *uspi, uint32_t u32Mask);
void USPI_EnableWakeup(USPI_T *uspi);
void USPI_DisableWakeup(USPI_T *uspi);
/**@}*/ /* end of group USCI_SPI_EXPORTED_FUNCTIONS */
/**@}*/ /* end of group USCI_SPI_Driver */
/**@}*/ /* end of group Standard_Driver */
#ifdef __cplusplus
}
#endif
#endif /* __NU_USCI_SPI_H__ */

View File

@ -0,0 +1,445 @@
/******************************************************************************
* @file nu_usci_uart.h
* @version V3.00
* @brief M2354 series USCI UART (UUART) driver header file
*
* @copyright SPDX-License-Identifier: Apache-2.0
* @copyright Copyright (C) 2020 Nuvoton Technology Corp. All rights reserved.
*****************************************************************************/
#ifndef __NU_USCI_UART_H__
#define __NU_USCI_UART_H__
#ifdef __cplusplus
extern "C"
{
#endif
/** @addtogroup Standard_Driver Standard Driver
@{
*/
/** @addtogroup USCI_UART_Driver USCI_UART Driver
@{
*/
/** @addtogroup USCI_UART_EXPORTED_CONSTANTS USCI_UART Exported Constants
@{
*/
/*---------------------------------------------------------------------------------------------------------*/
/* UUART_LINECTL constants definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define UUART_WORD_LEN_6 (6UL << UUART_LINECTL_DWIDTH_Pos) /*!< UUART_LINECTL setting to set UART word length to 6 bits */
#define UUART_WORD_LEN_7 (7UL << UUART_LINECTL_DWIDTH_Pos) /*!< UUART_LINECTL setting to set UART word length to 7 bits */
#define UUART_WORD_LEN_8 (8UL << UUART_LINECTL_DWIDTH_Pos) /*!< UUART_LINECTL setting to set UART word length to 8 bits */
#define UUART_WORD_LEN_9 (9UL << UUART_LINECTL_DWIDTH_Pos) /*!< UUART_LINECTL setting to set UART word length to 9 bits */
/*---------------------------------------------------------------------------------------------------------*/
/* UUART_PROTCTL constants definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define UUART_PARITY_NONE (0x0UL << UUART_PROTCTL_PARITYEN_Pos) /*!< UUART_PROTCTL setting to set UART as no parity */
#define UUART_PARITY_ODD (0x1UL << UUART_PROTCTL_PARITYEN_Pos) /*!< UUART_PROTCTL setting to set UART as odd parity */
#define UUART_PARITY_EVEN (0x3UL << UUART_PROTCTL_PARITYEN_Pos) /*!< UUART_PROTCTL setting to set UART as even parity */
#define UUART_STOP_BIT_1 (0x0UL) /*!< UUART_PROTCTL setting for one stop bit */
#define UUART_STOP_BIT_2 (0x1UL) /*!< UUART_PROTCTL setting for two stop bit */
/*---------------------------------------------------------------------------------------------------------*/
/* USCI UART interrupt mask definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define UUART_ABR_INT_MASK (0x002UL) /*!< Auto-baud rate interrupt mask */
#define UUART_RLS_INT_MASK (0x004UL) /*!< Receive line status interrupt mask */
#define UUART_BUF_RXOV_INT_MASK (0x008UL) /*!< Buffer RX overrun interrupt mask */
#define UUART_TXST_INT_MASK (0x010UL) /*!< TX start interrupt mask */
#define UUART_TXEND_INT_MASK (0x020UL) /*!< Tx end interrupt mask */
#define UUART_RXST_INT_MASK (0x040UL) /*!< RX start interrupt mask */
#define UUART_RXEND_INT_MASK (0x080UL) /*!< RX end interrupt mask */
/**@}*/ /* end of group USCI_UART_EXPORTED_CONSTANTS */
/** @addtogroup USCI_UART_EXPORTED_FUNCTIONS USCI_UART Exported Functions
@{
*/
/**
* @brief Write USCI_UART data
*
* @param[in] uuart The pointer of the specified USCI_UART module
* @param[in] u8Data Data byte to transmit.
*
* @return None
*
* @details This macro write Data to Tx data register.
*/
#define UUART_WRITE(uuart, u8Data) ((uuart)->TXDAT = (u8Data))
/**
* @brief Read USCI_UART data
*
* @param[in] uuart The pointer of the specified USCI_UART module
*
* @return The oldest data byte in RX buffer.
*
* @details This macro read Rx data register.
*/
#define UUART_READ(uuart) ((uuart)->RXDAT)
/**
* @brief Get Tx empty
*
* @param[in] uuart The pointer of the specified USCI_UART module
*
* @retval 0 Tx buffer is not empty
* @retval >=1 Tx buffer is empty
*
* @details This macro get Transmitter buffer empty register value.
*/
#define UUART_GET_TX_EMPTY(uuart) ((uuart)->BUFSTS & UUART_BUFSTS_TXEMPTY_Msk)
/**
* @brief Get Rx empty
*
* @param[in] uuart The pointer of the specified USCI_UART module
*
* @retval 0 Rx buffer is not empty
* @retval >=1 Rx buffer is empty
*
* @details This macro get Receiver buffer empty register value.
*/
#define UUART_GET_RX_EMPTY(uuart) ((uuart)->BUFSTS & UUART_BUFSTS_RXEMPTY_Msk)
/**
* @brief Check specified usci_uart port transmission is over.
*
* @param[in] uuart The pointer of the specified USCI_UART module
*
* @retval 0 Tx transmission is not over
* @retval 1 Tx transmission is over
*
* @details This macro return Transmitter Empty Flag register bit value. \n
* It indicates if specified usci_uart port transmission is over nor not.
*/
#define UUART_IS_TX_EMPTY(uuart) (((uuart)->BUFSTS & UUART_BUFSTS_TXEMPTY_Msk) >> UUART_BUFSTS_TXEMPTY_Pos)
/**
* @brief Check specified usci_uart port receiver is empty.
*
* @param[in] uuart The pointer of the specified USCI_UART module
*
* @retval 0 Rx receiver is not empty
* @retval 1 Rx receiver is empty
*
* @details This macro return Receive Empty Flag register bit value. \n
* It indicates if specified usci_uart port receiver is empty nor not.
*/
#define UUART_IS_RX_EMPTY(uuart) (((uuart)->BUFSTS & UUART_BUFSTS_RXEMPTY_Msk) >> UUART_BUFSTS_RXEMPTY_Pos)
/**
* @brief Wait specified usci_uart port transmission is over
*
* @param[in] uuart The pointer of the specified USCI_UART module
*
* @return None
*
* @details This macro wait specified usci_uart port transmission is over.
*/
#define UUART_WAIT_TX_EMPTY(uuart) while(!((((uuart)->BUFSTS) & UUART_BUFSTS_TXEMPTY_Msk) >> UUART_BUFSTS_TXEMPTY_Pos))
/**
* @brief Check TX buffer is full or not
*
* @param[in] uuart The pointer of the specified USCI_UART module
*
* @retval 1 TX buffer is full
* @retval 0 TX buffer is not full
*
* @details This macro check TX buffer is full or not.
*/
#define UUART_IS_TX_FULL(uuart) (((uuart)->BUFSTS & UUART_BUFSTS_TXFULL_Msk)>>UUART_BUFSTS_TXFULL_Pos)
/**
* @brief Check RX buffer is full or not
*
* @param[in] uuart The pointer of the specified USCI_UART module
*
* @retval 1 RX buffer is full
* @retval 0 RX buffer is not full
*
* @details This macro check RX buffer is full or not.
*/
#define UUART_IS_RX_FULL(uuart) (((uuart)->BUFSTS & UUART_BUFSTS_RXFULL_Msk)>>UUART_BUFSTS_RXFULL_Pos)
/**
* @brief Get Tx full register value
*
* @param[in] uuart The pointer of the specified USCI_UART module
*
* @retval 0 Tx buffer is not full.
* @retval >=1 Tx buffer is full.
*
* @details This macro get Tx full register value.
*/
#define UUART_GET_TX_FULL(uuart) ((uuart)->BUFSTS & UUART_BUFSTS_TXFULL_Msk)
/**
* @brief Get Rx full register value
*
* @param[in] uuart The pointer of the specified USCI_UART module
*
* @retval 0 Rx buffer is not full.
* @retval >=1 Rx buffer is full.
*
* @details This macro get Rx full register value.
*/
#define UUART_GET_RX_FULL(uuart) ((uuart)->BUFSTS & UUART_BUFSTS_RXFULL_Msk)
/**
* @brief Enable specified USCI_UART protocol interrupt
*
* @param[in] uuart The pointer of the specified USCI_UART module
* @param[in] u32IntSel Interrupt type select
* - \ref UUART_PROTIEN_RLSIEN_Msk : Rx Line status interrupt
* - \ref UUART_PROTIEN_ABRIEN_Msk : Auto-baud rate interrupt
*
* @return None
*
* @details This macro enable specified USCI_UART protocol interrupt.
*/
#define UUART_ENABLE_PROT_INT(uuart, u32IntSel) ((uuart)->PROTIEN |= (u32IntSel))
/**
* @brief Disable specified USCI_UART protocol interrupt
*
* @param[in] uuart The pointer of the specified USCI_UART module
* @param[in] u32IntSel Interrupt type select
* - \ref UUART_PROTIEN_RLSIEN_Msk : Rx Line status interrupt
* - \ref UUART_PROTIEN_ABRIEN_Msk : Auto-baud rate interrupt
*
* @return None
*
* @details This macro disable specified USCI_UART protocol interrupt.
*/
#define UUART_DISABLE_PROT_INT(uuart, u32IntSel) ((uuart)->PROTIEN &= ~(u32IntSel))
/**
* @brief Enable specified USCI_UART buffer interrupt
*
* @param[in] uuart The pointer of the specified USCI_UART module
* @param[in] u32IntSel Interrupt type select
* - \ref UUART_BUFCTL_RXOVIEN_Msk : Receive buffer overrun error interrupt
*
* @return None
*
* @details This macro enable specified USCI_UART buffer interrupt.
*/
#define UUART_ENABLE_BUF_INT(uuart, u32IntSel) ((uuart)->BUFCTL |= (u32IntSel))
/**
* @brief Disable specified USCI_UART buffer interrupt
*
* @param[in] uuart The pointer of the specified USCI_UART module
* @param[in] u32IntSel Interrupt type select
* - \ref UUART_BUFCTL_RXOVIEN_Msk : Receive buffer overrun error interrupt
*
* @return None
*
* @details This macro disable specified USCI_UART buffer interrupt.
*/
#define UUART_DISABLE_BUF_INT(uuart, u32IntSel) ((uuart)->BUFCTL &= ~ (u32IntSel))
/**
* @brief Enable specified USCI_UART transfer interrupt
*
* @param[in] uuart The pointer of the specified USCI_UART module
* @param[in] u32IntSel Interrupt type select
* - \ref UUART_INTEN_RXENDIEN_Msk : Receive end interrupt
* - \ref UUART_INTEN_RXSTIEN_Msk : Receive start interrupt
* - \ref UUART_INTEN_TXENDIEN_Msk : Transmit end interrupt
* - \ref UUART_INTEN_TXSTIEN_Msk : Transmit start interrupt
*
* @return None
*
* @details This macro enable specified USCI_UART transfer interrupt.
*/
#define UUART_ENABLE_TRANS_INT(uuart, u32IntSel) ((uuart)->INTEN |= (u32IntSel))
/**
* @brief Disable specified USCI_UART transfer interrupt
*
* @param[in] uuart The pointer of the specified USCI_UART module
* @param[in] u32IntSel Interrupt type select
* - \ref UUART_INTEN_RXENDIEN_Msk : Receive end interrupt
* - \ref UUART_INTEN_RXSTIEN_Msk : Receive start interrupt
* - \ref UUART_INTEN_TXENDIEN_Msk : Transmit end interrupt
* - \ref UUART_INTEN_TXSTIEN_Msk : Transmit start interrupt
*
* @return None
*
* @details This macro disable specified USCI_UART transfer interrupt.
*/
#define UUART_DISABLE_TRANS_INT(uuart, u32IntSel) ((uuart)->INTEN &= ~(u32IntSel))
/**
* @brief Get protocol interrupt flag/status
*
* @param[in] uuart The pointer of the specified USCI_UART module
*
* @return The interrupt flag/status of protocol status register.
*
* @details This macro get protocol status register value.
*/
#define UUART_GET_PROT_STATUS(uuart) ((uuart)->PROTSTS)
/**
* @brief Clear specified protocol interrupt flag
*
* @param[in] uuart The pointer of the specified USCI_UART module
* @param[in] u32IntTypeFlag Interrupt Type Flag, should be
* - \ref UUART_PROTSTS_ABERRSTS_Msk : Auto-baud Rate Error Interrupt Indicator
* - \ref UUART_PROTSTS_ABRDETIF_Msk : Auto-baud Rate Detected Interrupt Flag
* - \ref UUART_PROTSTS_BREAK_Msk : Break Flag
* - \ref UUART_PROTSTS_FRMERR_Msk : Framing Error Flag
* - \ref UUART_PROTSTS_PARITYERR_Msk : Parity Error Flag
* - \ref UUART_PROTSTS_RXENDIF_Msk : Receive End Interrupt Flag
* - \ref UUART_PROTSTS_RXSTIF_Msk : Receive Start Interrupt Flag
* - \ref UUART_PROTSTS_TXENDIF_Msk : Transmit End Interrupt Flag
* - \ref UUART_PROTSTS_TXSTIF_Msk : Transmit Start Interrupt Flag
*
* @return None
*
* @details This macro clear specified protocol interrupt flag.
*/
#define UUART_CLR_PROT_INT_FLAG(uuart,u32IntTypeFlag) ((uuart)->PROTSTS = (u32IntTypeFlag))
/**
* @brief Get transmit/receive buffer interrupt flag/status
*
* @param[in] uuart The pointer of the specified USCI_UART module
*
* @return The interrupt flag/status of buffer status register.
*
* @details This macro get buffer status register value.
*/
#define UUART_GET_BUF_STATUS(uuart) ((uuart)->BUFSTS)
/**
* @brief Clear specified buffer interrupt flag
*
* @param[in] uuart The pointer of the specified USCI_UART module
* @param[in] u32IntTypeFlag Interrupt Type Flag, should be
* - \ref UUART_BUFSTS_RXOVIF_Msk : Receive Buffer Over-run Error Interrupt Indicator
*
* @return None
*
* @details This macro clear specified buffer interrupt flag.
*/
#define UUART_CLR_BUF_INT_FLAG(uuart,u32IntTypeFlag) ((uuart)->BUFSTS = (u32IntTypeFlag))
/**
* @brief Get wakeup flag
*
* @param[in] uuart The pointer of the specified USCI_UART module
*
* @retval 0 Chip did not wake up from power-down mode.
* @retval 1 Chip waked up from power-down mode.
*
* @details This macro get wakeup flag.
*/
#define UUART_GET_WAKEUP_FLAG(uuart) ((uuart)->WKSTS & UUART_WKSTS_WKF_Msk ? 1: 0 )
/**
* @brief Clear wakeup flag
*
* @param[in] uuart The pointer of the specified USCI_UART module
*
* @return None
*
* @details This macro clear wakeup flag.
*/
#define UUART_CLR_WAKEUP_FLAG(uuart) ((uuart)->WKSTS = UUART_WKSTS_WKF_Msk)
/**
* @brief Enable specified USCI_UART PDMA function
*
* @param[in] uuart The pointer of the specified USCI_UART module
* @param[in] u32FuncSel Combination of following functions
* - \ref UUART_PDMACTL_TXPDMAEN_Msk
* - \ref UUART_PDMACTL_RXPDMAEN_Msk
* - \ref UUART_PDMACTL_PDMAEN_Msk
*
* @return None
*
* @details This macro enable specified USCI_UART PDMA function.
*/
#define UUART_PDMA_ENABLE(uuart, u32FuncSel) ((uuart)->PDMACTL |= (u32FuncSel))
/**
* @brief Disable specified USCI_UART PDMA function
*
* @param[in] uuart The pointer of the specified USCI_UART module
* @param[in] u32FuncSel Combination of following functions
* - \ref UUART_PDMACTL_TXPDMAEN_Msk
* - \ref UUART_PDMACTL_RXPDMAEN_Msk
* - \ref UUART_PDMACTL_PDMAEN_Msk
*
* @return None
*
* @details This macro disable specified USCI_UART PDMA function.
*/
#define UUART_PDMA_DISABLE(uuart, u32FuncSel) ((uuart)->PDMACTL &= ~(u32FuncSel))
void UUART_ClearIntFlag(UUART_T* uuart, uint32_t u32Mask);
uint32_t UUART_GetIntFlag(UUART_T* uuart, uint32_t u32Mask);
void UUART_Close(UUART_T* uuart);
void UUART_DisableInt(UUART_T* uuart, uint32_t u32Mask);
void UUART_EnableInt(UUART_T* uuart, uint32_t u32Mask);
uint32_t UUART_Open(UUART_T* uuart, uint32_t u32baudrate);
uint32_t UUART_Read(UUART_T* uuart, uint8_t pu8RxBuf[], uint32_t u32ReadBytes);
uint32_t UUART_SetLine_Config(UUART_T* uuart, uint32_t u32baudrate, uint32_t u32data_width, uint32_t u32parity, uint32_t u32stop_bits);
uint32_t UUART_Write(UUART_T* uuart, uint8_t pu8TxBuf[], uint32_t u32WriteBytes);
void UUART_EnableWakeup(UUART_T* uuart, uint32_t u32WakeupMode);
void UUART_DisableWakeup(UUART_T* uuart);
void UUART_EnableFlowCtrl(UUART_T* uuart);
void UUART_DisableFlowCtrl(UUART_T* uuart);
/**@}*/ /* end of group USCI_UART_EXPORTED_FUNCTIONS */
/**@}*/ /* end of group USCI_UART_Driver */
/**@}*/ /* end of group Standard_Driver */
#ifdef __cplusplus
}
#endif
#endif /* __NU_USCI_UART_H__ */

View File

@ -0,0 +1,217 @@
/**************************************************************************//**
* @file nu_wdt.h
* @version V3.00
* @brief Watchdog Timer(WDT) driver header file
*
* @copyright SPDX-License-Identifier: Apache-2.0
* @copyright Copyright (C) 2020 Nuvoton Technology Corp. All rights reserved.
*****************************************************************************/
#ifndef __NU_WDT_H__
#define __NU_WDT_H__
#ifdef __cplusplus
extern "C"
{
#endif
/** @addtogroup Standard_Driver Standard Driver
@{
*/
/** @addtogroup WDT_Driver WDT Driver
@{
*/
/** @addtogroup WDT_EXPORTED_CONSTANTS WDT Exported Constants
@{
*/
/*---------------------------------------------------------------------------------------------------------*/
/* WDT Time-out Interval Period Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define WDT_TIMEOUT_2POW4 (0UL << WDT_CTL_TOUTSEL_Pos) /*!< Setting WDT time-out interval to 2^4 * WDT clocks \hideinitializer */
#define WDT_TIMEOUT_2POW6 (1UL << WDT_CTL_TOUTSEL_Pos) /*!< Setting WDT time-out interval to 2^6 * WDT clocks \hideinitializer */
#define WDT_TIMEOUT_2POW8 (2UL << WDT_CTL_TOUTSEL_Pos) /*!< Setting WDT time-out interval to 2^8 * WDT clocks \hideinitializer */
#define WDT_TIMEOUT_2POW10 (3UL << WDT_CTL_TOUTSEL_Pos) /*!< Setting WDT time-out interval to 2^10 * WDT clocks \hideinitializer */
#define WDT_TIMEOUT_2POW12 (4UL << WDT_CTL_TOUTSEL_Pos) /*!< Setting WDT time-out interval to 2^12 * WDT clocks \hideinitializer */
#define WDT_TIMEOUT_2POW14 (5UL << WDT_CTL_TOUTSEL_Pos) /*!< Setting WDT time-out interval to 2^14 * WDT clocks \hideinitializer */
#define WDT_TIMEOUT_2POW16 (6UL << WDT_CTL_TOUTSEL_Pos) /*!< Setting WDT time-out interval to 2^16 * WDT clocks \hideinitializer */
#define WDT_TIMEOUT_2POW18 (7UL << WDT_CTL_TOUTSEL_Pos) /*!< Setting WDT time-out interval to 2^18 * WDT clocks \hideinitializer */
#define WDT_TIMEOUT_2POW20 (8UL << WDT_CTL_TOUTSEL_Pos) /*!< Setting WDT time-out interval to 2^20 * WDT clocks \hideinitializer */
/*---------------------------------------------------------------------------------------------------------*/
/* WDT Reset Delay Period Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define WDT_RESET_DELAY_1026CLK (0UL << WDT_ALTCTL_RSTDSEL_Pos) /*!< Setting WDT reset delay period to 1026 * WDT clocks \hideinitializer */
#define WDT_RESET_DELAY_130CLK (1UL << WDT_ALTCTL_RSTDSEL_Pos) /*!< Setting WDT reset delay period to 130 * WDT clocks \hideinitializer */
#define WDT_RESET_DELAY_18CLK (2UL << WDT_ALTCTL_RSTDSEL_Pos) /*!< Setting WDT reset delay period to 18 * WDT clocks \hideinitializer */
#define WDT_RESET_DELAY_3CLK (3UL << WDT_ALTCTL_RSTDSEL_Pos) /*!< Setting WDT reset delay period to 3 * WDT clocks \hideinitializer */
/*---------------------------------------------------------------------------------------------------------*/
/* WDT Free Reset Counter Keyword Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define WDT_RESET_COUNTER_KEYWORD (0x00005AA5UL) /*!< Fill this value to WDT_RSTCNT register to free reset WDT counter \hideinitializer */
/**@}*/ /* end of group WDT_EXPORTED_CONSTANTS */
/** @addtogroup WDT_EXPORTED_FUNCTIONS WDT Exported Functions
@{
*/
/**
* @brief Clear WDT Reset System Flag
*
* @param None
*
* @return None
*
* @details This macro clears WDT time-out reset system flag.
* \hideinitializer
*/
#define WDT_CLEAR_RESET_FLAG() (WDT->CTL = (WDT->CTL & ~(WDT_CTL_IF_Msk | WDT_CTL_WKF_Msk)) | WDT_CTL_RSTF_Msk)
/**
* @brief Clear WDT Time-out Interrupt Flag
*
* @param None
*
* @return None
*
* @details This macro clears WDT time-out interrupt flag.
* \hideinitializer
*/
#define WDT_CLEAR_TIMEOUT_INT_FLAG() (WDT->CTL = (WDT->CTL & ~(WDT_CTL_RSTF_Msk | WDT_CTL_WKF_Msk)) | WDT_CTL_IF_Msk)
/**
* @brief Clear WDT Wake-up Flag
*
* @param None
*
* @return None
*
* @details This macro clears WDT time-out wake-up system flag.
* \hideinitializer
*/
#define WDT_CLEAR_TIMEOUT_WAKEUP_FLAG() (WDT->CTL = (WDT->CTL & ~(WDT_CTL_RSTF_Msk | WDT_CTL_IF_Msk)) | WDT_CTL_WKF_Msk)
/**
* @brief Get WDT Time-out Reset Flag
*
* @param None
*
* @retval 0 WDT time-out reset system did not occur
* @retval 1 WDT time-out reset system occurred
*
* @details This macro indicates system has been reset by WDT time-out reset or not.
* \hideinitializer
*/
#define WDT_GET_RESET_FLAG() ((WDT->CTL & WDT_CTL_RSTF_Msk)? 1UL : 0UL)
/**
* @brief Get WDT Time-out Interrupt Flag
*
* @param None
*
* @retval 0 WDT time-out interrupt did not occur
* @retval 1 WDT time-out interrupt occurred
*
* @details This macro indicates WDT time-out interrupt occurred or not.
* \hideinitializer
*/
#define WDT_GET_TIMEOUT_INT_FLAG() ((WDT->CTL & WDT_CTL_IF_Msk)? 1UL : 0UL)
/**
* @brief Get WDT Time-out Wake-up Flag
*
* @param None
*
* @retval 0 WDT time-out interrupt does not cause CPU wake-up
* @retval 1 WDT time-out interrupt event cause CPU wake-up
*
* @details This macro indicates WDT time-out interrupt event has waked up system or not.
* \hideinitializer
*/
#define WDT_GET_TIMEOUT_WAKEUP_FLAG() ((WDT->CTL & WDT_CTL_WKF_Msk)? 1UL : 0UL)
/**
* @brief Reset WDT Counter
*
* @param None
*
* @return None
*
* @details This macro is used to reset the internal 20-bit WDT up counter value.
* @note If WDT is activated and time-out reset system function is enabled also, user should \n
* reset the 20-bit WDT up counter value to avoid generate WDT time-out reset signal to \n
* reset system before the WDT time-out reset delay period expires.
* \hideinitializer
*/
#define WDT_RESET_COUNTER() (WDT->RSTCNT = WDT_RESET_COUNTER_KEYWORD)
/*---------------------------------------------------------------------------------------------------------*/
/* static inline functions */
/*---------------------------------------------------------------------------------------------------------*/
/* Declare these inline functions here to avoid MISRA C 2004 rule 8.1 error */
__STATIC_INLINE void WDT_Close(void);
__STATIC_INLINE void WDT_EnableInt(void);
__STATIC_INLINE void WDT_DisableInt(void);
/**
* @brief Stop WDT Counting
*
* @param None
*
* @return None
*
* @details This function will stop WDT counting and disable WDT module.
*/
__STATIC_INLINE void WDT_Close(void)
{
WDT->CTL = 0UL;
while(WDT->CTL & WDT_CTL_SYNC_Msk) {} /* Wait disable WDTEN bit completed, it needs 2 * WDT_CLK. */
}
/**
* @brief Enable WDT Time-out Interrupt
*
* @param None
*
* @return None
*
* @details This function will enable the WDT time-out interrupt function.
*/
__STATIC_INLINE void WDT_EnableInt(void)
{
WDT->CTL |= WDT_CTL_INTEN_Msk;
}
/**
* @brief Disable WDT Time-out Interrupt
*
* @param None
*
* @return None
*
* @details This function will disable the WDT time-out interrupt function.
*/
__STATIC_INLINE void WDT_DisableInt(void)
{
/* Do not touch another write 1 clear bits */
WDT->CTL &= ~(WDT_CTL_INTEN_Msk | WDT_CTL_RSTF_Msk | WDT_CTL_IF_Msk | WDT_CTL_WKF_Msk);
}
void WDT_Open(uint32_t u32TimeoutInterval, uint32_t u32ResetDelay, uint32_t u32EnableReset, uint32_t u32EnableWakeup);
/**@}*/ /* end of group WDT_EXPORTED_FUNCTIONS */
/**@}*/ /* end of group WDT_Driver */
/**@}*/ /* end of group Standard_Driver */
#ifdef __cplusplus
}
#endif
#endif /* __NU_WDT_H__ */

View File

@ -0,0 +1,151 @@
/**************************************************************************//**
* @file nu_wwdt.h
* @version V3.00
* @brief Window Watchdog Timer(WWDT) driver header file
*
* @copyright SPDX-License-Identifier: Apache-2.0
* @copyright Copyright (C) 2020 Nuvoton Technology Corp. All rights reserved.
*****************************************************************************/
#ifndef __NU_WWDT_H__
#define __NU_WWDT_H__
#ifdef __cplusplus
extern "C"
{
#endif
/** @addtogroup Standard_Driver Standard Driver
@{
*/
/** @addtogroup WWDT_Driver WWDT Driver
@{
*/
/** @addtogroup WWDT_EXPORTED_CONSTANTS WWDT Exported Constants
@{
*/
/*---------------------------------------------------------------------------------------------------------*/
/* WWDT Prescale Period Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define WWDT_PRESCALER_1 (0 << WWDT_CTL_PSCSEL_Pos) /*!< Select max time-out period to 1 * (64*WWDT_CLK) \hideinitializer */
#define WWDT_PRESCALER_2 (1 << WWDT_CTL_PSCSEL_Pos) /*!< Select max time-out period to 2 * (64*WWDT_CLK) \hideinitializer */
#define WWDT_PRESCALER_4 (2 << WWDT_CTL_PSCSEL_Pos) /*!< Select max time-out period to 4 * (64*WWDT_CLK) \hideinitializer */
#define WWDT_PRESCALER_8 (3 << WWDT_CTL_PSCSEL_Pos) /*!< Select max time-out period to 8 * (64*WWDT_CLK) \hideinitializer */
#define WWDT_PRESCALER_16 (4 << WWDT_CTL_PSCSEL_Pos) /*!< Select max time-out period to 16 * (64*WWDT_CLK) \hideinitializer */
#define WWDT_PRESCALER_32 (5 << WWDT_CTL_PSCSEL_Pos) /*!< Select max time-out period to 32 * (64*WWDT_CLK) \hideinitializer */
#define WWDT_PRESCALER_64 (6 << WWDT_CTL_PSCSEL_Pos) /*!< Select max time-out period to 64 * (64*WWDT_CLK) \hideinitializer */
#define WWDT_PRESCALER_128 (7 << WWDT_CTL_PSCSEL_Pos) /*!< Select max time-out period to 128 * (64*WWDT_CLK) \hideinitializer */
#define WWDT_PRESCALER_192 (8 << WWDT_CTL_PSCSEL_Pos) /*!< Select max time-out period to 192 * (64*WWDT_CLK) \hideinitializer */
#define WWDT_PRESCALER_256 (9 << WWDT_CTL_PSCSEL_Pos) /*!< Select max time-out period to 256 * (64*WWDT_CLK) \hideinitializer */
#define WWDT_PRESCALER_384 (10 << WWDT_CTL_PSCSEL_Pos) /*!< Select max time-out period to 384 * (64*WWDT_CLK) \hideinitializer */
#define WWDT_PRESCALER_512 (11 << WWDT_CTL_PSCSEL_Pos) /*!< Select max time-out period to 512 * (64*WWDT_CLK) \hideinitializer */
#define WWDT_PRESCALER_768 (12 << WWDT_CTL_PSCSEL_Pos) /*!< Select max time-out period to 768 * (64*WWDT_CLK) \hideinitializer */
#define WWDT_PRESCALER_1024 (13 << WWDT_CTL_PSCSEL_Pos) /*!< Select max time-out period to 1024 * (64*WWDT_CLK) \hideinitializer */
#define WWDT_PRESCALER_1536 (14 << WWDT_CTL_PSCSEL_Pos) /*!< Select max time-out period to 1536 * (64*WWDT_CLK) \hideinitializer */
#define WWDT_PRESCALER_2048 (15 << WWDT_CTL_PSCSEL_Pos) /*!< Select max time-out period to 2048 * (64*WWDT_CLK) \hideinitializer */
/*---------------------------------------------------------------------------------------------------------*/
/* WWDT Reload Counter Keyword Constant Definitions */
/*---------------------------------------------------------------------------------------------------------*/
#define WWDT_RELOAD_WORD (0x00005AA5) /*!< Fill this value to WWDT_RLDCNT register to reload WWDT counter \hideinitializer */
/**@}*/ /* end of group WWDT_EXPORTED_CONSTANTS */
/** @addtogroup WWDT_EXPORTED_FUNCTIONS WWDT Exported Functions
@{
*/
/**
* @brief Clear WWDT Reset System Flag
*
* @param None
*
* @return None
*
* @details This macro is used to clear WWDT time-out reset system flag.
* \hideinitializer
*/
#define WWDT_CLEAR_RESET_FLAG() (WWDT->STATUS = WWDT_STATUS_WWDTRF_Msk)
/**
* @brief Clear WWDT Compared Match Interrupt Flag
*
* @param None
*
* @return None
*
* @details This macro is used to clear WWDT compared match interrupt flag.
* \hideinitializer
*/
#define WWDT_CLEAR_INT_FLAG() (WWDT->STATUS = WWDT_STATUS_WWDTIF_Msk)
/**
* @brief Get WWDT Reset System Flag
*
* @param None
*
* @retval 0 WWDT time-out reset system did not occur
* @retval 1 WWDT time-out reset system occurred
*
* @details This macro is used to indicate system has been reset by WWDT time-out reset or not.
* \hideinitializer
*/
#define WWDT_GET_RESET_FLAG() ((WWDT->STATUS & WWDT_STATUS_WWDTRF_Msk)? 1 : 0)
/**
* @brief Get WWDT Compared Match Interrupt Flag
*
* @param None
*
* @retval 0 WWDT compare match interrupt did not occur
* @retval 1 WWDT compare match interrupt occurred
*
* @details This macro is used to indicate WWDT counter value matches CMPDAT value or not.
* \hideinitializer
*/
#define WWDT_GET_INT_FLAG() ((WWDT->STATUS & WWDT_STATUS_WWDTIF_Msk)? 1 : 0)
/**
* @brief Get WWDT Counter
*
* @param None
*
* @return WWDT Counter Value
*
* @details This macro reflects the current WWDT counter value.
* \hideinitializer
*/
#define WWDT_GET_COUNTER() (WWDT->CNT)
/**
* @brief Reload WWDT Counter
*
* @param None
*
* @return None
*
* @details This macro is used to reload the WWDT counter value to 0x3F.
* @note User can only write WWDT_RLDCNT register to reload WWDT counter value when current WWDT counter value \n
* between 0 and CMPDAT value. If user writes WWDT_RLDCNT when current WWDT counter value is larger than CMPDAT, \n
* WWDT reset signal will generate immediately to reset system.
* \hideinitializer
*/
#define WWDT_RELOAD_COUNTER() (WWDT->RLDCNT = WWDT_RELOAD_WORD)
void WWDT_Open(uint32_t u32PreScale, uint32_t u32CmpValue, uint32_t u32EnableInt);
/**@}*/ /* end of group WWDT_EXPORTED_FUNCTIONS */
/**@}*/ /* end of group WWDT_Driver */
/**@}*/ /* end of group Standard_Driver */
#ifdef __cplusplus
}
#endif
#endif /* __NU_WWDT_H__ */

View File

@ -0,0 +1,215 @@
/**************************************************************************//**
*
* @copyright (C) 2020 Nuvoton Technology Corp. All rights reserved.
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2020-2-7 Wayne First version
*
******************************************************************************/
#ifndef __NU_BITUTIL_H__
#define __NU_BITUTIL_H__
#if defined(__ICCARM__)
#include <arm_math.h>
#endif
#ifdef __cplusplus
extern "C" {
#endif
/* ----------------------------------------------
* Count Leading Zeros Count Trailing Zeros
* (MSB)00000000000000001000000000001000(LSB)
* ################| |!!!
* Find Highest Set Find First Set
* ----------------------------------------------
*
* ----------------------------------------------
* Count Leading Ones Count Trailing Ones
* (MSB)11111111111111110111111111110111(LSB)
* ^^^^^^^^^^^^^^^^| |@@@
* Find Highest Zero Find First Zero
* ----------------------------------------------
*/
/* Count Leading Zeros in word - Find Highest Set
EX: x=(MSB)00000000000000001000000000001000(LSB)
################|
Find Highest Set
nu_clz will start zero-counting from MSB and return the number.
*/
__STATIC_INLINE int nu_clz(uint32_t x)
{
return x ? __CLZ(x):32;
}
/* Count Leading Ones in word - Find Highest Zero
EX: x=(MSB)11111111111111110111111111110111(LSB)
^^^^^^^^^^^^^^^^|
Find Highest Zero
nu_clo will start one-counting from MSB and return the number.
*/
__STATIC_INLINE int nu_clo(uint32_t x)
{
return nu_clz(~x);
}
/* Count Trailing Zero in word - Find First Set
EX: x=(MSB)00000000000000001000000000001000(LSB)
|!!!
Find First Set
nu_ctz will start zero-counting from LSB and return the number.
*/
__STATIC_INLINE int nu_ctz(uint32_t x)
{
int c = 32;
if (x)
c = __CLZ(x & -x);
return x ? 31 - c : c;
}
/* Count Trailing Ones in word - Find First Zero
EX: x=(MSB)11111111111111110111111111110111(LSB)
|@@@
Find First Zero
nu_cto will start one-counting from LSB and return the number.
*/
__STATIC_INLINE int nu_cto(uint32_t x)
{
return nu_ctz(~x);
}
/* Get 16-bit from a byte-array in little-endian */
__STATIC_INLINE uint16_t nu_get16_le(const uint8_t *pos)
{
uint16_t val;
val = *pos ++;
val += (*pos << 8);
return val;
}
/* Set 16-bit to a byte-array in little-endian */
__STATIC_INLINE void nu_set16_le(uint8_t *pos, uint16_t val)
{
*pos ++ = val & 0xFF;
*pos = val >> 8;
}
/* Get 32-bit from a byte-array in little-endian */
__STATIC_INLINE uint32_t nu_get32_le(const uint8_t *pos)
{
uint32_t val;
val = *pos ++;
val += (*pos ++ << 8);
val += (*pos ++ << 16);
val += (*pos ++ << 24);
return val;
}
/* Get 24-bit from a byte-array in little-endian */
__STATIC_INLINE uint32_t nu_get24_le(const uint8_t *pos)
{
uint32_t val;
val = *pos ++;
val += (*pos ++ << 8);
val += (*pos ++ << 16);
return val;
}
/* Set 24-bit to a byte-array in little-endian */
__STATIC_INLINE void nu_set24_le(uint8_t *pos, uint32_t val)
{
*pos ++ = val & 0xFF;
*pos ++ = (val >> 8) & 0xFF;
*pos ++ = (val >> 16) & 0xFF;
}
/* Set 32-bit to a byte-array in little-endian */
__STATIC_INLINE void nu_set32_le(uint8_t *pos, uint32_t val)
{
*pos ++ = val & 0xFF;
*pos ++ = (val >> 8) & 0xFF;
*pos ++ = (val >> 16) & 0xFF;
*pos = (val >> 24) & 0xFF;
}
/* Get 16-bit from a byte-array in big-endian */
__STATIC_INLINE uint16_t nu_get16_be(const uint8_t *pos)
{
uint16_t val;
val = *pos ++;
val <<= 8;
val += *pos;
return val;
}
/* Set 16-bit to a byte-array in big-endian */
__STATIC_INLINE void nu_set16_be(uint8_t *pos, uint16_t val)
{
*pos ++ = val >> 8;
*pos = (val & 0xFF);
}
/* Get 24-bit from a byte-array in big-endian */
__STATIC_INLINE uint32_t nu_get24_be(const uint8_t *pos)
{
uint32_t val;
val = *pos ++;
val <<= 8;
val += *pos ++;
val <<= 8;
val += *pos ++;
return val;
}
/* Set 24-bit to a byte-array in big-endian */
__STATIC_INLINE void nu_set24_be(uint8_t *pos, uint32_t val)
{
*pos ++ = val >> 16;
*pos ++ = val >> 8;
*pos ++ = (val & 0xFF);
}
/* Get 32-bit from a byte-array in big-endian */
__STATIC_INLINE uint32_t nu_get32_be(const uint8_t *pos)
{
uint32_t val;
val = *pos ++;
val <<= 8;
val += *pos ++;
val <<= 8;
val += *pos ++;
val <<= 8;
val += *pos;
return val;
}
/* Set 32-bit to a byte-array in big-endian */
__STATIC_INLINE void nu_set32_be(uint8_t *pos, uint32_t val)
{
*pos ++ = val >> 24;
*pos ++ = val >> 16;
*pos ++ = val >> 8;
*pos ++ = (val & 0xFF);
}
#ifdef __cplusplus
}
#endif
#endif //__NU_BITUTIL_H__

View File

@ -0,0 +1,39 @@
/**************************************************************************//**
*
* @copyright (C) 2020 Nuvoton Technology Corp. All rights reserved.
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2020-2-7 Wayne First version
*
******************************************************************************/
#ifndef NU_MISC_UTIL_H
#define NU_MISC_UTIL_H
#ifdef __cplusplus
extern "C" {
#endif
#define NU_MAX(a,b) ((a)>(b)?(a):(b))
#define NU_MIN(a,b) ((a)<(b)?(a):(b))
#define NU_CLAMP(x, min, max) NU_MIN(NU_MAX((x), (min)), (max))
#define NU_ALIGN_DOWN(X, ALIGN) ((X) & ~((ALIGN) - 1))
#define NU_ALIGN_UP(X, ALIGN) (((X) + (ALIGN) - 1) & ~((ALIGN) - 1))
#define NU_ISALIGNED(a, b) (((a) & (b - 1)) == 0)
#define SET_BIT(REG, BIT) ((REG) |= (BIT))
#define CLEAR_BIT(REG, BIT) ((REG) &= ~(BIT))
#define READ_BIT(REG, BIT) ((REG) & (BIT))
#define CLEAR_REG(REG) ((REG) = (0x0))
#define WRITE_REG(REG, VAL) ((REG) = (VAL))
#define READ_REG(REG) ((REG))
#define MODIFY_REG(REG, CLEARMASK, SETMASK) WRITE_REG((REG), (((READ_REG(REG)) & (~(CLEARMASK))) | (SETMASK)))
#ifdef __cplusplus
}
#endif
#endif

File diff suppressed because it is too large Load Diff

Some files were not shown because too many files have changed in this diff Show More