transplant development board of gd32vf103_rvstar

This commit is contained in:
Wang_Weigen 2021-12-02 15:17:59 +08:00
parent 4fc79c211a
commit 607b8ca017
49 changed files with 11946 additions and 3 deletions

View File

@ -12,7 +12,7 @@
#include <stdio.h>
#include <string.h>
#include <user_api.h>
// #include <user_api.h>
#include <transform.h>
extern int FrameworkInit();

View File

@ -1,4 +1,14 @@
SRC_FILES := pthread.c semaphore.c pthread_mutex.c mqueue.c
SRC_FILES := pthread.c
ifeq ($(CONFIG_KERNEL_SEMAPHORE),y)
SRC_FILES += semaphore.c
endif
ifeq ($(CONFIG_KERNEL_MUTEX),y)
SRC_FILES += pthread_mutex.c
endif
ifeq ($(CONFIG_KERNEL_MESSAGEQUEUE),y)
SRC_FILES += mqueue.c
endif
include $(KERNEL_ROOT)/compiler.mk

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
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 gd32vf103_rvstar
SRC_DIR:=
export BOARD ?=kd233

View File

@ -20,4 +20,8 @@ ifeq ($(CONFIG_BOARD_GAPUINO),y)
SRC_DIR +=gap8
endif
ifeq ($(CONFIG_BOARD_GD32VF103RVSTAR),y)
SRC_DIR +=gd32vf103_rvstar
endif
include $(KERNEL_ROOT)/compiler.mk

View File

@ -0,0 +1,3 @@
SRC_FILES := boot.S intexc_gd32vf103.S interrupt.c tick.c
include $(KERNEL_ROOT)/compiler.mk

View File

@ -0,0 +1,12 @@
#ifndef ARCH_INTERRUPT_H__
#define ARCH_INTERRUPT_H__
#include <nuclei_sdk_soc.h>
#define ARCH_MAX_IRQ_NUM 128
#define ARCH_IRQ_NUM_OFFSET 0
int ArchEnableHwIrq(uint32_t irq_num);
int ArchDisableHwIrq(uint32_t irq_num);
#endif

View File

@ -0,0 +1,486 @@
/*
* Copyright (c) 2019 Nuclei 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.
*/
/******************************************************************************
* \file startup_gd32vf103.S
* \brief NMSIS Nuclei N/NX Class Core based Core Device Startup File for
* Device gd32vf103
* \version V1.00
* \date 21 Nov 2019
*
*
******************************************************************************/
#include "boot.h"
#include "riscv_encoding.h"
#ifndef __riscv_32e
#define portRegNum 30
#else
#define portRegNum 14
#endif
#define portCONTEXT_SIZE ( portRegNum * REGBYTES )
# .align 2
# .global eclic_msip_handler
# eclic_msip_handler:
# addi sp, sp, -portCONTEXT_SIZE
# STORE x1, 1 * REGBYTES(sp) /* RA */
# STORE x5, 2 * REGBYTES(sp)
# STORE x6, 3 * REGBYTES(sp)
# STORE x7, 4 * REGBYTES(sp)
# STORE x8, 5 * REGBYTES(sp)
# STORE x9, 6 * REGBYTES(sp)
# STORE x10, 7 * REGBYTES(sp)
# STORE x11, 8 * REGBYTES(sp)
# STORE x12, 9 * REGBYTES(sp)
# STORE x13, 10 * REGBYTES(sp)
# STORE x14, 11 * REGBYTES(sp)
# STORE x15, 12 * REGBYTES(sp)
# #ifndef __riscv_32e
# STORE x16, 13 * REGBYTES(sp)
# STORE x17, 14 * REGBYTES(sp)
# STORE x18, 15 * REGBYTES(sp)
# STORE x19, 16 * REGBYTES(sp)
# STORE x20, 17 * REGBYTES(sp)
# STORE x21, 18 * REGBYTES(sp)
# STORE x22, 19 * REGBYTES(sp)
# STORE x23, 20 * REGBYTES(sp)
# STORE x24, 21 * REGBYTES(sp)
# STORE x25, 22 * REGBYTES(sp)
# STORE x26, 23 * REGBYTES(sp)
# STORE x27, 24 * REGBYTES(sp)
# STORE x28, 25 * REGBYTES(sp)
# STORE x29, 26 * REGBYTES(sp)
# STORE x30, 27 * REGBYTES(sp)
# STORE x31, 28 * REGBYTES(sp)
# #endif
# /* Push mstatus to stack */
# csrr t0, CSR_MSTATUS
# STORE t0, (portRegNum - 1) * REGBYTES(sp)
# /* Push additional registers */
# /* Store sp to task stack */
# LOAD t0, rt_interrupt_from_thread
# STORE sp, 0(t0)
# csrr t0, CSR_MEPC
# STORE t0, 0(sp)
# jal xPortTaskSwitch
# /* Switch task context */
# LOAD t0, rt_interrupt_to_thread
# LOAD sp, 0x0(t0)
# /* Pop PC from stack and set MEPC */
# LOAD t0, 0 * REGBYTES(sp)
# csrw CSR_MEPC, t0
# /* Pop additional registers */
# /* Pop mstatus from stack and set it */
# LOAD t0, (portRegNum - 1) * REGBYTES(sp)
# csrw CSR_MSTATUS, t0
# /* Interrupt still disable here */
# /* Restore Registers from Stack */
# LOAD x1, 1 * REGBYTES(sp) /* RA */
# LOAD x5, 2 * REGBYTES(sp)
# LOAD x6, 3 * REGBYTES(sp)
# LOAD x7, 4 * REGBYTES(sp)
# LOAD x8, 5 * REGBYTES(sp)
# LOAD x9, 6 * REGBYTES(sp)
# LOAD x10, 7 * REGBYTES(sp)
# LOAD x11, 8 * REGBYTES(sp)
# LOAD x12, 9 * REGBYTES(sp)
# LOAD x13, 10 * REGBYTES(sp)
# LOAD x14, 11 * REGBYTES(sp)
# LOAD x15, 12 * REGBYTES(sp)
# #ifndef __riscv_32e
# LOAD x16, 13 * REGBYTES(sp)
# LOAD x17, 14 * REGBYTES(sp)
# LOAD x18, 15 * REGBYTES(sp)
# LOAD x19, 16 * REGBYTES(sp)
# LOAD x20, 17 * REGBYTES(sp)
# LOAD x21, 18 * REGBYTES(sp)
# LOAD x22, 19 * REGBYTES(sp)
# LOAD x23, 20 * REGBYTES(sp)
# LOAD x24, 21 * REGBYTES(sp)
# LOAD x25, 22 * REGBYTES(sp)
# LOAD x26, 23 * REGBYTES(sp)
# LOAD x27, 24 * REGBYTES(sp)
# LOAD x28, 25 * REGBYTES(sp)
# LOAD x29, 26 * REGBYTES(sp)
# LOAD x30, 27 * REGBYTES(sp)
# LOAD x31, 28 * REGBYTES(sp)
# #endif
# addi sp, sp, portCONTEXT_SIZE
# mret
.extern xPortTaskSwitch
.align 2
.global eclic_msip_handler
eclic_msip_handler:
SAVE_X_REGISTERS
jal xPortTaskSwitch
call KTaskOsAssignAfterIrq
j SwitchKTaskContextExit
.macro DECLARE_INT_HANDLER INT_HDL_NAME
#if defined(__riscv_xlen) && (__riscv_xlen == 32)
.word \INT_HDL_NAME
#else
.dword \INT_HDL_NAME
#endif
.endm
/*
* Put the interrupt vectors in this section according to vector remapped or not:
* .vtable: vector table's LMA and VMA are the same, it is not remapped
* .vtable_ilm: vector table's LMA and VMA are different, it is remapped, and
* VECTOR_TABLE_REMAPPED need to be defined
*/
#if defined(VECTOR_TABLE_REMAPPED)
.section .vtable_ilm
#else
.section .vtable
#endif
.weak eclic_msip_handler
.weak eclic_mtip_handler
.weak eclic_bwei_handler
.weak eclic_pmovi_handler
.weak WWDGT_IRQHandler
.weak LVD_IRQHandler
.weak TAMPER_IRQHandler
.weak RTC_IRQHandler
.weak FMC_IRQHandler
.weak RCU_IRQHandler
.weak EXTI0_IRQHandler
.weak EXTI1_IRQHandler
.weak EXTI2_IRQHandler
.weak EXTI3_IRQHandler
.weak EXTI4_IRQHandler
.weak DMA0_Channel0_IRQHandler
.weak DMA0_Channel1_IRQHandler
.weak DMA0_Channel2_IRQHandler
.weak DMA0_Channel3_IRQHandler
.weak DMA0_Channel4_IRQHandler
.weak DMA0_Channel5_IRQHandler
.weak DMA0_Channel6_IRQHandler
.weak ADC0_1_IRQHandler
.weak CAN0_TX_IRQHandler
.weak CAN0_RX0_IRQHandler
.weak CAN0_RX1_IRQHandler
.weak CAN0_EWMC_IRQHandler
.weak EXTI5_9_IRQHandler
.weak TIMER0_BRK_IRQHandler
.weak TIMER0_UP_IRQHandler
.weak TIMER0_TRG_CMT_IRQHandler
.weak TIMER0_Channel_IRQHandler
.weak TIMER1_IRQHandler
.weak TIMER2_IRQHandler
.weak TIMER3_IRQHandler
.weak I2C0_EV_IRQHandler
.weak I2C0_ER_IRQHandler
.weak I2C1_EV_IRQHandler
.weak I2C1_ER_IRQHandler
.weak SPI0_IRQHandler
.weak SPI1_IRQHandler
.weak USART0_IRQHandler
.weak USART1_IRQHandler
.weak USART2_IRQHandler
.weak EXTI10_15_IRQHandler
.weak RTC_Alarm_IRQHandler
.weak USBFS_WKUP_IRQHandler
.weak EXMC_IRQHandler
.weak TIMER4_IRQHandler
.weak SPI2_IRQHandler
.weak UART3_IRQHandler
.weak UART4_IRQHandler
.weak TIMER5_IRQHandler
.weak TIMER6_IRQHandler
.weak DMA1_Channel0_IRQHandler
.weak DMA1_Channel1_IRQHandler
.weak DMA1_Channel2_IRQHandler
.weak DMA1_Channel3_IRQHandler
.weak DMA1_Channel4_IRQHandler
.weak CAN1_TX_IRQHandler
.weak CAN1_RX0_IRQHandler
.weak CAN1_RX1_IRQHandler
.weak CAN1_EWMC_IRQHandler
.weak USBFS_IRQHandler
.globl vector_base
.type vector_base, @object
vector_base:
#ifndef VECTOR_TABLE_REMAPPED
j _start /* 0: Reserved, Jump to _start when reset for vector table not remapped cases.*/
.align LOG_REGBYTES /* Need to align 4 byte for RV32, 8 Byte for RV64 */
#else
DECLARE_INT_HANDLER default_intexc_handler /* 0: Reserved, default handler for vector table remapped cases */
#endif
DECLARE_INT_HANDLER default_intexc_handler /* 1: Reserved */
DECLARE_INT_HANDLER default_intexc_handler /* 2: Reserved */
DECLARE_INT_HANDLER eclic_msip_handler /* 3: Machine software interrupt */
DECLARE_INT_HANDLER default_intexc_handler /* 4: Reserved */
DECLARE_INT_HANDLER default_intexc_handler /* 5: Reserved */
DECLARE_INT_HANDLER default_intexc_handler /* 6: Reserved */
DECLARE_INT_HANDLER eclic_mtip_handler /* 7: Machine timer interrupt */
DECLARE_INT_HANDLER default_intexc_handler /* 8: Reserved */
DECLARE_INT_HANDLER default_intexc_handler /* 9: Reserved */
DECLARE_INT_HANDLER default_intexc_handler /* 10: Reserved */
DECLARE_INT_HANDLER default_intexc_handler /* 11: Reserved */
DECLARE_INT_HANDLER default_intexc_handler /* 12: Reserved */
DECLARE_INT_HANDLER default_intexc_handler /* 13: Reserved */
DECLARE_INT_HANDLER default_intexc_handler /* 14: Reserved */
DECLARE_INT_HANDLER default_intexc_handler /* 15: Reserved */
DECLARE_INT_HANDLER default_intexc_handler /* 16: Reserved */
DECLARE_INT_HANDLER eclic_bwei_handler /* 17: Bus Error interrupt */
DECLARE_INT_HANDLER eclic_pmovi_handler /* 18: Performance Monitor */
DECLARE_INT_HANDLER WWDGT_IRQHandler
DECLARE_INT_HANDLER LVD_IRQHandler
DECLARE_INT_HANDLER TAMPER_IRQHandler
DECLARE_INT_HANDLER RTC_IRQHandler
DECLARE_INT_HANDLER FMC_IRQHandler
DECLARE_INT_HANDLER RCU_IRQHandler
DECLARE_INT_HANDLER EXTI0_IRQHandler
DECLARE_INT_HANDLER EXTI1_IRQHandler
DECLARE_INT_HANDLER EXTI2_IRQHandler
DECLARE_INT_HANDLER EXTI3_IRQHandler
DECLARE_INT_HANDLER EXTI4_IRQHandler
DECLARE_INT_HANDLER DMA0_Channel0_IRQHandler
DECLARE_INT_HANDLER DMA0_Channel1_IRQHandler
DECLARE_INT_HANDLER DMA0_Channel2_IRQHandler
DECLARE_INT_HANDLER DMA0_Channel3_IRQHandler
DECLARE_INT_HANDLER DMA0_Channel4_IRQHandler
DECLARE_INT_HANDLER DMA0_Channel5_IRQHandler
DECLARE_INT_HANDLER DMA0_Channel6_IRQHandler
DECLARE_INT_HANDLER ADC0_1_IRQHandler
DECLARE_INT_HANDLER CAN0_TX_IRQHandler
DECLARE_INT_HANDLER CAN0_RX0_IRQHandler
DECLARE_INT_HANDLER CAN0_RX1_IRQHandler
DECLARE_INT_HANDLER CAN0_EWMC_IRQHandler
DECLARE_INT_HANDLER EXTI5_9_IRQHandler
DECLARE_INT_HANDLER TIMER0_BRK_IRQHandler
DECLARE_INT_HANDLER TIMER0_UP_IRQHandler
DECLARE_INT_HANDLER TIMER0_TRG_CMT_IRQHandler
DECLARE_INT_HANDLER TIMER0_Channel_IRQHandler
DECLARE_INT_HANDLER TIMER1_IRQHandler
DECLARE_INT_HANDLER TIMER2_IRQHandler
DECLARE_INT_HANDLER TIMER3_IRQHandler
DECLARE_INT_HANDLER I2C0_EV_IRQHandler
DECLARE_INT_HANDLER I2C0_ER_IRQHandler
DECLARE_INT_HANDLER I2C1_EV_IRQHandler
DECLARE_INT_HANDLER I2C1_ER_IRQHandler
DECLARE_INT_HANDLER SPI0_IRQHandler
DECLARE_INT_HANDLER SPI1_IRQHandler
DECLARE_INT_HANDLER USART0_IRQHandler
DECLARE_INT_HANDLER USART1_IRQHandler
DECLARE_INT_HANDLER USART2_IRQHandler
DECLARE_INT_HANDLER EXTI10_15_IRQHandler
DECLARE_INT_HANDLER RTC_Alarm_IRQHandler
DECLARE_INT_HANDLER USBFS_WKUP_IRQHandler
DECLARE_INT_HANDLER default_intexc_handler
DECLARE_INT_HANDLER default_intexc_handler
DECLARE_INT_HANDLER default_intexc_handler
DECLARE_INT_HANDLER default_intexc_handler
DECLARE_INT_HANDLER default_intexc_handler
DECLARE_INT_HANDLER EXMC_IRQHandler
DECLARE_INT_HANDLER default_intexc_handler
DECLARE_INT_HANDLER TIMER4_IRQHandler
DECLARE_INT_HANDLER SPI2_IRQHandler
DECLARE_INT_HANDLER UART3_IRQHandler
DECLARE_INT_HANDLER UART4_IRQHandler
DECLARE_INT_HANDLER TIMER5_IRQHandler
DECLARE_INT_HANDLER TIMER6_IRQHandler
DECLARE_INT_HANDLER DMA1_Channel0_IRQHandler
DECLARE_INT_HANDLER DMA1_Channel1_IRQHandler
DECLARE_INT_HANDLER DMA1_Channel2_IRQHandler
DECLARE_INT_HANDLER DMA1_Channel3_IRQHandler
DECLARE_INT_HANDLER DMA1_Channel4_IRQHandler
DECLARE_INT_HANDLER default_intexc_handler
DECLARE_INT_HANDLER default_intexc_handler
DECLARE_INT_HANDLER CAN1_TX_IRQHandler
DECLARE_INT_HANDLER CAN1_RX0_IRQHandler
DECLARE_INT_HANDLER CAN1_RX1_IRQHandler
DECLARE_INT_HANDLER CAN1_EWMC_IRQHandler
DECLARE_INT_HANDLER USBFS_IRQHandler
.extern Gd32vf103Start
.extern SystemInit
.extern _premain_init
.section .init
.globl _start
.type _start, @function
/**
* Reset Handler called on controller reset
*/
_start:
/* ===== Startup Stage 1 ===== */
/* Disable Global Interrupt */
csrc CSR_MSTATUS, MSTATUS_MIE
/* Jump to logical address first to ensure correct operation of RAM region */
la a0, _start
li a1, 1
slli a1, a1, 29
bleu a1, a0, _start0800
srli a1, a1, 2
bleu a1, a0, _start0800
la a0, _start0800
add a0, a0, a1
jr a0
_start0800:
/* Initialize GP and Stack Pointer SP */
.option push
.option norelax
la gp, __global_pointer$
.option pop
la sp, _sp
/*
* Set the the NMI base mnvec to share
* with mtvec by setting CSR_MMISC_CTL
* bit 9 NMI_CAUSE_FFF to 1
*/
li t0, MMISC_CTL_NMI_CAUSE_FFF
csrs CSR_MMISC_CTL, t0
/*
* Intialize ECLIC vector interrupt
* base address mtvt to vector_base
*/
la t0, vector_base
csrw CSR_MTVT, t0
/*
* Set ECLIC non-vector entry to be controlled
* by mtvt2 CSR register.
* Intialize ECLIC non-vector interrupt
* base address mtvt2 to irq_entry.
*/
la t0, irq_entry
csrw CSR_MTVT2, t0
csrs CSR_MTVT2, 0x1
/*
* Set Exception Entry MTVEC to exc_entry
* Due to settings above, Exception and NMI
* will share common entry.
*/
la t0, exc_entry
csrw CSR_MTVEC, t0
/* Set the interrupt processing mode to ECLIC mode */
li t0, 0x3f
csrc CSR_MTVEC, t0
csrs CSR_MTVEC, 0x3
/* ===== Startup Stage 2 ===== */
#if defined(__riscv_flen) && __riscv_flen > 0
/* Enable FPU */
li t0, MSTATUS_FS
csrs mstatus, t0
csrw fcsr, x0
#endif
/* Enable mcycle and minstret counter */
csrci CSR_MCOUNTINHIBIT, 0x5
/* ===== Startup Stage 3 ===== */
/*
* Load code section from FLASH to ILM
* when code LMA is different with VMA
*/
la a0, _ilm_lma
la a1, _ilm
/* If the ILM phy-address same as the logic-address, then quit */
beq a0, a1, 2f
la a2, _eilm
bgeu a1, a2, 2f
1:
/* Load code section if necessary */
lw t0, (a0)
sw t0, (a1)
addi a0, a0, 4
addi a1, a1, 4
bltu a1, a2, 1b
2:
/* Load data section */
la a0, _data_lma
la a1, _data
la a2, _edata
bgeu a1, a2, 2f
1:
lw t0, (a0)
sw t0, (a1)
addi a0, a0, 4
addi a1, a1, 4
bltu a1, a2, 1b
2:
/* Clear bss section */
la a0, __bss_start
la a1, _end
bgeu a0, a1, 2f
1:
sw zero, (a0)
addi a0, a0, 4
bltu a0, a1, 1b
2:
/*
* Call vendor defined SystemInit to
* initialize the micro-controller system
*/
call SystemInit
/* Call global constructors */
la a0, __libc_fini_array
call atexit
/* Call C/C++ constructor start up code */
call __libc_init_array
/* do pre-init steps before main */
call _premain_init
/* ===== Call entry Function ===== */
/* argc = argv = 0 */
li a0, 0
li a1, 0
j Gd32vf103Start
1:
j 1b

View File

@ -0,0 +1,61 @@
/**
* @file interrupt.c
* @brief support gap8 interrupt enable and disable
* @version 1.0
* @author AIIT XUOS Lab
* @date 2021-09-02
*/
#include <arch_interrupt.h>
#include <xs_base.h>
#include <xs_isr.h>
#include <core_feature_base.h>
int ArchDisableHwIrq(uint32_t irq_num)
{
ECLIC_DisableIRQ(irq_num);
return 0;
}
int ArchEnableHwIrq(uint32_t irq_num)
{
ECLIC_EnableIRQ(irq_num);
return 0;
}
x_base DisableLocalInterrupt(void)
{
return __RV_CSR_READ_CLEAR(CSR_MSTATUS, MSTATUS_MIE);
}
/****************************************************************************
* Name: EnableLocalInterrupt
*
* Description:
* Return the current interrupt state and enable interrupts
*
****************************************************************************/
void EnableLocalInterrupt(x_base oldstat)
{
__RV_CSR_WRITE(CSR_MSTATUS, oldstat);
}
// extern void KTaskOsAssignAfterIrq(void *context);
// void IsrEntry()
// {
// uint32 ipsr;
// isrManager.done->incCounter();
// isrManager.done->handleIrq(ipsr);
// KTaskOsAssignAfterIrq(NONE);
// isrManager.done->decCounter();
// }

View File

@ -0,0 +1,232 @@
/*
* Copyright (c) 2019 Nuclei 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.
*/
/******************************************************************************
* \file intexc_gd32vf103.S
* \brief NMSIS Interrupt and Exception Handling Template File
* for Device gd32vf103
* \version V1.00
* \date 7 Jan 2020
*
******************************************************************************/
#include "riscv_encoding.h"
/**
* \brief Global interrupt disabled
* \details
* This function disable global interrupt.
* \remarks
* - All the interrupt requests will be ignored by CPU.
*/
.macro DISABLE_MIE
csrc CSR_MSTATUS, MSTATUS_MIE
.endm
/**
* \brief Macro for context save
* \details
* This macro save ABI defined caller saved registers in the stack.
* \remarks
* - This Macro could use to save context when you enter to interrupt
* or exception
*/
/* Save caller registers */
.macro SAVE_CONTEXT
/* Allocate stack space for context saving */
#ifndef __riscv_32e
addi sp, sp, -20*REGBYTES
#else
addi sp, sp, -14*REGBYTES
#endif /* __riscv_32e */
STORE x1, 0*REGBYTES(sp)
STORE x4, 1*REGBYTES(sp)
STORE x5, 2*REGBYTES(sp)
STORE x6, 3*REGBYTES(sp)
STORE x7, 4*REGBYTES(sp)
STORE x10, 5*REGBYTES(sp)
STORE x11, 6*REGBYTES(sp)
STORE x12, 7*REGBYTES(sp)
STORE x13, 8*REGBYTES(sp)
STORE x14, 9*REGBYTES(sp)
STORE x15, 10*REGBYTES(sp)
#ifndef __riscv_32e
STORE x16, 14*REGBYTES(sp)
STORE x17, 15*REGBYTES(sp)
STORE x28, 16*REGBYTES(sp)
STORE x29, 17*REGBYTES(sp)
STORE x30, 18*REGBYTES(sp)
STORE x31, 19*REGBYTES(sp)
#endif /* __riscv_32e */
.endm
/**
* \brief Macro for restore caller registers
* \details
* This macro restore ABI defined caller saved registers from stack.
* \remarks
* - You could use this macro to restore context before you want return
* from interrupt or exeception
*/
/* Restore caller registers */
.macro RESTORE_CONTEXT
LOAD x1, 0*REGBYTES(sp)
LOAD x4, 1*REGBYTES(sp)
LOAD x5, 2*REGBYTES(sp)
LOAD x6, 3*REGBYTES(sp)
LOAD x7, 4*REGBYTES(sp)
LOAD x10, 5*REGBYTES(sp)
LOAD x11, 6*REGBYTES(sp)
LOAD x12, 7*REGBYTES(sp)
LOAD x13, 8*REGBYTES(sp)
LOAD x14, 9*REGBYTES(sp)
LOAD x15, 10*REGBYTES(sp)
#ifndef __riscv_32e
LOAD x16, 14*REGBYTES(sp)
LOAD x17, 15*REGBYTES(sp)
LOAD x28, 16*REGBYTES(sp)
LOAD x29, 17*REGBYTES(sp)
LOAD x30, 18*REGBYTES(sp)
LOAD x31, 19*REGBYTES(sp)
/* De-allocate the stack space */
addi sp, sp, 20*REGBYTES
#else
/* De-allocate the stack space */
addi sp, sp, 14*REGBYTES
#endif /* __riscv_32e */
.endm
/**
* \brief Macro for save necessary CSRs to stack
* \details
* This macro store MCAUSE, MEPC, MSUBM to stack.
*/
.macro SAVE_CSR_CONTEXT
/* Store CSR mcause to stack using pushmcause */
csrrwi x0, CSR_PUSHMCAUSE, 11
/* Store CSR mepc to stack using pushmepc */
csrrwi x0, CSR_PUSHMEPC, 12
/* Store CSR msub to stack using pushmsub */
csrrwi x0, CSR_PUSHMSUBM, 13
.endm
/**
* \brief Macro for restore necessary CSRs from stack
* \details
* This macro restore MSUBM, MEPC, MCAUSE from stack.
*/
.macro RESTORE_CSR_CONTEXT
LOAD x5, 13*REGBYTES(sp)
csrw CSR_MSUBM, x5
LOAD x5, 12*REGBYTES(sp)
csrw CSR_MEPC, x5
LOAD x5, 11*REGBYTES(sp)
csrw CSR_MCAUSE, x5
.endm
/**
* \brief Exception/NMI Entry
* \details
* This function provide common entry functions for exception/nmi.
* \remarks
* This function provide a default exception/nmi entry.
* ABI defined caller save register and some CSR registers
* to be saved before enter interrupt handler and be restored before return.
*/
.section .text.trap
/* In CLIC mode, the exeception entry must be 64bytes aligned */
.align 6
.global exc_entry
.weak exc_entry
exc_entry:
/* Save the caller saving registers (context) */
SAVE_CONTEXT
/* Save the necessary CSR registers */
SAVE_CSR_CONTEXT
/*
* Set the exception handler function arguments
* argument 1: mcause value
* argument 2: current stack point(SP) value
*/
csrr a0, mcause
mv a1, sp
/*
* TODO: Call the exception handler function
* By default, the function template is provided in
* system_Device.c, you can adjust it as you want
*/
call core_exception_handler
/* Restore the necessary CSR registers */
RESTORE_CSR_CONTEXT
/* Restore the caller saving registers (context) */
RESTORE_CONTEXT
/* Return to regular code */
mret
/**
* \brief Non-Vector Interrupt Entry
* \details
* This function provide common entry functions for handling
* non-vector interrupts
* \remarks
* This function provide a default non-vector interrupt entry.
* ABI defined caller save register and some CSR registers need
* to be saved before enter interrupt handler and be restored before return.
*/
.section .text.irq
/* In CLIC mode, the interrupt entry must be 4bytes aligned */
.align 2
.global irq_entry
.weak irq_entry
/* This label will be set to MTVT2 register */
irq_entry:
/* Save the caller saving registers (context) */
SAVE_CONTEXT
/* Save the necessary CSR registers */
SAVE_CSR_CONTEXT
/* This special CSR read/write operation, which is actually
* claim the CLIC to find its pending highest ID, if the ID
* is not 0, then automatically enable the mstatus.MIE, and
* jump to its vector-entry-label, and update the link register
*/
csrrw ra, CSR_JALMNXTI, ra
/* Critical section with interrupts disabled */
DISABLE_MIE
/* Restore the necessary CSR registers */
RESTORE_CSR_CONTEXT
/* Restore the caller saving registers (context) */
RESTORE_CONTEXT
/* Return to regular code */
mret
/* Default Handler for Exceptions / Interrupts */
.global default_intexc_handler
.weak default_intexc_handler
Undef_Handler:
default_intexc_handler:
1:
j 1b

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.
*/
#include <xs_ktick.h>
#include <gd32vf103.h>
#include <core_feature_timer.h>
#define SysTick_Handler eclic_mtip_handler
/* This is the timer interrupt service routine. */
void SysTick_Handler(void)
{
SysTick_Reload(SYSTICK_TICK_CONST);
// isrManager.done->incCounter();
TickAndTaskTimesliceUpdate();
// isrManager.done->decCounter();
}

View File

@ -0,0 +1,31 @@
mainmenu "XiUOS Project Configuration"
config BSP_DIR
string
option env="BSP_ROOT"
default "."
config KERNEL_DIR
string
option env="KERNEL_ROOT"
default "../.."
config BOARD_GD32VF103RVSTAR
bool
select ARCH_RISCV
default y
source "$KERNEL_DIR/arch/Kconfig"
menu "gd32vf103_rvstar feature"
source "$BSP_DIR/third_party_driver/Kconfig"
endmenu
menu "Hardware feature"
source "$KERNEL_DIR/resources/Kconfig"
endmenu
source "$KERNEL_DIR/Kconfig"

View File

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

View File

@ -0,0 +1,175 @@
# 从零开始构建矽璓工业物联操作系统使用risc-v架构的gapuino 开发板
[XiUOS](http://xuos.io/) (X Industrial Ubiquitous Operating System) 矽璓工业物联操作系统是一款面向工业物联场景的泛在操作系统,来自泛在操作系统研究计划。所谓泛在操作系统(UOS: Ubiquitous Operating Systems)是支持互联网时代人机物融合泛在计算应用模式的新型操作系统是传统操作系统概念的泛化与延伸。在泛在操作系统技术体系中不同的泛在计算设备和泛在应用场景需要符合各自特性的不同UOSXiUOS即是面向工业物联场景的一种UOS主要由一个极简的微型实时操作系统(RTOS)内核和其上的智能工业物联框架构成,支持工业物联网(IIoT: Industrial Internet of Things)应用。
## 开发环境搭建
### 推荐使用:
**操作系统:** ubuntu18.04 [https://ubuntu.com/download/desktop](https://ubuntu.com/download/desktop)
**开发工具推荐使用 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
$ sudo apt install gcc make libncurses5-dev openssl libssl-dev bison flex libelf-dev autoconf libtool gperf libc6-dev git
```
**源码下载:** XiUOS [https://forgeplus.trustie.net/projects/xuos/xiuos](https://forgeplus.trustie.net/projects/xuos/xiuos)
新建一个空文件夹并进入文件夹中,并下载源码,具体命令如下:
```c
mkdir test && cd test
git clone https://git.trustie.net/xuos/xiuos.git
```
打开源码文件包可以看到以下目录:
| 名称 | 说明 |
| -- | -- |
| application | 应用代码 |
| board | 板级支持包 |
| framework | 应用框架 |
| fs | 文件系统 |
| kernel | 内核源码 |
| resources | 驱动文件 |
| tool | 系统工具 |
使用VScode打开代码具体操作步骤为在源码文件夹下打开系统终端输入`code .`即可打开VScode开发环境如下图所示
![vscode](img/vscode.jpg)
### 裁减配置工具的下载
裁减配置工具:
**工具地址:** 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://git.trustie.net/xuos/kconfig-frontends.git
```
下载源码后按以下步骤执行软件安装:
```c
cd kconfig-frontends
./xs_build.sh
```
### 编译工具链:
RISC-V: riscv-none-embed-默认安装到Ubuntu的/opt/,下载源码并解压。[下载网址 http://101.36.126.201:8011/gnu-mcu-eclipse.tar.bz2](http://101.36.126.201:8011/gnu-mcu-eclipse.tar.bz2)
```shell
$ tar -xjf gnu-mcu-eclipse.tar.bz2 -C /opt/
```
将上述解压的编译工具链的路径添加到board/hifive1-rev-B/config.mk文件当中例如
```
export CROSS_COMPILE ?=/opt/gnu-mcu-eclipse/riscv-none-gcc/8.2.0-2.1-20190425-1021/bin/riscv-none-embed-
```
若已存在`export CROSS_COMPILE ?=xxxx` 应该将原有的语句注释,再写入上面的语句。
# 在gapuino board 上创建第一个应用
## 1.gapuino board 简介
| 硬件 | 描述 |
| -- | -- |
|芯片型号| gap8 |
|架构| RV32IMAC |
|主频| 200+MHz |
|片内SRAM| 512KB |
| 外设 | UART、SPI、I2C |
XiUOS板级当前支持使用UART。
## 2. 代码编写与编译说明
编辑环境:`VScode`
编译工具链:`riscv-none-embed-gcc`
使用`VScode`打开工程的方法有多种,本文介绍一种快捷键,在项目目录下将`code .`输入终端即可打开目标项目
修改`applications`文件夹下`main.c`
在输出函数中写入 Hello, world! \n 完成代码编辑。
编译步骤:
1.在VScode终端下执行以下命令生成配置文件
```
make BOARD=gapuino menuconfig
```
2.在menuconfig界面配置需要关闭和开启的功能按回车键进入下级菜单按Y键选中需要开启的功能按N键选中需要关闭的功能配置结束后选择Exit保存并退出
![menuconfig](img/menuconfig.png)
3.继续执行以下命令,进行编译
```
make BOARD=gapuino
```
4.如果编译正确无误build文件夹下会产生XiUOS_gapuino.elf、XiUOS_gapuino.bin文件。
>注:最后可以执行以下命令,清除配置文件和编译生成的文件
```
make BOARD=gapuino distclean
```
## 3. 烧写及执行
gapuino支持jtag可以通过jtag进行烧录和调试。
调试烧写需要下载gap sdk和openocd,下载配置方法参见以下文档:
https://greenwaves-technologies.com/setting-up-sdk/
在SDK 和openocd安装完成以后按照如下步骤进行调试
1、进入sdk目录路径下
```
cd ~/gap_sdk
```
2、在当前终端输入
```
source sourceme.sh
```
出现如下图所示的界面输入7选择单板名称
![choose](./img/choose_board.png)
3、先按开发板的复位键再在当前终端输入
```
gap8-openocd -f interface/ftdi/gapuino_ftdi.cfg -f target/gap8.tcl -f tcl/jtag_boot_entry.tcl
```
在当前终端连接openocd连接如下图所示
![openocd](./img/openocd.png)
4、打开一个新的终端输入以下命令打开终端串口
```
sudo apt install screen
screen /dev/ttyUSB0 115200
```
5、打开一个新的终端进入编译生成的elf路径,输入例如:
```
riscv32-unknown-elf-gdb build/XiUOS_gapuino.elf -ex "target remote localhost:3333"
```
结果如下图所示:
![gdb](./img/gdb_load.png)
6、再输入load最后输入continue命令即可在串口终端看到系统运行界面如下图所示
![terminal](./img/terminal.png)

View File

@ -0,0 +1,86 @@
/*
* 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.c
* @brief support gap8 init configure and start-up
* @version 1.0
* @author AIIT XUOS Lab
* @date 2021-09-02
*/
#include <board.h>
#include <xiuos.h>
#include <device.h>
#include <nuclei_sdk_soc.h>
// #include <gd32vf103.h>
#include <core_feature_timer.h>
extern void entry(void);
extern int InitHwUart();
#ifndef configKERNEL_INTERRUPT_PRIORITY
#define configKERNEL_INTERRUPT_PRIORITY 0
#endif
void xPortTaskSwitch(void)
{
/* Clear Software IRQ, A MUST */
SysTimer_ClearSWIRQ();
isrManager.done->setSwitchTrigerFlag();
}
void vPortSetupTimerInterrupt(void)
{
uint64_t ticks = SYSTICK_TICK_CONST;
/* Make SWI and SysTick the lowest priority interrupts. */
/* Stop and clear the SysTimer. SysTimer as Non-Vector Interrupt */
SysTick_Config(ticks);
ECLIC_DisableIRQ(SysTimer_IRQn);
ECLIC_SetLevelIRQ(SysTimer_IRQn, configKERNEL_INTERRUPT_PRIORITY);
ECLIC_SetShvIRQ(SysTimer_IRQn, ECLIC_NON_VECTOR_INTERRUPT);
ECLIC_EnableIRQ(SysTimer_IRQn);
/* Set SWI interrupt level to lowest level/priority, SysTimerSW as Vector Interrupt */
ECLIC_SetShvIRQ(SysTimerSW_IRQn, ECLIC_VECTOR_INTERRUPT);
ECLIC_SetLevelIRQ(SysTimerSW_IRQn, configKERNEL_INTERRUPT_PRIORITY);
ECLIC_EnableIRQ(SysTimerSW_IRQn);
}
void Gd32vf103Start(void)
{
entry();
}
void InitBoardHardware(void)
{
vPortSetupTimerInterrupt();
InitBoardMemory(MEMORY_START_ADDRESS, MEMORY_END_ADDRESS);
InitHwUart();
InstallConsole("uart4", "uart4_drv", "uart4_dev4");
KPrintf("console init completed.\n");
KPrintf("board initialization......\n");
// InitHwTick();
KPrintf("memory address range: [0x%08x - 0x%08x], size: %d\n", (x_ubase) MEMORY_START_ADDRESS, (x_ubase) MEMORY_END_ADDRESS, gd32vf103_SRAM_SIZE);
/* initialize memory system */
KPrintf("board init done.\n");
KPrintf("start kernel...\n");
return;
}

View File

@ -0,0 +1,67 @@
/*
* 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 gapuino-board init configure and start-up function
* @version 1.0
* @author AIIT XUOS Lab
* @date 2021-09-02
*/
/*************************************************
File name: board.h
Description: define gapuino-board init configure and start-up function
Others:
History:
1. Date: 2021-09-02
Author: AIIT XUOS Lab
Modification:
1. define gapuino-board InitBoardHardware
2. define gapuino-board data and bss struct
*************************************************/
#ifndef BOARD_H__
#define BOARD_H__
#include <xsconfig.h>
#include <stdint.h>
#ifndef __ASSEMBLY__
#undef EXTERN
#if defined(__cplusplus)
#define EXTERN extern "C"
extern "C"
{
#else
#define EXTERN extern
#endif
extern unsigned int __bss_start__;
extern unsigned int __bss_end__;
extern unsigned int _end;
extern unsigned int __stack_end__;
extern unsigned int g_service_table_start;
extern unsigned int g_service_table_end;
#define MEMORY_START_ADDRESS (void*)(&_end)
#define gd32vf103_SRAM_SIZE 0x00008000
#define MEMORY_END_ADDRESS (void*)(0x20000000 + gd32vf103_SRAM_SIZE)
#undef EXTERN
#if defined(__cplusplus)
}
#endif
#endif
#endif

View File

@ -0,0 +1,34 @@
# export CFLAGS := -mcmodel=medany -march=rv32imac -mabi=ilp32 -fno-common -ffunction-sections -fdata-sections -fstrict-volatile-bitfields -O0 -ggdb -fgnu89-inline -Werror
# export AFLAGS := -c -mcmodel=medany -march=rv32imac -mabi=ilp32 -x assembler-with-cpp -ggdb
# export LFLAGS := --specs=nano.specs --specs=nosys.specs -nostartfiles -Wl,--gc-sections,-Map=XiUOS_gd32vf103.map,-cref,-u,_start -T $(BSP_ROOT)/link.lds
# export APPLFLAGS := -mcmodel=medany -march=rv32imac -mabi=ilp32 -nostartfiles -Wl,--gc-sections,-Map=XiUOS_app.map,-cref,-u, -T $(BSP_ROOT)/link_userspace.lds
# export CXXFLAGS := -mcmodel=medany -march=rv32imac -mabi=ilp32 -fno-common -ffunction-sections -fdata-sections -fstrict-volatile-bitfields -O0 -ggdb -Werror
# export CROSS_COMPILE ?=/opt/Nuclei/gcc/bin/riscv-nuclei-elf-
# export DEFINES := -DHAVE_CCONFIG_H -DHAVE_SIGINFO
# export ARCH = risc-v
# export MCU = GD32VF103
export CFLAGS := -march=rv32imac -mabi=ilp32 -fno-common -ffunction-sections -fdata-sections -O0 -ggdb -fgnu89-inline -Werror
export AFLAGS := -march=rv32imac -mabi=ilp32 -x assembler-with-cpp -ggdb
export LFLAGS := -march=rv32imac -mabi=ilp32 -nostartfiles -Wl,--gc-sections,-Map=XiUOS_gd32vf103.map,-cref,-u,_start -T $(BSP_ROOT)/link.lds
export APPLFLAGS := -nostartfiles -Wl,--gc-sections,-Map=XiUOS_app.map,-cref,-u, -T $(BSP_ROOT)/link_userspace.lds
export CXXFLAGS := -fno-common -ffunction-sections -fdata-sections -fstrict-volatile-bitfields -O0 -ggdb -Werror
export CROSS_COMPILE ?=/opt/Nuclei/gcc/bin/riscv-nuclei-elf-
export DEFINES := -DHAVE_CCONFIG_H -DHAVE_SIGINFO
export ARCH = risc-v
export MCU = GD32VF103

View File

@ -0,0 +1,191 @@
/*!
* \file gd32vf103c_start.c
* \brief firmware functions to manage leds, keys, COM ports
*
* \version 2020-02-05, V1.0.0, rvstar board functions for GD32VF103
*/
/*
Copyright (c) 2019, GigaDevice Semiconductor Inc.
Redistribution and use in source and binary forms, with or without modification,
are permitted provided that the following conditions are met:
1. Redistributions of source code must retain the above copyright notice, this
list of conditions and the following disclaimer.
2. Redistributions in binary form must reproduce the above copyright notice,
this list of conditions and the following disclaimer in the documentation
and/or other materials provided with the distribution.
3. Neither the name of the copyright holder nor the names of its contributors
may be used to endorse or promote products derived from this software without
specific prior written permission.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED.
IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT,
INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT
NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY
OF SUCH DAMAGE.
*/
#include "gd32vf103v_rvstar.h"
// /* private variables */
// static const uint32_t GPIO_PORT[LEDn] = {LEDG_GPIO_PORT, LEDB_GPIO_PORT, LEDR_GPIO_PORT};
// static const uint32_t GPIO_PIN[LEDn] = {LEDG_PIN, LEDB_PIN, LEDR_PIN};
// static const rcu_periph_enum GPIO_CLK[LEDn] = {LEDG_GPIO_CLK, LEDB_GPIO_CLK, LEDR_GPIO_CLK};
// static const uint32_t KEY_PORT[KEYn] = {WAKEUP_KEY_GPIO_PORT};
// static const uint32_t KEY_PIN[KEYn] = {WAKEUP_KEY_PIN};
// static const rcu_periph_enum KEY_CLK[KEYn] = {WAKEUP_KEY_GPIO_CLK};
// static const exti_line_enum KEY_EXTI_LINE[KEYn] = {WAKEUP_KEY_EXTI_LINE};
// static const uint8_t KEY_PORT_SOURCE[KEYn] = {WAKEUP_KEY_EXTI_PORT_SOURCE};
// static const uint8_t KEY_PIN_SOURCE[KEYn] = {WAKEUP_KEY_EXTI_PIN_SOURCE};
// static const uint8_t KEY_IRQn[KEYn] = {WAKEUP_KEY_EXTI_IRQn};
/* eval board low layer private functions */
/*!
* \brief configure led GPIO
* \param[in] lednum: specify the led to be configured
* \arg LED1
* \param[out] none
* \retval none
*/
// void gd_led_init(led_typedef_enum lednum)
// {
// /* enable the led clock */
// rcu_periph_clock_enable(GPIO_CLK[lednum]);
// /* configure led GPIO port */
// gpio_init(GPIO_PORT[lednum], GPIO_MODE_OUT_PP, GPIO_OSPEED_50MHZ, GPIO_PIN[lednum]);
// GPIO_BOP(GPIO_PORT[lednum]) = GPIO_PIN[lednum];
// }
/*!
* \brief turn on selected led
* \param[in] lednum: specify the led to be turned on
* \arg LED1
* \param[out] none
* \retval none
*/
// void gd_led_on(led_typedef_enum lednum)
// {
// GPIO_BC(GPIO_PORT[lednum]) = GPIO_PIN[lednum];
// }
/*!
* \brief turn off selected led
* \param[in] lednum: specify the led to be turned off
* \arg LED1
* \param[out] none
* \retval none
*/
// void gd_led_off(led_typedef_enum lednum)
// {
// GPIO_BOP(GPIO_PORT[lednum]) = GPIO_PIN[lednum];
// }
/*!
* \brief toggle selected led
* \param[in] lednum: specify the led to be toggled
* \arg LED1
* \param[out] none
* \retval none
*/
// void gd_led_toggle(led_typedef_enum lednum)
// {
// gpio_bit_write(GPIO_PORT[lednum], GPIO_PIN[lednum],
// (bit_status)(1 - gpio_input_bit_get(GPIO_PORT[lednum], GPIO_PIN[lednum])));
// }
/*!
* \brief configure key
* \param[in] keynum: specify the key to be configured
* \arg KEY_WAKEUP: wakeup key
* \param[in] keymode: specify button mode
* \arg KEY_MODE_GPIO: key will be used as simple IO
* \arg KEY_MODE_EXTI: key will be connected to EXTI line with interrupt
* \param[out] none
* \retval none
*/
// void gd_key_init(key_typedef_enum keynum, keymode_typedef_enum keymode)
// {
// /* enable the key clock */
// rcu_periph_clock_enable(KEY_CLK[keynum]);
// rcu_periph_clock_enable(RCU_AF);
// /* configure button pin as input */
// gpio_init(KEY_PORT[keynum], GPIO_MODE_IN_FLOATING, GPIO_OSPEED_50MHZ, KEY_PIN[keynum]);
// if (keymode == KEY_MODE_EXTI) {
// /* enable and set key EXTI interrupt to the lowest priority */
// ECLIC_EnableIRQ(KEY_IRQn[keynum]);
// ECLIC_SetLevelIRQ(KEY_IRQn[keynum], 1);
// ECLIC_SetPriorityIRQ(KEY_IRQn[keynum], 1);
// /* connect key EXTI line to key GPIO pin */
// gpio_exti_source_select(KEY_PORT_SOURCE[keynum], KEY_PIN_SOURCE[keynum]);
// /* configure key EXTI line */
// exti_init(KEY_EXTI_LINE[keynum], EXTI_INTERRUPT, EXTI_TRIG_FALLING);
// exti_interrupt_flag_clear(KEY_EXTI_LINE[keynum]);
// }
// }
/*!
* \brief return the selected key state
* \param[in] keynum: specify the key to be checked
* \arg KEY_WAKEUP: wakeup key
* \param[out] none
* \retval the key's GPIO pin value
*/
// uint8_t gd_key_state_get(key_typedef_enum keynum)
// {
// return gpio_input_bit_get(KEY_PORT[keynum], KEY_PIN[keynum]);
// }
/*!
* \brief configure COM port
* \param[in] com: COM on the board
* \arg GD32_COM0: COM0 on the board
* \param[out] none
* \retval none
*/
void gd_com_init(uint32_t usart_periph)
{
/* enable GPIO TX and RX clock */
rcu_periph_clock_enable(GD32_COM_TX_GPIO_CLK);
rcu_periph_clock_enable(GD32_COM_RX_GPIO_CLK);
/* enable USART clock */
rcu_periph_clock_enable(GD32_COM_CLK);
/* connect port to USARTx_Tx */
gpio_init(GD32_COM_TX_GPIO_PORT, GPIO_MODE_AF_PP, GPIO_OSPEED_50MHZ, GD32_COM_TX_PIN);
/* connect port to USARTx_Rx */
gpio_init(GD32_COM_RX_GPIO_PORT, GPIO_MODE_IN_FLOATING, GPIO_OSPEED_50MHZ, GD32_COM_RX_PIN);
/* USART configure */
usart_deinit(usart_periph);
usart_baudrate_set(usart_periph, 115200U);
usart_word_length_set(usart_periph, USART_WL_8BIT);
usart_stop_bit_set(usart_periph, USART_STB_1BIT);
usart_parity_config(usart_periph, USART_PM_NONE);
usart_hardware_flow_rts_config(usart_periph, USART_RTS_DISABLE);
usart_hardware_flow_cts_config(usart_periph, USART_CTS_DISABLE);
usart_receive_config(usart_periph, USART_RECEIVE_ENABLE);
usart_transmit_config(usart_periph, USART_TRANSMIT_ENABLE);
usart_enable(usart_periph);
}

View File

@ -0,0 +1,131 @@
/*!
\file gd32vf103c_start.h
\brief definitions for GD32VF103C_START's leds, keys and COM ports hardware resources
\version 2019-06-05, V1.0.0, demo for GD32VF103
*/
/*
Copyright (c) 2019, GigaDevice Semiconductor Inc.
Redistribution and use in source and binary forms, with or without modification,
are permitted provided that the following conditions are met:
1. Redistributions of source code must retain the above copyright notice, this
list of conditions and the following disclaimer.
2. Redistributions in binary form must reproduce the above copyright notice,
this list of conditions and the following disclaimer in the documentation
and/or other materials provided with the distribution.
3. Neither the name of the copyright holder nor the names of its contributors
may be used to endorse or promote products derived from this software without
specific prior written permission.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED.
IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT,
INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT
NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY
OF SUCH DAMAGE.
*/
#ifndef GD32VF103C_RVSTART_H
#define GD32VF103C_RVSTART_H
#ifdef __cplusplus
extern "C" {
#endif
#include "nuclei_sdk_soc.h"
/* exported types */
typedef enum {
LED1 = 0,
LED2 = 1,
LED3 = 2,
LED_1 = 0,
LED_2 = 1,
LED_3 = 2
} led_typedef_enum;
typedef enum {
KEY_WAKEUP = 0,
} key_typedef_enum;
typedef enum {
KEY_MODE_GPIO = 0,
KEY_MODE_EXTI = 1
} keymode_typedef_enum;
// /* rvstar board low layer led */
// #define LEDn 3U
// #define LEDG_PIN GPIO_PIN_1
// #define LEDG_GPIO_PORT GPIOA
// #define LEDG_GPIO_CLK RCU_GPIOA
// #define LEDB_PIN GPIO_PIN_3
// #define LEDB_GPIO_PORT GPIOA
// #define LEDB_GPIO_CLK RCU_GPIOA
// #define LEDR_PIN GPIO_PIN_2
// #define LEDR_GPIO_PORT GPIOA
// #define LEDR_GPIO_CLK RCU_GPIOA
/* rvstar board UART com port */
#define GD32_COM0 UART4
#define GD32_COM_CLK RCU_UART4
#define GD32_COM_TX_PIN GPIO_PIN_12
#define GD32_COM_RX_PIN GPIO_PIN_2
#define GD32_COM_TX_GPIO_PORT GPIOC
#define GD32_COM_RX_GPIO_PORT GPIOD
#define GD32_COM_TX_GPIO_CLK RCU_GPIOC
#define GD32_COM_RX_GPIO_CLK RCU_GPIOD
/* rvstar board low layer button */
#define KEYn (1U)
/* wakeup push-button */
#define WAKEUP_KEY_PIN GPIO_PIN_0
#define WAKEUP_KEY_GPIO_PORT GPIOA
#define WAKEUP_KEY_GPIO_CLK RCU_GPIOA
#define WAKEUP_KEY_EXTI_LINE EXTI_0
#define WAKEUP_KEY_EXTI_PORT_SOURCE GPIO_PORT_SOURCE_GPIOA
#define WAKEUP_KEY_EXTI_PIN_SOURCE GPIO_PIN_SOURCE_0
#define WAKEUP_KEY_EXTI_IRQn EXTI0_IRQn
/* function declarations */
/* configure led GPIO */
void gd_led_init(led_typedef_enum lednum);
/* turn on selected led */
void gd_led_on(led_typedef_enum lednum);
/* turn off selected led */
void gd_led_off(led_typedef_enum lednum);
/* toggle the selected led */
void gd_led_toggle(led_typedef_enum lednum);
/* configure key */
void gd_key_init(key_typedef_enum keynum, keymode_typedef_enum keymode);
/* return the selected key state */
uint8_t gd_key_state_get(key_typedef_enum keynum);
/* configure COM port */
void gd_com_init(uint32_t usart_periph);
/* Defines for LED functions to new / general API */
#define gd_rvstar_led_init gd_led_init
#define gd_rvstar_led_on gd_led_on
#define gd_rvstar_led_off gd_led_off
#define gd_rvstar_led_toggle gd_led_toggle
#define gd_rvstar_key_init gd_key_init
#define gd_rvstar_key_state_get gd_key_state_get
#ifdef __cplusplus
}
#endif
#endif /* GD32VF103V_RVSTART_H */

View File

@ -0,0 +1,299 @@
/*
* Copyright (c) 2019 Nuclei 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.
*/
/******************************************************************************
* @file gcc_Device.ld
* @brief GNU Linker Script for gd32vf103 based device
* @version V1.0.0
* @date 17. Dec 2019
******************************************************************************/
/*********** Use Configuration Wizard in Context Menu *************************/
OUTPUT_ARCH( "riscv" )
/********************* Flash Configuration ************************************
* <h> Flash Configuration
* <o0> Flash Base Address <0x0-0xFFFFFFFF:8>
* <o1> Flash Size (in Bytes) <0x0-0xFFFFFFFF:8>
* </h>
*/
__ROM_BASE = 0x08000000;
__ROM_SIZE = 0x00020000;
/*--------------------- ILM RAM Configuration ---------------------------
* <h> ILM RAM Configuration
* <o0> ILM RAM Base Address <0x0-0xFFFFFFFF:8>
* <o1> ILM RAM Size (in Bytes) <0x0-0xFFFFFFFF:8>
* </h>
*/
__ILM_RAM_BASE = 0x80000000;
__ILM_RAM_SIZE = 0x00010000;
/*--------------------- Embedded RAM Configuration ---------------------------
* <h> RAM Configuration
* <o0> RAM Base Address <0x0-0xFFFFFFFF:8>
* <o1> RAM Size (in Bytes) <0x0-0xFFFFFFFF:8>
* </h>
*/
__RAM_BASE = 0x20000000;
__RAM_SIZE = 0x00005000;
/********************* Stack / Heap Configuration ****************************
* <h> Stack / Heap Configuration
* <o0> Stack Size (in Bytes) <0x0-0xFFFFFFFF:8>
* <o1> Heap Size (in Bytes) <0x0-0xFFFFFFFF:8>
* </h>
*/
__STACK_SIZE = 0x00000800;
__HEAP_SIZE = 0x00000800;
/**************************** end of configuration section ********************/
/* Define base address and length of flash and ram */
MEMORY
{
flash (rxai!w) : ORIGIN = __ROM_BASE, LENGTH = __ROM_SIZE
ram (wxa!ri) : ORIGIN = __RAM_BASE, LENGTH = __RAM_SIZE
}
/* Linker script to place sections and symbol values. Should be used together
* with other linker script that defines memory regions FLASH,ILM and RAM.
* It references following symbols, which must be defined in code:
* _Start : Entry of reset handler
*
* It defines following symbols, which code can use without definition:
* _ilm_lma
* _ilm
* __etext
* _etext
* etext
* _eilm
* __preinit_array_start
* __preinit_array_end
* __init_array_start
* __init_array_end
* __fini_array_start
* __fini_array_end
* _data_lma
* _edata
* edata
* __data_end__
* __bss_start
* __fbss
* _end
* end
* __heap_end
* __StackLimit
* __StackTop
* __STACK_SIZE
*/
/* Define entry label of program */
ENTRY(_start)
SECTIONS
{
__STACK_SIZE = DEFINED(__STACK_SIZE) ? __STACK_SIZE : 2K;
.init :
{
/* vector table locate at flash */
*(.vtable)
KEEP (*(SORT_NONE(.init)))
} >flash AT>flash
.ilalign :
{
. = ALIGN(4);
/* Create a section label as _ilm_lma which located at flash */
PROVIDE( _ilm_lma = . );
} >flash AT>flash
.ialign :
{
/* Create a section label as _ilm which located at flash */
PROVIDE( _ilm = . );
} >flash AT>flash
/* Code section located at flash */
.text :
{
*(.text.unlikely .text.unlikely.*)
*(.text.startup .text.startup.*)
*(.text .text.*)
/* section information for shell */
. = ALIGN(4);
_shell_command_start = .;
KEEP (*(shellCommand))
_shell_command_end = .;
. = ALIGN(4);
PROVIDE(__ctors_start__ = .);
KEEP (*(SORT(.init_array.*)))
KEEP (*(.init_array))
PROVIDE(__ctors_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(.));
*(.gnu.linkonce.t.*)
} >flash AT>flash
.rodata : ALIGN(4)
{
. = ALIGN(4);
*(.rdata)
*(.rodata .rodata.*)
/* section information for initial. */
. = ALIGN(4);
*(.gnu.linkonce.r.*)
. = ALIGN(8);
*(.srodata.cst16)
*(.srodata.cst8)
*(.srodata.cst4)
*(.srodata.cst2)
*(.srodata .srodata.*)
} >flash AT>flash
.fini :
{
KEEP (*(SORT_NONE(.fini)))
} >flash AT>flash
. = ALIGN(4);
PROVIDE (__etext = .);
PROVIDE (_etext = .);
PROVIDE (etext = .);
PROVIDE( _eilm = . );
.preinit_array :
{
PROVIDE_HIDDEN (__preinit_array_start = .);
KEEP (*(.preinit_array))
PROVIDE_HIDDEN (__preinit_array_end = .);
} >flash AT>flash
.init_array :
{
PROVIDE_HIDDEN (__init_array_start = .);
KEEP (*(SORT_BY_INIT_PRIORITY(.init_array.*) SORT_BY_INIT_PRIORITY(.ctors.*)))
KEEP (*(.init_array EXCLUDE_FILE (*crtbegin.o *crtbegin?.o *crtend.o *crtend?.o ) .ctors))
PROVIDE_HIDDEN (__init_array_end = .);
} >flash AT>flash
.fini_array :
{
PROVIDE_HIDDEN (__fini_array_start = .);
KEEP (*(SORT_BY_INIT_PRIORITY(.fini_array.*) SORT_BY_INIT_PRIORITY(.dtors.*)))
KEEP (*(.fini_array EXCLUDE_FILE (*crtbegin.o *crtbegin?.o *crtend.o *crtend?.o ) .dtors))
PROVIDE_HIDDEN (__fini_array_end = .);
} >flash AT>flash
.ctors :
{
/* gcc uses crtbegin.o to find the start of
* the constructors, so we make sure it is
* first. Because this is a wildcard, it
* doesn't matter if the user does not
* actually link against crtbegin.o; the
* linker won't look for a file to match a
* wildcard. The wildcard also means that it
* doesn't matter which directory crtbegin.o
* is in.
*/
KEEP (*crtbegin.o(.ctors))
KEEP (*crtbegin?.o(.ctors))
/* We don't want to include the .ctor section from
* the crtend.o file until after the sorted ctors.
* The .ctor section from the crtend file contains the
* end of ctors marker and it must be last
*/
KEEP (*(EXCLUDE_FILE (*crtend.o *crtend?.o ) .ctors))
KEEP (*(SORT(.ctors.*)))
KEEP (*(.ctors))
} >flash AT>flash
.dtors :
{
KEEP (*crtbegin.o(.dtors))
KEEP (*crtbegin?.o(.dtors))
KEEP (*(EXCLUDE_FILE (*crtend.o *crtend?.o ) .dtors))
KEEP (*(SORT(.dtors.*)))
KEEP (*(.dtors))
} >flash AT>flash
.lalign :
{
. = ALIGN(4);
PROVIDE( _data_lma = . );
} >flash AT>flash
.dalign :
{
. = ALIGN(4);
PROVIDE( _data = . );
} >ram AT>flash
/* Define data section virtual address is ram and physical address is flash */
.data :
{
*(.data .data.*)
*(.gnu.linkonce.d.*)
. = ALIGN(8);
PROVIDE( __global_pointer$ = . + 0x800 );
*(.sdata .sdata.* .sdata*)
*(.gnu.linkonce.s.*)
} >ram AT>flash
. = ALIGN(4);
PROVIDE( _edata = . );
PROVIDE( edata = . );
PROVIDE( _fbss = . );
PROVIDE( __bss_start = . );
.bss :
{
*(.sbss*)
*(.gnu.linkonce.sb.*)
*(.bss .bss.*)
*(.gnu.linkonce.b.*)
*(COMMON)
. = ALIGN(4);
} >ram AT>ram
. = ALIGN(8);
/* Define stack and head location at ram */
.stack :
{
. = . + __STACK_SIZE;
PROVIDE( _sp = . );
} >ram AT>ram
PROVIDE( _end = . );
PROVIDE( end = . );
}

View File

@ -0,0 +1,20 @@
// See LICENSE for license details.
#ifndef _NUCLEI_SDK_HAL_H
#define _NUCLEI_SDK_HAL_H
#ifdef __cplusplus
extern "C" {
#endif
#include "gd32vf103v_rvstar.h"
#define SOC_DEBUG_UART GD32_COM0
#ifndef NUCLEI_BANNER
#define NUCLEI_BANNER 1
#endif
#ifdef __cplusplus
}
#endif
#endif

View File

@ -0,0 +1,20 @@
// See LICENSE for license details.
#ifndef _NUCLEI_SDK_SOC_H
#define _NUCLEI_SDK_SOC_H
#ifdef __cplusplus
extern "C" {
#endif
#include "gd32vf103.h"
// #include "gd32vf103_libopt.h"
#include "gd32vf103_rcu.h"
#include "gd32vf103_gpio.h"
#include "gd32vf103_usart.h"
#include "gd32vf103_timer.h"
#ifdef __cplusplus
}
#endif
#endif

View File

@ -0,0 +1,25 @@
menuconfig BSP_USING_GPIO
bool "Using GPIO device"
default y
select RESOURCES_PIN
if BSP_USING_GPIO
source "$BSP_DIR/third_party_driver/gpio/Kconfig"
endif
menuconfig BSP_USING_SYSCLOCK
bool "Using SYSCLOCK device"
default y
if BSP_USING_SYSCLOCK
source "$BSP_DIR/third_party_driver/sys_clock/Kconfig"
endif
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,17 @@
SRC_FILES := system_gd32vf103.c
SRC_DIR :=
ifeq ($(CONFIG_BSP_USING_GPIO),y)
SRC_DIR += gpio
endif
ifeq ($(CONFIG_BSP_USING_SYSCLOCK),y)
SRC_DIR += sys_clock
endif
ifeq ($(CONFIG_BSP_USING_UART),y)
SRC_DIR += uart
endif
include $(KERNEL_ROOT)/compiler.mk

View File

@ -0,0 +1,11 @@
config PIN_BUS_NAME
string "pin bus name"
default "pin"
config PIN_DRIVER_NAME
string "pin driver name"
default "pin_drv"
config PIN_DEVICE_NAME
string "pin device name"
default "pin_dev"

View File

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

View File

@ -0,0 +1,502 @@
/*!
\file gd32vf103_gpio.c
\brief GPIO driver
\version 2019-6-5, V1.0.0, firmware for GD32VF103
*/
/*
Copyright (c) 2019, GigaDevice Semiconductor Inc.
Redistribution and use in source and binary forms, with or without modification,
are permitted provided that the following conditions are met:
1. Redistributions of source code must retain the above copyright notice, this
list of conditions and the following disclaimer.
2. Redistributions in binary form must reproduce the above copyright notice,
this list of conditions and the following disclaimer in the documentation
and/or other materials provided with the distribution.
3. Neither the name of the copyright holder nor the names of its contributors
may be used to endorse or promote products derived from this software without
specific prior written permission.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED.
IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT,
INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT
NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY
OF SUCH DAMAGE.
*/
#include "gd32vf103_gpio.h"
#define AFIO_EXTI_SOURCE_MASK ((uint8_t)0x03U) /*!< AFIO exti source selection mask*/
#define AFIO_EXTI_SOURCE_FIELDS ((uint8_t)0x04U) /*!< select AFIO exti source registers */
#define LSB_16BIT_MASK ((uint16_t)0xFFFFU) /*!< LSB 16-bit mask */
#define PCF_POSITION_MASK ((uint32_t)0x000F0000U) /*!< AFIO_PCF register position mask */
#define PCF_SWJCFG_MASK ((uint32_t)0xF0FFFFFFU) /*!< AFIO_PCF register SWJCFG mask */
#define PCF_LOCATION1_MASK ((uint32_t)0x00200000U) /*!< AFIO_PCF register location1 mask */
#define PCF_LOCATION2_MASK ((uint32_t)0x00100000U) /*!< AFIO_PCF register location2 mask */
#define AFIO_PCF1_FIELDS ((uint32_t)0x80000000U) /*!< select AFIO_PCF1 register */
#define GPIO_OUTPUT_PORT_OFFSET ((uint32_t)4U) /*!< GPIO event output port offset*/
/*!
\brief reset GPIO port
\param[in] gpio_periph: GPIOx(x = A,B,C,D,E)
\param[out] none
\retval none
*/
void gpio_deinit(uint32_t gpio_periph)
{
switch (gpio_periph) {
case GPIOA:
/* reset GPIOA */
rcu_periph_reset_enable(RCU_GPIOARST);
rcu_periph_reset_disable(RCU_GPIOARST);
break;
case GPIOB:
/* reset GPIOB */
rcu_periph_reset_enable(RCU_GPIOBRST);
rcu_periph_reset_disable(RCU_GPIOBRST);
break;
case GPIOC:
/* reset GPIOC */
rcu_periph_reset_enable(RCU_GPIOCRST);
rcu_periph_reset_disable(RCU_GPIOCRST);
break;
case GPIOD:
/* reset GPIOD */
rcu_periph_reset_enable(RCU_GPIODRST);
rcu_periph_reset_disable(RCU_GPIODRST);
break;
case GPIOE:
/* reset GPIOE */
rcu_periph_reset_enable(RCU_GPIOERST);
rcu_periph_reset_disable(RCU_GPIOERST);
break;
default:
break;
}
}
/*!
\brief reset alternate function I/O(AFIO)
\param[in] none
\param[out] none
\retval none
*/
void gpio_afio_deinit(void)
{
rcu_periph_reset_enable(RCU_AFRST);
rcu_periph_reset_disable(RCU_AFRST);
}
/*!
\brief GPIO parameter initialization
\param[in] gpio_periph: GPIOx(x = A,B,C,D,E)
\param[in] mode: gpio pin mode
only one parameter can be selected which is shown as below:
\arg GPIO_MODE_AIN: analog input mode
\arg GPIO_MODE_IN_FLOATING: floating input mode
\arg GPIO_MODE_IPD: pull-down input mode
\arg GPIO_MODE_IPU: pull-up input mode
\arg GPIO_MODE_OUT_OD: GPIO output with open-drain
\arg GPIO_MODE_OUT_PP: GPIO output with push-pull
\arg GPIO_MODE_AF_OD: AFIO output with open-drain
\arg GPIO_MODE_AF_PP: AFIO output with push-pull
\param[in] speed: gpio output max speed value
only one parameter can be selected which is shown as below:
\arg GPIO_OSPEED_10MHZ: output max speed 10MHz
\arg GPIO_OSPEED_2MHZ: output max speed 2MHz
\arg GPIO_OSPEED_50MHZ: output max speed 50MHz
\param[in] pin: GPIO pin
one or more parameters can be selected which are shown as below:
\arg GPIO_PIN_x(x=0..15), GPIO_PIN_ALL
\param[out] none
\retval none
*/
void gpio_init(uint32_t gpio_periph, uint32_t mode, uint32_t speed,
uint32_t pin)
{
uint16_t i;
uint32_t temp_mode = 0U;
uint32_t reg = 0U;
/* GPIO mode configuration */
temp_mode = (uint32_t)(mode & ((uint32_t) 0x0FU));
/* GPIO speed configuration */
if (((uint32_t) 0x00U) != ((uint32_t) mode & ((uint32_t) 0x10U))) {
/* output mode max speed:10MHz,2MHz,50MHz */
temp_mode |= (uint32_t) speed;
}
/* configure the eight low port pins with GPIO_CTL0 */
for (i = 0U; i < 8U; i++) {
if ((1U << i) & pin) {
reg = GPIO_CTL0(gpio_periph);
/* clear the specified pin mode bits */
reg &= ~GPIO_MODE_MASK(i);
/* set the specified pin mode bits */
reg |= GPIO_MODE_SET(i, temp_mode);
/* set IPD or IPU */
if (GPIO_MODE_IPD == mode) {
/* reset the corresponding OCTL bit */
GPIO_BC(gpio_periph) = (uint32_t)((1U << i) & pin);
} else {
/* set the corresponding OCTL bit */
if (GPIO_MODE_IPU == mode) {
GPIO_BOP(gpio_periph) = (uint32_t)((1U << i) & pin);
}
}
/* set GPIO_CTL0 register */
GPIO_CTL0(gpio_periph) = reg;
}
}
/* configure the eight high port pins with GPIO_CTL1 */
for (i = 8U; i < 16U; i++) {
if ((1U << i) & pin) {
reg = GPIO_CTL1(gpio_periph);
/* clear the specified pin mode bits */
reg &= ~GPIO_MODE_MASK(i - 8U);
/* set the specified pin mode bits */
reg |= GPIO_MODE_SET(i - 8U, temp_mode);
/* set IPD or IPU */
if (GPIO_MODE_IPD == mode) {
/* reset the corresponding OCTL bit */
GPIO_BC(gpio_periph) = (uint32_t)((1U << i) & pin);
} else {
/* set the corresponding OCTL bit */
if (GPIO_MODE_IPU == mode) {
GPIO_BOP(gpio_periph) = (uint32_t)((1U << i) & pin);
}
}
/* set GPIO_CTL1 register */
GPIO_CTL1(gpio_periph) = reg;
}
}
}
/*!
\brief set GPIO pin
\param[in] gpio_periph: GPIOx(x = A,B,C,D,E)
\param[in] pin: GPIO pin
one or more parameters can be selected which are shown as below:
\arg GPIO_PIN_x(x=0..15), GPIO_PIN_ALL
\param[out] none
\retval none
*/
void gpio_bit_set(uint32_t gpio_periph, uint32_t pin)
{
GPIO_BOP(gpio_periph) = (uint32_t) pin;
}
/*!
\brief reset GPIO pin
\param[in] gpio_periph: GPIOx(x = A,B,C,D,E)
\param[in] pin: GPIO pin
one or more parameters can be selected which are shown as below:
\arg GPIO_PIN_x(x=0..15), GPIO_PIN_ALL
\param[out] none
\retval none
*/
void gpio_bit_reset(uint32_t gpio_periph, uint32_t pin)
{
GPIO_BC(gpio_periph) = (uint32_t) pin;
}
/*!
\brief write data to the specified GPIO pin
\param[in] gpio_periph: GPIOx(x = A,B,C,D,E)
\param[in] pin: GPIO pin
one or more parameters can be selected which are shown as below:
\arg GPIO_PIN_x(x=0..15), GPIO_PIN_ALL
\param[in] bit_value: SET or RESET
only one parameter can be selected which is shown as below:
\arg RESET: clear the port pin
\arg SET: set the port pin
\param[out] none
\retval none
*/
void gpio_bit_write(uint32_t gpio_periph, uint32_t pin, bit_status bit_value)
{
if (RESET != bit_value) {
GPIO_BOP(gpio_periph) = (uint32_t) pin;
} else {
GPIO_BC(gpio_periph) = (uint32_t) pin;
}
}
/*!
\brief write data to the specified GPIO port
\param[in] gpio_periph: GPIOx(x = A,B,C,D,E)
\param[in] data: specify the value to be written to the port output data register
\param[out] none
\retval none
*/
void gpio_port_write(uint32_t gpio_periph, uint16_t data)
{
GPIO_OCTL(gpio_periph) = (uint32_t) data;
}
/*!
\brief get GPIO pin input status
\param[in] gpio_periph: GPIOx(x = A,B,C,D,E)
\param[in] pin: GPIO pin
only one parameter can be selected which are shown as below:
\arg GPIO_PIN_x(x=0..15), GPIO_PIN_ALL
\param[out] none
\retval input status of gpio pin: SET or RESET
*/
FlagStatus gpio_input_bit_get(uint32_t gpio_periph, uint32_t pin)
{
if ((uint32_t) RESET != (GPIO_ISTAT(gpio_periph) & (pin))) {
return SET;
} else {
return RESET;
}
}
/*!
\brief get GPIO port input status
\param[in] gpio_periph: GPIOx(x = A,B,C,D,E)
\param[out] none
\retval input status of gpio all pins
*/
uint16_t gpio_input_port_get(uint32_t gpio_periph)
{
return (uint16_t)(GPIO_ISTAT(gpio_periph));
}
/*!
\brief get GPIO pin output status
\param[in] gpio_periph: GPIOx(x = A,B,C,D,E)
\param[in] pin: GPIO pin
only one parameter can be selected which are shown as below:
\arg GPIO_PIN_x(x=0..15), GPIO_PIN_ALL
\param[out] none
\retval output status of gpio pin: SET or RESET
*/
FlagStatus gpio_output_bit_get(uint32_t gpio_periph, uint32_t pin)
{
if ((uint32_t) RESET != (GPIO_OCTL(gpio_periph) & (pin))) {
return SET;
} else {
return RESET;
}
}
/*!
\brief get GPIO port output status
\param[in] gpio_periph: GPIOx(x = A,B,C,D,E)
\param[out] none
\retval output status of gpio all pins
*/
uint16_t gpio_output_port_get(uint32_t gpio_periph)
{
return ((uint16_t) GPIO_OCTL(gpio_periph));
}
/*!
\brief configure GPIO pin remap
\param[in] gpio_remap: select the pin to remap
only one parameter can be selected which are shown as below:
\arg GPIO_SPI0_REMAP: SPI0 remapping
\arg GPIO_I2C0_REMAP: I2C0 remapping
\arg GPIO_USART0_REMAP: USART0 remapping
\arg GPIO_USART1_REMAP: USART1 remapping
\arg GPIO_USART2_PARTIAL_REMAP: USART2 partial remapping
\arg GPIO_USART2_FULL_REMAP: USART2 full remapping
\arg GPIO_TIMER0_PARTIAL_REMAP: TIMER0 partial remapping
\arg GPIO_TIMER0_FULL_REMAP: TIMER0 full remapping
\arg GPIO_TIMER1_PARTIAL_REMAP0: TIMER1 partial remapping
\arg GPIO_TIMER1_PARTIAL_REMAP1: TIMER1 partial remapping
\arg GPIO_TIMER1_FULL_REMAP: TIMER1 full remapping
\arg GPIO_TIMER2_PARTIAL_REMAP: TIMER2 partial remapping
\arg GPIO_TIMER2_FULL_REMAP: TIMER2 full remapping
\arg GPIO_TIMER3_REMAP: TIMER3 remapping
\arg GPIO_CAN0_PARTIAL_REMAP: CAN0 partial remapping
\arg GPIO_CAN0_FULL_REMAP: CAN0 full remapping
\arg GPIO_PD01_REMAP: PD01 remapping
\arg GPIO_TIMER4CH3_IREMAP: TIMER4 channel3 internal remapping
\arg GPIO_CAN1_REMAP: CAN1 remapping
\arg GPIO_SWJ_NONJTRST_REMAP: JTAG-DP,but without NJTRST
\arg GPIO_SWJ_DISABLE_REMAP: JTAG-DP disabled
\arg GPIO_SPI2_REMAP: SPI2 remapping
\arg GPIO_TIMER1ITI1_REMAP: TIMER1 internal trigger 1 remapping
\arg GPIO_EXMC_NADV_REMAP: EXMC_NADV connect/disconnect
\param[in] newvalue: ENABLE or DISABLE
\param[out] none
\retval none
*/
void gpio_pin_remap_config(uint32_t remap, ControlStatus newvalue)
{
uint32_t remap1 = 0U, remap2 = 0U, temp_reg = 0U, temp_mask = 0U;
if (AFIO_PCF1_FIELDS == (remap & AFIO_PCF1_FIELDS)) {
/* get AFIO_PCF1 regiter value */
temp_reg = AFIO_PCF1;
} else {
/* get AFIO_PCF0 regiter value */
temp_reg = AFIO_PCF0;
}
temp_mask = (remap & PCF_POSITION_MASK) >> 0x10U;
remap1 = remap & LSB_16BIT_MASK;
/* judge pin remap type */
if ((PCF_LOCATION1_MASK | PCF_LOCATION2_MASK)
== (remap & (PCF_LOCATION1_MASK | PCF_LOCATION2_MASK))) {
temp_reg &= PCF_SWJCFG_MASK;
AFIO_PCF0 &= PCF_SWJCFG_MASK;
} else if (PCF_LOCATION2_MASK == (remap & PCF_LOCATION2_MASK)) {
remap2 = ((uint32_t) 0x03U) << temp_mask;
temp_reg &= ~remap2;
temp_reg |= ~PCF_SWJCFG_MASK;
} else {
temp_reg &= ~(remap1 << ((remap >> 0x15U) * 0x10U));
temp_reg |= ~PCF_SWJCFG_MASK;
}
/* set pin remap value */
if (DISABLE != newvalue) {
temp_reg |= (remap1 << ((remap >> 0x15U) * 0x10U));
}
if (AFIO_PCF1_FIELDS == (remap & AFIO_PCF1_FIELDS)) {
/* set AFIO_PCF1 regiter value */
AFIO_PCF1 = temp_reg;
} else {
/* set AFIO_PCF0 regiter value */
AFIO_PCF0 = temp_reg;
}
}
/*!
\brief select GPIO pin exti sources
\param[in] gpio_outputport: gpio event output port
only one parameter can be selected which are shown as below:
\arg GPIO_PORT_SOURCE_GPIOA: output port source A
\arg GPIO_PORT_SOURCE_GPIOB: output port source B
\arg GPIO_PORT_SOURCE_GPIOC: output port source C
\arg GPIO_PORT_SOURCE_GPIOD: output port source D
\arg GPIO_PORT_SOURCE_GPIOE: output port source E
\param[in] gpio_outputpin: GPIO_PIN_SOURCE_x(x=0..15)
\param[out] none
\retval none
*/
void gpio_exti_source_select(uint8_t output_port, uint8_t output_pin)
{
uint32_t source = 0U;
source = ((uint32_t) 0x0FU)
<< (AFIO_EXTI_SOURCE_FIELDS * (output_pin & AFIO_EXTI_SOURCE_MASK));
/* select EXTI sources */
if (GPIO_PIN_SOURCE_4 > output_pin) {
/* select EXTI0/EXTI1/EXTI2/EXTI3 */
AFIO_EXTISS0 &= ~source;
AFIO_EXTISS0 |= (((uint32_t) output_port)
<< (AFIO_EXTI_SOURCE_FIELDS
* (output_pin & AFIO_EXTI_SOURCE_MASK)));
} else if (GPIO_PIN_SOURCE_8 > output_pin) {
/* select EXTI4/EXTI5/EXTI6/EXTI7 */
AFIO_EXTISS1 &= ~source;
AFIO_EXTISS1 |= (((uint32_t) output_port)
<< (AFIO_EXTI_SOURCE_FIELDS
* (output_pin & AFIO_EXTI_SOURCE_MASK)));
} else if (GPIO_PIN_SOURCE_12 > output_pin) {
/* select EXTI8/EXTI9/EXTI10/EXTI11 */
AFIO_EXTISS2 &= ~source;
AFIO_EXTISS2 |= (((uint32_t) output_port)
<< (AFIO_EXTI_SOURCE_FIELDS
* (output_pin & AFIO_EXTI_SOURCE_MASK)));
} else {
/* select EXTI12/EXTI13/EXTI14/EXTI15 */
AFIO_EXTISS3 &= ~source;
AFIO_EXTISS3 |= (((uint32_t) output_port)
<< (AFIO_EXTI_SOURCE_FIELDS
* (output_pin & AFIO_EXTI_SOURCE_MASK)));
}
}
/*!
\brief configure GPIO pin event output
\param[in] output_port: gpio event output port
only one parameter can be selected which are shown as below:
\arg GPIO_EVENT_PORT_GPIOA: event output port A
\arg GPIO_EVENT_PORT_GPIOB: event output port B
\arg GPIO_EVENT_PORT_GPIOC: event output port C
\arg GPIO_EVENT_PORT_GPIOD: event output port D
\arg GPIO_EVENT_PORT_GPIOE: event output port E
\param[in] output_pin:
only one parameter can be selected which are shown as below:
\arg GPIO_EVENT_PIN_x(x=0..15)
\param[out] none
\retval none
*/
void gpio_event_output_config(uint8_t output_port, uint8_t output_pin)
{
uint32_t reg = 0U;
reg = AFIO_EC;
/* clear AFIO_EC_PORT and AFIO_EC_PIN bits */
reg &= (uint32_t)(~(AFIO_EC_PORT | AFIO_EC_PIN));
reg |= (uint32_t)((uint32_t) output_port << GPIO_OUTPUT_PORT_OFFSET);
reg |= (uint32_t) output_pin;
AFIO_EC = reg;
}
/*!
\brief enable GPIO pin event output
\param[in] none
\param[out] none
\retval none
*/
void gpio_event_output_enable(void)
{
AFIO_EC |= AFIO_EC_EOE;
}
/*!
\brief disable GPIO pin event output
\param[in] none
\param[out] none
\retval none
*/
void gpio_event_output_disable(void)
{
AFIO_EC &= (uint32_t)(~AFIO_EC_EOE);
}
/*!
\brief lock GPIO pin
\param[in] gpio_periph: GPIOx(x = A,B,C,D,E)
\param[in] pin: GPIO pin
one or more parameters can be selected which are shown as below:
\arg GPIO_PIN_x(x=0..15), GPIO_PIN_ALL
\param[out] none
\retval none
*/
void gpio_pin_lock(uint32_t gpio_periph, uint32_t pin)
{
uint32_t lock = 0x00010000U;
lock |= pin;
/* lock key writing sequence: write 1 -> write 0 -> write 1 -> read 0 -> read 1 */
GPIO_LOCK(gpio_periph) = (uint32_t) lock;
GPIO_LOCK(gpio_periph) = (uint32_t) pin;
GPIO_LOCK(gpio_periph) = (uint32_t) lock;
lock = GPIO_LOCK(gpio_periph);
lock = GPIO_LOCK(gpio_periph);
}

View File

@ -0,0 +1,38 @@
/*
* 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 connect_uart.h
* @brief define gap8-board uart function and struct
* @version 1.1
* @author AIIT XUOS Lab
* @date 2021-07-27
*/
#ifndef CONNECT_UART_H
#define CONNECT_UART_H
#include <device.h>
#ifdef __cplusplus
extern "C" {
#endif
int InitHwUart(void);
#ifdef __cplusplus
}
#endif
#endif

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,894 @@
/*
* Copyright (c) 2019 Nuclei 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 __CORE_FEATURE_ECLIC__
#define __CORE_FEATURE_ECLIC__
/*!
* @file core_feature_eclic.h
* @brief ECLIC feature API header file for Nuclei N/NX Core
*/
/*
* ECLIC Feature Configuration Macro:
* 1. __ECLIC_PRESENT: Define whether Enhanced Core Local Interrupt Controller (ECLIC) Unit is present or not
* * 0: Not present
* * 1: Present
* 2. __ECLIC_BASEADDR: Base address of the ECLIC unit.
* 3. ECLIC_GetInfoCtlbits(): Define the number of hardware bits are actually implemented in the clicintctl registers.
* Valid number is 1 - 8.
* 4. __ECLIC_INTNUM : Define the external interrupt number of ECLIC Unit
*
*/
#ifdef __cplusplus
extern "C" {
#endif
#include "nmsis_gcc.h"
#include "core_feature_base.h"
#if defined(__ECLIC_PRESENT) && (__ECLIC_PRESENT == 1)
/**
* \defgroup NMSIS_Core_ECLIC_Registers Register Define and Type Definitions Of ECLIC
* \ingroup NMSIS_Core_Registers
* \brief Type definitions and defines for eclic registers.
*
* @{
*/
/**
* \brief Union type to access CLICFG configure register.
*/
typedef union
{
struct {
uint8_t _reserved0:1; /*!< bit: 0 Overflow condition code flag */
uint8_t nlbits:4; /*!< bit: 29 Carry condition code flag */
uint8_t _reserved1:2; /*!< bit: 30 Zero condition code flag */
uint8_t _reserved2:1; /*!< bit: 31 Negative condition code flag */
} b; /*!< Structure used for bit access */
uint8_t w; /*!< Type used for byte access */
} CLICCFG_Type;
/**
* \brief Union type to access CLICINFO information register.
*/
typedef union {
struct {
uint32_t numint:13; /*!< bit: 0..12 number of maximum interrupt inputs supported */
uint32_t version:8; /*!< bit: 13..20 20:17 for architecture version,16:13 for implementation version */
uint32_t intctlbits:4; /*!< bit: 21..24 specifies how many hardware bits are actually implemented in the clicintctl registers */
uint32_t _reserved0:7; /*!< bit: 25..31 Reserved */
} b; /*!< Structure used for bit access */
uint32_t w; /*!< Type used for word access */
} CLICINFO_Type;
/**
* \brief Access to the structure of a vector interrupt controller.
*/
typedef struct {
__IOM uint8_t INTIP; /*!< Offset: 0x000 (R/W) Interrupt set pending register */
__IOM uint8_t INTIE; /*!< Offset: 0x001 (R/W) Interrupt set enable register */
__IOM uint8_t INTATTR; /*!< Offset: 0x002 (R/W) Interrupt set attributes register */
__IOM uint8_t INTCTRL; /*!< Offset: 0x003 (R/W) Interrupt configure register */
} CLIC_CTRL_Type;
typedef struct {
__IOM uint8_t CFG; /*!< Offset: 0x000 (R/W) CLIC configuration register */
uint8_t RESERVED0[3];
__IM uint32_t INFO; /*!< Offset: 0x004 (R/ ) CLIC information register */
uint8_t RESERVED1[3];
__IOM uint8_t MTH; /*!< Offset: 0x00B (R/W) CLIC machine mode threshold register */
uint32_t RESERVED2[0x3FD];
CLIC_CTRL_Type CTRL[4096]; /*!< Offset: 0x1000 (R/W) CLIC register structure for INTIP, INTIE, INTATTR, INTCTL */
} CLIC_Type;
#define CLIC_CLICCFG_NLBIT_Pos 1U /*!< CLIC CLICCFG: NLBIT Position */
#define CLIC_CLICCFG_NLBIT_Msk (0xFUL << CLIC_CLICCFG_NLBIT_Pos) /*!< CLIC CLICCFG: NLBIT Mask */
#define CLIC_CLICINFO_CTLBIT_Pos 21U /*!< CLIC INTINFO: __ECLIC_GetInfoCtlbits() Position */
#define CLIC_CLICINFO_CTLBIT_Msk (0xFUL << CLIC_CLICINFO_CTLBIT_Pos) /*!< CLIC INTINFO: __ECLIC_GetInfoCtlbits() Mask */
#define CLIC_CLICINFO_VER_Pos 13U /*!< CLIC CLICINFO: VERSION Position */
#define CLIC_CLICINFO_VER_Msk (0xFFUL << CLIC_CLICCFG_NLBIT_Pos) /*!< CLIC CLICINFO: VERSION Mask */
#define CLIC_CLICINFO_NUM_Pos 0U /*!< CLIC CLICINFO: NUM Position */
#define CLIC_CLICINFO_NUM_Msk (0xFFFUL << CLIC_CLICINFO_NUM_Pos) /*!< CLIC CLICINFO: NUM Mask */
#define CLIC_INTIP_IP_Pos 0U /*!< CLIC INTIP: IP Position */
#define CLIC_INTIP_IP_Msk (0x1UL << CLIC_INTIP_IP_Pos) /*!< CLIC INTIP: IP Mask */
#define CLIC_INTIE_IE_Pos 0U /*!< CLIC INTIE: IE Position */
#define CLIC_INTIE_IE_Msk (0x1UL << CLIC_INTIE_IE_Pos) /*!< CLIC INTIE: IE Mask */
#define CLIC_INTATTR_TRIG_Pos 1U /*!< CLIC INTATTR: TRIG Position */
#define CLIC_INTATTR_TRIG_Msk (0x3UL << CLIC_INTATTR_TRIG_Pos) /*!< CLIC INTATTR: TRIG Mask */
#define CLIC_INTATTR_SHV_Pos 0U /*!< CLIC INTATTR: SHV Position */
#define CLIC_INTATTR_SHV_Msk (0x1UL << CLIC_INTATTR_SHV_Pos) /*!< CLIC INTATTR: SHV Mask */
#define ECLIC_MAX_NLBITS 8U /*!< Max nlbit of the CLICINTCTLBITS */
#define ECLIC_MODE_MTVEC_Msk 3U /*!< ECLIC Mode mask for MTVT CSR Register */
#define ECLIC_NON_VECTOR_INTERRUPT 0x0 /*!< Non-Vector Interrupt Mode of ECLIC */
#define ECLIC_VECTOR_INTERRUPT 0x1 /*!< Vector Interrupt Mode of ECLIC */
/**\brief ECLIC Trigger Enum for different Trigger Type */
typedef enum ECLIC_TRIGGER {
ECLIC_LEVEL_TRIGGER = 0x0, /*!< Level Triggerred, trig[0] = 0 */
ECLIC_POSTIVE_EDGE_TRIGGER = 0x1, /*!< Postive/Rising Edge Triggered, trig[0] = 1, trig[1] = 0 */
ECLIC_NEGTIVE_EDGE_TRIGGER = 0x3, /*!< Negtive/Falling Edge Triggered, trig[0] = 1, trig[1] = 1 */
ECLIC_MAX_TRIGGER = 0x3 /*!< MAX Supported Trigger Mode */
} ECLIC_TRIGGER_Type;
#ifndef __ECLIC_BASEADDR
/* Base address of ECLIC(__ECLIC_BASEADDR) should be defined in <Device.h> */
#error "__ECLIC_BASEADDR is not defined, please check!"
#endif
#ifndef __ECLIC_INTCTLBITS
/* Define __ECLIC_INTCTLBITS to get via ECLIC->INFO if not defined */
#define __ECLIC_INTCTLBITS (__ECLIC_GetInfoCtlbits())
#endif
/* ECLIC Memory mapping of Device */
#define ECLIC_BASE __ECLIC_BASEADDR /*!< ECLIC Base Address */
#define ECLIC ((CLIC_Type *) ECLIC_BASE) /*!< CLIC configuration struct */
/** @} */ /* end of group NMSIS_Core_ECLIC_Registers */
/* ########################## ECLIC functions #################################### */
/**
* \defgroup NMSIS_Core_IntExc Interrupts and Exceptions
* \brief Functions that manage interrupts and exceptions via the ECLIC.
*
* @{
*/
/**
* \brief Definition of IRQn numbers
* \details
* The core interrupt enumeration names for IRQn values are defined in the file <b><Device>.h</b>.
* - Interrupt ID(IRQn) from 0 to 18 are reserved for core internal interrupts.
* - Interrupt ID(IRQn) start from 19 represent device-specific external interrupts.
* - The first device-specific interrupt has the IRQn value 19.
*
* The table below describes the core interrupt names and their availability in various Nuclei Cores.
*/
/* The following enum IRQn definition in this file
* is only used for doxygen documentation generation,
* The <Device>.h is the real file to define it by vendor
*/
#if defined(__ONLY_FOR_DOXYGEN_DOCUMENT_GENERATION__)
typedef enum IRQn {
/* ========= Nuclei N/NX Core Specific Interrupt Numbers =========== */
/* Core Internal Interrupt IRQn definitions */
Reserved0_IRQn = 0, /*!< Internal reserved */
Reserved1_IRQn = 1, /*!< Internal reserved */
Reserved2_IRQn = 2, /*!< Internal reserved */
SysTimerSW_IRQn = 3, /*!< System Timer SW interrupt */
Reserved3_IRQn = 4, /*!< Internal reserved */
Reserved4_IRQn = 5, /*!< Internal reserved */
Reserved5_IRQn = 6, /*!< Internal reserved */
SysTimer_IRQn = 7, /*!< System Timer Interrupt */
Reserved6_IRQn = 8, /*!< Internal reserved */
Reserved7_IRQn = 9, /*!< Internal reserved */
Reserved8_IRQn = 10, /*!< Internal reserved */
Reserved9_IRQn = 11, /*!< Internal reserved */
Reserved10_IRQn = 12, /*!< Internal reserved */
Reserved11_IRQn = 13, /*!< Internal reserved */
Reserved12_IRQn = 14, /*!< Internal reserved */
Reserved13_IRQn = 15, /*!< Internal reserved */
Reserved14_IRQn = 16, /*!< Internal reserved */
Reserved15_IRQn = 17, /*!< Internal reserved */
Reserved16_IRQn = 18, /*!< Internal reserved */
/* ========= Device Specific Interrupt Numbers =================== */
/* ToDo: add here your device specific external interrupt numbers.
* 19~max(NUM_INTERRUPT, 1023) is reserved number for user.
* Maxmum interrupt supported could get from clicinfo.NUM_INTERRUPT.
* According the interrupt handlers defined in startup_Device.S
* eg.: Interrupt for Timer#1 eclic_tim1_handler -> TIM1_IRQn */
FirstDeviceSpecificInterrupt_IRQn = 19, /*!< First Device Specific Interrupt */
SOC_INT_MAX, /*!< Number of total interrupts */
} IRQn_Type;
#endif /* __ONLY_FOR_DOXYGEN_DOCUMENT_GENERATION__ */
#ifdef NMSIS_ECLIC_VIRTUAL
#ifndef NMSIS_ECLIC_VIRTUAL_HEADER_FILE
#define NMSIS_ECLIC_VIRTUAL_HEADER_FILE "nmsis_eclic_virtual.h"
#endif
#include NMSIS_ECLIC_VIRTUAL_HEADER_FILE
#else
#define ECLIC_SetCfgNlbits __ECLIC_SetCfgNlbits
#define ECLIC_GetCfgNlbits __ECLIC_GetCfgNlbits
#define ECLIC_GetInfoVer __ECLIC_GetInfoVer
#define ECLIC_GetInfoCtlbits __ECLIC_GetInfoCtlbits
#define ECLIC_GetInfoNum __ECLIC_GetInfoNum
#define ECLIC_SetMth __ECLIC_SetMth
#define ECLIC_GetMth __ECLIC_GetMth
#define ECLIC_EnableIRQ __ECLIC_EnableIRQ
#define ECLIC_GetEnableIRQ __ECLIC_GetEnableIRQ
#define ECLIC_DisableIRQ __ECLIC_DisableIRQ
#define ECLIC_SetPendingIRQ __ECLIC_SetPendingIRQ
#define ECLIC_GetPendingIRQ __ECLIC_GetPendingIRQ
#define ECLIC_ClearPendingIRQ __ECLIC_ClearPendingIRQ
#define ECLIC_SetTrigIRQ __ECLIC_SetTrigIRQ
#define ECLIC_GetTrigIRQ __ECLIC_GetTrigIRQ
#define ECLIC_SetShvIRQ __ECLIC_SetShvIRQ
#define ECLIC_GetShvIRQ __ECLIC_GetShvIRQ
#define ECLIC_SetCtrlIRQ __ECLIC_SetCtrlIRQ
#define ECLIC_GetCtrlIRQ __ECLIC_GetCtrlIRQ
#define ECLIC_SetLevelIRQ __ECLIC_SetLevelIRQ
#define ECLIC_GetLevelIRQ __ECLIC_GetLevelIRQ
#define ECLIC_SetPriorityIRQ __ECLIC_SetPriorityIRQ
#define ECLIC_GetPriorityIRQ __ECLIC_GetPriorityIRQ
#endif /* NMSIS_ECLIC_VIRTUAL */
#ifdef NMSIS_VECTAB_VIRTUAL
#ifndef NMSIS_VECTAB_VIRTUAL_HEADER_FILE
#define NMSIS_VECTAB_VIRTUAL_HEADER_FILE "nmsis_vectab_virtual.h"
#endif
#include NMSIS_VECTAB_VIRTUAL_HEADER_FILE
#else
#define ECLIC_SetVector __ECLIC_SetVector
#define ECLIC_GetVector __ECLIC_GetVector
#endif /* (NMSIS_VECTAB_VIRTUAL) */
/**
* \brief Set nlbits value
* \details
* This function set the nlbits value of CLICCFG register.
* \param [in] nlbits nlbits value
* \remarks
* - nlbits is used to set the width of level in the CLICINTCTL[i].
* \sa
* - \ref ECLIC_GetCfgNlbits
*/
__STATIC_FORCEINLINE void __ECLIC_SetCfgNlbits(uint32_t nlbits)
{
ECLIC->CFG &= ~CLIC_CLICCFG_NLBIT_Msk;
ECLIC->CFG |= (uint8_t)((nlbits <<CLIC_CLICCFG_NLBIT_Pos) & CLIC_CLICCFG_NLBIT_Msk);
}
/**
* \brief Get nlbits value
* \details
* This function get the nlbits value of CLICCFG register.
* \return nlbits value of CLICCFG register
* \remarks
* - nlbits is used to set the width of level in the CLICINTCTL[i].
* \sa
* - \ref ECLIC_SetCfgNlbits
*/
__STATIC_FORCEINLINE uint32_t __ECLIC_GetCfgNlbits(void)
{
return ((uint32_t)((ECLIC->CFG & CLIC_CLICCFG_NLBIT_Msk) >> CLIC_CLICCFG_NLBIT_Pos));
}
/**
* \brief Get the ECLIC version number
* \details
* This function gets the hardware version information from CLICINFO register.
* \return hardware version number in CLICINFO register.
* \remarks
* - This function gets harware version information from CLICINFO register.
* - Bit 20:17 for architecture version, bit 16:13 for implementation version.
* \sa
* - \ref ECLIC_GetInfoNum
*/
__STATIC_FORCEINLINE uint32_t __ECLIC_GetInfoVer(void)
{
return ((uint32_t)((ECLIC->INFO & CLIC_CLICINFO_VER_Msk) >> CLIC_CLICINFO_VER_Pos));
}
/**
* \brief Get CLICINTCTLBITS
* \details
* This function gets CLICINTCTLBITS from CLICINFO register.
* \return CLICINTCTLBITS from CLICINFO register.
* \remarks
* - In the CLICINTCTL[i] registers, with 2 <= CLICINTCTLBITS <= 8.
* - The implemented bits are kept left-justified in the most-significant bits of each 8-bit
* CLICINTCTL[I] register, with the lower unimplemented bits treated as hardwired to 1.
* \sa
* - \ref ECLIC_GetInfoNum
*/
__STATIC_FORCEINLINE uint32_t __ECLIC_GetInfoCtlbits(void)
{
return ((uint32_t)((ECLIC->INFO & CLIC_CLICINFO_CTLBIT_Msk) >> CLIC_CLICINFO_CTLBIT_Pos));
}
/**
* \brief Get number of maximum interrupt inputs supported
* \details
* This function gets number of maximum interrupt inputs supported from CLICINFO register.
* \return number of maximum interrupt inputs supported from CLICINFO register.
* \remarks
* - This function gets number of maximum interrupt inputs supported from CLICINFO register.
* - The num_interrupt field specifies the actual number of maximum interrupt inputs supported in this implementation.
* \sa
* - \ref ECLIC_GetInfoCtlbits
*/
__STATIC_FORCEINLINE uint32_t __ECLIC_GetInfoNum(void)
{
return ((uint32_t)((ECLIC->INFO & CLIC_CLICINFO_NUM_Msk) >> CLIC_CLICINFO_NUM_Pos));
}
/**
* \brief Set Machine Mode Interrupt Level Threshold
* \details
* This function sets machine mode interrupt level threshold.
* \param [in] mth Interrupt Level Threshold.
* \sa
* - \ref ECLIC_GetMth
*/
__STATIC_FORCEINLINE void __ECLIC_SetMth(uint8_t mth)
{
ECLIC->MTH = mth;
}
/**
* \brief Get Machine Mode Interrupt Level Threshold
* \details
* This function gets machine mode interrupt level threshold.
* \return Interrupt Level Threshold.
* \sa
* - \ref ECLIC_SetMth
*/
__STATIC_FORCEINLINE uint8_t __ECLIC_GetMth(void)
{
return (ECLIC->MTH);
}
/**
* \brief Enable a specific interrupt
* \details
* This function enables the specific interrupt \em IRQn.
* \param [in] IRQn Interrupt number
* \remarks
* - IRQn must not be negative.
* \sa
* - \ref ECLIC_DisableIRQ
*/
__STATIC_FORCEINLINE void __ECLIC_EnableIRQ(IRQn_Type IRQn)
{
ECLIC->CTRL[IRQn].INTIE |= CLIC_INTIE_IE_Msk;
}
/**
* \brief Get a specific interrupt enable status
* \details
* This function returns the interrupt enable status for the specific interrupt \em IRQn.
* \param [in] IRQn Interrupt number
* \returns
* - 0 Interrupt is not enabled
* - 1 Interrupt is pending
* \remarks
* - IRQn must not be negative.
* \sa
* - \ref ECLIC_EnableIRQ
* - \ref ECLIC_DisableIRQ
*/
__STATIC_FORCEINLINE uint32_t __ECLIC_GetEnableIRQ(IRQn_Type IRQn)
{
return((uint32_t) (ECLIC->CTRL[IRQn].INTIE) & CLIC_INTIE_IE_Msk);
}
/**
* \brief Disable a specific interrupt
* \details
* This function disables the specific interrupt \em IRQn.
* \param [in] IRQn Number of the external interrupt to disable
* \remarks
* - IRQn must not be negative.
* \sa
* - \ref ECLIC_EnableIRQ
*/
__STATIC_FORCEINLINE void __ECLIC_DisableIRQ(IRQn_Type IRQn)
{
ECLIC->CTRL[IRQn].INTIE &= ~CLIC_INTIE_IE_Msk;
}
/**
* \brief Get the pending specific interrupt
* \details
* This function returns the pending status of the specific interrupt \em IRQn.
* \param [in] IRQn Interrupt number
* \returns
* - 0 Interrupt is not pending
* - 1 Interrupt is pending
* \remarks
* - IRQn must not be negative.
* \sa
* - \ref ECLIC_SetPendingIRQ
* - \ref ECLIC_ClearPendingIRQ
*/
__STATIC_FORCEINLINE int32_t __ECLIC_GetPendingIRQ(IRQn_Type IRQn)
{
return((uint32_t)(ECLIC->CTRL[IRQn].INTIP) & CLIC_INTIP_IP_Msk);
}
/**
* \brief Set a specific interrupt to pending
* \details
* This function sets the pending bit for the specific interrupt \em IRQn.
* \param [in] IRQn Interrupt number
* \remarks
* - IRQn must not be negative.
* \sa
* - \ref ECLIC_GetPendingIRQ
* - \ref ECLIC_ClearPendingIRQ
*/
__STATIC_FORCEINLINE void __ECLIC_SetPendingIRQ(IRQn_Type IRQn)
{
ECLIC->CTRL[IRQn].INTIP |= CLIC_INTIP_IP_Msk;
}
/**
* \brief Clear a specific interrupt from pending
* \details
* This function removes the pending state of the specific interrupt \em IRQn.
* \em IRQn cannot be a negative number.
* \param [in] IRQn Interrupt number
* \remarks
* - IRQn must not be negative.
* \sa
* - \ref ECLIC_SetPendingIRQ
* - \ref ECLIC_GetPendingIRQ
*/
__STATIC_FORCEINLINE void __ECLIC_ClearPendingIRQ(IRQn_Type IRQn)
{
ECLIC->CTRL[IRQn].INTIP &= ~ CLIC_INTIP_IP_Msk;
}
/**
* \brief Set trigger mode and polarity for a specific interrupt
* \details
* This function set trigger mode and polarity of the specific interrupt \em IRQn.
* \param [in] IRQn Interrupt number
* \param [in] trig
* - 00 level trigger, \ref ECLIC_LEVEL_TRIGGER
* - 01 positive edge trigger, \ref ECLIC_POSTIVE_EDGE_TRIGGER
* - 02 level trigger, \ref ECLIC_LEVEL_TRIGGER
* - 03 negative edge trigger, \ref ECLIC_NEGTIVE_EDGE_TRIGGER
* \remarks
* - IRQn must not be negative.
*
* \sa
* - \ref ECLIC_GetTrigIRQ
*/
__STATIC_FORCEINLINE void __ECLIC_SetTrigIRQ(IRQn_Type IRQn, uint32_t trig)
{
ECLIC->CTRL[IRQn].INTATTR &= ~CLIC_INTATTR_TRIG_Msk;
ECLIC->CTRL[IRQn].INTATTR |= (uint8_t)(trig<<CLIC_INTATTR_TRIG_Pos);
}
/**
* \brief Get trigger mode and polarity for a specific interrupt
* \details
* This function get trigger mode and polarity of the specific interrupt \em IRQn.
* \param [in] IRQn Interrupt number
* \return
* - 00 level trigger, \ref ECLIC_LEVEL_TRIGGER
* - 01 positive edge trigger, \ref ECLIC_POSTIVE_EDGE_TRIGGER
* - 02 level trigger, \ref ECLIC_LEVEL_TRIGGER
* - 03 negative edge trigger, \ref ECLIC_NEGTIVE_EDGE_TRIGGER
* \remarks
* - IRQn must not be negative.
* \sa
* - \ref ECLIC_SetTrigIRQ
*/
__STATIC_FORCEINLINE uint32_t __ECLIC_GetTrigIRQ(IRQn_Type IRQn)
{
return ((int32_t)(((ECLIC->CTRL[IRQn].INTATTR) & CLIC_INTATTR_TRIG_Msk)>>CLIC_INTATTR_TRIG_Pos));
}
/**
* \brief Set interrupt working mode for a specific interrupt
* \details
* This function set selective hardware vector or non-vector working mode of the specific interrupt \em IRQn.
* \param [in] IRQn Interrupt number
* \param [in] shv
* - 0 non-vector mode, \ref ECLIC_NON_VECTOR_INTERRUPT
* - 1 vector mode, \ref ECLIC_VECTOR_INTERRUPT
* \remarks
* - IRQn must not be negative.
* \sa
* - \ref ECLIC_GetShvIRQ
*/
__STATIC_FORCEINLINE void __ECLIC_SetShvIRQ(IRQn_Type IRQn, uint32_t shv)
{
ECLIC->CTRL[IRQn].INTATTR &= ~CLIC_INTATTR_SHV_Msk;
ECLIC->CTRL[IRQn].INTATTR |= (uint8_t)(shv<<CLIC_INTATTR_SHV_Pos);
}
/**
* \brief Get interrupt working mode for a specific interrupt
* \details
* This function get selective hardware vector or non-vector working mode of the specific interrupt \em IRQn.
* \param [in] IRQn Interrupt number
* \return shv
* - 0 non-vector mode, \ref ECLIC_NON_VECTOR_INTERRUPT
* - 1 vector mode, \ref ECLIC_VECTOR_INTERRUPT
* \remarks
* - IRQn must not be negative.
* \sa
* - \ref ECLIC_SetShvIRQ
*/
__STATIC_FORCEINLINE uint32_t __ECLIC_GetShvIRQ(IRQn_Type IRQn)
{
return ((int32_t)(((ECLIC->CTRL[IRQn].INTATTR) & CLIC_INTATTR_SHV_Msk)>>CLIC_INTATTR_SHV_Pos));
}
/**
* \brief Modify ECLIC Interrupt Input Control Register for a specific interrupt
* \details
* This function modify ECLIC Interrupt Input Control(CLICINTCTL[i]) register of the specific interrupt \em IRQn.
* \param [in] IRQn Interrupt number
* \param [in] intctrl Set value for CLICINTCTL[i] register
* \remarks
* - IRQn must not be negative.
* \sa
* - \ref ECLIC_GetCtrlIRQ
*/
__STATIC_FORCEINLINE void __ECLIC_SetCtrlIRQ(IRQn_Type IRQn, uint8_t intctrl)
{
ECLIC->CTRL[IRQn].INTCTRL = intctrl;
}
/**
* \brief Get ECLIC Interrupt Input Control Register value for a specific interrupt
* \details
* This function modify ECLIC Interrupt Input Control register of the specific interrupt \em IRQn.
* \param [in] IRQn Interrupt number
* \return value of ECLIC Interrupt Input Control register
* \remarks
* - IRQn must not be negative.
* \sa
* - \ref ECLIC_SetCtrlIRQ
*/
__STATIC_FORCEINLINE uint8_t __ECLIC_GetCtrlIRQ(IRQn_Type IRQn)
{
return (ECLIC->CTRL[IRQn].INTCTRL);
}
/**
* \brief Set ECLIC Interrupt level of a specific interrupt
* \details
* This function set interrupt level of the specific interrupt \em IRQn.
* \param [in] IRQn Interrupt number
* \param [in] lvl_abs Interrupt level
* \remarks
* - IRQn must not be negative.
* - If lvl_abs to be set is larger than the max level allowed, it will be force to be max level.
* - When you set level value you need use clciinfo.nlbits to get the width of level.
* Then we could know the maximum of level. CLICINTCTLBITS is how many total bits are
* present in the CLICINTCTL register.
* \sa
* - \ref ECLIC_GetLevelIRQ
*/
__STATIC_FORCEINLINE void __ECLIC_SetLevelIRQ(IRQn_Type IRQn, uint8_t lvl_abs)
{
uint8_t nlbits = __ECLIC_GetCfgNlbits();
uint8_t intctlbits = (uint8_t)__ECLIC_INTCTLBITS;
if (nlbits == 0) {
return;
}
if (nlbits > intctlbits) {
nlbits = intctlbits;
}
uint8_t maxlvl = ((1 << nlbits) - 1);
if (lvl_abs > maxlvl) {
lvl_abs = maxlvl;
}
uint8_t lvl = lvl_abs << (ECLIC_MAX_NLBITS - nlbits);
uint8_t cur_ctrl = __ECLIC_GetCtrlIRQ(IRQn);
cur_ctrl = cur_ctrl << nlbits;
cur_ctrl = cur_ctrl >> nlbits;
__ECLIC_SetCtrlIRQ(IRQn, (cur_ctrl | lvl));
}
/**
* \brief Get ECLIC Interrupt level of a specific interrupt
* \details
* This function get interrupt level of the specific interrupt \em IRQn.
* \param [in] IRQn Interrupt number
* \return Interrupt level
* \remarks
* - IRQn must not be negative.
* \sa
* - \ref ECLIC_SetLevelIRQ
*/
__STATIC_FORCEINLINE uint8_t __ECLIC_GetLevelIRQ(IRQn_Type IRQn)
{
uint8_t nlbits = __ECLIC_GetCfgNlbits();
uint8_t intctlbits = (uint8_t)__ECLIC_INTCTLBITS;
if (nlbits == 0) {
return 0;
}
if (nlbits > intctlbits) {
nlbits = intctlbits;
}
uint8_t intctrl = __ECLIC_GetCtrlIRQ(IRQn);
uint8_t lvl_abs = intctrl >> (ECLIC_MAX_NLBITS - nlbits);
return lvl_abs;
}
/**
* \brief Get ECLIC Interrupt priority of a specific interrupt
* \details
* This function get interrupt priority of the specific interrupt \em IRQn.
* \param [in] IRQn Interrupt number
* \param [in] pri Interrupt priority
* \remarks
* - IRQn must not be negative.
* - If pri to be set is larger than the max priority allowed, it will be force to be max priority.
* - Priority width is CLICINTCTLBITS minus clciinfo.nlbits if clciinfo.nlbits
* is less than CLICINTCTLBITS. Otherwise priority width is 0.
* \sa
* - \ref ECLIC_GetPriorityIRQ
*/
__STATIC_FORCEINLINE void __ECLIC_SetPriorityIRQ(IRQn_Type IRQn, uint8_t pri)
{
uint8_t nlbits = __ECLIC_GetCfgNlbits();
uint8_t intctlbits = (uint8_t)__ECLIC_INTCTLBITS;
if (nlbits < intctlbits) {
uint8_t maxpri = ((1 << (intctlbits - nlbits)) - 1);
if (pri > maxpri) {
pri = maxpri;
}
pri = pri << (ECLIC_MAX_NLBITS - intctlbits);
uint8_t mask = ((uint8_t)(-1)) >> intctlbits;
pri = pri | mask;
uint8_t cur_ctrl = __ECLIC_GetCtrlIRQ(IRQn);
cur_ctrl = cur_ctrl >> (ECLIC_MAX_NLBITS - nlbits);
cur_ctrl = cur_ctrl << (ECLIC_MAX_NLBITS - nlbits);
__ECLIC_SetCtrlIRQ(IRQn, (cur_ctrl | pri));
}
}
/**
* \brief Get ECLIC Interrupt priority of a specific interrupt
* \details
* This function get interrupt priority of the specific interrupt \em IRQn.
* \param [in] IRQn Interrupt number
* \return Interrupt priority
* \remarks
* - IRQn must not be negative.
* \sa
* - \ref ECLIC_SetPriorityIRQ
*/
__STATIC_FORCEINLINE uint8_t __ECLIC_GetPriorityIRQ(IRQn_Type IRQn)
{
uint8_t nlbits = __ECLIC_GetCfgNlbits();
uint8_t intctlbits = (uint8_t)__ECLIC_INTCTLBITS;
if (nlbits < intctlbits) {
uint8_t cur_ctrl = __ECLIC_GetCtrlIRQ(IRQn);
uint8_t pri = cur_ctrl << nlbits;
pri = pri >> nlbits;
pri = pri >> (ECLIC_MAX_NLBITS - intctlbits);
return pri;
} else {
return 0;
}
}
/**
* \brief Set Interrupt Vector of a specific interrupt
* \details
* This function set interrupt handler address of the specific interrupt \em IRQn.
* \param [in] IRQn Interrupt number
* \param [in] vector Interrupt handler address
* \remarks
* - IRQn must not be negative.
* - You can set the \ref CSR_CSR_MTVT to set interrupt vector table entry address.
* - If your vector table is placed in readonly section, the vector for IRQn will not be modified.
* For this case, you need to use the correct irq handler name defined in your vector table as
* your irq handler function name.
* - This function will only work correctly when the vector table is placed in an read-write enabled section.
* \sa
* - \ref ECLIC_GetVector
*/
__STATIC_FORCEINLINE void __ECLIC_SetVector(IRQn_Type IRQn, rv_csr_t vector)
{
volatile unsigned long vec_base;
vec_base = ((unsigned long)__RV_CSR_READ(CSR_MTVT));
vec_base += ((unsigned long)IRQn) * sizeof(unsigned long);
(* (unsigned long *) vec_base) = vector;
#if (defined(__DCACHE_PRESENT) && (__DCACHE_PRESENT == 1))
MFlushDCacheLine((unsigned long)vec_base);
#endif
}
/**
* \brief Get Interrupt Vector of a specific interrupt
* \details
* This function get interrupt handler address of the specific interrupt \em IRQn.
* \param [in] IRQn Interrupt number
* \return Interrupt handler address
* \remarks
* - IRQn must not be negative.
* - You can read \ref CSR_CSR_MTVT to get interrupt vector table entry address.
* \sa
* - \ref ECLIC_SetVector
*/
__STATIC_FORCEINLINE rv_csr_t __ECLIC_GetVector(IRQn_Type IRQn)
{
#if __RISCV_XLEN == 32
return (*(uint32_t *)(__RV_CSR_READ(CSR_MTVT)+IRQn*4));
#elif __RISCV_XLEN == 64
return (*(uint64_t *)(__RV_CSR_READ(CSR_MTVT)+IRQn*8));
#else // TODO Need cover for XLEN=128 case in future
return (*(uint64_t *)(__RV_CSR_READ(CSR_MTVT)+IRQn*8));
#endif
}
/**
* \brief Set Exception entry address
* \details
* This function set exception handler address to 'CSR_MTVEC'.
* \param [in] addr Exception handler address
* \remarks
* - This function use to set exception handler address to 'CSR_MTVEC'. Address is 4 bytes align.
* \sa
* - \ref __get_exc_entry
*/
__STATIC_FORCEINLINE void __set_exc_entry(rv_csr_t addr)
{
addr &= (rv_csr_t)(~0x3F);
addr |= ECLIC_MODE_MTVEC_Msk;
__RV_CSR_WRITE(CSR_MTVEC, addr);
}
/**
* \brief Get Exception entry address
* \details
* This function get exception handler address from 'CSR_MTVEC'.
* \return Exception handler address
* \remarks
* - This function use to get exception handler address from 'CSR_MTVEC'. Address is 4 bytes align
* \sa
* - \ref __set_exc_entry
*/
__STATIC_FORCEINLINE rv_csr_t __get_exc_entry(void)
{
unsigned long addr = __RV_CSR_READ(CSR_MTVEC);
return (addr & ~ECLIC_MODE_MTVEC_Msk);
}
/**
* \brief Set Non-vector interrupt entry address
* \details
* This function set Non-vector interrupt address.
* \param [in] addr Non-vector interrupt entry address
* \remarks
* - This function use to set non-vector interrupt entry address to 'CSR_MTVT2' if
* - CSR_MTVT2 bit0 is 1. If 'CSR_MTVT2' bit0 is 0 then set address to 'CSR_MTVEC'
* \sa
* - \ref __get_nonvec_entry
*/
__STATIC_FORCEINLINE void __set_nonvec_entry(rv_csr_t addr)
{
if (__RV_CSR_READ(CSR_MTVT2) & 0x1){
__RV_CSR_WRITE(CSR_MTVT2, addr | 0x01);
} else {
addr &= (rv_csr_t)(~0x3F);
addr |= ECLIC_MODE_MTVEC_Msk;
__RV_CSR_WRITE(CSR_MTVEC, addr);
}
}
/**
* \brief Get Non-vector interrupt entry address
* \details
* This function get Non-vector interrupt address.
* \return Non-vector interrupt handler address
* \remarks
* - This function use to get non-vector interrupt entry address from 'CSR_MTVT2' if
* - CSR_MTVT2 bit0 is 1. If 'CSR_MTVT2' bit0 is 0 then get address from 'CSR_MTVEC'.
* \sa
* - \ref __set_nonvec_entry
*/
__STATIC_FORCEINLINE rv_csr_t __get_nonvec_entry(void)
{
if (__RV_CSR_READ(CSR_MTVT2) & 0x1) {
return __RV_CSR_READ(CSR_MTVT2) & (~(rv_csr_t)(0x1));
} else {
rv_csr_t addr = __RV_CSR_READ(CSR_MTVEC);
return (addr & ~ECLIC_MODE_MTVEC_Msk);
}
}
/**
* \brief Get NMI interrupt entry from 'CSR_MNVEC'
* \details
* This function get NMI interrupt address from 'CSR_MNVEC'.
* \return NMI interrupt handler address
* \remarks
* - This function use to get NMI interrupt handler address from 'CSR_MNVEC'. If CSR_MMISC_CTL[9] = 1 'CSR_MNVEC'
* - will be equal as mtvec. If CSR_MMISC_CTL[9] = 0 'CSR_MNVEC' will be equal as reset vector.
* - NMI entry is defined via \ref CSR_MMISC_CTL, writing to \ref CSR_MNVEC will be ignored.
*/
__STATIC_FORCEINLINE rv_csr_t __get_nmi_entry(void)
{
return __RV_CSR_READ(CSR_MNVEC);
}
/**
* \brief Save necessary CSRs into variables for vector interrupt nesting
* \details
* This macro is used to declare variables which are used for saving
* CSRs(MCAUSE, MEPC, MSUB), and it will read these CSR content into
* these variables, it need to be used in a vector-interrupt if nesting
* is required.
* \remarks
* - Interrupt will be enabled after this macro is called
* - It need to be used together with \ref RESTORE_IRQ_CSR_CONTEXT
* - Don't use variable names __mcause, __mpec, __msubm in your ISR code
* - If you want to enable interrupt nesting feature for vector interrupt,
* you can do it like this:
* \code
* // __INTERRUPT attribute will generates function entry and exit sequences suitable
* // for use in an interrupt handler when this attribute is present
* __INTERRUPT void eclic_mtip_handler(void)
* {
* // Must call this to save CSRs
* SAVE_IRQ_CSR_CONTEXT();
* // !!!Interrupt is enabled here!!!
* // !!!Higher priority interrupt could nest it!!!
*
* // put you own interrupt handling code here
*
* // Must call this to restore CSRs
* RESTORE_IRQ_CSR_CONTEXT();
* }
* \endcode
*/
#define SAVE_IRQ_CSR_CONTEXT() \
rv_csr_t __mcause = __RV_CSR_READ(CSR_MCAUSE); \
rv_csr_t __mepc = __RV_CSR_READ(CSR_MEPC); \
rv_csr_t __msubm = __RV_CSR_READ(CSR_MSUBM); \
__enable_irq();
/**
* \brief Restore necessary CSRs from variables for vector interrupt nesting
* \details
* This macro is used restore CSRs(MCAUSE, MEPC, MSUB) from pre-defined variables
* in \ref SAVE_IRQ_CSR_CONTEXT macro.
* \remarks
* - Interrupt will be disabled after this macro is called
* - It need to be used together with \ref SAVE_IRQ_CSR_CONTEXT
*/
#define RESTORE_IRQ_CSR_CONTEXT() \
__disable_irq(); \
__RV_CSR_WRITE(CSR_MSUBM, __msubm); \
__RV_CSR_WRITE(CSR_MEPC, __mepc); \
__RV_CSR_WRITE(CSR_MCAUSE, __mcause);
/** @} */ /* End of Doxygen Group NMSIS_Core_IntExc */
#endif /* defined(__ECLIC_PRESENT) && (__ECLIC_PRESENT == 1) */
#ifdef __cplusplus
}
#endif
#endif /** __CORE_FEATURE_ECLIC__ */

View File

@ -0,0 +1,364 @@
/*
* Copyright (c) 2019 Nuclei 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 __CORE_FEATURE_TIMER_H__
#define __CORE_FEATURE_TIMER_H__
/*!
* @file core_feature_timer.h
* @brief System Timer feature API header file for Nuclei N/NX Core
*/
/*
* System Timer Feature Configuration Macro:
* 1. __SYSTIMER_PRESENT: Define whether Private System Timer is present or not.
* * 0: Not present
* * 1: Present
* 2. __SYSTIMER_BASEADDR: Define the base address of the System Timer.
*/
#ifdef __cplusplus
extern "C" {
#endif
#if defined(__SYSTIMER_PRESENT) && (__SYSTIMER_PRESENT == 1)
/**
* \defgroup NMSIS_Core_SysTimer_Registers Register Define and Type Definitions Of System Timer
* \ingroup NMSIS_Core_Registers
* \brief Type definitions and defines for system timer registers.
*
* @{
*/
/**
* \brief Structure type to access the System Timer (SysTimer).
* \details
* Structure definition to access the system timer(SysTimer).
* \remarks
* - MSFTRST register is introduced in Nuclei N Core version 1.3(\ref __NUCLEI_N_REV >= 0x0103)
* - MSTOP register is renamed to MTIMECTL register in Nuclei N Core version 1.4(\ref __NUCLEI_N_REV >= 0x0104)
* - CMPCLREN and CLKSRC bit in MTIMECTL register is introduced in Nuclei N Core version 1.4(\ref __NUCLEI_N_REV >= 0x0104)
*/
typedef struct {
__IOM uint64_t MTIMER; /*!< Offset: 0x000 (R/W) System Timer current value 64bits Register */
__IOM uint64_t MTIMERCMP; /*!< Offset: 0x008 (R/W) System Timer compare Value 64bits Register */
__IOM uint32_t RESERVED0[0x3F8]; /*!< Offset: 0x010 - 0xFEC Reserved */
__IOM uint32_t MSFTRST; /*!< Offset: 0xFF0 (R/W) System Timer Software Core Reset Register */
__IOM uint32_t RESERVED1; /*!< Offset: 0xFF4 Reserved */
__IOM uint32_t MTIMECTL; /*!< Offset: 0xFF8 (R/W) System Timer Control Register, previously MSTOP register */
__IOM uint32_t MSIP; /*!< Offset: 0xFFC (R/W) System Timer SW interrupt Register */
} SysTimer_Type;
/* Timer Control / Status Register Definitions */
#define SysTimer_MTIMECTL_TIMESTOP_Pos 0U /*!< SysTick Timer MTIMECTL: TIMESTOP bit Position */
#define SysTimer_MTIMECTL_TIMESTOP_Msk (1UL << SysTimer_MTIMECTL_TIMESTOP_Pos) /*!< SysTick Timer MTIMECTL: TIMESTOP Mask */
#define SysTimer_MTIMECTL_CMPCLREN_Pos 1U /*!< SysTick Timer MTIMECTL: CMPCLREN bit Position */
#define SysTimer_MTIMECTL_CMPCLREN_Msk (1UL << SysTimer_MTIMECTL_CMPCLREN_Pos) /*!< SysTick Timer MTIMECTL: CMPCLREN Mask */
#define SysTimer_MTIMECTL_CLKSRC_Pos 2U /*!< SysTick Timer MTIMECTL: CLKSRC bit Position */
#define SysTimer_MTIMECTL_CLKSRC_Msk (1UL << SysTimer_MTIMECTL_CLKSRC_Pos) /*!< SysTick Timer MTIMECTL: CLKSRC Mask */
#define SysTimer_MSIP_MSIP_Pos 0U /*!< SysTick Timer MSIP: MSIP bit Position */
#define SysTimer_MSIP_MSIP_Msk (1UL << SysTimer_MSIP_MSIP_Pos) /*!< SysTick Timer MSIP: MSIP Mask */
#define SysTimer_MTIMER_Msk (0xFFFFFFFFFFFFFFFFULL) /*!< SysTick Timer MTIMER value Mask */
#define SysTimer_MTIMERCMP_Msk (0xFFFFFFFFFFFFFFFFULL) /*!< SysTick Timer MTIMERCMP value Mask */
#define SysTimer_MTIMECTL_Msk (0xFFFFFFFFUL) /*!< SysTick Timer MTIMECTL/MSTOP value Mask */
#define SysTimer_MSIP_Msk (0xFFFFFFFFUL) /*!< SysTick Timer MSIP value Mask */
#define SysTimer_MSFTRST_Msk (0xFFFFFFFFUL) /*!< SysTick Timer MSFTRST value Mask */
#define SysTimer_MSFRST_KEY (0x80000A5FUL) /*!< SysTick Timer Software Reset Request Key */
#ifndef __SYSTIMER_BASEADDR
/* Base address of SYSTIMER(__SYSTIMER_BASEADDR) should be defined in <Device.h> */
#error "__SYSTIMER_BASEADDR is not defined, please check!"
#endif
/* System Timer Memory mapping of Device */
#define SysTimer_BASE __SYSTIMER_BASEADDR /*!< SysTick Base Address */
#define SysTimer ((SysTimer_Type *) SysTimer_BASE) /*!< SysTick configuration struct */
/** @} */ /* end of group NMSIS_Core_SysTimer_Registers */
/* ################################## SysTimer function ############################################ */
/**
* \defgroup NMSIS_Core_SysTimer SysTimer Functions
* \brief Functions that configure the Core System Timer.
* @{
*/
/**
* \brief Set system timer load value
* \details
* This function set the system timer load value in MTIMER register.
* \param [in] value value to set system timer MTIMER register.
* \remarks
* - Load value is 64bits wide.
* - \ref SysTimer_GetLoadValue
*/
__STATIC_FORCEINLINE void SysTimer_SetLoadValue(uint64_t value)
{
SysTimer->MTIMER = value;
}
/**
* \brief Get system timer load value
* \details
* This function get the system timer current value in MTIMER register.
* \return current value(64bit) of system timer MTIMER register.
* \remarks
* - Load value is 64bits wide.
* - \ref SysTimer_SetLoadValue
*/
__STATIC_FORCEINLINE uint64_t SysTimer_GetLoadValue(void)
{
return SysTimer->MTIMER;
}
/**
* \brief Set system timer compare value
* \details
* This function set the system Timer compare value in MTIMERCMP register.
* \param [in] value compare value to set system timer MTIMERCMP register.
* \remarks
* - Compare value is 64bits wide.
* - If compare value is larger than current value timer interrupt generate.
* - Modify the load value or compare value less to clear the interrupt.
* - \ref SysTimer_GetCompareValue
*/
__STATIC_FORCEINLINE void SysTimer_SetCompareValue(uint64_t value)
{
SysTimer->MTIMERCMP = value;
}
/**
* \brief Get system timer compare value
* \details
* This function get the system timer compare value in MTIMERCMP register.
* \return compare value of system timer MTIMERCMP register.
* \remarks
* - Compare value is 64bits wide.
* - \ref SysTimer_SetCompareValue
*/
__STATIC_FORCEINLINE uint64_t SysTimer_GetCompareValue(void)
{
return SysTimer->MTIMERCMP;
}
/**
* \brief Enable system timer counter running
* \details
* Enable system timer counter running by clear
* TIMESTOP bit in MTIMECTL register.
*/
__STATIC_FORCEINLINE void SysTimer_Start(void)
{
SysTimer->MTIMECTL &= ~(SysTimer_MTIMECTL_TIMESTOP_Msk);
}
/**
* \brief Stop system timer counter running
* \details
* Stop system timer counter running by set
* TIMESTOP bit in MTIMECTL register.
*/
__STATIC_FORCEINLINE void SysTimer_Stop(void)
{
SysTimer->MTIMECTL |= SysTimer_MTIMECTL_TIMESTOP_Msk;
}
/**
* \brief Set system timer control value
* \details
* This function set the system timer MTIMECTL register value.
* \param [in] mctl value to set MTIMECTL register
* \remarks
* - Bit TIMESTOP is used to start and stop timer.
* Clear TIMESTOP bit to 0 to start timer, otherwise to stop timer.
* - Bit CMPCLREN is used to enable auto MTIMER clear to zero when MTIMER >= MTIMERCMP.
* Clear CMPCLREN bit to 0 to stop auto clear MTIMER feature, otherwise to enable it.
* - Bit CLKSRC is used to select timer clock source.
* Clear CLKSRC bit to 0 to use *mtime_toggle_a*, otherwise use *core_clk_aon*
* - \ref SysTimer_GetControlValue
*/
__STATIC_FORCEINLINE void SysTimer_SetControlValue(uint32_t mctl)
{
SysTimer->MTIMECTL = (mctl & SysTimer_MTIMECTL_Msk);
}
/**
* \brief Get system timer control value
* \details
* This function get the system timer MTIMECTL register value.
* \return MTIMECTL register value
* \remarks
* - \ref SysTimer_SetControlValue
*/
__STATIC_FORCEINLINE uint32_t SysTimer_GetControlValue(void)
{
return (SysTimer->MTIMECTL & SysTimer_MTIMECTL_Msk);
}
/**
* \brief Trigger or set software interrupt via system timer
* \details
* This function set the system timer MSIP bit in MSIP register.
* \remarks
* - Set system timer MSIP bit and generate a SW interrupt.
* - \ref SysTimer_ClearSWIRQ
* - \ref SysTimer_GetMsipValue
*/
__STATIC_FORCEINLINE void SysTimer_SetSWIRQ(void)
{
SysTimer->MSIP |= SysTimer_MSIP_MSIP_Msk;
}
/**
* \brief Clear system timer software interrupt pending request
* \details
* This function clear the system timer MSIP bit in MSIP register.
* \remarks
* - Clear system timer MSIP bit in MSIP register to clear the software interrupt pending.
* - \ref SysTimer_SetSWIRQ
* - \ref SysTimer_GetMsipValue
*/
__STATIC_FORCEINLINE void SysTimer_ClearSWIRQ(void)
{
SysTimer->MSIP &= ~SysTimer_MSIP_MSIP_Msk;
}
/**
* \brief Get system timer MSIP register value
* \details
* This function get the system timer MSIP register value.
* \return Value of Timer MSIP register.
* \remarks
* - Bit0 is SW interrupt flag.
* Bit0 is 1 then SW interrupt set. Bit0 is 0 then SW interrupt clear.
* - \ref SysTimer_SetSWIRQ
* - \ref SysTimer_ClearSWIRQ
*/
__STATIC_FORCEINLINE uint32_t SysTimer_GetMsipValue(void)
{
return (uint32_t)(SysTimer->MSIP & SysTimer_MSIP_Msk);
}
/**
* \brief Set system timer MSIP register value
* \details
* This function set the system timer MSIP register value.
* \param [in] msip value to set MSIP register
*/
__STATIC_FORCEINLINE void SysTimer_SetMsipValue(uint32_t msip)
{
SysTimer->MSIP = (msip & SysTimer_MSIP_Msk);
}
/**
* \brief Do software reset request
* \details
* This function will do software reset request through MTIMER
* - Software need to write \ref SysTimer_MSFRST_KEY to generate software reset request
* - The software request flag can be cleared by reset operation to clear
* \remarks
* - The software reset is sent to SoC, SoC need to generate reset signal and send back to Core
* - This function will not return, it will do while(1) to wait the Core reset happened
*/
__STATIC_FORCEINLINE void SysTimer_SoftwareReset(void)
{
SysTimer->MSFTRST = SysTimer_MSFRST_KEY;
while(1);
}
#if defined (__Vendor_SysTickConfig) && (__Vendor_SysTickConfig == 0U) && defined(__ECLIC_PRESENT) && (__ECLIC_PRESENT == 1)
/**
* \brief System Tick Configuration
* \details Initializes the System Timer and its non-vector interrupt, and starts the System Tick Timer.
*
* In our default implementation, the timer counter will be set to zero, and it will start a timer compare non-vector interrupt
* when it matchs the ticks user set, during the timer interrupt user should reload the system tick using \ref SysTick_Reload function
* or similar function written by user, so it can produce period timer interrupt.
* \param [in] ticks Number of ticks between two interrupts.
* \return 0 Function succeeded.
* \return 1 Function failed.
* \remarks
* - For \ref __NUCLEI_N_REV >= 0x0104, the CMPCLREN bit in MTIMECTL is introduced,
* but we assume that the CMPCLREN bit is set to 0, so MTIMER register will not be
* auto cleared to 0 when MTIMER >= MTIMERCMP.
* - When the variable \ref __Vendor_SysTickConfig is set to 1, then the
* function \ref SysTick_Config is not included.
* - In this case, the file <b><Device>.h</b> must contain a vendor-specific implementation
* of this function.
* - If user need this function to start a period timer interrupt, then in timer interrupt handler
* routine code, user should call \ref SysTick_Reload with ticks to reload the timer.
* - This function only available when __SYSTIMER_PRESENT == 1 and __ECLIC_PRESENT == 1 and __Vendor_SysTickConfig == 0
* \sa
* - \ref SysTimer_SetCompareValue; SysTimer_SetLoadValue
*/
__STATIC_INLINE uint32_t SysTick_Config(uint64_t ticks)
{
SysTimer_SetLoadValue(0);
SysTimer_SetCompareValue(ticks);
ECLIC_SetShvIRQ(SysTimer_IRQn, ECLIC_NON_VECTOR_INTERRUPT);
ECLIC_SetLevelIRQ(SysTimer_IRQn, 0);
ECLIC_EnableIRQ(SysTimer_IRQn);
return (0UL);
}
/**
* \brief System Tick Reload
* \details Reload the System Timer Tick when the MTIMECMP reached TIME value
*
* \param [in] ticks Number of ticks between two interrupts.
* \return 0 Function succeeded.
* \return 1 Function failed.
* \remarks
* - For \ref __NUCLEI_N_REV >= 0x0104, the CMPCLREN bit in MTIMECTL is introduced,
* but for this \ref SysTick_Config function, we assume this CMPCLREN bit is set to 0,
* so in interrupt handler function, user still need to set the MTIMERCMP or MTIMER to reload
* the system tick, if vendor want to use this timer's auto clear feature, they can define
* \ref __Vendor_SysTickConfig to 1, and implement \ref SysTick_Config and \ref SysTick_Reload functions.
* - When the variable \ref __Vendor_SysTickConfig is set to 1, then the
* function \ref SysTick_Reload is not included.
* - In this case, the file <b><Device>.h</b> must contain a vendor-specific implementation
* of this function.
* - This function only available when __SYSTIMER_PRESENT == 1 and __ECLIC_PRESENT == 1 and __Vendor_SysTickConfig == 0
* - Since the MTIMERCMP value might overflow, if overflowed, MTIMER will be set to 0, and MTIMERCMP set to ticks
* \sa
* - \ref SysTimer_SetCompareValue
* - \ref SysTimer_SetLoadValue
*/
__STATIC_FORCEINLINE uint32_t SysTick_Reload(uint64_t ticks)
{
uint64_t cur_ticks = SysTimer->MTIMER;
uint64_t reload_ticks = ticks + cur_ticks;
if (__USUALLY(reload_ticks > cur_ticks)) {
SysTimer->MTIMERCMP = reload_ticks;
} else {
/* When added the ticks value, then the MTIMERCMP < TIMER,
* which means the MTIMERCMP is overflowed,
* so we need to reset the counter to zero */
SysTimer->MTIMER = 0;
SysTimer->MTIMERCMP = ticks;
}
return (0UL);
}
#endif /* defined(__Vendor_SysTickConfig) && (__Vendor_SysTickConfig == 0U) */
/** @} */ /* End of Doxygen Group NMSIS_Core_SysTimer */
#endif /* defined(__SYSTIMER_PRESENT) && (__SYSTIMER_PRESENT == 1) */
#ifdef __cplusplus
}
#endif
#endif /** __CORE_FEATURE_TIMER_H__ */

View File

@ -0,0 +1,445 @@
/******************************************************************************
* @file gd32vf103.h
* @brief NMSIS Core Peripheral Access Layer Header File for GD32VF103 series
*
* @version V1.00
* @date 4. Jan 2020
******************************************************************************/
/*
* Copyright (c) 2019 Nuclei 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 __GD32VF103_H__
#define __GD32VF103_H__
#include <stddef.h>
#ifdef __cplusplus
extern "C" {
#endif
/** @addtogroup gd32
* @{
*/
/** @addtogroup gd32vf103
* @{
*/
/** @addtogroup Configuration_of_NMSIS
* @{
*/
/** \brief SoC Download mode definition */
typedef enum {
DOWNLOAD_MODE_FLASHXIP = 0, /*!< Flashxip download mode */
DOWNLOAD_MODE_FLASH = 1, /*!< Flash download mode */
DOWNLOAD_MODE_ILM = 2, /*!< ilm download mode */
DOWNLOAD_MODE_DDR = 3, /*!< ddr download mode */
DOWNLOAD_MODE_MAX,
} DownloadMode_Type;
/* =========================================================================================================================== */
/* ================ Interrupt Number Definition ================ */
/* =========================================================================================================================== */
typedef enum IRQn {
/* ======================================= Nuclei Core Specific Interrupt Numbers ======================================== */
Reserved0_IRQn = 0, /*!< Internal reserved */
Reserved1_IRQn = 1, /*!< Internal reserved */
Reserved2_IRQn = 2, /*!< Internal reserved */
SysTimerSW_IRQn = 3, /*!< System Timer SW interrupt */
Reserved3_IRQn = 4, /*!< Internal reserved */
Reserved4_IRQn = 5, /*!< Internal reserved */
Reserved5_IRQn = 6, /*!< Internal reserved */
SysTimer_IRQn = 7, /*!< System Timer Interrupt */
Reserved6_IRQn = 8, /*!< Internal reserved */
Reserved7_IRQn = 9, /*!< Internal reserved */
Reserved8_IRQn = 10, /*!< Internal reserved */
Reserved9_IRQn = 11, /*!< Internal reserved */
Reserved10_IRQn = 12, /*!< Internal reserved */
Reserved11_IRQn = 13, /*!< Internal reserved */
Reserved12_IRQn = 14, /*!< Internal reserved */
Reserved13_IRQn = 15, /*!< Internal reserved */
Reserved14_IRQn = 16, /*!< Internal reserved */
BusError_IRQn = 17, /*!< Bus Error interrupt */
PerfMon_IRQn = 18, /*!< Performance Monitor */
/* =========================================== GD32VF103 Specific Interrupt Numbers ========================================= */
/* ToDo: add here your device specific external interrupt numbers. 19~1023 is reserved number for user. Maxmum interrupt supported
could get from clicinfo.NUM_INTERRUPT. According the interrupt handlers defined in startup_Device.s
eg.: Interrupt for Timer#1 TIM1_IRQHandler -> TIM1_IRQn */
/* interruput numbers */
WWDGT_IRQn = 19, /*!< window watchDog timer interrupt */
LVD_IRQn = 20, /*!< LVD through EXTI line detect interrupt */
TAMPER_IRQn = 21, /*!< tamper through EXTI line detect */
RTC_IRQn = 22, /*!< RTC alarm interrupt */
FMC_IRQn = 23, /*!< FMC interrupt */
RCU_CTC_IRQn = 24, /*!< RCU and CTC interrupt */
EXTI0_IRQn = 25, /*!< EXTI line 0 interrupts */
EXTI1_IRQn = 26, /*!< EXTI line 1 interrupts */
EXTI2_IRQn = 27, /*!< EXTI line 2 interrupts */
EXTI3_IRQn = 28, /*!< EXTI line 3 interrupts */
EXTI4_IRQn = 29, /*!< EXTI line 4 interrupts */
DMA0_Channel0_IRQn = 30, /*!< DMA0 channel0 interrupt */
DMA0_Channel1_IRQn = 31, /*!< DMA0 channel1 interrupt */
DMA0_Channel2_IRQn = 32, /*!< DMA0 channel2 interrupt */
DMA0_Channel3_IRQn = 33, /*!< DMA0 channel3 interrupt */
DMA0_Channel4_IRQn = 34, /*!< DMA0 channel4 interrupt */
DMA0_Channel5_IRQn = 35, /*!< DMA0 channel5 interrupt */
DMA0_Channel6_IRQn = 36, /*!< DMA0 channel6 interrupt */
ADC0_1_IRQn = 37, /*!< ADC0 and ADC1 interrupt */
CAN0_TX_IRQn = 38, /*!< CAN0 TX interrupts */
CAN0_RX0_IRQn = 39, /*!< CAN0 RX0 interrupts */
CAN0_RX1_IRQn = 40, /*!< CAN0 RX1 interrupts */
CAN0_EWMC_IRQn = 41, /*!< CAN0 EWMC interrupts */
EXTI5_9_IRQn = 42, /*!< EXTI[9:5] interrupts */
TIMER0_BRK_IRQn = 43, /*!< TIMER0 break interrupts */
TIMER0_UP_IRQn = 44, /*!< TIMER0 update interrupts */
TIMER0_TRG_CMT_IRQn = 45, /*!< TIMER0 trigger and commutation interrupts */
TIMER0_Channel_IRQn = 46, /*!< TIMER0 channel capture compare interrupts */
TIMER1_IRQn = 47, /*!< TIMER1 interrupt */
TIMER2_IRQn = 48, /*!< TIMER2 interrupt */
TIMER3_IRQn = 49, /*!< TIMER3 interrupts */
I2C0_EV_IRQn = 50, /*!< I2C0 event interrupt */
I2C0_ER_IRQn = 51, /*!< I2C0 error interrupt */
I2C1_EV_IRQn = 52, /*!< I2C1 event interrupt */
I2C1_ER_IRQn = 53, /*!< I2C1 error interrupt */
SPI0_IRQn = 54, /*!< SPI0 interrupt */
SPI1_IRQn = 55, /*!< SPI1 interrupt */
USART0_IRQn = 56, /*!< USART0 interrupt */
USART1_IRQn = 57, /*!< USART1 interrupt */
USART2_IRQn = 58, /*!< USART2 interrupt */
EXTI10_15_IRQn = 59, /*!< EXTI[15:10] interrupts */
RTC_ALARM_IRQn = 60, /*!< RTC alarm interrupt EXTI */
USBFS_WKUP_IRQn = 61, /*!< USBFS wakeup interrupt */
EXMC_IRQn = 67, /*!< EXMC global interrupt */
TIMER4_IRQn = 69, /*!< TIMER4 global interrupt */
SPI2_IRQn = 70, /*!< SPI2 global interrupt */
UART3_IRQn = 71, /*!< UART3 global interrupt */
UART4_IRQn = 72, /*!< UART4 global interrupt */
TIMER5_IRQn = 73, /*!< TIMER5 global interrupt */
TIMER6_IRQn = 74, /*!< TIMER6 global interrupt */
DMA1_Channel0_IRQn = 75, /*!< DMA1 channel0 global interrupt */
DMA1_Channel1_IRQn = 76, /*!< DMA1 channel1 global interrupt */
DMA1_Channel2_IRQn = 77, /*!< DMA1 channel2 global interrupt */
DMA1_Channel3_IRQn = 78, /*!< DMA1 channel3 global interrupt */
DMA1_Channel4_IRQn = 79, /*!< DMA1 channel3 global interrupt */
CAN1_TX_IRQn = 82, /*!< CAN1 TX interrupt */
CAN1_RX0_IRQn = 83, /*!< CAN1 RX0 interrupt */
CAN1_RX1_IRQn = 84, /*!< CAN1 RX1 interrupt */
CAN1_EWMC_IRQn = 85, /*!< CAN1 EWMC interrupt */
USBFS_IRQn = 86, /*!< USBFS global interrupt */
SOC_INT_MAX,
} IRQn_Type;
/* =========================================================================================================================== */
/* ================ Exception Code Definition ================ */
/* =========================================================================================================================== */
typedef enum EXCn {
/* ======================================= Nuclei N/NX Specific Exception Code ======================================== */
InsUnalign_EXCn = 0, /*!< Instruction address misaligned */
InsAccFault_EXCn = 1, /*!< Instruction access fault */
IlleIns_EXCn = 2, /*!< Illegal instruction */
Break_EXCn = 3, /*!< Beakpoint */
LdAddrUnalign_EXCn = 4, /*!< Load address misaligned */
LdFault_EXCn = 5, /*!< Load access fault */
StAddrUnalign_EXCn = 6, /*!< Store or AMO address misaligned */
StAccessFault_EXCn = 7, /*!< Store or AMO access fault */
UmodeEcall_EXCn = 8, /*!< Environment call from User mode */
MmodeEcall_EXCn = 11, /*!< Environment call from Machine mode */
NMI_EXCn = 0xfff, /*!< NMI interrupt*/
} EXCn_Type;
/* =========================================================================================================================== */
/* ================ Processor and Core Peripheral Section ================ */
/* =========================================================================================================================== */
/* ToDo: set the defines according your Device */
/* ToDo: define the correct core revision */
#define __NUCLEI_N_REV 0x0100 /*!< Core Revision r1p0 */
/* ToDo: define the correct core features for the nuclei_soc */
#define __ECLIC_PRESENT 1 /*!< Set to 1 if ECLIC is present */
#define __ECLIC_BASEADDR 0xD2000000UL /*!< Set to ECLIC baseaddr of your device */
#define __ECLIC_INTCTLBITS 4 /*!< Set to 1 - 8, the number of hardware bits are actually implemented in the clicintctl registers. */
#define __ECLIC_INTNUM 86 /*!< Set to 1 - 1005, the external interrupt number of ECLIC Unit */
#define __SYSTIMER_PRESENT 1 /*!< Set to 1 if System Timer is present */
#define __SYSTIMER_BASEADDR 0xD1000000UL /*!< Set to SysTimer baseaddr of your device */
/*!< Set to 0, 1, or 2, 0 not present, 1 single floating point unit present, 2 double floating point unit present */
#define __FPU_PRESENT 0
#define __DSP_PRESENT 0 /*!< Set to 1 if DSP is present */
#define __PMP_PRESENT 1 /*!< Set to 1 if PMP is present */
#define __PMP_ENTRY_NUM 8 /*!< Set to 8 or 16, the number of PMP entries */
#define __ICACHE_PRESENT 0 /*!< Set to 1 if I-Cache is present */
#define __DCACHE_PRESENT 0 /*!< Set to 1 if D-Cache is present */
#define __Vendor_SysTickConfig 0 /*!< Set to 1 if different SysTick Config is used */
#define __Vendor_EXCEPTION 0 /*!< Set to 1 if vendor exception hander is present */
/** @} */ /* End of group Configuration_of_CMSIS */
// #include <nmsis_core.h> /*!< Nuclei N/NX class processor and core peripherals */
/* ToDo: include your system_nuclei_soc.h file
replace 'Device' with your device name */
#include "system_gd32vf103.h" /*!< gd32vf103 System */
/* ======================================== Start of section using anonymous unions ======================================== */
#if defined (__GNUC__)
/* anonymous unions are enabled by default */
#else
#warning Not supported compiler type
#endif
/* system frequency define */
#define __IRC8M (IRC8M_VALUE) /* internal 8 MHz RC oscillator frequency */
#define __HXTAL (HXTAL_VALUE) /* high speed crystal oscillator frequency */
#define __SYS_OSC_CLK (__IRC8M) /* main oscillator frequency */
#define __SYSTEM_CLOCK_108M_PLL_HXTAL (uint32_t)(108000000)
#define RTC_FREQ LXTAL_VALUE
// The TIMER frequency is just the RTC frequency
#define SOC_TIMER_FREQ ((uint32_t)SystemCoreClock/4) //LXTAL_VALUE units HZ
#define SYSTICK_TICK_CONST (SOC_TIMER_FREQ / TICK_PER_SECOND)
/* enum definitions */
typedef enum {
DISABLE = 0,
ENABLE = !DISABLE
} EventStatus, ControlStatus;
typedef enum {
FALSE = 0,
TRUE = !FALSE
} BOOL;
typedef enum {
RESET = 0,
SET = 1,
MAX = 0X7FFFFFFF
} FlagStatus;
typedef enum {
ERR = 0,
SUCCESS = !ERR
} ErrStatus;
/* =========================================================================================================================== */
/* ================ Device Specific Peripheral Section ================ */
/* =========================================================================================================================== */
/** @addtogroup Device_Peripheral_peripherals
* @{
*/
/****************************************************************************
* Platform definitions
*****************************************************************************/
/* ToDo: add here your device specific peripheral access structure typedefs
following is an example for Systick Timer*/
/* =========================================================================================================================== */
/* ================ SysTick Timer ================ */
/* =========================================================================================================================== */
/*@}*/ /* end of group nuclei_soc_Peripherals */
/* ========================================= End of section using anonymous unions ========================================= */
#if defined (__GNUC__)
/* anonymous unions are enabled by default */
#else
#warning Not supported compiler type
#endif
/* =========================================================================================================================== */
/* ================ Device Specific Peripheral Address Map ================ */
/* =========================================================================================================================== */
/* ToDo: add here your device peripherals base addresses
following is an example for timer */
/** @addtogroup Device_Peripheral_peripheralAddr
* @{
*/
/* main flash and SRAM memory map */
#define FLASH_BASE ((uint32_t)0x08000000U) /*!< main FLASH base address */
#define SRAM_BASE ((uint32_t)0x20000000U) /*!< SRAM0 base address */
#define OB_BASE ((uint32_t)0x1FFFF800U) /*!< OB base address */
#define DBG_BASE ((uint32_t)0xE0042000U) /*!< DBG base address */
#define EXMC_BASE ((uint32_t)0xA0000000U) /*!< EXMC register base address */
/* peripheral memory map */
#define APB1_BUS_BASE ((uint32_t)0x40000000U) /*!< apb1 base address */
#define APB2_BUS_BASE ((uint32_t)0x40010000U) /*!< apb2 base address */
#define AHB1_BUS_BASE ((uint32_t)0x40018000U) /*!< ahb1 base address */
#define AHB3_BUS_BASE ((uint32_t)0x60000000U) /*!< ahb3 base address */
/* advanced peripheral bus 1 memory map */
#define TIMER_BASE (APB1_BUS_BASE + 0x00000000U) /*!< TIMER base address */
#define RTC_BASE (APB1_BUS_BASE + 0x00002800U) /*!< RTC base address */
#define WWDGT_BASE (APB1_BUS_BASE + 0x00002C00U) /*!< WWDGT base address */
#define FWDGT_BASE (APB1_BUS_BASE + 0x00003000U) /*!< FWDGT base address */
#define SPI_BASE (APB1_BUS_BASE + 0x00003800U) /*!< SPI base address */
#define USART_BASE (APB1_BUS_BASE + 0x00004400U) /*!< USART base address */
#define I2C_BASE (APB1_BUS_BASE + 0x00005400U) /*!< I2C base address */
#define CAN_BASE (APB1_BUS_BASE + 0x00006400U) /*!< CAN base address */
#define BKP_BASE (APB1_BUS_BASE + 0x00006C00U) /*!< BKP base address */
#define PMU_BASE (APB1_BUS_BASE + 0x00007000U) /*!< PMU base address */
#define DAC_BASE (APB1_BUS_BASE + 0x00007400U) /*!< DAC base address */
/* advanced peripheral bus 2 memory map */
#define AFIO_BASE (APB2_BUS_BASE + 0x00000000U) /*!< AFIO base address */
#define EXTI_BASE (APB2_BUS_BASE + 0x00000400U) /*!< EXTI base address */
#define GPIO_BASE (APB2_BUS_BASE + 0x00000800U) /*!< GPIO base address */
#define ADC_BASE (APB2_BUS_BASE + 0x00002400U) /*!< ADC base address */
/* advanced high performance bus 1 memory map */
#define DMA_BASE (AHB1_BUS_BASE + 0x00008000U) /*!< DMA base address */
#define RCU_BASE (AHB1_BUS_BASE + 0x00009000U) /*!< RCU base address */
#define FMC_BASE (AHB1_BUS_BASE + 0x0000A000U) /*!< FMC base address */
#define CRC_BASE (AHB1_BUS_BASE + 0x0000B000U) /*!< CRC base address */
#define USBFS_BASE (AHB1_BUS_BASE + 0x0FFE8000U) /*!< USBFS base address */
/** @} */ /* End of group Device_Peripheral_peripheralAddr */
/* =========================================================================================================================== */
/* ================ Peripheral declaration ================ */
/* =========================================================================================================================== */
/* Macros for memory access operations */
#define _REG8P(p, i) ((volatile uint8_t *) ((uintptr_t)((p) + (i))))
#define _REG16P(p, i) ((volatile uint16_t *) ((uintptr_t)((p) + (i))))
#define _REG32P(p, i) ((volatile uint32_t *) ((uintptr_t)((p) + (i))))
#define _REG64P(p, i) ((volatile uint64_t *) ((uintptr_t)((p) + (i))))
#define _REG8(p, i) (*(_REG8P(p, i)))
#define _REG16(p, i) (*(_REG16P(p, i)))
#define _REG32(p, i) (*(_REG32P(p, i)))
#define _REG64(p, i) (*(_REG64P(p, i)))
#define REG8(addr) _REG8((addr), 0)
#define REG16(addr) _REG16((addr), 0)
#define REG32(addr) _REG32((addr), 0)
#define REG64(addr) _REG64((addr), 0)
/* Macros for address type convert and access operations */
#define ADDR16(addr) ((uint16_t)(uintptr_t)(addr))
#define ADDR32(addr) ((uint32_t)(uintptr_t)(addr))
#define ADDR64(addr) ((uint64_t)(uintptr_t)(addr))
#define ADDR8P(addr) ((uint8_t *)(uintptr_t)(addr))
#define ADDR16P(addr) ((uint16_t *)(uintptr_t)(addr))
#define ADDR32P(addr) ((uint32_t *)(uintptr_t)(addr))
#define ADDR64P(addr) ((uint64_t *)(uintptr_t)(addr))
/* Macros for Bit Operations */
#if __riscv_xlen == 32
#define BITMASK_MAX 0xFFFFFFFFUL
#define BITOFS_MAX 31
#else
#define BITMASK_MAX 0xFFFFFFFFFFFFFFFFULL
#define BITOFS_MAX 63
#endif
// BIT/BITS only support bit mask for __riscv_xlen
// For RISC-V 32 bit, it support mask 32 bit wide
// For RISC-V 64 bit, it support mask 64 bit wide
#define BIT(ofs) (0x1UL << (ofs))
#define BITS(start, end) ((BITMASK_MAX) << (start) & (BITMASK_MAX) >> (BITOFS_MAX - (end)))
#define GET_BIT(regval, bitofs) (((regval) >> (bitofs)) & 0x1)
#define SET_BIT(regval, bitofs) ((regval) |= BIT(bitofs))
#define CLR_BIT(regval, bitofs) ((regval) &= (~BIT(bitofs)))
#define FLIP_BIT(regval, bitofs) ((regval) ^= BIT(bitofs))
#define WRITE_BIT(regval, bitofs, val) CLR_BIT(regval, bitofs); ((regval) |= ((val) << bitofs) & BIT(bitofs))
#define CHECK_BIT(regval, bitofs) (!!((regval) & (0x1UL<<(bitofs))))
#define GET_BITS(regval, start, end) (((regval) & BITS((start), (end))) >> (start))
#define SET_BITS(regval, start, end) ((regval) |= BITS((start), (end)))
#define CLR_BITS(regval, start, end) ((regval) &= (~BITS((start), (end))))
#define FLIP_BITS(regval, start, end) ((regval) ^= BITS((start), (end)))
#define WRITE_BITS(regval, start, end, val) CLR_BITS(regval, start, end); ((regval) |= ((val) << start) & BITS((start), (end)))
#define CHECK_BITS_ALL(regval, start, end) (!((~(regval)) & BITS((start), (end))))
#define CHECK_BITS_ANY(regval, start, end) ((regval) & BITS((start), (end)))
#define BITMASK_SET(regval, mask) ((regval) |= (mask))
#define BITMASK_CLR(regval, mask) ((regval) &= (~(mask)))
#define BITMASK_FLIP(regval, mask) ((regval) ^= (mask))
#define BITMASK_CHECK_ALL(regval, mask) (!((~(regval)) & (mask)))
#define BITMASK_CHECK_ANY(regval, mask) ((regval) & (mask))
/* ToDo: add here your device peripherals pointer definitions
following is an example for timer */
/** @addtogroup Device_Peripheral_declaration
* @{
*/
// Interrupt Numbers
#define SOC_ECLIC_NUM_INTERRUPTS 86
#define SOC_ECLIC_INT_GPIO_BASE 19
// Interrupt Handler Definitions
#define SOC_MTIMER_HANDLER eclic_mtip_handler
#define SOC_SOFTINT_HANDLER eclic_msip_handler
#define NUM_GPIO 32
extern uint32_t get_cpu_freq(void);
/**
* \brief delay a time in milliseconds
* \param[in] count: count in milliseconds
* \param[out] none
* \retval none
*/
extern void delay_1ms(uint32_t count);
/** @} */ /* End of group gd32vf103_soc */
/** @} */ /* End of group gd32vf103 */
#ifdef __cplusplus
}
#endif
#endif /* __GD32VF103_SOC_H__ */

View File

@ -0,0 +1,423 @@
/*!
\file gd32vf103_gpio.h
\brief definitions for the GPIO
\version 2019-06-5, V1.0.0, firmware for GD32VF103
*/
/*
Copyright (c) 2019, GigaDevice Semiconductor Inc.
Redistribution and use in source and binary forms, with or without modification,
are permitted provided that the following conditions are met:
1. Redistributions of source code must retain the above copyright notice, this
list of conditions and the following disclaimer.
2. Redistributions in binary form must reproduce the above copyright notice,
this list of conditions and the following disclaimer in the documentation
and/or other materials provided with the distribution.
3. Neither the name of the copyright holder nor the names of its contributors
may be used to endorse or promote products derived from this software without
specific prior written permission.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED.
IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT,
INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT
NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY
OF SUCH DAMAGE.
*/
#ifndef GD32VF103_GPIO_H
#define GD32VF103_GPIO_H
#include "gd32vf103.h"
#include "gd32vf103_rcu.h"
// #include "gd32vf103_dbg.h"
/* GPIOx(x=A,B,C,D,E) definitions */
#define GPIOA (GPIO_BASE + 0x00000000U)
#define GPIOB (GPIO_BASE + 0x00000400U)
#define GPIOC (GPIO_BASE + 0x00000800U)
#define GPIOD (GPIO_BASE + 0x00000C00U)
#define GPIOE (GPIO_BASE + 0x00001000U)
/* AFIO definitions */
#define AFIO AFIO_BASE
/* registers definitions */
/* GPIO registers definitions */
#define GPIO_CTL0(gpiox) REG32((gpiox) + 0x00U) /*!< GPIO port control register 0 */
#define GPIO_CTL1(gpiox) REG32((gpiox) + 0x04U) /*!< GPIO port control register 1 */
#define GPIO_ISTAT(gpiox) REG32((gpiox) + 0x08U) /*!< GPIO port input status register */
#define GPIO_OCTL(gpiox) REG32((gpiox) + 0x0CU) /*!< GPIO port output control register */
#define GPIO_BOP(gpiox) REG32((gpiox) + 0x10U) /*!< GPIO port bit operation register */
#define GPIO_BC(gpiox) REG32((gpiox) + 0x14U) /*!< GPIO bit clear register */
#define GPIO_LOCK(gpiox) REG32((gpiox) + 0x18U) /*!< GPIO port configuration lock register */
/* AFIO registers definitions */
#define AFIO_EC REG32(AFIO + 0x00U) /*!< AFIO event control register */
#define AFIO_PCF0 REG32(AFIO + 0x04U) /*!< AFIO port configuration register 0 */
#define AFIO_EXTISS0 REG32(AFIO + 0x08U) /*!< AFIO port EXTI sources selection register 0 */
#define AFIO_EXTISS1 REG32(AFIO + 0x0CU) /*!< AFIO port EXTI sources selection register 1 */
#define AFIO_EXTISS2 REG32(AFIO + 0x10U) /*!< AFIO port EXTI sources selection register 2 */
#define AFIO_EXTISS3 REG32(AFIO + 0x14U) /*!< AFIO port EXTI sources selection register 3 */
#define AFIO_PCF1 REG32(AFIO + 0x1CU) /*!< AFIO port configuration register 1 */
/* bits definitions */
/* GPIO_CTL0 */
#define GPIO_CTL0_MD0 BITS(0, 1) /*!< port 0 mode bits */
#define GPIO_CTL0_CTL0 BITS(2, 3) /*!< pin 0 configuration bits */
#define GPIO_CTL0_MD1 BITS(4, 5) /*!< port 1 mode bits */
#define GPIO_CTL0_CTL1 BITS(6, 7) /*!< pin 1 configuration bits */
#define GPIO_CTL0_MD2 BITS(8, 9) /*!< port 2 mode bits */
#define GPIO_CTL0_CTL2 BITS(10, 11) /*!< pin 2 configuration bits */
#define GPIO_CTL0_MD3 BITS(12, 13) /*!< port 3 mode bits */
#define GPIO_CTL0_CTL3 BITS(14, 15) /*!< pin 3 configuration bits */
#define GPIO_CTL0_MD4 BITS(16, 17) /*!< port 4 mode bits */
#define GPIO_CTL0_CTL4 BITS(18, 19) /*!< pin 4 configuration bits */
#define GPIO_CTL0_MD5 BITS(20, 21) /*!< port 5 mode bits */
#define GPIO_CTL0_CTL5 BITS(22, 23) /*!< pin 5 configuration bits */
#define GPIO_CTL0_MD6 BITS(24, 25) /*!< port 6 mode bits */
#define GPIO_CTL0_CTL6 BITS(26, 27) /*!< pin 6 configuration bits */
#define GPIO_CTL0_MD7 BITS(28, 29) /*!< port 7 mode bits */
#define GPIO_CTL0_CTL7 BITS(30, 31) /*!< pin 7 configuration bits */
/* GPIO_CTL1 */
#define GPIO_CTL1_MD8 BITS(0, 1) /*!< port 8 mode bits */
#define GPIO_CTL1_CTL8 BITS(2, 3) /*!< pin 8 configuration bits */
#define GPIO_CTL1_MD9 BITS(4, 5) /*!< port 9 mode bits */
#define GPIO_CTL1_CTL9 BITS(6, 7) /*!< pin 9 configuration bits */
#define GPIO_CTL1_MD10 BITS(8, 9) /*!< port 10 mode bits */
#define GPIO_CTL1_CTL10 BITS(10, 11) /*!< pin 10 configuration bits */
#define GPIO_CTL1_MD11 BITS(12, 13) /*!< port 11 mode bits */
#define GPIO_CTL1_CTL11 BITS(14, 15) /*!< pin 11 configuration bits */
#define GPIO_CTL1_MD12 BITS(16, 17) /*!< port 12 mode bits */
#define GPIO_CTL1_CTL12 BITS(18, 19) /*!< pin 12 configuration bits */
#define GPIO_CTL1_MD13 BITS(20, 21) /*!< port 13 mode bits */
#define GPIO_CTL1_CTL13 BITS(22, 23) /*!< pin 13 configuration bits */
#define GPIO_CTL1_MD14 BITS(24, 25) /*!< port 14 mode bits */
#define GPIO_CTL1_CTL14 BITS(26, 27) /*!< pin 14 configuration bits */
#define GPIO_CTL1_MD15 BITS(28, 29) /*!< port 15 mode bits */
#define GPIO_CTL1_CTL15 BITS(30, 31) /*!< pin 15 configuration bits */
/* GPIO_ISTAT */
#define GPIO_ISTAT_ISTAT0 BIT(0) /*!< pin 0 input status */
#define GPIO_ISTAT_ISTAT1 BIT(1) /*!< pin 1 input status */
#define GPIO_ISTAT_ISTAT2 BIT(2) /*!< pin 2 input status */
#define GPIO_ISTAT_ISTAT3 BIT(3) /*!< pin 3 input status */
#define GPIO_ISTAT_ISTAT4 BIT(4) /*!< pin 4 input status */
#define GPIO_ISTAT_ISTAT5 BIT(5) /*!< pin 5 input status */
#define GPIO_ISTAT_ISTAT6 BIT(6) /*!< pin 6 input status */
#define GPIO_ISTAT_ISTAT7 BIT(7) /*!< pin 7 input status */
#define GPIO_ISTAT_ISTAT8 BIT(8) /*!< pin 8 input status */
#define GPIO_ISTAT_ISTAT9 BIT(9) /*!< pin 9 input status */
#define GPIO_ISTAT_ISTAT10 BIT(10) /*!< pin 10 input status */
#define GPIO_ISTAT_ISTAT11 BIT(11) /*!< pin 11 input status */
#define GPIO_ISTAT_ISTAT12 BIT(12) /*!< pin 12 input status */
#define GPIO_ISTAT_ISTAT13 BIT(13) /*!< pin 13 input status */
#define GPIO_ISTAT_ISTAT14 BIT(14) /*!< pin 14 input status */
#define GPIO_ISTAT_ISTAT15 BIT(15) /*!< pin 15 input status */
/* GPIO_OCTL */
#define GPIO_OCTL_OCTL0 BIT(0) /*!< pin 0 output bit */
#define GPIO_OCTL_OCTL1 BIT(1) /*!< pin 1 output bit */
#define GPIO_OCTL_OCTL2 BIT(2) /*!< pin 2 output bit */
#define GPIO_OCTL_OCTL3 BIT(3) /*!< pin 3 output bit */
#define GPIO_OCTL_OCTL4 BIT(4) /*!< pin 4 output bit */
#define GPIO_OCTL_OCTL5 BIT(5) /*!< pin 5 output bit */
#define GPIO_OCTL_OCTL6 BIT(6) /*!< pin 6 output bit */
#define GPIO_OCTL_OCTL7 BIT(7) /*!< pin 7 output bit */
#define GPIO_OCTL_OCTL8 BIT(8) /*!< pin 8 output bit */
#define GPIO_OCTL_OCTL9 BIT(9) /*!< pin 9 output bit */
#define GPIO_OCTL_OCTL10 BIT(10) /*!< pin 10 output bit */
#define GPIO_OCTL_OCTL11 BIT(11) /*!< pin 11 output bit */
#define GPIO_OCTL_OCTL12 BIT(12) /*!< pin 12 output bit */
#define GPIO_OCTL_OCTL13 BIT(13) /*!< pin 13 output bit */
#define GPIO_OCTL_OCTL14 BIT(14) /*!< pin 14 output bit */
#define GPIO_OCTL_OCTL15 BIT(15) /*!< pin 15 output bit */
/* GPIO_BOP */
#define GPIO_BOP_BOP0 BIT(0) /*!< pin 0 set bit */
#define GPIO_BOP_BOP1 BIT(1) /*!< pin 1 set bit */
#define GPIO_BOP_BOP2 BIT(2) /*!< pin 2 set bit */
#define GPIO_BOP_BOP3 BIT(3) /*!< pin 3 set bit */
#define GPIO_BOP_BOP4 BIT(4) /*!< pin 4 set bit */
#define GPIO_BOP_BOP5 BIT(5) /*!< pin 5 set bit */
#define GPIO_BOP_BOP6 BIT(6) /*!< pin 6 set bit */
#define GPIO_BOP_BOP7 BIT(7) /*!< pin 7 set bit */
#define GPIO_BOP_BOP8 BIT(8) /*!< pin 8 set bit */
#define GPIO_BOP_BOP9 BIT(9) /*!< pin 9 set bit */
#define GPIO_BOP_BOP10 BIT(10) /*!< pin 10 set bit */
#define GPIO_BOP_BOP11 BIT(11) /*!< pin 11 set bit */
#define GPIO_BOP_BOP12 BIT(12) /*!< pin 12 set bit */
#define GPIO_BOP_BOP13 BIT(13) /*!< pin 13 set bit */
#define GPIO_BOP_BOP14 BIT(14) /*!< pin 14 set bit */
#define GPIO_BOP_BOP15 BIT(15) /*!< pin 15 set bit */
#define GPIO_BOP_CR0 BIT(16) /*!< pin 0 clear bit */
#define GPIO_BOP_CR1 BIT(17) /*!< pin 1 clear bit */
#define GPIO_BOP_CR2 BIT(18) /*!< pin 2 clear bit */
#define GPIO_BOP_CR3 BIT(19) /*!< pin 3 clear bit */
#define GPIO_BOP_CR4 BIT(20) /*!< pin 4 clear bit */
#define GPIO_BOP_CR5 BIT(21) /*!< pin 5 clear bit */
#define GPIO_BOP_CR6 BIT(22) /*!< pin 6 clear bit */
#define GPIO_BOP_CR7 BIT(23) /*!< pin 7 clear bit */
#define GPIO_BOP_CR8 BIT(24) /*!< pin 8 clear bit */
#define GPIO_BOP_CR9 BIT(25) /*!< pin 9 clear bit */
#define GPIO_BOP_CR10 BIT(26) /*!< pin 10 clear bit */
#define GPIO_BOP_CR11 BIT(27) /*!< pin 11 clear bit */
#define GPIO_BOP_CR12 BIT(28) /*!< pin 12 clear bit */
#define GPIO_BOP_CR13 BIT(29) /*!< pin 13 clear bit */
#define GPIO_BOP_CR14 BIT(30) /*!< pin 14 clear bit */
#define GPIO_BOP_CR15 BIT(31) /*!< pin 15 clear bit */
/* GPIO_BC */
#define GPIO_BC_CR0 BIT(0) /*!< pin 0 clear bit */
#define GPIO_BC_CR1 BIT(1) /*!< pin 1 clear bit */
#define GPIO_BC_CR2 BIT(2) /*!< pin 2 clear bit */
#define GPIO_BC_CR3 BIT(3) /*!< pin 3 clear bit */
#define GPIO_BC_CR4 BIT(4) /*!< pin 4 clear bit */
#define GPIO_BC_CR5 BIT(5) /*!< pin 5 clear bit */
#define GPIO_BC_CR6 BIT(6) /*!< pin 6 clear bit */
#define GPIO_BC_CR7 BIT(7) /*!< pin 7 clear bit */
#define GPIO_BC_CR8 BIT(8) /*!< pin 8 clear bit */
#define GPIO_BC_CR9 BIT(9) /*!< pin 9 clear bit */
#define GPIO_BC_CR10 BIT(10) /*!< pin 10 clear bit */
#define GPIO_BC_CR11 BIT(11) /*!< pin 11 clear bit */
#define GPIO_BC_CR12 BIT(12) /*!< pin 12 clear bit */
#define GPIO_BC_CR13 BIT(13) /*!< pin 13 clear bit */
#define GPIO_BC_CR14 BIT(14) /*!< pin 14 clear bit */
#define GPIO_BC_CR15 BIT(15) /*!< pin 15 clear bit */
/* GPIO_LOCK */
#define GPIO_LOCK_LK0 BIT(0) /*!< pin 0 lock bit */
#define GPIO_LOCK_LK1 BIT(1) /*!< pin 1 lock bit */
#define GPIO_LOCK_LK2 BIT(2) /*!< pin 2 lock bit */
#define GPIO_LOCK_LK3 BIT(3) /*!< pin 3 lock bit */
#define GPIO_LOCK_LK4 BIT(4) /*!< pin 4 lock bit */
#define GPIO_LOCK_LK5 BIT(5) /*!< pin 5 lock bit */
#define GPIO_LOCK_LK6 BIT(6) /*!< pin 6 lock bit */
#define GPIO_LOCK_LK7 BIT(7) /*!< pin 7 lock bit */
#define GPIO_LOCK_LK8 BIT(8) /*!< pin 8 lock bit */
#define GPIO_LOCK_LK9 BIT(9) /*!< pin 9 lock bit */
#define GPIO_LOCK_LK10 BIT(10) /*!< pin 10 lock bit */
#define GPIO_LOCK_LK11 BIT(11) /*!< pin 11 lock bit */
#define GPIO_LOCK_LK12 BIT(12) /*!< pin 12 lock bit */
#define GPIO_LOCK_LK13 BIT(13) /*!< pin 13 lock bit */
#define GPIO_LOCK_LK14 BIT(14) /*!< pin 14 lock bit */
#define GPIO_LOCK_LK15 BIT(15) /*!< pin 15 lock bit */
#define GPIO_LOCK_LKK BIT(16) /*!< pin sequence lock key */
/* AFIO_EC */
#define AFIO_EC_PIN BITS(0, 3) /*!< event output pin selection */
#define AFIO_EC_PORT BITS(4, 6) /*!< event output port selection */
#define AFIO_EC_EOE BIT(7) /*!< event output enable */
/* AFIO_PCF0 */
#define AFIO_PCF0_SPI0_REMAP BIT(0) /*!< SPI0 remapping */
#define AFIO_PCF0_I2C0_REMAP BIT(1) /*!< I2C0 remapping */
#define AFIO_PCF0_USART0_REMAP BIT(2) /*!< USART0 remapping */
#define AFIO_PCF0_USART1_REMAP BIT(3) /*!< USART1 remapping */
#define AFIO_PCF0_USART2_REMAP BITS(4, 5) /*!< USART2 remapping */
#define AFIO_PCF0_TIMER0_REMAP BITS(6, 7) /*!< TIMER0 remapping */
#define AFIO_PCF0_TIMER1_REMAP BITS(8, 9) /*!< TIMER1 remapping */
#define AFIO_PCF0_TIMER2_REMAP BITS(10, 11) /*!< TIMER2 remapping */
#define AFIO_PCF0_TIMER3_REMAP BIT(12) /*!< TIMER3 remapping */
#define AFIO_PCF0_CAN_REMAP BITS(13, 14) /*!< CAN remapping */
#define AFIO_PCF0_PD01_REMAP BIT(15) /*!< port D0/port D1 mapping on OSC_IN/OSC_OUT */
#define AFIO_PCF0_TIMER4CH3_IREMAP BIT(16) /*!< TIMER3 channel3 internal remapping */
#define AFIO_PCF0_SWJ_CFG BITS(24, 26) /*!< serial wire JTAG configuration */
#define AFIO_PCF0_SPI2_REMAP BIT(28) /*!< SPI2/I2S2 remapping */
#define AFIO_PCF0_TIMER1_ITI1_REMAP BIT(29) /*!< TIMER1 internal trigger 1 remapping */
/* AFIO_EXTISS0 */
#define AFIO_EXTI0_SS BITS(0, 3) /*!< EXTI 0 sources selection */
#define AFIO_EXTI1_SS BITS(4, 7) /*!< EXTI 1 sources selection */
#define AFIO_EXTI2_SS BITS(8, 11) /*!< EXTI 2 sources selection */
#define AFIO_EXTI3_SS BITS(12, 15) /*!< EXTI 3 sources selection */
/* AFIO_EXTISS1 */
#define AFIO_EXTI4_SS BITS(0, 3) /*!< EXTI 4 sources selection */
#define AFIO_EXTI5_SS BITS(4, 7) /*!< EXTI 5 sources selection */
#define AFIO_EXTI6_SS BITS(8, 11) /*!< EXTI 6 sources selection */
#define AFIO_EXTI7_SS BITS(12, 15) /*!< EXTI 7 sources selection */
/* AFIO_EXTISS2 */
#define AFIO_EXTI8_SS BITS(0, 3) /*!< EXTI 8 sources selection */
#define AFIO_EXTI9_SS BITS(4, 7) /*!< EXTI 9 sources selection */
#define AFIO_EXTI10_SS BITS(8, 11) /*!< EXTI 10 sources selection */
#define AFIO_EXTI11_SS BITS(12, 15) /*!< EXTI 11 sources selection */
/* AFIO_EXTISS3 */
#define AFIO_EXTI12_SS BITS(0, 3) /*!< EXTI 12 sources selection */
#define AFIO_EXTI13_SS BITS(4, 7) /*!< EXTI 13 sources selection */
#define AFIO_EXTI14_SS BITS(8, 11) /*!< EXTI 14 sources selection */
#define AFIO_EXTI15_SS BITS(12, 15) /*!< EXTI 15 sources selection */
/* AFIO_PCF1 */
#define AFIO_PCF1_EXMC_NADV BIT(10) /*!< EXMC_NADV connect/disconnect */
/* constants definitions */
typedef FlagStatus bit_status;
/* GPIO mode values set */
#define GPIO_MODE_SET(n, mode) ((uint32_t)((uint32_t)(mode) << (4U * (n))))
#define GPIO_MODE_MASK(n) (0xFU << (4U * (n)))
/* GPIO mode definitions */
#define GPIO_MODE_AIN ((uint8_t)0x00U) /*!< analog input mode */
#define GPIO_MODE_IN_FLOATING ((uint8_t)0x04U) /*!< floating input mode */
#define GPIO_MODE_IPD ((uint8_t)0x28U) /*!< pull-down input mode */
#define GPIO_MODE_IPU ((uint8_t)0x48U) /*!< pull-up input mode */
#define GPIO_MODE_OUT_OD ((uint8_t)0x14U) /*!< GPIO output with open-drain */
#define GPIO_MODE_OUT_PP ((uint8_t)0x10U) /*!< GPIO output with push-pull */
#define GPIO_MODE_AF_OD ((uint8_t)0x1CU) /*!< AFIO output with open-drain */
#define GPIO_MODE_AF_PP ((uint8_t)0x18U) /*!< AFIO output with push-pull */
/* GPIO output max speed value */
#define GPIO_OSPEED_10MHZ ((uint8_t)0x01U) /*!< output max speed 10MHz */
#define GPIO_OSPEED_2MHZ ((uint8_t)0x02U) /*!< output max speed 2MHz */
#define GPIO_OSPEED_50MHZ ((uint8_t)0x03U) /*!< output max speed 50MHz */
/* GPIO event output port definitions */
#define GPIO_EVENT_PORT_GPIOA ((uint8_t)0x00U) /*!< event output port A */
#define GPIO_EVENT_PORT_GPIOB ((uint8_t)0x01U) /*!< event output port B */
#define GPIO_EVENT_PORT_GPIOC ((uint8_t)0x02U) /*!< event output port C */
#define GPIO_EVENT_PORT_GPIOD ((uint8_t)0x03U) /*!< event output port D */
#define GPIO_EVENT_PORT_GPIOE ((uint8_t)0x04U) /*!< event output port E */
/* GPIO output port source definitions */
#define GPIO_PORT_SOURCE_GPIOA ((uint8_t)0x00U) /*!< output port source A */
#define GPIO_PORT_SOURCE_GPIOB ((uint8_t)0x01U) /*!< output port source B */
#define GPIO_PORT_SOURCE_GPIOC ((uint8_t)0x02U) /*!< output port source C */
#define GPIO_PORT_SOURCE_GPIOD ((uint8_t)0x03U) /*!< output port source D */
#define GPIO_PORT_SOURCE_GPIOE ((uint8_t)0x04U) /*!< output port source E */
/* GPIO event output pin definitions */
#define GPIO_EVENT_PIN_0 ((uint8_t)0x00U) /*!< GPIO event pin 0 */
#define GPIO_EVENT_PIN_1 ((uint8_t)0x01U) /*!< GPIO event pin 1 */
#define GPIO_EVENT_PIN_2 ((uint8_t)0x02U) /*!< GPIO event pin 2 */
#define GPIO_EVENT_PIN_3 ((uint8_t)0x03U) /*!< GPIO event pin 3 */
#define GPIO_EVENT_PIN_4 ((uint8_t)0x04U) /*!< GPIO event pin 4 */
#define GPIO_EVENT_PIN_5 ((uint8_t)0x05U) /*!< GPIO event pin 5 */
#define GPIO_EVENT_PIN_6 ((uint8_t)0x06U) /*!< GPIO event pin 6 */
#define GPIO_EVENT_PIN_7 ((uint8_t)0x07U) /*!< GPIO event pin 7 */
#define GPIO_EVENT_PIN_8 ((uint8_t)0x08U) /*!< GPIO event pin 8 */
#define GPIO_EVENT_PIN_9 ((uint8_t)0x09U) /*!< GPIO event pin 9 */
#define GPIO_EVENT_PIN_10 ((uint8_t)0x0AU) /*!< GPIO event pin 10 */
#define GPIO_EVENT_PIN_11 ((uint8_t)0x0BU) /*!< GPIO event pin 11 */
#define GPIO_EVENT_PIN_12 ((uint8_t)0x0CU) /*!< GPIO event pin 12 */
#define GPIO_EVENT_PIN_13 ((uint8_t)0x0DU) /*!< GPIO event pin 13 */
#define GPIO_EVENT_PIN_14 ((uint8_t)0x0EU) /*!< GPIO event pin 14 */
#define GPIO_EVENT_PIN_15 ((uint8_t)0x0FU) /*!< GPIO event pin 15 */
/* GPIO output pin source definitions */
#define GPIO_PIN_SOURCE_0 ((uint8_t)0x00U) /*!< GPIO pin source 0 */
#define GPIO_PIN_SOURCE_1 ((uint8_t)0x01U) /*!< GPIO pin source 1 */
#define GPIO_PIN_SOURCE_2 ((uint8_t)0x02U) /*!< GPIO pin source 2 */
#define GPIO_PIN_SOURCE_3 ((uint8_t)0x03U) /*!< GPIO pin source 3 */
#define GPIO_PIN_SOURCE_4 ((uint8_t)0x04U) /*!< GPIO pin source 4 */
#define GPIO_PIN_SOURCE_5 ((uint8_t)0x05U) /*!< GPIO pin source 5 */
#define GPIO_PIN_SOURCE_6 ((uint8_t)0x06U) /*!< GPIO pin source 6 */
#define GPIO_PIN_SOURCE_7 ((uint8_t)0x07U) /*!< GPIO pin source 7 */
#define GPIO_PIN_SOURCE_8 ((uint8_t)0x08U) /*!< GPIO pin source 8 */
#define GPIO_PIN_SOURCE_9 ((uint8_t)0x09U) /*!< GPIO pin source 9 */
#define GPIO_PIN_SOURCE_10 ((uint8_t)0x0AU) /*!< GPIO pin source 10 */
#define GPIO_PIN_SOURCE_11 ((uint8_t)0x0BU) /*!< GPIO pin source 11 */
#define GPIO_PIN_SOURCE_12 ((uint8_t)0x0CU) /*!< GPIO pin source 12 */
#define GPIO_PIN_SOURCE_13 ((uint8_t)0x0DU) /*!< GPIO pin source 13 */
#define GPIO_PIN_SOURCE_14 ((uint8_t)0x0EU) /*!< GPIO pin source 14 */
#define GPIO_PIN_SOURCE_15 ((uint8_t)0x0FU) /*!< GPIO pin source 15 */
/* GPIO pin definitions */
#define GPIO_PIN_0 BIT(0) /*!< GPIO pin 0 */
#define GPIO_PIN_1 BIT(1) /*!< GPIO pin 1 */
#define GPIO_PIN_2 BIT(2) /*!< GPIO pin 2 */
#define GPIO_PIN_3 BIT(3) /*!< GPIO pin 3 */
#define GPIO_PIN_4 BIT(4) /*!< GPIO pin 4 */
#define GPIO_PIN_5 BIT(5) /*!< GPIO pin 5 */
#define GPIO_PIN_6 BIT(6) /*!< GPIO pin 6 */
#define GPIO_PIN_7 BIT(7) /*!< GPIO pin 7 */
#define GPIO_PIN_8 BIT(8) /*!< GPIO pin 8 */
#define GPIO_PIN_9 BIT(9) /*!< GPIO pin 9 */
#define GPIO_PIN_10 BIT(10) /*!< GPIO pin 10 */
#define GPIO_PIN_11 BIT(11) /*!< GPIO pin 11 */
#define GPIO_PIN_12 BIT(12) /*!< GPIO pin 12 */
#define GPIO_PIN_13 BIT(13) /*!< GPIO pin 13 */
#define GPIO_PIN_14 BIT(14) /*!< GPIO pin 14 */
#define GPIO_PIN_15 BIT(15) /*!< GPIO pin 15 */
#define GPIO_PIN_ALL BITS(0, 15) /*!< GPIO pin all */
/* GPIO remap definitions */
#define GPIO_SPI0_REMAP ((uint32_t)0x00000001U) /*!< SPI0 remapping */
#define GPIO_I2C0_REMAP ((uint32_t)0x00000002U) /*!< I2C0 remapping */
#define GPIO_USART0_REMAP ((uint32_t)0x00000004U) /*!< USART0 remapping */
#define GPIO_USART1_REMAP ((uint32_t)0x00000008U) /*!< USART1 remapping */
#define GPIO_USART2_PARTIAL_REMAP ((uint32_t)0x00140010U) /*!< USART2 partial remapping */
#define GPIO_USART2_FULL_REMAP ((uint32_t)0x00140030U) /*!< USART2 full remapping */
#define GPIO_TIMER0_PARTIAL_REMAP ((uint32_t)0x00160040U) /*!< TIMER0 partial remapping */
#define GPIO_TIMER0_FULL_REMAP ((uint32_t)0x001600C0U) /*!< TIMER0 full remapping */
#define GPIO_TIMER1_PARTIAL_REMAP0 ((uint32_t)0x00180100U) /*!< TIMER1 partial remapping */
#define GPIO_TIMER1_PARTIAL_REMAP1 ((uint32_t)0x00180200U) /*!< TIMER1 partial remapping */
#define GPIO_TIMER1_FULL_REMAP ((uint32_t)0x00180300U) /*!< TIMER1 full remapping */
#define GPIO_TIMER2_PARTIAL_REMAP ((uint32_t)0x001A0800U) /*!< TIMER2 partial remapping */
#define GPIO_TIMER2_FULL_REMAP ((uint32_t)0x001A0C00U) /*!< TIMER2 full remapping */
#define GPIO_TIMER3_REMAP ((uint32_t)0x00001000U) /*!< TIMER3 remapping */
#define GPIO_CAN0_PARTIAL_REMAP ((uint32_t)0x001D4000U) /*!< CAN0 partial remapping */
#define GPIO_CAN0_FULL_REMAP ((uint32_t)0x001D6000U) /*!< CAN0 full remapping */
#define GPIO_PD01_REMAP ((uint32_t)0x00008000U) /*!< PD01 remapping */
#define GPIO_TIMER4CH3_IREMAP ((uint32_t)0x00200001U) /*!< TIMER4 channel3 internal remapping */
#define GPIO_CAN1_REMAP ((uint32_t)0x00200040U) /*!< CAN1 remapping */
#define GPIO_SWJ_NONJTRST_REMAP ((uint32_t)0x00300100U) /*!< JTAG-DP,but without NJTRST */
#define GPIO_SWJ_DISABLE_REMAP ((uint32_t)0x00300200U) /*!< JTAG-DP disabled */
#define GPIO_SPI2_REMAP ((uint32_t)0x00201100U) /*!< SPI2 remapping */
#define GPIO_TIMER1ITI1_REMAP ((uint32_t)0x00202000U) /*!< TIMER1 internal trigger 1 remapping */
#define GPIO_EXMC_NADV_REMAP ((uint32_t)0x80000400U) /*!< EXMC_NADV connect/disconnect */
/* function declarations */
/* reset GPIO port */
void gpio_deinit(uint32_t gpio_periph);
/* reset alternate function I/O(AFIO) */
void gpio_afio_deinit(void);
/* GPIO parameter initialization */
void gpio_init(uint32_t gpio_periph, uint32_t mode, uint32_t speed, uint32_t pin);
/* set GPIO pin bit */
void gpio_bit_set(uint32_t gpio_periph, uint32_t pin);
/* reset GPIO pin bit */
void gpio_bit_reset(uint32_t gpio_periph, uint32_t pin);
/* write data to the specified GPIO pin */
void gpio_bit_write(uint32_t gpio_periph, uint32_t pin, bit_status bit_value);
/* write data to the specified GPIO port */
void gpio_port_write(uint32_t gpio_periph, uint16_t data);
/* get GPIO pin input status */
FlagStatus gpio_input_bit_get(uint32_t gpio_periph, uint32_t pin);
/* get GPIO port input status */
uint16_t gpio_input_port_get(uint32_t gpio_periph);
/* get GPIO pin output status */
FlagStatus gpio_output_bit_get(uint32_t gpio_periph, uint32_t pin);
/* get GPIO port output status */
uint16_t gpio_output_port_get(uint32_t gpio_periph);
/* configure GPIO pin remap */
void gpio_pin_remap_config(uint32_t remap, ControlStatus newvalue);
/* select GPIO pin exti sources */
void gpio_exti_source_select(uint8_t output_port, uint8_t output_pin);
/* configure GPIO pin event output */
void gpio_event_output_config(uint8_t output_port, uint8_t output_pin);
/* enable GPIO pin event output */
void gpio_event_output_enable(void);
/* disable GPIO pin event output */
void gpio_event_output_disable(void);
/* lock GPIO pin bit */
void gpio_pin_lock(uint32_t gpio_periph, uint32_t pin);
#endif /* GD32VF103_GPIO_H */

View File

@ -0,0 +1,760 @@
/*!
\file gd32vf103_rcu.h
\brief definitions for the RCU
\version 2019-6-5, V1.0.0, firmware for GD32VF103
*/
/*
Copyright (c) 2019, GigaDevice Semiconductor Inc.
Redistribution and use in source and binary forms, with or without modification,
are permitted provided that the following conditions are met:
1. Redistributions of source code must retain the above copyright notice, this
list of conditions and the following disclaimer.
2. Redistributions in binary form must reproduce the above copyright notice,
this list of conditions and the following disclaimer in the documentation
and/or other materials provided with the distribution.
3. Neither the name of the copyright holder nor the names of its contributors
may be used to endorse or promote products derived from this software without
specific prior written permission.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED.
IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT,
INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT
NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY
OF SUCH DAMAGE.
*/
#ifndef GD32VF103_RCU_H
#define GD32VF103_RCU_H
#include "gd32vf103.h"
/* RCU definitions */
#define RCU RCU_BASE
/* registers definitions */
#define RCU_CTL REG32(RCU + 0x00U) /*!< control register */
#define RCU_CFG0 REG32(RCU + 0x04U) /*!< clock configuration register 0 */
#define RCU_INT REG32(RCU + 0x08U) /*!< clock interrupt register */
#define RCU_APB2RST REG32(RCU + 0x0CU) /*!< APB2 reset register */
#define RCU_APB1RST REG32(RCU + 0x10U) /*!< APB1 reset register */
#define RCU_AHBEN REG32(RCU + 0x14U) /*!< AHB1 enable register */
#define RCU_APB2EN REG32(RCU + 0x18U) /*!< APB2 enable register */
#define RCU_APB1EN REG32(RCU + 0x1CU) /*!< APB1 enable register */
#define RCU_BDCTL REG32(RCU + 0x20U) /*!< backup domain control register */
#define RCU_RSTSCK REG32(RCU + 0x24U) /*!< reset source / clock register */
#define RCU_AHBRST REG32(RCU + 0x28U) /*!< AHB reset register */
#define RCU_CFG1 REG32(RCU + 0x2CU) /*!< clock configuration register 1 */
#define RCU_DSV REG32(RCU + 0x34U) /*!< deep-sleep mode voltage register */
/* bits definitions */
/* RCU_CTL */
#define RCU_CTL_IRC8MEN BIT(0) /*!< internal high speed oscillator enable */
#define RCU_CTL_IRC8MSTB BIT(1) /*!< IRC8M high speed internal oscillator stabilization flag */
#define RCU_CTL_IRC8MADJ BITS(3,7) /*!< high speed internal oscillator clock trim adjust value */
#define RCU_CTL_IRC8MCALIB BITS(8,15) /*!< high speed internal oscillator calibration value register */
#define RCU_CTL_HXTALEN BIT(16) /*!< external high speed oscillator enable */
#define RCU_CTL_HXTALSTB BIT(17) /*!< external crystal oscillator clock stabilization flag */
#define RCU_CTL_HXTALBPS BIT(18) /*!< external crystal oscillator clock bypass mode enable */
#define RCU_CTL_CKMEN BIT(19) /*!< HXTAL clock monitor enable */
#define RCU_CTL_PLLEN BIT(24) /*!< PLL enable */
#define RCU_CTL_PLLSTB BIT(25) /*!< PLL clock stabilization flag */
#define RCU_CTL_PLL1EN BIT(26) /*!< PLL1 enable */
#define RCU_CTL_PLL1STB BIT(27) /*!< PLL1 clock stabilization flag */
#define RCU_CTL_PLL2EN BIT(28) /*!< PLL2 enable */
#define RCU_CTL_PLL2STB BIT(29) /*!< PLL2 clock stabilization flag */
#define RCU_CFG0_SCS BITS(0,1) /*!< system clock switch */
#define RCU_CFG0_SCSS BITS(2,3) /*!< system clock switch status */
#define RCU_CFG0_AHBPSC BITS(4,7) /*!< AHB prescaler selection */
#define RCU_CFG0_APB1PSC BITS(8,10) /*!< APB1 prescaler selection */
#define RCU_CFG0_APB2PSC BITS(11,13) /*!< APB2 prescaler selection */
#define RCU_CFG0_ADCPSC BITS(14,15) /*!< ADC prescaler selection */
#define RCU_CFG0_PLLSEL BIT(16) /*!< PLL clock source selection */
#define RCU_CFG0_PREDV0_LSB BIT(17) /*!< the LSB of PREDV0 division factor */
#define RCU_CFG0_PLLMF BITS(18,21) /*!< PLL clock multiplication factor */
#define RCU_CFG0_USBFSPSC BITS(22,23) /*!< USBFS clock prescaler selection */
#define RCU_CFG0_CKOUT0SEL BITS(24,27) /*!< CKOUT0 clock source selection */
#define RCU_CFG0_ADCPSC_2 BIT(28) /*!< bit 2 of ADCPSC */
#define RCU_CFG0_PLLMF_4 BIT(29) /*!< bit 4 of PLLMF */
/* RCU_INT */
#define RCU_INT_IRC40KSTBIF BIT(0) /*!< IRC40K stabilization interrupt flag */
#define RCU_INT_LXTALSTBIF BIT(1) /*!< LXTAL stabilization interrupt flag */
#define RCU_INT_IRC8MSTBIF BIT(2) /*!< IRC8M stabilization interrupt flag */
#define RCU_INT_HXTALSTBIF BIT(3) /*!< HXTAL stabilization interrupt flag */
#define RCU_INT_PLLSTBIF BIT(4) /*!< PLL stabilization interrupt flag */
#define RCU_INT_PLL1STBIF BIT(5) /*!< PLL1 stabilization interrupt flag */
#define RCU_INT_PLL2STBIF BIT(6) /*!< PLL2 stabilization interrupt flag */
#define RCU_INT_CKMIF BIT(7) /*!< HXTAL clock stuck interrupt flag */
#define RCU_INT_IRC40KSTBIE BIT(8) /*!< IRC40K stabilization interrupt enable */
#define RCU_INT_LXTALSTBIE BIT(9) /*!< LXTAL stabilization interrupt enable */
#define RCU_INT_IRC8MSTBIE BIT(10) /*!< IRC8M stabilization interrupt enable */
#define RCU_INT_HXTALSTBIE BIT(11) /*!< HXTAL stabilization interrupt enable */
#define RCU_INT_PLLSTBIE BIT(12) /*!< PLL stabilization interrupt enable */
#define RCU_INT_PLL1STBIE BIT(13) /*!< PLL1 stabilization interrupt enable */
#define RCU_INT_PLL2STBIE BIT(14) /*!< PLL2 stabilization interrupt enable */
#define RCU_INT_IRC40KSTBIC BIT(16) /*!< IRC40K stabilization interrupt clear */
#define RCU_INT_LXTALSTBIC BIT(17) /*!< LXTAL stabilization interrupt clear */
#define RCU_INT_IRC8MSTBIC BIT(18) /*!< IRC8M stabilization interrupt clear */
#define RCU_INT_HXTALSTBIC BIT(19) /*!< HXTAL stabilization interrupt clear */
#define RCU_INT_PLLSTBIC BIT(20) /*!< PLL stabilization interrupt clear */
#define RCU_INT_PLL1STBIC BIT(21) /*!< PLL1 stabilization interrupt clear */
#define RCU_INT_PLL2STBIC BIT(22) /*!< PLL2 stabilization interrupt clear */
#define RCU_INT_CKMIC BIT(23) /*!< HXTAL clock stuck interrupt clear */
/* RCU_APB2RST */
#define RCU_APB2RST_AFRST BIT(0) /*!< alternate function I/O reset */
#define RCU_APB2RST_PARST BIT(2) /*!< GPIO port A reset */
#define RCU_APB2RST_PBRST BIT(3) /*!< GPIO port B reset */
#define RCU_APB2RST_PCRST BIT(4) /*!< GPIO port C reset */
#define RCU_APB2RST_PDRST BIT(5) /*!< GPIO port D reset */
#define RCU_APB2RST_PERST BIT(6) /*!< GPIO port E reset */
#define RCU_APB2RST_ADC0RST BIT(9) /*!< ADC0 reset */
#define RCU_APB2RST_ADC1RST BIT(10) /*!< ADC1 reset */
#define RCU_APB2RST_TIMER0RST BIT(11) /*!< TIMER0 reset */
#define RCU_APB2RST_SPI0RST BIT(12) /*!< SPI0 reset */
#define RCU_APB2RST_USART0RST BIT(14) /*!< USART0 reset */
/* RCU_APB1RST */
#define RCU_APB1RST_TIMER1RST BIT(0) /*!< TIMER1 reset */
#define RCU_APB1RST_TIMER2RST BIT(1) /*!< TIMER2 reset */
#define RCU_APB1RST_TIMER3RST BIT(2) /*!< TIMER3 reset */
#define RCU_APB1RST_TIMER4RST BIT(3) /*!< TIMER4 reset */
#define RCU_APB1RST_TIMER5RST BIT(4) /*!< TIMER5 reset */
#define RCU_APB1RST_TIMER6RST BIT(5) /*!< TIMER6 reset */
#define RCU_APB1RST_WWDGTRST BIT(11) /*!< WWDGT reset */
#define RCU_APB1RST_SPI1RST BIT(14) /*!< SPI1 reset */
#define RCU_APB1RST_SPI2RST BIT(15) /*!< SPI2 reset */
#define RCU_APB1RST_USART1RST BIT(17) /*!< USART1 reset */
#define RCU_APB1RST_USART2RST BIT(18) /*!< USART2 reset */
#define RCU_APB1RST_UART3RST BIT(19) /*!< UART3 reset */
#define RCU_APB1RST_UART4RST BIT(20) /*!< UART4 reset */
#define RCU_APB1RST_I2C0RST BIT(21) /*!< I2C0 reset */
#define RCU_APB1RST_I2C1RST BIT(22) /*!< I2C1 reset */
#define RCU_APB1RST_CAN0RST BIT(25) /*!< CAN0 reset */
#define RCU_APB1RST_CAN1RST BIT(26) /*!< CAN1 reset */
#define RCU_APB1RST_BKPIRST BIT(27) /*!< backup interface reset */
#define RCU_APB1RST_PMURST BIT(28) /*!< PMU reset */
#define RCU_APB1RST_DACRST BIT(29) /*!< DAC reset */
/* RCU_AHBEN */
#define RCU_AHBEN_DMA0EN BIT(0) /*!< DMA0 clock enable */
#define RCU_AHBEN_DMA1EN BIT(1) /*!< DMA1 clock enable */
#define RCU_AHBEN_SRAMSPEN BIT(2) /*!< SRAM clock enable when sleep mode */
#define RCU_AHBEN_FMCSPEN BIT(4) /*!< FMC clock enable when sleep mode */
#define RCU_AHBEN_CRCEN BIT(6) /*!< CRC clock enable */
#define RCU_AHBEN_EXMCEN BIT(8) /*!< EXMC clock enable */
#define RCU_AHBEN_USBFSEN BIT(12) /*!< USBFS clock enable */
/* RCU_APB2EN */
#define RCU_APB2EN_AFEN BIT(0) /*!< alternate function IO clock enable */
#define RCU_APB2EN_PAEN BIT(2) /*!< GPIO port A clock enable */
#define RCU_APB2EN_PBEN BIT(3) /*!< GPIO port B clock enable */
#define RCU_APB2EN_PCEN BIT(4) /*!< GPIO port C clock enable */
#define RCU_APB2EN_PDEN BIT(5) /*!< GPIO port D clock enable */
#define RCU_APB2EN_PEEN BIT(6) /*!< GPIO port E clock enable */
#define RCU_APB2EN_ADC0EN BIT(9) /*!< ADC0 clock enable */
#define RCU_APB2EN_ADC1EN BIT(10) /*!< ADC1 clock enable */
#define RCU_APB2EN_TIMER0EN BIT(11) /*!< TIMER0 clock enable */
#define RCU_APB2EN_SPI0EN BIT(12) /*!< SPI0 clock enable */
#define RCU_APB2EN_USART0EN BIT(14) /*!< USART0 clock enable */
/* RCU_APB1EN */
#define RCU_APB1EN_TIMER1EN BIT(0) /*!< TIMER1 clock enable */
#define RCU_APB1EN_TIMER2EN BIT(1) /*!< TIMER2 clock enable */
#define RCU_APB1EN_TIMER3EN BIT(2) /*!< TIMER3 clock enable */
#define RCU_APB1EN_TIMER4EN BIT(3) /*!< TIMER4 clock enable */
#define RCU_APB1EN_TIMER5EN BIT(4) /*!< TIMER5 clock enable */
#define RCU_APB1EN_TIMER6EN BIT(5) /*!< TIMER6 clock enable */
#define RCU_APB1EN_WWDGTEN BIT(11) /*!< WWDGT clock enable */
#define RCU_APB1EN_SPI1EN BIT(14) /*!< SPI1 clock enable */
#define RCU_APB1EN_SPI2EN BIT(15) /*!< SPI2 clock enable */
#define RCU_APB1EN_USART1EN BIT(17) /*!< USART1 clock enable */
#define RCU_APB1EN_USART2EN BIT(18) /*!< USART2 clock enable */
#define RCU_APB1EN_UART3EN BIT(19) /*!< UART3 clock enable */
#define RCU_APB1EN_UART4EN BIT(20) /*!< UART4 clock enable */
#define RCU_APB1EN_I2C0EN BIT(21) /*!< I2C0 clock enable */
#define RCU_APB1EN_I2C1EN BIT(22) /*!< I2C1 clock enable */
#define RCU_APB1EN_CAN0EN BIT(25) /*!< CAN0 clock enable */
#define RCU_APB1EN_CAN1EN BIT(26) /*!< CAN1 clock enable */
#define RCU_APB1EN_BKPIEN BIT(27) /*!< backup interface clock enable */
#define RCU_APB1EN_PMUEN BIT(28) /*!< PMU clock enable */
#define RCU_APB1EN_DACEN BIT(29) /*!< DAC clock enable */
/* RCU_BDCTL */
#define RCU_BDCTL_LXTALEN BIT(0) /*!< LXTAL enable */
#define RCU_BDCTL_LXTALSTB BIT(1) /*!< low speed crystal oscillator stabilization flag */
#define RCU_BDCTL_LXTALBPS BIT(2) /*!< LXTAL bypass mode enable */
#define RCU_BDCTL_RTCSRC BITS(8,9) /*!< RTC clock entry selection */
#define RCU_BDCTL_RTCEN BIT(15) /*!< RTC clock enable */
#define RCU_BDCTL_BKPRST BIT(16) /*!< backup domain reset */
/* RCU_RSTSCK */
#define RCU_RSTSCK_IRC40KEN BIT(0) /*!< IRC40K enable */
#define RCU_RSTSCK_IRC40KSTB BIT(1) /*!< IRC40K stabilization flag */
#define RCU_RSTSCK_RSTFC BIT(24) /*!< reset flag clear */
#define RCU_RSTSCK_EPRSTF BIT(26) /*!< external pin reset flag */
#define RCU_RSTSCK_PORRSTF BIT(27) /*!< power reset flag */
#define RCU_RSTSCK_SWRSTF BIT(28) /*!< software reset flag */
#define RCU_RSTSCK_FWDGTRSTF BIT(29) /*!< free watchdog timer reset flag */
#define RCU_RSTSCK_WWDGTRSTF BIT(30) /*!< window watchdog timer reset flag */
#define RCU_RSTSCK_LPRSTF BIT(31) /*!< low-power reset flag */
/* RCU_AHBRST */
#define RCU_AHBRST_USBFSRST BIT(12) /*!< USBFS reset */
/* RCU_CFG1 */
#define RCU_CFG1_PREDV0 BITS(0,3) /*!< PREDV0 division factor */
#define RCU_CFG1_PREDV1 BITS(4,7) /*!< PREDV1 division factor */
#define RCU_CFG1_PLL1MF BITS(8,11) /*!< PLL1 clock multiplication factor */
#define RCU_CFG1_PLL2MF BITS(12,15) /*!< PLL2 clock multiplication factor */
#define RCU_CFG1_PREDV0SEL BIT(16) /*!< PREDV0 input clock source selection */
#define RCU_CFG1_I2S1SEL BIT(17) /*!< I2S1 clock source selection */
#define RCU_CFG1_I2S2SEL BIT(18) /*!< I2S2 clock source selection */
/* RCU_DSV */
#define RCU_DSV_DSLPVS BITS(0,1) /*!< deep-sleep mode voltage select */
/* constants definitions */
/* define value of high speed crystal oscillator (HXTAL) in Hz */
#if !defined HXTAL_VALUE
#define HXTAL_VALUE ((uint32_t)8000000) /*!< value of the external oscillator in Hz */
#define HXTAL_VALUE_25M HXTAL_VALUE
#endif /* high speed crystal oscillator value */
/* define startup timeout value of high speed crystal oscillator (HXTAL) */
#if !defined (HXTAL_STARTUP_TIMEOUT)
#define HXTAL_STARTUP_TIMEOUT ((uint16_t)0xFFFF)
#endif /* high speed crystal oscillator startup timeout */
/* define value of internal 8MHz RC oscillator (IRC8M) in Hz */
#if !defined (IRC8M_VALUE)
#define IRC8M_VALUE ((uint32_t)8000000)
#endif /* internal 8MHz RC oscillator value */
/* define startup timeout value of internal 8MHz RC oscillator (IRC8M) */
#if !defined (IRC8M_STARTUP_TIMEOUT)
#define IRC8M_STARTUP_TIMEOUT ((uint16_t)0x0500)
#endif /* internal 8MHz RC oscillator startup timeout */
/* define value of internal 40KHz RC oscillator(IRC40K) in Hz */
#if !defined (IRC40K_VALUE)
#define IRC40K_VALUE ((uint32_t)40000)
#endif /* internal 40KHz RC oscillator value */
/* define value of low speed crystal oscillator (LXTAL)in Hz */
#if !defined (LXTAL_VALUE)
#define LXTAL_VALUE ((uint32_t)32768)
#endif /* low speed crystal oscillator value */
/* define clock source */
#define SEL_IRC8M ((uint16_t)0U)
#define SEL_HXTAL ((uint16_t)1U)
#define SEL_PLL ((uint16_t)2U)
/* define startup timeout count */
#define OSC_STARTUP_TIMEOUT ((uint32_t)0xFFFFFU)
#define LXTAL_STARTUP_TIMEOUT ((uint32_t)0x3FFFFFFU)
/* define the peripheral clock enable bit position and its register index offset */
#define RCU_REGIDX_BIT(regidx, bitpos) (((uint32_t)(regidx) << 6) | (uint32_t)(bitpos))
#define RCU_REG_VAL(periph) (REG32(RCU + ((uint32_t)(periph) >> 6)))
#define RCU_BIT_POS(val) ((uint32_t)(val) & 0x1FU)
/* register offset */
/* peripherals enable */
#define AHBEN_REG_OFFSET 0x14U /*!< AHB enable register offset */
#define APB1EN_REG_OFFSET 0x1CU /*!< APB1 enable register offset */
#define APB2EN_REG_OFFSET 0x18U /*!< APB2 enable register offset */
/* peripherals reset */
#define AHBRST_REG_OFFSET 0x28U /*!< AHB reset register offset */
#define APB1RST_REG_OFFSET 0x10U /*!< APB1 reset register offset */
#define APB2RST_REG_OFFSET 0x0CU /*!< APB2 reset register offset */
#define RSTSCK_REG_OFFSET 0x24U /*!< reset source/clock register offset */
/* clock control */
#define CTL_REG_OFFSET 0x00U /*!< control register offset */
#define BDCTL_REG_OFFSET 0x20U /*!< backup domain control register offset */
/* clock stabilization and stuck interrupt */
#define INT_REG_OFFSET 0x08U /*!< clock interrupt register offset */
/* configuration register */
#define CFG0_REG_OFFSET 0x04U /*!< clock configuration register 0 offset */
#define CFG1_REG_OFFSET 0x2CU /*!< clock configuration register 1 offset */
/* peripheral clock enable */
typedef enum {
/* AHB peripherals */
RCU_DMA0 = RCU_REGIDX_BIT(AHBEN_REG_OFFSET, 0U), /*!< DMA0 clock */
RCU_DMA1 = RCU_REGIDX_BIT(AHBEN_REG_OFFSET, 1U), /*!< DMA1 clock */
RCU_CRC = RCU_REGIDX_BIT(AHBEN_REG_OFFSET, 6U), /*!< CRC clock */
RCU_EXMC = RCU_REGIDX_BIT(AHBEN_REG_OFFSET, 8U), /*!< EXMC clock */
RCU_USBFS = RCU_REGIDX_BIT(AHBEN_REG_OFFSET, 12U), /*!< USBFS clock */
/* APB1 peripherals */
RCU_TIMER1 = RCU_REGIDX_BIT(APB1EN_REG_OFFSET, 0U), /*!< TIMER1 clock */
RCU_TIMER2 = RCU_REGIDX_BIT(APB1EN_REG_OFFSET, 1U), /*!< TIMER2 clock */
RCU_TIMER3 = RCU_REGIDX_BIT(APB1EN_REG_OFFSET, 2U), /*!< TIMER3 clock */
RCU_TIMER4 = RCU_REGIDX_BIT(APB1EN_REG_OFFSET, 3U), /*!< TIMER4 clock */
RCU_TIMER5 = RCU_REGIDX_BIT(APB1EN_REG_OFFSET, 4U), /*!< TIMER5 clock */
RCU_TIMER6 = RCU_REGIDX_BIT(APB1EN_REG_OFFSET, 5U), /*!< TIMER6 clock */
RCU_WWDGT = RCU_REGIDX_BIT(APB1EN_REG_OFFSET, 11U), /*!< WWDGT clock */
RCU_SPI1 = RCU_REGIDX_BIT(APB1EN_REG_OFFSET, 14U), /*!< SPI1 clock */
RCU_SPI2 = RCU_REGIDX_BIT(APB1EN_REG_OFFSET, 15U), /*!< SPI2 clock */
RCU_USART1 = RCU_REGIDX_BIT(APB1EN_REG_OFFSET, 17U), /*!< USART1 clock */
RCU_USART2 = RCU_REGIDX_BIT(APB1EN_REG_OFFSET, 18U), /*!< USART2 clock */
RCU_UART3 = RCU_REGIDX_BIT(APB1EN_REG_OFFSET, 19U), /*!< UART3 clock */
RCU_UART4 = RCU_REGIDX_BIT(APB1EN_REG_OFFSET, 20U), /*!< UART4 clock */
RCU_I2C0 = RCU_REGIDX_BIT(APB1EN_REG_OFFSET, 21U), /*!< I2C0 clock */
RCU_I2C1 = RCU_REGIDX_BIT(APB1EN_REG_OFFSET, 22U), /*!< I2C1 clock */
RCU_CAN0 = RCU_REGIDX_BIT(APB1EN_REG_OFFSET, 25U), /*!< CAN0 clock */
RCU_CAN1 = RCU_REGIDX_BIT(APB1EN_REG_OFFSET, 26U), /*!< CAN1 clock */
RCU_BKPI = RCU_REGIDX_BIT(APB1EN_REG_OFFSET, 27U), /*!< BKPI clock */
RCU_PMU = RCU_REGIDX_BIT(APB1EN_REG_OFFSET, 28U), /*!< PMU clock */
RCU_DAC = RCU_REGIDX_BIT(APB1EN_REG_OFFSET, 29U), /*!< DAC clock */
RCU_RTC = RCU_REGIDX_BIT(BDCTL_REG_OFFSET, 15U), /*!< RTC clock */
/* APB2 peripherals */
RCU_AF = RCU_REGIDX_BIT(APB2EN_REG_OFFSET, 0U), /*!< alternate function clock */
RCU_GPIOA = RCU_REGIDX_BIT(APB2EN_REG_OFFSET, 2U), /*!< GPIOA clock */
RCU_GPIOB = RCU_REGIDX_BIT(APB2EN_REG_OFFSET, 3U), /*!< GPIOB clock */
RCU_GPIOC = RCU_REGIDX_BIT(APB2EN_REG_OFFSET, 4U), /*!< GPIOC clock */
RCU_GPIOD = RCU_REGIDX_BIT(APB2EN_REG_OFFSET, 5U), /*!< GPIOD clock */
RCU_GPIOE = RCU_REGIDX_BIT(APB2EN_REG_OFFSET, 6U), /*!< GPIOE clock */
RCU_ADC0 = RCU_REGIDX_BIT(APB2EN_REG_OFFSET, 9U), /*!< ADC0 clock */
RCU_ADC1 = RCU_REGIDX_BIT(APB2EN_REG_OFFSET, 10U), /*!< ADC1 clock */
RCU_TIMER0 = RCU_REGIDX_BIT(APB2EN_REG_OFFSET, 11U), /*!< TIMER0 clock */
RCU_SPI0 = RCU_REGIDX_BIT(APB2EN_REG_OFFSET, 12U), /*!< SPI0 clock */
RCU_USART0 = RCU_REGIDX_BIT(APB2EN_REG_OFFSET, 14U), /*!< USART0 clock */
} rcu_periph_enum;
/* peripheral clock enable when sleep mode*/
typedef enum {
/* AHB peripherals */
RCU_SRAM_SLP = RCU_REGIDX_BIT(AHBEN_REG_OFFSET, 2U), /*!< SRAM clock */
RCU_FMC_SLP = RCU_REGIDX_BIT(AHBEN_REG_OFFSET, 4U), /*!< FMC clock */
} rcu_periph_sleep_enum;
/* peripherals reset */
typedef enum {
/* AHB peripherals */
RCU_USBFSRST = RCU_REGIDX_BIT(AHBRST_REG_OFFSET, 12U), /*!< USBFS clock reset */
/* APB1 peripherals */
RCU_TIMER1RST = RCU_REGIDX_BIT(APB1RST_REG_OFFSET, 0U), /*!< TIMER1 clock reset */
RCU_TIMER2RST = RCU_REGIDX_BIT(APB1RST_REG_OFFSET, 1U), /*!< TIMER2 clock reset */
RCU_TIMER3RST = RCU_REGIDX_BIT(APB1RST_REG_OFFSET, 2U), /*!< TIMER3 clock reset */
RCU_TIMER4RST = RCU_REGIDX_BIT(APB1RST_REG_OFFSET, 3U), /*!< TIMER4 clock reset */
RCU_TIMER5RST = RCU_REGIDX_BIT(APB1RST_REG_OFFSET, 4U), /*!< TIMER5 clock reset */
RCU_TIMER6RST = RCU_REGIDX_BIT(APB1RST_REG_OFFSET, 5U), /*!< TIMER6 clock reset */
RCU_WWDGTRST = RCU_REGIDX_BIT(APB1RST_REG_OFFSET, 11U), /*!< WWDGT clock reset */
RCU_SPI1RST = RCU_REGIDX_BIT(APB1RST_REG_OFFSET, 14U), /*!< SPI1 clock reset */
RCU_SPI2RST = RCU_REGIDX_BIT(APB1RST_REG_OFFSET, 15U), /*!< SPI2 clock reset */
RCU_USART1RST = RCU_REGIDX_BIT(APB1RST_REG_OFFSET, 17U), /*!< USART1 clock reset */
RCU_USART2RST = RCU_REGIDX_BIT(APB1RST_REG_OFFSET, 18U), /*!< USART2 clock reset */
RCU_UART3RST = RCU_REGIDX_BIT(APB1RST_REG_OFFSET, 19U), /*!< UART3 clock reset */
RCU_UART4RST = RCU_REGIDX_BIT(APB1RST_REG_OFFSET, 20U), /*!< UART4 clock reset */
RCU_I2C0RST = RCU_REGIDX_BIT(APB1RST_REG_OFFSET, 21U), /*!< I2C0 clock reset */
RCU_I2C1RST = RCU_REGIDX_BIT(APB1RST_REG_OFFSET, 22U), /*!< I2C1 clock reset */
RCU_CAN0RST = RCU_REGIDX_BIT(APB1RST_REG_OFFSET, 25U), /*!< CAN0 clock reset */
RCU_CAN1RST = RCU_REGIDX_BIT(APB1RST_REG_OFFSET, 26U), /*!< CAN1 clock reset */
RCU_BKPIRST = RCU_REGIDX_BIT(APB1RST_REG_OFFSET, 27U), /*!< BKPI clock reset */
RCU_PMURST = RCU_REGIDX_BIT(APB1RST_REG_OFFSET, 28U), /*!< PMU clock reset */
RCU_DACRST = RCU_REGIDX_BIT(APB1RST_REG_OFFSET, 29U), /*!< DAC clock reset */
/* APB2 peripherals */
RCU_AFRST = RCU_REGIDX_BIT(APB2RST_REG_OFFSET, 0U), /*!< alternate function clock reset */
RCU_GPIOARST = RCU_REGIDX_BIT(APB2RST_REG_OFFSET, 2U), /*!< GPIOA clock reset */
RCU_GPIOBRST = RCU_REGIDX_BIT(APB2RST_REG_OFFSET, 3U), /*!< GPIOB clock reset */
RCU_GPIOCRST = RCU_REGIDX_BIT(APB2RST_REG_OFFSET, 4U), /*!< GPIOC clock reset */
RCU_GPIODRST = RCU_REGIDX_BIT(APB2RST_REG_OFFSET, 5U), /*!< GPIOD clock reset */
RCU_GPIOERST = RCU_REGIDX_BIT(APB2RST_REG_OFFSET, 6U), /*!< GPIOE clock reset */
RCU_ADC0RST = RCU_REGIDX_BIT(APB2RST_REG_OFFSET, 9U), /*!< ADC0 clock reset */
RCU_ADC1RST = RCU_REGIDX_BIT(APB2RST_REG_OFFSET, 10U), /*!< ADC1 clock reset */
RCU_TIMER0RST = RCU_REGIDX_BIT(APB2RST_REG_OFFSET, 11U), /*!< TIMER0 clock reset */
RCU_SPI0RST = RCU_REGIDX_BIT(APB2RST_REG_OFFSET, 12U), /*!< SPI0 clock reset */
RCU_USART0RST = RCU_REGIDX_BIT(APB2RST_REG_OFFSET, 14U), /*!< USART0 clock reset */
} rcu_periph_reset_enum;
/* clock stabilization and peripheral reset flags */
typedef enum {
/* clock stabilization flags */
RCU_FLAG_IRC8MSTB = RCU_REGIDX_BIT(CTL_REG_OFFSET, 1U), /*!< IRC8M stabilization flags */
RCU_FLAG_HXTALSTB = RCU_REGIDX_BIT(CTL_REG_OFFSET, 17U), /*!< HXTAL stabilization flags */
RCU_FLAG_PLLSTB = RCU_REGIDX_BIT(CTL_REG_OFFSET, 25U), /*!< PLL stabilization flags */
RCU_FLAG_PLL1STB = RCU_REGIDX_BIT(CTL_REG_OFFSET, 27U), /*!< PLL1 stabilization flags */
RCU_FLAG_PLL2STB = RCU_REGIDX_BIT(CTL_REG_OFFSET, 29U), /*!< PLL2 stabilization flags */
RCU_FLAG_LXTALSTB = RCU_REGIDX_BIT(BDCTL_REG_OFFSET, 1U), /*!< LXTAL stabilization flags */
RCU_FLAG_IRC40KSTB = RCU_REGIDX_BIT(RSTSCK_REG_OFFSET, 1U), /*!< IRC40K stabilization flags */
/* reset source flags */
RCU_FLAG_EPRST = RCU_REGIDX_BIT(RSTSCK_REG_OFFSET, 26U), /*!< external PIN reset flags */
RCU_FLAG_PORRST = RCU_REGIDX_BIT(RSTSCK_REG_OFFSET, 27U), /*!< power reset flags */
RCU_FLAG_SWRST = RCU_REGIDX_BIT(RSTSCK_REG_OFFSET, 28U), /*!< software reset flags */
RCU_FLAG_FWDGTRST = RCU_REGIDX_BIT(RSTSCK_REG_OFFSET, 29U), /*!< FWDGT reset flags */
RCU_FLAG_WWDGTRST = RCU_REGIDX_BIT(RSTSCK_REG_OFFSET, 30U), /*!< WWDGT reset flags */
RCU_FLAG_LPRST = RCU_REGIDX_BIT(RSTSCK_REG_OFFSET, 31U), /*!< low-power reset flags */
} rcu_flag_enum;
/* clock stabilization and ckm interrupt flags */
typedef enum {
RCU_INT_FLAG_IRC40KSTB = RCU_REGIDX_BIT(INT_REG_OFFSET, 0U), /*!< IRC40K stabilization interrupt flag */
RCU_INT_FLAG_LXTALSTB = RCU_REGIDX_BIT(INT_REG_OFFSET, 1U), /*!< LXTAL stabilization interrupt flag */
RCU_INT_FLAG_IRC8MSTB = RCU_REGIDX_BIT(INT_REG_OFFSET, 2U), /*!< IRC8M stabilization interrupt flag */
RCU_INT_FLAG_HXTALSTB = RCU_REGIDX_BIT(INT_REG_OFFSET, 3U), /*!< HXTAL stabilization interrupt flag */
RCU_INT_FLAG_PLLSTB = RCU_REGIDX_BIT(INT_REG_OFFSET, 4U), /*!< PLL stabilization interrupt flag */
RCU_INT_FLAG_PLL1STB = RCU_REGIDX_BIT(INT_REG_OFFSET, 5U), /*!< PLL1 stabilization interrupt flag */
RCU_INT_FLAG_PLL2STB = RCU_REGIDX_BIT(INT_REG_OFFSET, 6U), /*!< PLL2 stabilization interrupt flag */
RCU_INT_FLAG_CKM = RCU_REGIDX_BIT(INT_REG_OFFSET, 7U), /*!< HXTAL clock stuck interrupt flag */
} rcu_int_flag_enum;
/* clock stabilization and stuck interrupt flags clear */
typedef enum {
RCU_INT_FLAG_IRC40KSTB_CLR = RCU_REGIDX_BIT(INT_REG_OFFSET, 16U), /*!< IRC40K stabilization interrupt flags clear */
RCU_INT_FLAG_LXTALSTB_CLR = RCU_REGIDX_BIT(INT_REG_OFFSET, 17U), /*!< LXTAL stabilization interrupt flags clear */
RCU_INT_FLAG_IRC8MSTB_CLR = RCU_REGIDX_BIT(INT_REG_OFFSET, 18U), /*!< IRC8M stabilization interrupt flags clear */
RCU_INT_FLAG_HXTALSTB_CLR = RCU_REGIDX_BIT(INT_REG_OFFSET, 19U), /*!< HXTAL stabilization interrupt flags clear */
RCU_INT_FLAG_PLLSTB_CLR = RCU_REGIDX_BIT(INT_REG_OFFSET, 20U), /*!< PLL stabilization interrupt flags clear */
RCU_INT_FLAG_PLL1STB_CLR = RCU_REGIDX_BIT(INT_REG_OFFSET, 21U), /*!< PLL1 stabilization interrupt flags clear */
RCU_INT_FLAG_PLL2STB_CLR = RCU_REGIDX_BIT(INT_REG_OFFSET, 22U), /*!< PLL2 stabilization interrupt flags clear */
RCU_INT_FLAG_CKM_CLR = RCU_REGIDX_BIT(INT_REG_OFFSET, 23U), /*!< CKM interrupt flags clear */
} rcu_int_flag_clear_enum;
/* clock stabilization interrupt enable or disable */
typedef enum {
RCU_INT_IRC40KSTB = RCU_REGIDX_BIT(INT_REG_OFFSET, 8U), /*!< IRC40K stabilization interrupt */
RCU_INT_LXTALSTB = RCU_REGIDX_BIT(INT_REG_OFFSET, 9U), /*!< LXTAL stabilization interrupt */
RCU_INT_IRC8MSTB = RCU_REGIDX_BIT(INT_REG_OFFSET, 10U), /*!< IRC8M stabilization interrupt */
RCU_INT_HXTALSTB = RCU_REGIDX_BIT(INT_REG_OFFSET, 11U), /*!< HXTAL stabilization interrupt */
RCU_INT_PLLSTB = RCU_REGIDX_BIT(INT_REG_OFFSET, 12U), /*!< PLL stabilization interrupt */
RCU_INT_PLL1STB = RCU_REGIDX_BIT(INT_REG_OFFSET, 13U), /*!< PLL1 stabilization interrupt */
RCU_INT_PLL2STB = RCU_REGIDX_BIT(INT_REG_OFFSET, 14U), /*!< PLL2 stabilization interrupt */
} rcu_int_enum;
/* oscillator types */
typedef enum {
RCU_HXTAL = RCU_REGIDX_BIT(CTL_REG_OFFSET, 16U), /*!< HXTAL */
RCU_LXTAL = RCU_REGIDX_BIT(BDCTL_REG_OFFSET, 0U), /*!< LXTAL */
RCU_IRC8M = RCU_REGIDX_BIT(CTL_REG_OFFSET, 0U), /*!< IRC8M */
RCU_IRC40K = RCU_REGIDX_BIT(RSTSCK_REG_OFFSET, 0U), /*!< IRC40K */
RCU_PLL_CK = RCU_REGIDX_BIT(CTL_REG_OFFSET, 24U), /*!< PLL */
RCU_PLL1_CK = RCU_REGIDX_BIT(CTL_REG_OFFSET, 26U), /*!< PLL1 */
RCU_PLL2_CK = RCU_REGIDX_BIT(CTL_REG_OFFSET, 28U), /*!< PLL2 */
} rcu_osci_type_enum;
/* rcu clock frequency */
typedef enum {
CK_SYS = 0, /*!< system clock */
CK_AHB, /*!< AHB clock */
CK_APB1, /*!< APB1 clock */
CK_APB2, /*!< APB2 clock */
} rcu_clock_freq_enum;
/* RCU_CFG0 register bit define */
/* system clock source select */
#define CFG0_SCS(regval) (BITS(0,1) & ((uint32_t)(regval) << 0))
#define RCU_CKSYSSRC_IRC8M CFG0_SCS(0) /*!< system clock source select IRC8M */
#define RCU_CKSYSSRC_HXTAL CFG0_SCS(1) /*!< system clock source select HXTAL */
#define RCU_CKSYSSRC_PLL CFG0_SCS(2) /*!< system clock source select PLL */
/* system clock source select status */
#define CFG0_SCSS(regval) (BITS(2,3) & ((uint32_t)(regval) << 2))
#define RCU_SCSS_IRC8M CFG0_SCSS(0) /*!< system clock source select IRC8M */
#define RCU_SCSS_HXTAL CFG0_SCSS(1) /*!< system clock source select HXTAL */
#define RCU_SCSS_PLL CFG0_SCSS(2) /*!< system clock source select PLLP */
/* AHB prescaler selection */
#define CFG0_AHBPSC(regval) (BITS(4,7) & ((uint32_t)(regval) << 4))
#define RCU_AHB_CKSYS_DIV1 CFG0_AHBPSC(0) /*!< AHB prescaler select CK_SYS */
#define RCU_AHB_CKSYS_DIV2 CFG0_AHBPSC(8) /*!< AHB prescaler select CK_SYS/2 */
#define RCU_AHB_CKSYS_DIV4 CFG0_AHBPSC(9) /*!< AHB prescaler select CK_SYS/4 */
#define RCU_AHB_CKSYS_DIV8 CFG0_AHBPSC(10) /*!< AHB prescaler select CK_SYS/8 */
#define RCU_AHB_CKSYS_DIV16 CFG0_AHBPSC(11) /*!< AHB prescaler select CK_SYS/16 */
#define RCU_AHB_CKSYS_DIV64 CFG0_AHBPSC(12) /*!< AHB prescaler select CK_SYS/64 */
#define RCU_AHB_CKSYS_DIV128 CFG0_AHBPSC(13) /*!< AHB prescaler select CK_SYS/128 */
#define RCU_AHB_CKSYS_DIV256 CFG0_AHBPSC(14) /*!< AHB prescaler select CK_SYS/256 */
#define RCU_AHB_CKSYS_DIV512 CFG0_AHBPSC(15) /*!< AHB prescaler select CK_SYS/512 */
/* APB1 prescaler selection */
#define CFG0_APB1PSC(regval) (BITS(8,10) & ((uint32_t)(regval) << 8))
#define RCU_APB1_CKAHB_DIV1 CFG0_APB1PSC(0) /*!< APB1 prescaler select CK_AHB */
#define RCU_APB1_CKAHB_DIV2 CFG0_APB1PSC(4) /*!< APB1 prescaler select CK_AHB/2 */
#define RCU_APB1_CKAHB_DIV4 CFG0_APB1PSC(5) /*!< APB1 prescaler select CK_AHB/4 */
#define RCU_APB1_CKAHB_DIV8 CFG0_APB1PSC(6) /*!< APB1 prescaler select CK_AHB/8 */
#define RCU_APB1_CKAHB_DIV16 CFG0_APB1PSC(7) /*!< APB1 prescaler select CK_AHB/16 */
/* APB2 prescaler selection */
#define CFG0_APB2PSC(regval) (BITS(11,13) & ((uint32_t)(regval) << 11))
#define RCU_APB2_CKAHB_DIV1 CFG0_APB2PSC(0) /*!< APB2 prescaler select CK_AHB */
#define RCU_APB2_CKAHB_DIV2 CFG0_APB2PSC(4) /*!< APB2 prescaler select CK_AHB/2 */
#define RCU_APB2_CKAHB_DIV4 CFG0_APB2PSC(5) /*!< APB2 prescaler select CK_AHB/4 */
#define RCU_APB2_CKAHB_DIV8 CFG0_APB2PSC(6) /*!< APB2 prescaler select CK_AHB/8 */
#define RCU_APB2_CKAHB_DIV16 CFG0_APB2PSC(7) /*!< APB2 prescaler select CK_AHB/16 */
/* ADC prescaler select */
#define RCU_CKADC_CKAPB2_DIV2 ((uint32_t)0x00000000U) /*!< ADC prescaler select CK_APB2/2 */
#define RCU_CKADC_CKAPB2_DIV4 ((uint32_t)0x00000001U) /*!< ADC prescaler select CK_APB2/4 */
#define RCU_CKADC_CKAPB2_DIV6 ((uint32_t)0x00000002U) /*!< ADC prescaler select CK_APB2/6 */
#define RCU_CKADC_CKAPB2_DIV8 ((uint32_t)0x00000003U) /*!< ADC prescaler select CK_APB2/8 */
#define RCU_CKADC_CKAPB2_DIV12 ((uint32_t)0x00000005U) /*!< ADC prescaler select CK_APB2/12 */
#define RCU_CKADC_CKAPB2_DIV16 ((uint32_t)0x00000007U) /*!< ADC prescaler select CK_APB2/16 */
/* PLL clock source selection */
#define RCU_PLLSRC_IRC8M_DIV2 ((uint32_t)0x00000000U) /*!< IRC8M/2 clock selected as source clock of PLL */
#define RCU_PLLSRC_HXTAL RCU_CFG0_PLLSEL /*!< HXTAL clock selected as source clock of PLL */
/* PLL clock multiplication factor */
#define PLLMF_4 RCU_CFG0_PLLMF_4 /* bit 4 of PLLMF */
#define CFG0_PLLMF(regval) (BITS(18,21) & ((uint32_t)(regval) << 18))
#define RCU_PLL_MUL2 CFG0_PLLMF(0) /*!< PLL source clock multiply by 2 */
#define RCU_PLL_MUL3 CFG0_PLLMF(1) /*!< PLL source clock multiply by 3 */
#define RCU_PLL_MUL4 CFG0_PLLMF(2) /*!< PLL source clock multiply by 4 */
#define RCU_PLL_MUL5 CFG0_PLLMF(3) /*!< PLL source clock multiply by 5 */
#define RCU_PLL_MUL6 CFG0_PLLMF(4) /*!< PLL source clock multiply by 6 */
#define RCU_PLL_MUL7 CFG0_PLLMF(5) /*!< PLL source clock multiply by 7 */
#define RCU_PLL_MUL8 CFG0_PLLMF(6) /*!< PLL source clock multiply by 8 */
#define RCU_PLL_MUL9 CFG0_PLLMF(7) /*!< PLL source clock multiply by 9 */
#define RCU_PLL_MUL10 CFG0_PLLMF(8) /*!< PLL source clock multiply by 10 */
#define RCU_PLL_MUL11 CFG0_PLLMF(9) /*!< PLL source clock multiply by 11 */
#define RCU_PLL_MUL12 CFG0_PLLMF(10) /*!< PLL source clock multiply by 12 */
#define RCU_PLL_MUL13 CFG0_PLLMF(11) /*!< PLL source clock multiply by 13 */
#define RCU_PLL_MUL14 CFG0_PLLMF(12) /*!< PLL source clock multiply by 14 */
#define RCU_PLL_MUL6_5 CFG0_PLLMF(13) /*!< PLL source clock multiply by 6.5 */
#define RCU_PLL_MUL16 CFG0_PLLMF(14) /*!< PLL source clock multiply by 16 */
#define RCU_PLL_MUL17 (PLLMF_4 | CFG0_PLLMF(0)) /*!< PLL source clock multiply by 17 */
#define RCU_PLL_MUL18 (PLLMF_4 | CFG0_PLLMF(1)) /*!< PLL source clock multiply by 18 */
#define RCU_PLL_MUL19 (PLLMF_4 | CFG0_PLLMF(2)) /*!< PLL source clock multiply by 19 */
#define RCU_PLL_MUL20 (PLLMF_4 | CFG0_PLLMF(3)) /*!< PLL source clock multiply by 20 */
#define RCU_PLL_MUL21 (PLLMF_4 | CFG0_PLLMF(4)) /*!< PLL source clock multiply by 21 */
#define RCU_PLL_MUL22 (PLLMF_4 | CFG0_PLLMF(5)) /*!< PLL source clock multiply by 22 */
#define RCU_PLL_MUL23 (PLLMF_4 | CFG0_PLLMF(6)) /*!< PLL source clock multiply by 23 */
#define RCU_PLL_MUL24 (PLLMF_4 | CFG0_PLLMF(7)) /*!< PLL source clock multiply by 24 */
#define RCU_PLL_MUL25 (PLLMF_4 | CFG0_PLLMF(8)) /*!< PLL source clock multiply by 25 */
#define RCU_PLL_MUL26 (PLLMF_4 | CFG0_PLLMF(9)) /*!< PLL source clock multiply by 26 */
#define RCU_PLL_MUL27 (PLLMF_4 | CFG0_PLLMF(10)) /*!< PLL source clock multiply by 27 */
#define RCU_PLL_MUL28 (PLLMF_4 | CFG0_PLLMF(11)) /*!< PLL source clock multiply by 28 */
#define RCU_PLL_MUL29 (PLLMF_4 | CFG0_PLLMF(12)) /*!< PLL source clock multiply by 29 */
#define RCU_PLL_MUL30 (PLLMF_4 | CFG0_PLLMF(13)) /*!< PLL source clock multiply by 30 */
#define RCU_PLL_MUL31 (PLLMF_4 | CFG0_PLLMF(14)) /*!< PLL source clock multiply by 31 */
#define RCU_PLL_MUL32 (PLLMF_4 | CFG0_PLLMF(15)) /*!< PLL source clock multiply by 32 */
/* USBFS prescaler select */
#define CFG0_USBPSC(regval) (BITS(22,23) & ((uint32_t)(regval) << 22))
#define RCU_CKUSB_CKPLL_DIV1_5 CFG0_USBPSC(0) /*!< USBFS prescaler select CK_PLL/1.5 */
#define RCU_CKUSB_CKPLL_DIV1 CFG0_USBPSC(1) /*!< USBFS prescaler select CK_PLL/1 */
#define RCU_CKUSB_CKPLL_DIV2_5 CFG0_USBPSC(2) /*!< USBFS prescaler select CK_PLL/2.5 */
#define RCU_CKUSB_CKPLL_DIV2 CFG0_USBPSC(3) /*!< USBFS prescaler select CK_PLL/2 */
/* CKOUT0 clock source selection */
#define CFG0_CKOUT0SEL(regval) (BITS(24,27) & ((uint32_t)(regval) << 24))
#define RCU_CKOUT0SRC_NONE CFG0_CKOUT0SEL(0) /*!< no clock selected */
#define RCU_CKOUT0SRC_CKSYS CFG0_CKOUT0SEL(4) /*!< system clock selected */
#define RCU_CKOUT0SRC_IRC8M CFG0_CKOUT0SEL(5) /*!< internal 8M RC oscillator clock selected */
#define RCU_CKOUT0SRC_HXTAL CFG0_CKOUT0SEL(6) /*!< high speed crystal oscillator clock (HXTAL) selected */
#define RCU_CKOUT0SRC_CKPLL_DIV2 CFG0_CKOUT0SEL(7) /*!< CK_PLL/2 clock selected */
#define RCU_CKOUT0SRC_CKPLL1 CFG0_CKOUT0SEL(8) /*!< CK_PLL1 clock selected */
#define RCU_CKOUT0SRC_CKPLL2_DIV2 CFG0_CKOUT0SEL(9) /*!< CK_PLL2/2 clock selected */
#define RCU_CKOUT0SRC_EXT1 CFG0_CKOUT0SEL(10) /*!< EXT1 selected */
#define RCU_CKOUT0SRC_CKPLL2 CFG0_CKOUT0SEL(11) /*!< CK_PLL2 clock selected */
/* RTC clock entry selection */
#define BDCTL_RTCSRC(regval) (BITS(8,9) & ((uint32_t)(regval) << 8))
#define RCU_RTCSRC_NONE BDCTL_RTCSRC(0) /*!< no clock selected */
#define RCU_RTCSRC_LXTAL BDCTL_RTCSRC(1) /*!< RTC source clock select LXTAL */
#define RCU_RTCSRC_IRC40K BDCTL_RTCSRC(2) /*!< RTC source clock select IRC40K */
#define RCU_RTCSRC_HXTAL_DIV_128 BDCTL_RTCSRC(3) /*!< RTC source clock select HXTAL/128 */
/* PREDV0 division factor */
#define CFG1_PREDV0(regval) (BITS(0,3) & ((uint32_t)(regval) << 0))
#define RCU_PREDV0_DIV1 CFG1_PREDV0(0) /*!< PREDV0 input source clock not divided */
#define RCU_PREDV0_DIV2 CFG1_PREDV0(1) /*!< PREDV0 input source clock divided by 2 */
#define RCU_PREDV0_DIV3 CFG1_PREDV0(2) /*!< PREDV0 input source clock divided by 3 */
#define RCU_PREDV0_DIV4 CFG1_PREDV0(3) /*!< PREDV0 input source clock divided by 4 */
#define RCU_PREDV0_DIV5 CFG1_PREDV0(4) /*!< PREDV0 input source clock divided by 5 */
#define RCU_PREDV0_DIV6 CFG1_PREDV0(5) /*!< PREDV0 input source clock divided by 6 */
#define RCU_PREDV0_DIV7 CFG1_PREDV0(6) /*!< PREDV0 input source clock divided by 7 */
#define RCU_PREDV0_DIV8 CFG1_PREDV0(7) /*!< PREDV0 input source clock divided by 8 */
#define RCU_PREDV0_DIV9 CFG1_PREDV0(8) /*!< PREDV0 input source clock divided by 9 */
#define RCU_PREDV0_DIV10 CFG1_PREDV0(9) /*!< PREDV0 input source clock divided by 10 */
#define RCU_PREDV0_DIV11 CFG1_PREDV0(10) /*!< PREDV0 input source clock divided by 11 */
#define RCU_PREDV0_DIV12 CFG1_PREDV0(11) /*!< PREDV0 input source clock divided by 12 */
#define RCU_PREDV0_DIV13 CFG1_PREDV0(12) /*!< PREDV0 input source clock divided by 13 */
#define RCU_PREDV0_DIV14 CFG1_PREDV0(13) /*!< PREDV0 input source clock divided by 14 */
#define RCU_PREDV0_DIV15 CFG1_PREDV0(14) /*!< PREDV0 input source clock divided by 15 */
#define RCU_PREDV0_DIV16 CFG1_PREDV0(15) /*!< PREDV0 input source clock divided by 16 */
/* PREDV1 division factor */
#define CFG1_PREDV1(regval) (BITS(4,7) & ((uint32_t)(regval) << 4))
#define RCU_PREDV1_DIV1 CFG1_PREDV1(0) /*!< PREDV1 input source clock not divided */
#define RCU_PREDV1_DIV2 CFG1_PREDV1(1) /*!< PREDV1 input source clock divided by 2 */
#define RCU_PREDV1_DIV3 CFG1_PREDV1(2) /*!< PREDV1 input source clock divided by 3 */
#define RCU_PREDV1_DIV4 CFG1_PREDV1(3) /*!< PREDV1 input source clock divided by 4 */
#define RCU_PREDV1_DIV5 CFG1_PREDV1(4) /*!< PREDV1 input source clock divided by 5 */
#define RCU_PREDV1_DIV6 CFG1_PREDV1(5) /*!< PREDV1 input source clock divided by 6 */
#define RCU_PREDV1_DIV7 CFG1_PREDV1(6) /*!< PREDV1 input source clock divided by 7 */
#define RCU_PREDV1_DIV8 CFG1_PREDV1(7) /*!< PREDV1 input source clock divided by 8 */
#define RCU_PREDV1_DIV9 CFG1_PREDV1(8) /*!< PREDV1 input source clock divided by 9 */
#define RCU_PREDV1_DIV10 CFG1_PREDV1(9) /*!< PREDV1 input source clock divided by 10 */
#define RCU_PREDV1_DIV11 CFG1_PREDV1(10) /*!< PREDV1 input source clock divided by 11 */
#define RCU_PREDV1_DIV12 CFG1_PREDV1(11) /*!< PREDV1 input source clock divided by 12 */
#define RCU_PREDV1_DIV13 CFG1_PREDV1(12) /*!< PREDV1 input source clock divided by 13 */
#define RCU_PREDV1_DIV14 CFG1_PREDV1(13) /*!< PREDV1 input source clock divided by 14 */
#define RCU_PREDV1_DIV15 CFG1_PREDV1(14) /*!< PREDV1 input source clock divided by 15 */
#define RCU_PREDV1_DIV16 CFG1_PREDV1(15) /*!< PREDV1 input source clock divided by 16 */
/* PLL1 clock multiplication factor */
#define CFG1_PLL1MF(regval) (BITS(8,11) & ((uint32_t)(regval) << 8))
#define RCU_PLL1_MUL8 CFG1_PLL1MF(6) /*!< PLL1 source clock multiply by 8 */
#define RCU_PLL1_MUL9 CFG1_PLL1MF(7) /*!< PLL1 source clock multiply by 9 */
#define RCU_PLL1_MUL10 CFG1_PLL1MF(8) /*!< PLL1 source clock multiply by 10 */
#define RCU_PLL1_MUL11 CFG1_PLL1MF(9) /*!< PLL1 source clock multiply by 11 */
#define RCU_PLL1_MUL12 CFG1_PLL1MF(10) /*!< PLL1 source clock multiply by 12 */
#define RCU_PLL1_MUL13 CFG1_PLL1MF(11) /*!< PLL1 source clock multiply by 13 */
#define RCU_PLL1_MUL14 CFG1_PLL1MF(12) /*!< PLL1 source clock multiply by 14 */
#define RCU_PLL1_MUL15 CFG1_PLL1MF(13) /*!< PLL1 source clock multiply by 15 */
#define RCU_PLL1_MUL16 CFG1_PLL1MF(14) /*!< PLL1 source clock multiply by 16 */
#define RCU_PLL1_MUL20 CFG1_PLL1MF(15) /*!< PLL1 source clock multiply by 20 */
/* PLL2 clock multiplication factor */
#define CFG1_PLL2MF(regval) (BITS(12,15) & ((uint32_t)(regval) << 12))
#define RCU_PLL2_MUL8 CFG1_PLL2MF(6) /*!< PLL2 source clock multiply by 8 */
#define RCU_PLL2_MUL9 CFG1_PLL2MF(7) /*!< PLL2 source clock multiply by 9 */
#define RCU_PLL2_MUL10 CFG1_PLL2MF(8) /*!< PLL2 source clock multiply by 10 */
#define RCU_PLL2_MUL11 CFG1_PLL2MF(9) /*!< PLL2 source clock multiply by 11 */
#define RCU_PLL2_MUL12 CFG1_PLL2MF(10) /*!< PLL2 source clock multiply by 12 */
#define RCU_PLL2_MUL13 CFG1_PLL2MF(11) /*!< PLL2 source clock multiply by 13 */
#define RCU_PLL2_MUL14 CFG1_PLL2MF(12) /*!< PLL2 source clock multiply by 14 */
#define RCU_PLL2_MUL15 CFG1_PLL2MF(13) /*!< PLL2 source clock multiply by 15 */
#define RCU_PLL2_MUL16 CFG1_PLL2MF(14) /*!< PLL2 source clock multiply by 16 */
#define RCU_PLL2_MUL20 CFG1_PLL2MF(15) /*!< PLL2 source clock multiply by 20 */
/* PREDV0 input clock source selection */
#define RCU_PREDV0SRC_HXTAL ((uint32_t)0x00000000U) /*!< HXTAL selected as PREDV0 input source clock */
#define RCU_PREDV0SRC_CKPLL1 RCU_CFG1_PREDV0SEL /*!< CK_PLL1 selected as PREDV0 input source clock */
/* I2S1 clock source selection */
#define RCU_I2S1SRC_CKSYS ((uint32_t)0x00000000U) /*!< system clock selected as I2S1 source clock */
#define RCU_I2S1SRC_CKPLL2_MUL2 RCU_CFG1_I2S1SEL /*!< (CK_PLL2 x 2) selected as I2S1 source clock */
/* I2S2 clock source selection */
#define RCU_I2S2SRC_CKSYS ((uint32_t)0x00000000U) /*!< system clock selected as I2S2 source clock */
#define RCU_I2S2SRC_CKPLL2_MUL2 RCU_CFG1_I2S2SEL /*!< (CK_PLL2 x 2) selected as I2S2 source clock */
/* deep-sleep mode voltage */
#define DSV_DSLPVS(regval) (BITS(0,1) & ((uint32_t)(regval) << 0))
#define RCU_DEEPSLEEP_V_1_2 DSV_DSLPVS(0) /*!< core voltage is 1.2V in deep-sleep mode */
#define RCU_DEEPSLEEP_V_1_1 DSV_DSLPVS(1) /*!< core voltage is 1.1V in deep-sleep mode */
#define RCU_DEEPSLEEP_V_1_0 DSV_DSLPVS(2) /*!< core voltage is 1.0V in deep-sleep mode */
#define RCU_DEEPSLEEP_V_0_9 DSV_DSLPVS(3) /*!< core voltage is 0.9V in deep-sleep mode */
/* function declarations */
/* initialization, peripheral clock enable/disable functions */
/* deinitialize the RCU */
void rcu_deinit(void);
/* enable the peripherals clock */
void rcu_periph_clock_enable(rcu_periph_enum periph);
/* disable the peripherals clock */
void rcu_periph_clock_disable(rcu_periph_enum periph);
/* enable the peripherals clock when sleep mode */
void rcu_periph_clock_sleep_enable(rcu_periph_sleep_enum periph);
/* disable the peripherals clock when sleep mode */
void rcu_periph_clock_sleep_disable(rcu_periph_sleep_enum periph);
/* reset the peripherals */
void rcu_periph_reset_enable(rcu_periph_reset_enum periph_reset);
/* disable reset the peripheral */
void rcu_periph_reset_disable(rcu_periph_reset_enum periph_reset);
/* reset the BKP domain */
void rcu_bkp_reset_enable(void);
/* disable the BKP domain reset */
void rcu_bkp_reset_disable(void);
/* clock configuration functions */
/* configure the system clock source */
void rcu_system_clock_source_config(uint32_t ck_sys);
/* get the system clock source */
uint32_t rcu_system_clock_source_get(void);
/* configure the AHB prescaler selection */
void rcu_ahb_clock_config(uint32_t ck_ahb);
/* configure the APB1 prescaler selection */
void rcu_apb1_clock_config(uint32_t ck_apb1);
/* configure the APB2 prescaler selection */
void rcu_apb2_clock_config(uint32_t ck_apb2);
/* configure the CK_OUT0 clock source and divider */
void rcu_ckout0_config(uint32_t ckout0_src);
/* configure the PLL clock source selection and PLL multiply factor */
void rcu_pll_config(uint32_t pll_src, uint32_t pll_mul);
/* configure the PREDV0 division factor and clock source */
void rcu_predv0_config(uint32_t predv0_source, uint32_t predv0_div);
/* configure the PREDV1 division factor */
void rcu_predv1_config(uint32_t predv1_div);
/* configure the PLL1 clock */
void rcu_pll1_config(uint32_t pll_mul);
/* configure the PLL2 clock */
void rcu_pll2_config(uint32_t pll_mul);
/* peripheral clock configuration functions */
/* configure the ADC division factor */
void rcu_adc_clock_config(uint32_t adc_psc);
/* configure the USBD/USBFS prescaler factor */
void rcu_usb_clock_config(uint32_t usb_psc);
/* configure the RTC clock source selection */
void rcu_rtc_clock_config(uint32_t rtc_clock_source);
/* configure the I2S1 clock source selection */
void rcu_i2s1_clock_config(uint32_t i2s_clock_source);
/* configure the I2S2 clock source selection */
void rcu_i2s2_clock_config(uint32_t i2s_clock_source);
/* interrupt & flag functions */
/* get the clock stabilization and periphral reset flags */
FlagStatus rcu_flag_get(rcu_flag_enum flag);
/* clear the reset flag */
void rcu_all_reset_flag_clear(void);
/* get the clock stabilization interrupt and ckm flags */
FlagStatus rcu_interrupt_flag_get(rcu_int_flag_enum int_flag);
/* clear the interrupt flags */
void rcu_interrupt_flag_clear(rcu_int_flag_clear_enum int_flag_clear);
/* enable the stabilization interrupt */
void rcu_interrupt_enable(rcu_int_enum stab_int);
/* disable the stabilization interrupt */
void rcu_interrupt_disable(rcu_int_enum stab_int);
/* oscillator configuration functions */
/* wait for oscillator stabilization flags is SET or oscillator startup is timeout */
ErrStatus rcu_osci_stab_wait(rcu_osci_type_enum osci);
/* turn on the oscillator */
void rcu_osci_on(rcu_osci_type_enum osci);
/* turn off the oscillator */
void rcu_osci_off(rcu_osci_type_enum osci);
/* enable the oscillator bypass mode, HXTALEN or LXTALEN must be reset before it */
void rcu_osci_bypass_mode_enable(rcu_osci_type_enum osci);
/* disable the oscillator bypass mode, HXTALEN or LXTALEN must be reset before it */
void rcu_osci_bypass_mode_disable(rcu_osci_type_enum osci);
/* enable the HXTAL clock monitor */
void rcu_hxtal_clock_monitor_enable(void);
/* disable the HXTAL clock monitor */
void rcu_hxtal_clock_monitor_disable(void);
/* set the IRC8M adjust value */
void rcu_irc8m_adjust_value_set(uint32_t irc8m_adjval);
/* set the deep sleep mode voltage */
void rcu_deepsleep_voltage_set(uint32_t dsvol);
/* get the system clock, bus and peripheral clock frequency */
uint32_t rcu_clock_freq_get(rcu_clock_freq_enum clock);
#endif /* GD32VF103_RCU_H */

View File

@ -0,0 +1,720 @@
/*!
\file gd32vf103_timer.h
\brief definitions for the TIMER
\version 2019-6-5, V1.0.0, firmware for GD32VF103
*/
/*
Copyright (c) 2019, GigaDevice Semiconductor Inc.
Redistribution and use in source and binary forms, with or without modification,
are permitted provided that the following conditions are met:
1. Redistributions of source code must retain the above copyright notice, this
list of conditions and the following disclaimer.
2. Redistributions in binary form must reproduce the above copyright notice,
this list of conditions and the following disclaimer in the documentation
and/or other materials provided with the distribution.
3. Neither the name of the copyright holder nor the names of its contributors
may be used to endorse or promote products derived from this software without
specific prior written permission.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED.
IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT,
INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT
NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY
OF SUCH DAMAGE.
*/
#ifndef GD32VF103_TIMER_H
#define GD32VF103_TIMER_H
#include "gd32vf103.h"
#include "gd32vf103_rcu.h"
// #include "gd32vf103_dbg.h"
/* TIMERx(x=0..13) definitions */
#define TIMER0 (TIMER_BASE + 0x00012C00U)
#define TIMER1 (TIMER_BASE + 0x00000000U)
#define TIMER2 (TIMER_BASE + 0x00000400U)
#define TIMER3 (TIMER_BASE + 0x00000800U)
#define TIMER4 (TIMER_BASE + 0x00000C00U)
#define TIMER5 (TIMER_BASE + 0x00001000U)
#define TIMER6 (TIMER_BASE + 0x00001400U)
/* registers definitions */
#define TIMER_CTL0(timerx) REG32((timerx) + 0x00U) /*!< TIMER control register 0 */
#define TIMER_CTL1(timerx) REG32((timerx) + 0x04U) /*!< TIMER control register 1 */
#define TIMER_SMCFG(timerx) REG32((timerx) + 0x08U) /*!< TIMER slave mode configuration register */
#define TIMER_DMAINTEN(timerx) REG32((timerx) + 0x0CU) /*!< TIMER DMA and interrupt enable register */
#define TIMER_INTF(timerx) REG32((timerx) + 0x10U) /*!< TIMER interrupt flag register */
#define TIMER_SWEVG(timerx) REG32((timerx) + 0x14U) /*!< TIMER software event generation register */
#define TIMER_CHCTL0(timerx) REG32((timerx) + 0x18U) /*!< TIMER channel control register 0 */
#define TIMER_CHCTL1(timerx) REG32((timerx) + 0x1CU) /*!< TIMER channel control register 1 */
#define TIMER_CHCTL2(timerx) REG32((timerx) + 0x20U) /*!< TIMER channel control register 2 */
#define TIMER_CNT(timerx) REG32((timerx) + 0x24U) /*!< TIMER counter register */
#define TIMER_PSC(timerx) REG32((timerx) + 0x28U) /*!< TIMER prescaler register */
#define TIMER_CAR(timerx) REG32((timerx) + 0x2CU) /*!< TIMER counter auto reload register */
#define TIMER_CREP(timerx) REG32((timerx) + 0x30U) /*!< TIMER counter repetition register */
#define TIMER_CH0CV(timerx) REG32((timerx) + 0x34U) /*!< TIMER channel 0 capture/compare value register */
#define TIMER_CH1CV(timerx) REG32((timerx) + 0x38U) /*!< TIMER channel 1 capture/compare value register */
#define TIMER_CH2CV(timerx) REG32((timerx) + 0x3CU) /*!< TIMER channel 2 capture/compare value register */
#define TIMER_CH3CV(timerx) REG32((timerx) + 0x40U) /*!< TIMER channel 3 capture/compare value register */
#define TIMER_CCHP(timerx) REG32((timerx) + 0x44U) /*!< TIMER channel complementary protection register */
#define TIMER_DMACFG(timerx) REG32((timerx) + 0x48U) /*!< TIMER DMA configuration register */
#define TIMER_DMATB(timerx) REG32((timerx) + 0x4CU) /*!< TIMER DMA transfer buffer register */
/* bits definitions */
/* TIMER_CTL0 */
#define TIMER_CTL0_CEN BIT(0) /*!< TIMER counter enable */
#define TIMER_CTL0_UPDIS BIT(1) /*!< update disable */
#define TIMER_CTL0_UPS BIT(2) /*!< update source */
#define TIMER_CTL0_SPM BIT(3) /*!< single pulse mode */
#define TIMER_CTL0_DIR BIT(4) /*!< timer counter direction */
#define TIMER_CTL0_CAM BITS(5,6) /*!< center-aligned mode selection */
#define TIMER_CTL0_ARSE BIT(7) /*!< auto-reload shadow enable */
#define TIMER_CTL0_CKDIV BITS(8,9) /*!< clock division */
/* TIMER_CTL1 */
#define TIMER_CTL1_CCSE BIT(0) /*!< commutation control shadow enable */
#define TIMER_CTL1_CCUC BIT(2) /*!< commutation control shadow register update control */
#define TIMER_CTL1_DMAS BIT(3) /*!< DMA request source selection */
#define TIMER_CTL1_MMC BITS(4,6) /*!< master mode control */
#define TIMER_CTL1_TI0S BIT(7) /*!< channel 0 trigger input selection(hall mode selection) */
#define TIMER_CTL1_ISO0 BIT(8) /*!< idle state of channel 0 output */
#define TIMER_CTL1_ISO0N BIT(9) /*!< idle state of channel 0 complementary output */
#define TIMER_CTL1_ISO1 BIT(10) /*!< idle state of channel 1 output */
#define TIMER_CTL1_ISO1N BIT(11) /*!< idle state of channel 1 complementary output */
#define TIMER_CTL1_ISO2 BIT(12) /*!< idle state of channel 2 output */
#define TIMER_CTL1_ISO2N BIT(13) /*!< idle state of channel 2 complementary output */
#define TIMER_CTL1_ISO3 BIT(14) /*!< idle state of channel 3 output */
/* TIMER_SMCFG */
#define TIMER_SMCFG_SMC BITS(0,2) /*!< slave mode control */
#define TIMER_SMCFG_TRGS BITS(4,6) /*!< trigger selection */
#define TIMER_SMCFG_MSM BIT(7) /*!< master-slave mode */
#define TIMER_SMCFG_ETFC BITS(8,11) /*!< external trigger filter control */
#define TIMER_SMCFG_ETPSC BITS(12,13) /*!< external trigger prescaler */
#define TIMER_SMCFG_SMC1 BIT(14) /*!< part of SMC for enable external clock mode 1 */
#define TIMER_SMCFG_ETP BIT(15) /*!< external trigger polarity */
/* TIMER_DMAINTEN */
#define TIMER_DMAINTEN_UPIE BIT(0) /*!< update interrupt enable */
#define TIMER_DMAINTEN_CH0IE BIT(1) /*!< channel 0 capture/compare interrupt enable */
#define TIMER_DMAINTEN_CH1IE BIT(2) /*!< channel 1 capture/compare interrupt enable */
#define TIMER_DMAINTEN_CH2IE BIT(3) /*!< channel 2 capture/compare interrupt enable */
#define TIMER_DMAINTEN_CH3IE BIT(4) /*!< channel 3 capture/compare interrupt enable */
#define TIMER_DMAINTEN_CMTIE BIT(5) /*!< commutation interrupt request enable */
#define TIMER_DMAINTEN_TRGIE BIT(6) /*!< trigger interrupt enable */
#define TIMER_DMAINTEN_BRKIE BIT(7) /*!< break interrupt enable */
#define TIMER_DMAINTEN_UPDEN BIT(8) /*!< update DMA request enable */
#define TIMER_DMAINTEN_CH0DEN BIT(9) /*!< channel 0 capture/compare DMA request enable */
#define TIMER_DMAINTEN_CH1DEN BIT(10) /*!< channel 1 capture/compare DMA request enable */
#define TIMER_DMAINTEN_CH2DEN BIT(11) /*!< channel 2 capture/compare DMA request enable */
#define TIMER_DMAINTEN_CH3DEN BIT(12) /*!< channel 3 capture/compare DMA request enable */
#define TIMER_DMAINTEN_CMTDEN BIT(13) /*!< commutation DMA request enable */
#define TIMER_DMAINTEN_TRGDEN BIT(14) /*!< trigger DMA request enable */
/* TIMER_INTF */
#define TIMER_INTF_UPIF BIT(0) /*!< update interrupt flag */
#define TIMER_INTF_CH0IF BIT(1) /*!< channel 0 capture/compare interrupt flag */
#define TIMER_INTF_CH1IF BIT(2) /*!< channel 1 capture/compare interrupt flag */
#define TIMER_INTF_CH2IF BIT(3) /*!< channel 2 capture/compare interrupt flag */
#define TIMER_INTF_CH3IF BIT(4) /*!< channel 3 capture/compare interrupt flag */
#define TIMER_INTF_CMTIF BIT(5) /*!< channel commutation interrupt flag */
#define TIMER_INTF_TRGIF BIT(6) /*!< trigger interrupt flag */
#define TIMER_INTF_BRKIF BIT(7) /*!< break interrupt flag */
#define TIMER_INTF_CH0OF BIT(9) /*!< channel 0 over capture flag */
#define TIMER_INTF_CH1OF BIT(10) /*!< channel 1 over capture flag */
#define TIMER_INTF_CH2OF BIT(11) /*!< channel 2 over capture flag */
#define TIMER_INTF_CH3OF BIT(12) /*!< channel 3 over capture flag */
/* TIMER_SWEVG */
#define TIMER_SWEVG_UPG BIT(0) /*!< update event generate */
#define TIMER_SWEVG_CH0G BIT(1) /*!< channel 0 capture or compare event generation */
#define TIMER_SWEVG_CH1G BIT(2) /*!< channel 1 capture or compare event generation */
#define TIMER_SWEVG_CH2G BIT(3) /*!< channel 2 capture or compare event generation */
#define TIMER_SWEVG_CH3G BIT(4) /*!< channel 3 capture or compare event generation */
#define TIMER_SWEVG_CMTG BIT(5) /*!< channel commutation event generation */
#define TIMER_SWEVG_TRGG BIT(6) /*!< trigger event generation */
#define TIMER_SWEVG_BRKG BIT(7) /*!< break event generation */
/* TIMER_CHCTL0 */
/* output compare mode */
#define TIMER_CHCTL0_CH0MS BITS(0,1) /*!< channel 0 mode selection */
#define TIMER_CHCTL0_CH0COMFEN BIT(2) /*!< channel 0 output compare fast enable */
#define TIMER_CHCTL0_CH0COMSEN BIT(3) /*!< channel 0 output compare shadow enable */
#define TIMER_CHCTL0_CH0COMCTL BITS(4,6) /*!< channel 0 output compare control */
#define TIMER_CHCTL0_CH0COMCEN BIT(7) /*!< channel 0 output compare clear enable */
#define TIMER_CHCTL0_CH1MS BITS(8,9) /*!< channel 1 mode selection */
#define TIMER_CHCTL0_CH1COMFEN BIT(10) /*!< channel 1 output compare fast enable */
#define TIMER_CHCTL0_CH1COMSEN BIT(11) /*!< channel 1 output compare shadow enable */
#define TIMER_CHCTL0_CH1COMCTL BITS(12,14) /*!< channel 1 output compare control */
#define TIMER_CHCTL0_CH1COMCEN BIT(15) /*!< channel 1 output compare clear enable */
/* input capture mode */
#define TIMER_CHCTL0_CH0CAPPSC BITS(2,3) /*!< channel 0 input capture prescaler */
#define TIMER_CHCTL0_CH0CAPFLT BITS(4,7) /*!< channel 0 input capture filter control */
#define TIMER_CHCTL0_CH1CAPPSC BITS(10,11) /*!< channel 1 input capture prescaler */
#define TIMER_CHCTL0_CH1CAPFLT BITS(12,15) /*!< channel 1 input capture filter control */
/* TIMER_CHCTL1 */
/* output compare mode */
#define TIMER_CHCTL1_CH2MS BITS(0,1) /*!< channel 2 mode selection */
#define TIMER_CHCTL1_CH2COMFEN BIT(2) /*!< channel 2 output compare fast enable */
#define TIMER_CHCTL1_CH2COMSEN BIT(3) /*!< channel 2 output compare shadow enable */
#define TIMER_CHCTL1_CH2COMCTL BITS(4,6) /*!< channel 2 output compare control */
#define TIMER_CHCTL1_CH2COMCEN BIT(7) /*!< channel 2 output compare clear enable */
#define TIMER_CHCTL1_CH3MS BITS(8,9) /*!< channel 3 mode selection */
#define TIMER_CHCTL1_CH3COMFEN BIT(10) /*!< channel 3 output compare fast enable */
#define TIMER_CHCTL1_CH3COMSEN BIT(11) /*!< channel 3 output compare shadow enable */
#define TIMER_CHCTL1_CH3COMCTL BITS(12,14) /*!< channel 3 output compare control */
#define TIMER_CHCTL1_CH3COMCEN BIT(15) /*!< channel 3 output compare clear enable */
/* input capture mode */
#define TIMER_CHCTL1_CH2CAPPSC BITS(2,3) /*!< channel 2 input capture prescaler */
#define TIMER_CHCTL1_CH2CAPFLT BITS(4,7) /*!< channel 2 input capture filter control */
#define TIMER_CHCTL1_CH3CAPPSC BITS(10,11) /*!< channel 3 input capture prescaler */
#define TIMER_CHCTL1_CH3CAPFLT BITS(12,15) /*!< channel 3 input capture filter control */
/* TIMER_CHCTL2 */
#define TIMER_CHCTL2_CH0EN BIT(0) /*!< channel 0 capture/compare function enable */
#define TIMER_CHCTL2_CH0P BIT(1) /*!< channel 0 capture/compare function polarity */
#define TIMER_CHCTL2_CH0NEN BIT(2) /*!< channel 0 complementary output enable */
#define TIMER_CHCTL2_CH0NP BIT(3) /*!< channel 0 complementary output polarity */
#define TIMER_CHCTL2_CH1EN BIT(4) /*!< channel 1 capture/compare function enable */
#define TIMER_CHCTL2_CH1P BIT(5) /*!< channel 1 capture/compare function polarity */
#define TIMER_CHCTL2_CH1NEN BIT(6) /*!< channel 1 complementary output enable */
#define TIMER_CHCTL2_CH1NP BIT(7) /*!< channel 1 complementary output polarity */
#define TIMER_CHCTL2_CH2EN BIT(8) /*!< channel 2 capture/compare function enable */
#define TIMER_CHCTL2_CH2P BIT(9) /*!< channel 2 capture/compare function polarity */
#define TIMER_CHCTL2_CH2NEN BIT(10) /*!< channel 2 complementary output enable */
#define TIMER_CHCTL2_CH2NP BIT(11) /*!< channel 2 complementary output polarity */
#define TIMER_CHCTL2_CH3EN BIT(12) /*!< channel 3 capture/compare function enable */
#define TIMER_CHCTL2_CH3P BIT(13) /*!< channel 3 capture/compare function polarity */
/* TIMER_CNT */
#define TIMER_CNT_CNT BITS(0,15) /*!< 16 bit timer counter */
/* TIMER_PSC */
#define TIMER_PSC_PSC BITS(0,15) /*!< prescaler value of the counter clock */
/* TIMER_CAR */
#define TIMER_CAR_CARL BITS(0,15) /*!< 16 bit counter auto reload value */
/* TIMER_CREP */
#define TIMER_CREP_CREP BITS(0,7) /*!< counter repetition value */
/* TIMER_CH0CV */
#define TIMER_CH0CV_CH0VAL BITS(0,15) /*!< 16 bit capture/compare value of channel 0 */
/* TIMER_CH1CV */
#define TIMER_CH1CV_CH1VAL BITS(0,15) /*!< 16 bit capture/compare value of channel 1 */
/* TIMER_CH2CV */
#define TIMER_CH2CV_CH2VAL BITS(0,15) /*!< 16 bit capture/compare value of channel 2 */
/* TIMER_CH3CV */
#define TIMER_CH3CV_CH3VAL BITS(0,15) /*!< 16 bit capture/compare value of channel 3 */
/* TIMER_CCHP */
#define TIMER_CCHP_DTCFG BITS(0,7) /*!< dead time configure */
#define TIMER_CCHP_PROT BITS(8,9) /*!< complementary register protect control */
#define TIMER_CCHP_IOS BIT(10) /*!< idle mode off-state configure */
#define TIMER_CCHP_ROS BIT(11) /*!< run mode off-state configure */
#define TIMER_CCHP_BRKEN BIT(12) /*!< break enable */
#define TIMER_CCHP_BRKP BIT(13) /*!< break polarity */
#define TIMER_CCHP_OAEN BIT(14) /*!< output automatic enable */
#define TIMER_CCHP_POEN BIT(15) /*!< primary output enable */
/* TIMER_DMACFG */
#define TIMER_DMACFG_DMATA BITS(0,4) /*!< DMA transfer access start address */
#define TIMER_DMACFG_DMATC BITS(8,12) /*!< DMA transfer count */
/* TIMER_DMATB */
#define TIMER_DMATB_DMATB BITS(0,15) /*!< DMA transfer buffer address */
/* constants definitions */
/* TIMER init parameter struct definitions */
typedef struct {
uint16_t prescaler; /*!< prescaler value */
uint16_t alignedmode; /*!< aligned mode */
uint16_t counterdirection; /*!< counter direction */
uint32_t period; /*!< period value */
uint16_t clockdivision; /*!< clock division value */
uint8_t repetitioncounter; /*!< the counter repetition value */
} timer_parameter_struct;
/* break parameter struct definitions */
typedef struct {
uint16_t runoffstate; /*!< run mode off-state */
uint16_t ideloffstate; /*!< idle mode off-state */
uint16_t deadtime; /*!< dead time */
uint16_t breakpolarity; /*!< break polarity */
uint16_t outputautostate; /*!< output automatic enable */
uint16_t protectmode; /*!< complementary register protect control */
uint16_t breakstate; /*!< break enable */
} timer_break_parameter_struct;
/* channel output parameter struct definitions */
typedef struct {
uint16_t outputstate; /*!< channel output state */
uint16_t outputnstate; /*!< channel complementary output state */
uint16_t ocpolarity; /*!< channel output polarity */
uint16_t ocnpolarity; /*!< channel complementary output polarity */
uint16_t ocidlestate; /*!< idle state of channel output */
uint16_t ocnidlestate; /*!< idle state of channel complementary output */
} timer_oc_parameter_struct;
/* channel input parameter struct definitions */
typedef struct {
uint16_t icpolarity; /*!< channel input polarity */
uint16_t icselection; /*!< channel input mode selection */
uint16_t icprescaler; /*!< channel input capture prescaler */
uint16_t icfilter; /*!< channel input capture filter control */
} timer_ic_parameter_struct;
/* TIMER interrupt enable or disable */
#define TIMER_INT_UP TIMER_DMAINTEN_UPIE /*!< update interrupt */
#define TIMER_INT_CH0 TIMER_DMAINTEN_CH0IE /*!< channel 0 interrupt */
#define TIMER_INT_CH1 TIMER_DMAINTEN_CH1IE /*!< channel 1 interrupt */
#define TIMER_INT_CH2 TIMER_DMAINTEN_CH2IE /*!< channel 2 interrupt */
#define TIMER_INT_CH3 TIMER_DMAINTEN_CH3IE /*!< channel 3 interrupt */
#define TIMER_INT_CMT TIMER_DMAINTEN_CMTIE /*!< channel commutation interrupt flag */
#define TIMER_INT_TRG TIMER_DMAINTEN_TRGIE /*!< trigger interrupt */
#define TIMER_INT_BRK TIMER_DMAINTEN_BRKIE /*!< break interrupt */
/* TIMER interrupt flag */
#define TIMER_INT_FLAG_UP TIMER_INT_UP /*!< update interrupt */
#define TIMER_INT_FLAG_CH0 TIMER_INT_CH0 /*!< channel 0 interrupt */
#define TIMER_INT_FLAG_CH1 TIMER_INT_CH1 /*!< channel 1 interrupt */
#define TIMER_INT_FLAG_CH2 TIMER_INT_CH2 /*!< channel 2 interrupt */
#define TIMER_INT_FLAG_CH3 TIMER_INT_CH3 /*!< channel 3 interrupt */
#define TIMER_INT_FLAG_CMT TIMER_INT_CMT /*!< channel commutation interrupt flag */
#define TIMER_INT_FLAG_TRG TIMER_INT_TRG /*!< trigger interrupt */
#define TIMER_INT_FLAG_BRK TIMER_INT_BRK
/* TIMER flag */
#define TIMER_FLAG_UP TIMER_INTF_UPIF /*!< update flag */
#define TIMER_FLAG_CH0 TIMER_INTF_CH0IF /*!< channel 0 flag */
#define TIMER_FLAG_CH1 TIMER_INTF_CH1IF /*!< channel 1 flag */
#define TIMER_FLAG_CH2 TIMER_INTF_CH2IF /*!< channel 2 flag */
#define TIMER_FLAG_CH3 TIMER_INTF_CH3IF /*!< channel 3 flag */
#define TIMER_FLAG_CMT TIMER_INTF_CMTIF /*!< channel control update flag */
#define TIMER_FLAG_TRG TIMER_INTF_TRGIF /*!< trigger flag */
#define TIMER_FLAG_BRK TIMER_INTF_BRKIF /*!< break flag */
#define TIMER_FLAG_CH0O TIMER_INTF_CH0OF /*!< channel 0 overcapture flag */
#define TIMER_FLAG_CH1O TIMER_INTF_CH1OF /*!< channel 1 overcapture flag */
#define TIMER_FLAG_CH2O TIMER_INTF_CH2OF /*!< channel 2 overcapture flag */
#define TIMER_FLAG_CH3O TIMER_INTF_CH3OF /*!< channel 3 overcapture flag */
/* TIMER DMA source enable */
#define TIMER_DMA_UPD ((uint16_t)TIMER_DMAINTEN_UPDEN) /*!< update DMA enable */
#define TIMER_DMA_CH0D ((uint16_t)TIMER_DMAINTEN_CH0DEN) /*!< channel 0 DMA enable */
#define TIMER_DMA_CH1D ((uint16_t)TIMER_DMAINTEN_CH1DEN) /*!< channel 1 DMA enable */
#define TIMER_DMA_CH2D ((uint16_t)TIMER_DMAINTEN_CH2DEN) /*!< channel 2 DMA enable */
#define TIMER_DMA_CH3D ((uint16_t)TIMER_DMAINTEN_CH3DEN) /*!< channel 3 DMA enable */
#define TIMER_DMA_CMTD ((uint16_t)TIMER_DMAINTEN_CMTDEN) /*!< commutation DMA request enable */
#define TIMER_DMA_TRGD ((uint16_t)TIMER_DMAINTEN_TRGDEN) /*!< trigger DMA enable */
/* channel DMA request source selection */
#define TIMER_DMAREQUEST_UPDATEEVENT TIMER_CTL1_DMAS /*!< DMA request of channel n is sent when update event occurs */
#define TIMER_DMAREQUEST_CHANNELEVENT ((uint32_t)0x00000000U) /*!< DMA request of channel n is sent when channel n event occurs */
/* DMA access base address */
#define DMACFG_DMATA(regval) (BITS(0, 4) & ((uint32_t)(regval) << 0U))
#define TIMER_DMACFG_DMATA_CTL0 DMACFG_DMATA(0) /*!< DMA transfer address is TIMER_CTL0 */
#define TIMER_DMACFG_DMATA_CTL1 DMACFG_DMATA(1) /*!< DMA transfer address is TIMER_CTL1 */
#define TIMER_DMACFG_DMATA_SMCFG DMACFG_DMATA(2) /*!< DMA transfer address is TIMER_SMCFG */
#define TIMER_DMACFG_DMATA_DMAINTEN DMACFG_DMATA(3) /*!< DMA transfer address is TIMER_DMAINTEN */
#define TIMER_DMACFG_DMATA_INTF DMACFG_DMATA(4) /*!< DMA transfer address is TIMER_INTF */
#define TIMER_DMACFG_DMATA_SWEVG DMACFG_DMATA(5) /*!< DMA transfer address is TIMER_SWEVG */
#define TIMER_DMACFG_DMATA_CHCTL0 DMACFG_DMATA(6) /*!< DMA transfer address is TIMER_CHCTL0 */
#define TIMER_DMACFG_DMATA_CHCTL1 DMACFG_DMATA(7) /*!< DMA transfer address is TIMER_CHCTL1 */
#define TIMER_DMACFG_DMATA_CHCTL2 DMACFG_DMATA(8) /*!< DMA transfer address is TIMER_CHCTL2 */
#define TIMER_DMACFG_DMATA_CNT DMACFG_DMATA(9) /*!< DMA transfer address is TIMER_CNT */
#define TIMER_DMACFG_DMATA_PSC DMACFG_DMATA(10) /*!< DMA transfer address is TIMER_PSC */
#define TIMER_DMACFG_DMATA_CAR DMACFG_DMATA(11) /*!< DMA transfer address is TIMER_CAR */
#define TIMER_DMACFG_DMATA_CREP DMACFG_DMATA(12) /*!< DMA transfer address is TIMER_CREP */
#define TIMER_DMACFG_DMATA_CH0CV DMACFG_DMATA(13) /*!< DMA transfer address is TIMER_CH0CV */
#define TIMER_DMACFG_DMATA_CH1CV DMACFG_DMATA(14) /*!< DMA transfer address is TIMER_CH1CV */
#define TIMER_DMACFG_DMATA_CH2CV DMACFG_DMATA(15) /*!< DMA transfer address is TIMER_CH2CV */
#define TIMER_DMACFG_DMATA_CH3CV DMACFG_DMATA(16) /*!< DMA transfer address is TIMER_CH3CV */
#define TIMER_DMACFG_DMATA_CCHP DMACFG_DMATA(17) /*!< DMA transfer address is TIMER_CCHP */
#define TIMER_DMACFG_DMATA_DMACFG DMACFG_DMATA(18) /*!< DMA transfer address is TIMER_DMACFG */
/* DMA access burst length */
#define DMACFG_DMATC(regval) (BITS(8, 12) & ((uint32_t)(regval) << 8U))
#define TIMER_DMACFG_DMATC_1TRANSFER DMACFG_DMATC(0) /*!< DMA transfer 1 time */
#define TIMER_DMACFG_DMATC_2TRANSFER DMACFG_DMATC(1) /*!< DMA transfer 2 times */
#define TIMER_DMACFG_DMATC_3TRANSFER DMACFG_DMATC(2) /*!< DMA transfer 3 times */
#define TIMER_DMACFG_DMATC_4TRANSFER DMACFG_DMATC(3) /*!< DMA transfer 4 times */
#define TIMER_DMACFG_DMATC_5TRANSFER DMACFG_DMATC(4) /*!< DMA transfer 5 times */
#define TIMER_DMACFG_DMATC_6TRANSFER DMACFG_DMATC(5) /*!< DMA transfer 6 times */
#define TIMER_DMACFG_DMATC_7TRANSFER DMACFG_DMATC(6) /*!< DMA transfer 7 times */
#define TIMER_DMACFG_DMATC_8TRANSFER DMACFG_DMATC(7) /*!< DMA transfer 8 times */
#define TIMER_DMACFG_DMATC_9TRANSFER DMACFG_DMATC(8) /*!< DMA transfer 9 times */
#define TIMER_DMACFG_DMATC_10TRANSFER DMACFG_DMATC(9) /*!< DMA transfer 10 times */
#define TIMER_DMACFG_DMATC_11TRANSFER DMACFG_DMATC(10) /*!< DMA transfer 11 times */
#define TIMER_DMACFG_DMATC_12TRANSFER DMACFG_DMATC(11) /*!< DMA transfer 12 times */
#define TIMER_DMACFG_DMATC_13TRANSFER DMACFG_DMATC(12) /*!< DMA transfer 13 times */
#define TIMER_DMACFG_DMATC_14TRANSFER DMACFG_DMATC(13) /*!< DMA transfer 14 times */
#define TIMER_DMACFG_DMATC_15TRANSFER DMACFG_DMATC(14) /*!< DMA transfer 15 times */
#define TIMER_DMACFG_DMATC_16TRANSFER DMACFG_DMATC(15) /*!< DMA transfer 16 times */
#define TIMER_DMACFG_DMATC_17TRANSFER DMACFG_DMATC(16) /*!< DMA transfer 17 times */
#define TIMER_DMACFG_DMATC_18TRANSFER DMACFG_DMATC(17) /*!< DMA transfer 18 times */
/* TIMER software event generation source */
#define TIMER_EVENT_SRC_UPG ((uint16_t)0x0001U) /*!< update event generation */
#define TIMER_EVENT_SRC_CH0G ((uint16_t)0x0002U) /*!< channel 0 capture or compare event generation */
#define TIMER_EVENT_SRC_CH1G ((uint16_t)0x0004U) /*!< channel 1 capture or compare event generation */
#define TIMER_EVENT_SRC_CH2G ((uint16_t)0x0008U) /*!< channel 2 capture or compare event generation */
#define TIMER_EVENT_SRC_CH3G ((uint16_t)0x0010U) /*!< channel 3 capture or compare event generation */
#define TIMER_EVENT_SRC_CMTG ((uint16_t)0x0020U) /*!< channel commutation event generation */
#define TIMER_EVENT_SRC_TRGG ((uint16_t)0x0040U) /*!< trigger event generation */
#define TIMER_EVENT_SRC_BRKG ((uint16_t)0x0080U) /*!< break event generation */
/* center-aligned mode selection */
#define CTL0_CAM(regval) ((uint16_t)(BITS(5, 6) & ((uint32_t)(regval) << 5U)))
#define TIMER_COUNTER_EDGE CTL0_CAM(0) /*!< edge-aligned mode */
#define TIMER_COUNTER_CENTER_DOWN CTL0_CAM(1) /*!< center-aligned and counting down assert mode */
#define TIMER_COUNTER_CENTER_UP CTL0_CAM(2) /*!< center-aligned and counting up assert mode */
#define TIMER_COUNTER_CENTER_BOTH CTL0_CAM(3) /*!< center-aligned and counting up/down assert mode */
/* TIMER prescaler reload mode */
#define TIMER_PSC_RELOAD_NOW TIMER_SWEVG_UPG /*!< the prescaler is loaded right now */
#define TIMER_PSC_RELOAD_UPDATE ((uint32_t)0x00000000U) /*!< the prescaler is loaded at the next update event */
/* count direction */
#define TIMER_COUNTER_UP ((uint16_t)0x0000U) /*!< counter up direction */
#define TIMER_COUNTER_DOWN ((uint16_t)TIMER_CTL0_DIR) /*!< counter down direction */
/* specify division ratio between TIMER clock and dead-time and sampling clock */
#define CTL0_CKDIV(regval) ((uint16_t)(BITS(8, 9) & ((uint32_t)(regval) << 8U)))
#define TIMER_CKDIV_DIV1 CTL0_CKDIV(0) /*!< clock division value is 1,fDTS=fTIMER_CK */
#define TIMER_CKDIV_DIV2 CTL0_CKDIV(1) /*!< clock division value is 2,fDTS= fTIMER_CK/2 */
#define TIMER_CKDIV_DIV4 CTL0_CKDIV(2) /*!< clock division value is 4, fDTS= fTIMER_CK/4 */
/* single pulse mode */
#define TIMER_SP_MODE_SINGLE TIMER_CTL0_SPM /*!< single pulse mode */
#define TIMER_SP_MODE_REPETITIVE ((uint32_t)0x00000000U) /*!< repetitive pulse mode */
/* update source */
#define TIMER_UPDATE_SRC_REGULAR TIMER_CTL0_UPS /*!< update generate only by counter overflow/underflow */
#define TIMER_UPDATE_SRC_GLOBAL ((uint32_t)0x00000000U) /*!< update generate by setting of UPG bit or the counter overflow/underflow,or the slave mode controller trigger */
/* run mode off-state configure */
#define TIMER_ROS_STATE_ENABLE ((uint16_t)TIMER_CCHP_ROS) /*!< when POEN bit is set, the channel output signals(CHx_O/CHx_ON) are enabled, with relationship to CHxEN/CHxNEN bits */
#define TIMER_ROS_STATE_DISABLE ((uint16_t)0x0000U) /*!< when POEN bit is set, the channel output signals(CHx_O/CHx_ON) are disabled */
/* idle mode off-state configure */
#define TIMER_IOS_STATE_ENABLE ((uint16_t)TIMER_CCHP_IOS) /*!< when POEN bit is reset, he channel output signals(CHx_O/CHx_ON) are enabled, with relationship to CHxEN/CHxNEN bits */
#define TIMER_IOS_STATE_DISABLE ((uint16_t)0x0000U) /*!< when POEN bit is reset, the channel output signals(CHx_O/CHx_ON) are disabled */
/* break input polarity */
#define TIMER_BREAK_POLARITY_LOW ((uint16_t)0x0000U) /*!< break input polarity is low */
#define TIMER_BREAK_POLARITY_HIGH ((uint16_t)TIMER_CCHP_BRKP) /*!< break input polarity is high */
/* output automatic enable */
#define TIMER_OUTAUTO_ENABLE ((uint16_t)TIMER_CCHP_OAEN) /*!< output automatic enable */
#define TIMER_OUTAUTO_DISABLE ((uint16_t)0x0000U) /*!< output automatic disable */
/* complementary register protect control */
#define CCHP_PROT(regval) ((uint16_t)(BITS(8, 9) & ((uint32_t)(regval) << 8U)))
#define TIMER_CCHP_PROT_OFF CCHP_PROT(0) /*!< protect disable */
#define TIMER_CCHP_PROT_0 CCHP_PROT(1) /*!< PROT mode 0 */
#define TIMER_CCHP_PROT_1 CCHP_PROT(2) /*!< PROT mode 1 */
#define TIMER_CCHP_PROT_2 CCHP_PROT(3) /*!< PROT mode 2 */
/* break input enable */
#define TIMER_BREAK_ENABLE ((uint16_t)TIMER_CCHP_BRKEN) /*!< break input enable */
#define TIMER_BREAK_DISABLE ((uint16_t)0x0000U) /*!< break input disable */
/* TIMER channel n(n=0,1,2,3) */
#define TIMER_CH_0 ((uint16_t)0x0000U) /*!< TIMER channel 0(TIMERx(x=0..4)) */
#define TIMER_CH_1 ((uint16_t)0x0001U) /*!< TIMER channel 1(TIMERx(x=0..4)) */
#define TIMER_CH_2 ((uint16_t)0x0002U) /*!< TIMER channel 2(TIMERx(x=0..4)) */
#define TIMER_CH_3 ((uint16_t)0x0003U) /*!< TIMER channel 3(TIMERx(x=0..4)) */
/* channel enable state */
#define TIMER_CCX_ENABLE ((uint16_t)0x0001U) /*!< channel enable */
#define TIMER_CCX_DISABLE ((uint16_t)0x0000U) /*!< channel disable */
/* channel complementary output enable state */
#define TIMER_CCXN_ENABLE ((uint16_t)0x0004U) /*!< channel complementary enable */
#define TIMER_CCXN_DISABLE ((uint16_t)0x0000U) /*!< channel complementary disable */
/* channel output polarity */
#define TIMER_OC_POLARITY_HIGH ((uint16_t)0x0000U) /*!< channel output polarity is high */
#define TIMER_OC_POLARITY_LOW ((uint16_t)0x0002U) /*!< channel output polarity is low */
/* channel complementary output polarity */
#define TIMER_OCN_POLARITY_HIGH ((uint16_t)0x0000U) /*!< channel complementary output polarity is high */
#define TIMER_OCN_POLARITY_LOW ((uint16_t)0x0008U) /*!< channel complementary output polarity is low */
/* idle state of channel output */
#define TIMER_OC_IDLE_STATE_HIGH ((uint16_t)0x0100) /*!< idle state of channel output is high */
#define TIMER_OC_IDLE_STATE_LOW ((uint16_t)0x0000) /*!< idle state of channel output is low */
/* idle state of channel complementary output */
#define TIMER_OCN_IDLE_STATE_HIGH ((uint16_t)0x0200U) /*!< idle state of channel complementary output is high */
#define TIMER_OCN_IDLE_STATE_LOW ((uint16_t)0x0000U) /*!< idle state of channel complementary output is low */
/* channel output compare mode */
#define TIMER_OC_MODE_TIMING ((uint16_t)0x0000U) /*!< timing mode */
#define TIMER_OC_MODE_ACTIVE ((uint16_t)0x0010U) /*!< active mode */
#define TIMER_OC_MODE_INACTIVE ((uint16_t)0x0020U) /*!< inactive mode */
#define TIMER_OC_MODE_TOGGLE ((uint16_t)0x0030U) /*!< toggle mode */
#define TIMER_OC_MODE_LOW ((uint16_t)0x0040U) /*!< force low mode */
#define TIMER_OC_MODE_HIGH ((uint16_t)0x0050U) /*!< force high mode */
#define TIMER_OC_MODE_PWM0 ((uint16_t)0x0060U) /*!< PWM0 mode */
#define TIMER_OC_MODE_PWM1 ((uint16_t)0x0070U) /*!< PWM1 mode */
/* channel output compare shadow enable */
#define TIMER_OC_SHADOW_ENABLE ((uint16_t)0x0008U) /*!< channel output shadow state enable */
#define TIMER_OC_SHADOW_DISABLE ((uint16_t)0x0000U) /*!< channel output shadow state disable */
/* channel output compare fast enable */
#define TIMER_OC_FAST_ENABLE ((uint16_t)0x0004) /*!< channel output fast function enable */
#define TIMER_OC_FAST_DISABLE ((uint16_t)0x0000) /*!< channel output fast function disable */
/* channel output compare clear enable */
#define TIMER_OC_CLEAR_ENABLE ((uint16_t)0x0080U) /*!< channel output clear function enable */
#define TIMER_OC_CLEAR_DISABLE ((uint16_t)0x0000U) /*!< channel output clear function disable */
/* channel control shadow register update control */
#define TIMER_UPDATECTL_CCU ((uint32_t)0x00000000U) /*!< the shadow registers update by when CMTG bit is set */
#define TIMER_UPDATECTL_CCUTRI TIMER_CTL1_CCUC /*!< the shadow registers update by when CMTG bit is set or an rising edge of TRGI occurs */
/* channel input capture polarity */
#define TIMER_IC_POLARITY_RISING ((uint16_t)0x0000U) /*!< input capture rising edge */
#define TIMER_IC_POLARITY_FALLING ((uint16_t)0x0002U) /*!< input capture falling edge */
#define TIMER_IC_POLARITY_BOTH_EDGE ((uint16_t)0x000AU) /*!< input capture both edge */
/* TIMER input capture selection */
#define TIMER_IC_SELECTION_DIRECTTI ((uint16_t)0x0001U) /*!< channel n is configured as input and icy is mapped on CIy */
#define TIMER_IC_SELECTION_INDIRECTTI ((uint16_t)0x0002U) /*!< channel n is configured as input and icy is mapped on opposite input */
#define TIMER_IC_SELECTION_ITS ((uint16_t)0x0003U) /*!< channel n is configured as input and icy is mapped on ITS */
/* channel input capture prescaler */
#define TIMER_IC_PSC_DIV1 ((uint16_t)0x0000U) /*!< no prescaler */
#define TIMER_IC_PSC_DIV2 ((uint16_t)0x0004U) /*!< divided by 2 */
#define TIMER_IC_PSC_DIV4 ((uint16_t)0x0008U) /*!< divided by 4 */
#define TIMER_IC_PSC_DIV8 ((uint16_t)0x000CU) /*!< divided by 8 */
/* trigger selection */
#define SMCFG_TRGSEL(regval) (BITS(4, 6) & ((uint32_t)(regval) << 4U))
#define TIMER_SMCFG_TRGSEL_ITI0 SMCFG_TRGSEL(0) /*!< internal trigger 0 */
#define TIMER_SMCFG_TRGSEL_ITI1 SMCFG_TRGSEL(1) /*!< internal trigger 1 */
#define TIMER_SMCFG_TRGSEL_ITI2 SMCFG_TRGSEL(2) /*!< internal trigger 2 */
#define TIMER_SMCFG_TRGSEL_ITI3 SMCFG_TRGSEL(3) /*!< internal trigger 3 */
#define TIMER_SMCFG_TRGSEL_CI0F_ED SMCFG_TRGSEL(4) /*!< TI0 Edge Detector */
#define TIMER_SMCFG_TRGSEL_CI0FE0 SMCFG_TRGSEL(5) /*!< filtered TIMER input 0 */
#define TIMER_SMCFG_TRGSEL_CI1FE1 SMCFG_TRGSEL(6) /*!< filtered TIMER input 1 */
#define TIMER_SMCFG_TRGSEL_ETIFP SMCFG_TRGSEL(7) /*!< filtered external trigger input */
/* master mode control */
#define CTL1_MMC(regval) (BITS(4, 6) & ((uint32_t)(regval) << 4U))
#define TIMER_TRI_OUT_SRC_RESET CTL1_MMC(0) /*!< the UPG bit as trigger output */
#define TIMER_TRI_OUT_SRC_ENABLE CTL1_MMC(1) /*!< the counter enable signal TIMER_CTL0_CEN as trigger output */
#define TIMER_TRI_OUT_SRC_UPDATE CTL1_MMC(2) /*!< update event as trigger output */
#define TIMER_TRI_OUT_SRC_CH0 CTL1_MMC(3) /*!< a capture or a compare match occurred in channel 0 as trigger output TRGO */
#define TIMER_TRI_OUT_SRC_O0CPRE CTL1_MMC(4) /*!< O0CPRE as trigger output */
#define TIMER_TRI_OUT_SRC_O1CPRE CTL1_MMC(5) /*!< O1CPRE as trigger output */
#define TIMER_TRI_OUT_SRC_O2CPRE CTL1_MMC(6) /*!< O2CPRE as trigger output */
#define TIMER_TRI_OUT_SRC_O3CPRE CTL1_MMC(7) /*!< O3CPRE as trigger output */
/* slave mode control */
#define SMCFG_SMC(regval) (BITS(0, 2) & ((uint32_t)(regval) << 0U))
#define TIMER_SLAVE_MODE_DISABLE SMCFG_SMC(0) /*!< slave mode disable */
#define TIMER_ENCODER_MODE0 SMCFG_SMC(1) /*!< encoder mode 0 */
#define TIMER_ENCODER_MODE1 SMCFG_SMC(2) /*!< encoder mode 1 */
#define TIMER_ENCODER_MODE2 SMCFG_SMC(3) /*!< encoder mode 2 */
#define TIMER_SLAVE_MODE_RESTART SMCFG_SMC(4) /*!< restart mode */
#define TIMER_SLAVE_MODE_PAUSE SMCFG_SMC(5) /*!< pause mode */
#define TIMER_SLAVE_MODE_EVENT SMCFG_SMC(6) /*!< event mode */
#define TIMER_SLAVE_MODE_EXTERNAL0 SMCFG_SMC(7) /*!< external clock mode 0 */
/* master slave mode selection */
#define TIMER_MASTER_SLAVE_MODE_ENABLE TIMER_SMCFG_MSM /*!< master slave mode enable */
#define TIMER_MASTER_SLAVE_MODE_DISABLE ((uint32_t)0x00000000U) /*!< master slave mode disable */
/* external trigger prescaler */
#define SMCFG_ETPSC(regval) (BITS(12, 13) & ((uint32_t)(regval) << 12U))
#define TIMER_EXT_TRI_PSC_OFF SMCFG_ETPSC(0) /*!< no divided */
#define TIMER_EXT_TRI_PSC_DIV2 SMCFG_ETPSC(1) /*!< divided by 2 */
#define TIMER_EXT_TRI_PSC_DIV4 SMCFG_ETPSC(2) /*!< divided by 4 */
#define TIMER_EXT_TRI_PSC_DIV8 SMCFG_ETPSC(3) /*!< divided by 8 */
/* external trigger polarity */
#define TIMER_ETP_FALLING TIMER_SMCFG_ETP /*!< active low or falling edge active */
#define TIMER_ETP_RISING ((uint32_t)0x00000000U) /*!< active high or rising edge active */
/* channel 0 trigger input selection */
#define TIMER_HALLINTERFACE_ENABLE TIMER_CTL1_TI0S /*!< TIMER hall sensor mode enable */
#define TIMER_HALLINTERFACE_DISABLE ((uint32_t)0x00000000U) /*!< TIMER hall sensor mode disable */
/* TIMERx(x=0..4) write CHxVAL register selection */
#define TIMER_CHVSEL_ENABLE ((uint16_t)TIMER_CFG_OUTSEL) /*!< write CHxVAL register selection enable */
#define TIMER_CHVSEL_DISABLE ((uint16_t)0x0000U) /*!< write CHxVAL register selection disable */
/* function declarations */
/* TIMER timebase */
/* deinit a timer */
void timer_deinit(uint32_t timer_periph);
/* initialize TIMER init parameter struct */
void timer_struct_para_init(timer_parameter_struct* initpara);
/* initialize TIMER counter */
void timer_init(uint32_t timer_periph, timer_parameter_struct* initpara);
/* enable a timer */
void timer_enable(uint32_t timer_periph);
/* disable a timer */
void timer_disable(uint32_t timer_periph);
/* enable the auto reload shadow function */
void timer_auto_reload_shadow_enable(uint32_t timer_periph);
/* disable the auto reload shadow function */
void timer_auto_reload_shadow_disable(uint32_t timer_periph);
/* enable the update event */
void timer_update_event_enable(uint32_t timer_periph);
/* disable the update event */
void timer_update_event_disable(uint32_t timer_periph);
/* set TIMER counter alignment mode */
void timer_counter_alignment(uint32_t timer_periph, uint16_t aligned);
/* set TIMER counter up direction */
void timer_counter_up_direction(uint32_t timer_periph);
/* set TIMER counter down direction */
void timer_counter_down_direction(uint32_t timer_periph);
/* configure TIMER prescaler */
void timer_prescaler_config(uint32_t timer_periph, uint16_t prescaler, uint32_t pscreload);
/* configure TIMER repetition register value */
void timer_repetition_value_config(uint32_t timer_periph, uint16_t repetition);
/* configure TIMER autoreload register value */
void timer_autoreload_value_config(uint32_t timer_periph, uint16_t autoreload);
/* configure TIMER counter register value */
void timer_counter_value_config(uint32_t timer_periph, uint16_t counter);
/* read TIMER counter value */
uint32_t timer_counter_read(uint32_t timer_periph);
/* read TIMER prescaler value */
uint16_t timer_prescaler_read(uint32_t timer_periph);
/* configure TIMER single pulse mode */
void timer_single_pulse_mode_config(uint32_t timer_periph, uint32_t spmode);
/* configure TIMER update source */
void timer_update_source_config(uint32_t timer_periph, uint32_t update);
/* TIMER DMA and event */
/* enable the TIMER DMA */
void timer_dma_enable(uint32_t timer_periph, uint16_t dma);
/* disable the TIMER DMA */
void timer_dma_disable(uint32_t timer_periph, uint16_t dma);
/* channel DMA request source selection */
void timer_channel_dma_request_source_select(uint32_t timer_periph, uint32_t dma_request);
/* configure the TIMER DMA transfer */
void timer_dma_transfer_config(uint32_t timer_periph, uint32_t dma_baseaddr, uint32_t dma_lenth);
/* software generate events */
void timer_event_software_generate(uint32_t timer_periph, uint16_t event);
/* TIMER channel complementary protection */
/* initialize TIMER break parameter struct */
void timer_break_struct_para_init(timer_break_parameter_struct* breakpara);
/* configure TIMER break function */
void timer_break_config(uint32_t timer_periph, timer_break_parameter_struct* breakpara);
/* enable TIMER break function */
void timer_break_enable(uint32_t timer_periph);
/* disable TIMER break function */
void timer_break_disable(uint32_t timer_periph);
/* enable TIMER output automatic function */
void timer_automatic_output_enable(uint32_t timer_periph);
/* disable TIMER output automatic function */
void timer_automatic_output_disable(uint32_t timer_periph);
/* enable or disable TIMER primary output function */
void timer_primary_output_config(uint32_t timer_periph, ControlStatus newvalue);
/* enable or disable channel capture/compare control shadow register */
void timer_channel_control_shadow_config(uint32_t timer_periph, ControlStatus newvalue);
/* configure TIMER channel control shadow register update control */
void timer_channel_control_shadow_update_config(uint32_t timer_periph, uint32_t ccuctl);
/* TIMER channel output */
/* initialize TIMER channel output parameter struct */
void timer_channel_output_struct_para_init(timer_oc_parameter_struct* ocpara);
/* configure TIMER channel output function */
void timer_channel_output_config(uint32_t timer_periph, uint16_t channel, timer_oc_parameter_struct* ocpara);
/* configure TIMER channel output compare mode */
void timer_channel_output_mode_config(uint32_t timer_periph, uint16_t channel, uint16_t ocmode);
/* configure TIMER channel output pulse value */
void timer_channel_output_pulse_value_config(uint32_t timer_periph, uint16_t channel, uint32_t pulse);
/* configure TIMER channel output shadow function */
void timer_channel_output_shadow_config(uint32_t timer_periph, uint16_t channel, uint16_t ocshadow);
/* configure TIMER channel output fast function */
void timer_channel_output_fast_config(uint32_t timer_periph, uint16_t channel, uint16_t ocfast);
/* configure TIMER channel output clear function */
void timer_channel_output_clear_config(uint32_t timer_periph, uint16_t channel, uint16_t occlear);
/* configure TIMER channel output polarity */
void timer_channel_output_polarity_config(uint32_t timer_periph, uint16_t channel, uint16_t ocpolarity);
/* configure TIMER channel complementary output polarity */
void timer_channel_complementary_output_polarity_config(uint32_t timer_periph, uint16_t channel, uint16_t ocnpolarity);
/* configure TIMER channel enable state */
void timer_channel_output_state_config(uint32_t timer_periph, uint16_t channel, uint32_t state);
/* configure TIMER channel complementary output enable state */
void timer_channel_complementary_output_state_config(uint32_t timer_periph, uint16_t channel, uint16_t ocnstate);
/* TIMER channel input */
/* initialize TIMER channel input parameter struct */
void timer_channel_input_struct_para_init(timer_ic_parameter_struct* icpara);
/* configure TIMER input capture parameter */
void timer_input_capture_config(uint32_t timer_periph, uint16_t channel, timer_ic_parameter_struct* icpara);
/* configure TIMER channel input capture prescaler value */
void timer_channel_input_capture_prescaler_config(uint32_t timer_periph, uint16_t channel, uint16_t prescaler);
/* read TIMER channel capture compare register value */
uint32_t timer_channel_capture_value_register_read(uint32_t timer_periph, uint16_t channel);
/* configure TIMER input pwm capture function */
void timer_input_pwm_capture_config(uint32_t timer_periph, uint16_t channel, timer_ic_parameter_struct* icpwm);
/* configure TIMER hall sensor mode */
void timer_hall_mode_config(uint32_t timer_periph, uint32_t hallmode);
/* TIMER master and slave mode */
/* select TIMER input trigger source */
void timer_input_trigger_source_select(uint32_t timer_periph, uint32_t intrigger);
/* select TIMER master mode output trigger source */
void timer_master_output_trigger_source_select(uint32_t timer_periph, uint32_t outrigger);
/* select TIMER slave mode */
void timer_slave_mode_select(uint32_t timer_periph, uint32_t slavemode);
/* configure TIMER master slave mode */
void timer_master_slave_mode_config(uint32_t timer_periph, uint32_t masterslave);
/* configure TIMER external trigger input */
void timer_external_trigger_config(uint32_t timer_periph, uint32_t extprescaler, uint32_t extpolarity, uint32_t extfilter);
/* configure TIMER quadrature decoder mode */
void timer_quadrature_decoder_mode_config(uint32_t timer_periph, uint32_t decomode, uint16_t ic0polarity, uint16_t ic1polarity);
/* configure TIMER internal clock mode */
void timer_internal_clock_config(uint32_t timer_periph);
/* configure TIMER the internal trigger as external clock input */
void timer_internal_trigger_as_external_clock_config(uint32_t timer_periph, uint32_t intrigger);
/* configure TIMER the external trigger as external clock input */
void timer_external_trigger_as_external_clock_config(uint32_t timer_periph, uint32_t extrigger, uint16_t extpolarity, uint32_t extfilter);
/* configure TIMER the external clock mode 0 */
void timer_external_clock_mode0_config(uint32_t timer_periph, uint32_t extprescaler, uint32_t extpolarity, uint32_t extfilter);
/* configure TIMER the external clock mode 1 */
void timer_external_clock_mode1_config(uint32_t timer_periph, uint32_t extprescaler, uint32_t extpolarity, uint32_t extfilter);
/* disable TIMER the external clock mode 1 */
void timer_external_clock_mode1_disable(uint32_t timer_periph);
/* TIMER interrupt and flag */
/* enable the TIMER interrupt */
void timer_interrupt_enable(uint32_t timer_periph, uint32_t interrupt);
/* disable the TIMER interrupt */
void timer_interrupt_disable(uint32_t timer_periph, uint32_t interrupt);
/* get TIMER interrupt flag */
FlagStatus timer_interrupt_flag_get(uint32_t timer_periph, uint32_t interrupt);
/* clear TIMER interrupt flag */
void timer_interrupt_flag_clear(uint32_t timer_periph, uint32_t interrupt);
/* get TIMER flag */
FlagStatus timer_flag_get(uint32_t timer_periph, uint32_t flag);
/* clear TIMER flag */
void timer_flag_clear(uint32_t timer_periph, uint32_t flag);
#endif /* GD32VF103_TIMER_H */

View File

@ -0,0 +1,375 @@
/*!
\file gd32vf103_usart.h
\brief definitions for the USART
\version 2019-6-5, V1.0.0, firmware for GD32VF103
*/
/*
Copyright (c) 2018, GigaDevice Semiconductor Inc.
Redistribution and use in source and binary forms, with or without modification,
are permitted provided that the following conditions are met:
1. Redistributions of source code must retain the above copyright notice, this
list of conditions and the following disclaimer.
2. Redistributions in binary form must reproduce the above copyright notice,
this list of conditions and the following disclaimer in the documentation
and/or other materials provided with the distribution.
3. Neither the name of the copyright holder nor the names of its contributors
may be used to endorse or promote products derived from this software without
specific prior written permission.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED.
IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT,
INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT
NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY
OF SUCH DAMAGE.
*/
#ifndef GD32VF103_USART_H
#define GD32VF103_USART_H
#include "gd32vf103.h"
#include "gd32vf103_rcu.h"
// #include "gd32vf103_dbg.h"
/* USARTx(x=0,1,2)/UARTx(x=3,4) definitions */
#define USART1 USART_BASE /*!< USART1 base address */
#define USART2 (USART_BASE+(0x00000400U)) /*!< USART2 base address */
#define UART3 (USART_BASE+(0x00000800U)) /*!< UART3 base address */
#define UART4 (USART_BASE+(0x00000C00U)) /*!< UART4 base address */
#define USART0 (USART_BASE+(0x0000F400U)) /*!< USART0 base address */
/* registers definitions */
#define USART_STAT(usartx) REG32((usartx) + (0x00000000U)) /*!< USART status register */
#define USART_DATA(usartx) REG32((usartx) + (0x00000004U)) /*!< USART data register */
#define USART_BAUD(usartx) REG32((usartx) + (0x00000008U)) /*!< USART baud rate register */
#define USART_CTL0(usartx) REG32((usartx) + (0x0000000CU)) /*!< USART control register 0 */
#define USART_CTL1(usartx) REG32((usartx) + (0x00000010U)) /*!< USART control register 1 */
#define USART_CTL2(usartx) REG32((usartx) + (0x00000014U)) /*!< USART control register 2 */
#define USART_GP(usartx) REG32((usartx) + (0x00000018U)) /*!< USART guard time and prescaler register */
/* bits definitions */
/* USARTx_STAT */
#define USART_STAT_PERR BIT(0) /*!< parity error flag */
#define USART_STAT_FERR BIT(1) /*!< frame error flag */
#define USART_STAT_NERR BIT(2) /*!< noise error flag */
#define USART_STAT_ORERR BIT(3) /*!< overrun error */
#define USART_STAT_IDLEF BIT(4) /*!< IDLE frame detected flag */
#define USART_STAT_RBNE BIT(5) /*!< read data buffer not empty */
#define USART_STAT_TC BIT(6) /*!< transmission complete */
#define USART_STAT_TBE BIT(7) /*!< transmit data buffer empty */
#define USART_STAT_LBDF BIT(8) /*!< LIN break detected flag */
#define USART_STAT_CTSF BIT(9) /*!< CTS change flag */
/* USARTx_DATA */
#define USART_DATA_DATA BITS(0,8) /*!< transmit or read data value */
/* USARTx_BAUD */
#define USART_BAUD_FRADIV BITS(0,3) /*!< fraction part of baud-rate divider */
#define USART_BAUD_INTDIV BITS(4,15) /*!< integer part of baud-rate divider */
/* USARTx_CTL0 */
#define USART_CTL0_SBKCMD BIT(0) /*!< send break command */
#define USART_CTL0_RWU BIT(1) /*!< receiver wakeup from mute mode */
#define USART_CTL0_REN BIT(2) /*!< receiver enable */
#define USART_CTL0_TEN BIT(3) /*!< transmitter enable */
#define USART_CTL0_IDLEIE BIT(4) /*!< idle line detected interrupt enable */
#define USART_CTL0_RBNEIE BIT(5) /*!< read data buffer not empty interrupt and overrun error interrupt enable */
#define USART_CTL0_TCIE BIT(6) /*!< transmission complete interrupt enable */
#define USART_CTL0_TBEIE BIT(7) /*!< transmitter buffer empty interrupt enable */
#define USART_CTL0_PERRIE BIT(8) /*!< parity error interrupt enable */
#define USART_CTL0_PM BIT(9) /*!< parity mode */
#define USART_CTL0_PCEN BIT(10) /*!< parity check function enable */
#define USART_CTL0_WM BIT(11) /*!< wakeup method in mute mode */
#define USART_CTL0_WL BIT(12) /*!< word length */
#define USART_CTL0_UEN BIT(13) /*!< USART enable */
/* USARTx_CTL1 */
#define USART_CTL1_ADDR BITS(0,3) /*!< address of USART */
#define USART_CTL1_LBLEN BIT(5) /*!< LIN break frame length */
#define USART_CTL1_LBDIE BIT(6) /*!< LIN break detected interrupt eanble */
#define USART_CTL1_CLEN BIT(8) /*!< CK length */
#define USART_CTL1_CPH BIT(9) /*!< CK phase */
#define USART_CTL1_CPL BIT(10) /*!< CK polarity */
#define USART_CTL1_CKEN BIT(11) /*!< CK pin enable */
#define USART_CTL1_STB BITS(12,13) /*!< STOP bits length */
#define USART_CTL1_LMEN BIT(14) /*!< LIN mode enable */
/* USARTx_CTL2 */
#define USART_CTL2_ERRIE BIT(0) /*!< error interrupt enable */
#define USART_CTL2_IREN BIT(1) /*!< IrDA mode enable */
#define USART_CTL2_IRLP BIT(2) /*!< IrDA low-power */
#define USART_CTL2_HDEN BIT(3) /*!< half-duplex enable */
#define USART_CTL2_NKEN BIT(4) /*!< NACK enable in smartcard mode */
#define USART_CTL2_SCEN BIT(5) /*!< smartcard mode enable */
#define USART_CTL2_DENR BIT(6) /*!< DMA request enable for reception */
#define USART_CTL2_DENT BIT(7) /*!< DMA request enable for transmission */
#define USART_CTL2_RTSEN BIT(8) /*!< RTS enable */
#define USART_CTL2_CTSEN BIT(9) /*!< CTS enable */
#define USART_CTL2_CTSIE BIT(10) /*!< CTS interrupt enable */
/* USARTx_GP */
#define USART_GP_PSC BITS(0,7) /*!< prescaler value for dividing the system clock */
#define USART_GP_GUAT BITS(8,15) /*!< guard time value in smartcard mode */
/* constants definitions */
/* define the USART bit position and its register index offset */
#define USART_REGIDX_BIT(regidx, bitpos) (((uint32_t)(regidx) << 6) | (uint32_t)(bitpos))
#define USART_REG_VAL(usartx, offset) (REG32((usartx) + (((uint32_t)(offset) & (0x0000FFFFU)) >> 6)))
#define USART_BIT_POS(val) ((uint32_t)(val) & (0x0000001FU))
#define USART_REGIDX_BIT2(regidx, bitpos, regidx2, bitpos2) (((uint32_t)(regidx2) << 22) | (uint32_t)((bitpos2) << 16)\
| (((uint32_t)(regidx) << 6) | (uint32_t)(bitpos)))
#define USART_REG_VAL2(usartx, offset) (REG32((usartx) + ((uint32_t)(offset) >> 22)))
#define USART_BIT_POS2(val) (((uint32_t)(val) & (0x001F0000U)) >> 16)
/* register offset */
#define USART_STAT_REG_OFFSET (0x00000000U) /*!< STAT register offset */
#define USART_CTL0_REG_OFFSET (0x0000000CU) /*!< CTL0 register offset */
#define USART_CTL1_REG_OFFSET (0x00000010U) /*!< CTL1 register offset */
#define USART_CTL2_REG_OFFSET (0x00000014U) /*!< CTL2 register offset */
/* USART flags */
typedef enum {
/* flags in STAT register */
USART_FLAG_CTSF = USART_REGIDX_BIT(USART_STAT_REG_OFFSET, 9U), /*!< CTS change flag */
USART_FLAG_LBDF = USART_REGIDX_BIT(USART_STAT_REG_OFFSET, 8U), /*!< LIN break detected flag */
USART_FLAG_TBE = USART_REGIDX_BIT(USART_STAT_REG_OFFSET, 7U), /*!< transmit data buffer empty */
USART_FLAG_TC = USART_REGIDX_BIT(USART_STAT_REG_OFFSET, 6U), /*!< transmission complete */
USART_FLAG_RBNE = USART_REGIDX_BIT(USART_STAT_REG_OFFSET, 5U), /*!< read data buffer not empty */
USART_FLAG_IDLEF = USART_REGIDX_BIT(USART_STAT_REG_OFFSET, 4U), /*!< IDLE frame detected flag */
USART_FLAG_ORERR = USART_REGIDX_BIT(USART_STAT_REG_OFFSET, 3U), /*!< overrun error */
USART_FLAG_NERR = USART_REGIDX_BIT(USART_STAT_REG_OFFSET, 2U), /*!< noise error flag */
USART_FLAG_FERR = USART_REGIDX_BIT(USART_STAT_REG_OFFSET, 1U), /*!< frame error flag */
USART_FLAG_PERR = USART_REGIDX_BIT(USART_STAT_REG_OFFSET, 0U), /*!< parity error flag */
} usart_flag_enum;
/* USART interrupt flags */
typedef enum {
/* interrupt flags in CTL0 register */
USART_INT_FLAG_PERR = USART_REGIDX_BIT2(USART_CTL0_REG_OFFSET, 8U, USART_STAT_REG_OFFSET, 0U), /*!< parity error interrupt and flag */
USART_INT_FLAG_TBE = USART_REGIDX_BIT2(USART_CTL0_REG_OFFSET, 7U, USART_STAT_REG_OFFSET, 7U), /*!< transmitter buffer empty interrupt and flag */
USART_INT_FLAG_TC = USART_REGIDX_BIT2(USART_CTL0_REG_OFFSET, 6U, USART_STAT_REG_OFFSET, 6U), /*!< transmission complete interrupt and flag */
USART_INT_FLAG_RBNE = USART_REGIDX_BIT2(USART_CTL0_REG_OFFSET, 5U, USART_STAT_REG_OFFSET, 5U), /*!< read data buffer not empty interrupt and flag */
USART_INT_FLAG_RBNE_ORERR = USART_REGIDX_BIT2(USART_CTL0_REG_OFFSET, 5U, USART_STAT_REG_OFFSET, 3U), /*!< read data buffer not empty interrupt and overrun error flag */
USART_INT_FLAG_IDLE = USART_REGIDX_BIT2(USART_CTL0_REG_OFFSET, 4U, USART_STAT_REG_OFFSET, 4U), /*!< IDLE line detected interrupt and flag */
/* interrupt flags in CTL1 register */
USART_INT_FLAG_LBD = USART_REGIDX_BIT2(USART_CTL1_REG_OFFSET, 6U, USART_STAT_REG_OFFSET, 8U), /*!< LIN break detected interrupt and flag */
/* interrupt flags in CTL2 register */
USART_INT_FLAG_CTS = USART_REGIDX_BIT2(USART_CTL2_REG_OFFSET, 10U, USART_STAT_REG_OFFSET, 9U), /*!< CTS interrupt and flag */
USART_INT_FLAG_ERR_ORERR = USART_REGIDX_BIT2(USART_CTL2_REG_OFFSET, 0U, USART_STAT_REG_OFFSET, 3U), /*!< error interrupt and overrun error */
USART_INT_FLAG_ERR_NERR = USART_REGIDX_BIT2(USART_CTL2_REG_OFFSET, 0U, USART_STAT_REG_OFFSET, 2U), /*!< error interrupt and noise error flag */
USART_INT_FLAG_ERR_FERR = USART_REGIDX_BIT2(USART_CTL2_REG_OFFSET, 0U, USART_STAT_REG_OFFSET, 1U), /*!< error interrupt and frame error flag */
} usart_interrupt_flag_enum;
/* USART interrupt enable or disable */
typedef enum {
/* interrupt in CTL0 register */
USART_INT_PERR = USART_REGIDX_BIT(USART_CTL0_REG_OFFSET, 8U), /*!< parity error interrupt */
USART_INT_TBE = USART_REGIDX_BIT(USART_CTL0_REG_OFFSET, 7U), /*!< transmitter buffer empty interrupt */
USART_INT_TC = USART_REGIDX_BIT(USART_CTL0_REG_OFFSET, 6U), /*!< transmission complete interrupt */
USART_INT_RBNE = USART_REGIDX_BIT(USART_CTL0_REG_OFFSET, 5U), /*!< read data buffer not empty interrupt and overrun error interrupt */
USART_INT_IDLE = USART_REGIDX_BIT(USART_CTL0_REG_OFFSET, 4U), /*!< IDLE line detected interrupt */
/* interrupt in CTL1 register */
USART_INT_LBD = USART_REGIDX_BIT(USART_CTL1_REG_OFFSET, 6U), /*!< LIN break detected interrupt */
/* interrupt in CTL2 register */
USART_INT_CTS = USART_REGIDX_BIT(USART_CTL2_REG_OFFSET, 10U), /*!< CTS interrupt */
USART_INT_ERR = USART_REGIDX_BIT(USART_CTL2_REG_OFFSET, 0U), /*!< error interrupt */
} usart_interrupt_enum;
/* USART receiver configure */
#define CTL0_REN(regval) (BIT(2) & ((uint32_t)(regval) << 2))
#define USART_RECEIVE_ENABLE CTL0_REN(1) /*!< enable receiver */
#define USART_RECEIVE_DISABLE CTL0_REN(0) /*!< disable receiver */
/* USART transmitter configure */
#define CTL0_TEN(regval) (BIT(3) & ((uint32_t)(regval) << 3))
#define USART_TRANSMIT_ENABLE CTL0_TEN(1) /*!< enable transmitter */
#define USART_TRANSMIT_DISABLE CTL0_TEN(0) /*!< disable transmitter */
/* USART parity bits definitions */
#define CTL0_PM(regval) (BITS(9,10) & ((uint32_t)(regval) << 9))
#define USART_PM_NONE CTL0_PM(0) /*!< no parity */
#define USART_PM_EVEN CTL0_PM(2) /*!< even parity */
#define USART_PM_ODD CTL0_PM(3) /*!< odd parity */
/* USART wakeup method in mute mode */
#define CTL0_WM(regval) (BIT(11) & ((uint32_t)(regval) << 11))
#define USART_WM_IDLE CTL0_WM(0) /*!< idle line */
#define USART_WM_ADDR CTL0_WM(1) /*!< address match */
/* USART word length definitions */
#define CTL0_WL(regval) (BIT(12) & ((uint32_t)(regval) << 12))
#define USART_WL_8BIT CTL0_WL(0) /*!< 8 bits */
#define USART_WL_9BIT CTL0_WL(1) /*!< 9 bits */
/* USART stop bits definitions */
#define CTL1_STB(regval) (BITS(12,13) & ((uint32_t)(regval) << 12))
#define USART_STB_1BIT CTL1_STB(0) /*!< 1 bit */
#define USART_STB_0_5BIT CTL1_STB(1) /*!< 0.5 bit */
#define USART_STB_2BIT CTL1_STB(2) /*!< 2 bits */
#define USART_STB_1_5BIT CTL1_STB(3) /*!< 1.5 bits */
/* USART LIN break frame length */
#define CTL1_LBLEN(regval) (BIT(5) & ((uint32_t)(regval) << 5))
#define USART_LBLEN_10B CTL1_LBLEN(0) /*!< 10 bits */
#define USART_LBLEN_11B CTL1_LBLEN(1) /*!< 11 bits */
/* USART CK length */
#define CTL1_CLEN(regval) (BIT(8) & ((uint32_t)(regval) << 8))
#define USART_CLEN_NONE CTL1_CLEN(0) /*!< there are 7 CK pulses for an 8 bit frame and 8 CK pulses for a 9 bit frame */
#define USART_CLEN_EN CTL1_CLEN(1) /*!< there are 8 CK pulses for an 8 bit frame and 9 CK pulses for a 9 bit frame */
/* USART clock phase */
#define CTL1_CPH(regval) (BIT(9) & ((uint32_t)(regval) << 9))
#define USART_CPH_1CK CTL1_CPH(0) /*!< first clock transition is the first data capture edge */
#define USART_CPH_2CK CTL1_CPH(1) /*!< second clock transition is the first data capture edge */
/* USART clock polarity */
#define CTL1_CPL(regval) (BIT(10) & ((uint32_t)(regval) << 10))
#define USART_CPL_LOW CTL1_CPL(0) /*!< steady low value on CK pin */
#define USART_CPL_HIGH CTL1_CPL(1) /*!< steady high value on CK pin */
/* USART DMA request for receive configure */
#define CLT2_DENR(regval) (BIT(6) & ((uint32_t)(regval) << 6))
#define USART_DENR_ENABLE CLT2_DENR(1) /*!< DMA request enable for reception */
#define USART_DENR_DISABLE CLT2_DENR(0) /*!< DMA request disable for reception */
/* USART DMA request for transmission configure */
#define CLT2_DENT(regval) (BIT(7) & ((uint32_t)(regval) << 7))
#define USART_DENT_ENABLE CLT2_DENT(1) /*!< DMA request enable for transmission */
#define USART_DENT_DISABLE CLT2_DENT(0) /*!< DMA request disable for transmission */
/* USART RTS configure */
#define CLT2_RTSEN(regval) (BIT(8) & ((uint32_t)(regval) << 8))
#define USART_RTS_ENABLE CLT2_RTSEN(1) /*!< RTS enable */
#define USART_RTS_DISABLE CLT2_RTSEN(0) /*!< RTS disable */
/* USART CTS configure */
#define CLT2_CTSEN(regval) (BIT(9) & ((uint32_t)(regval) << 9))
#define USART_CTS_ENABLE CLT2_CTSEN(1) /*!< CTS enable */
#define USART_CTS_DISABLE CLT2_CTSEN(0) /*!< CTS disable */
/* USART IrDA low-power enable */
#define CTL2_IRLP(regval) (BIT(2) & ((uint32_t)(regval) << 2))
#define USART_IRLP_LOW CTL2_IRLP(1) /*!< low-power */
#define USART_IRLP_NORMAL CTL2_IRLP(0) /*!< normal */
/* function declarations */
/* initialization functions */
/* reset USART */
void usart_deinit(uint32_t usart_periph);
/* configure USART baud rate value */
void usart_baudrate_set(uint32_t usart_periph, uint32_t baudval);
/* configure USART parity function */
void usart_parity_config(uint32_t usart_periph, uint32_t paritycfg);
/* configure USART word length */
void usart_word_length_set(uint32_t usart_periph, uint32_t wlen);
/* configure USART stop bit length */
void usart_stop_bit_set(uint32_t usart_periph, uint32_t stblen);
/* USART normal mode communication */
/* enable USART */
void usart_enable(uint32_t usart_periph);
/* disable USART */
void usart_disable(uint32_t usart_periph);
/* configure USART transmitter */
void usart_transmit_config(uint32_t usart_periph, uint32_t txconfig);
/* configure USART receiver */
void usart_receive_config(uint32_t usart_periph, uint32_t rxconfig);
/* USART transmit data function */
void usart_data_transmit(uint32_t usart_periph, uint32_t data);
/* USART receive data function */
uint16_t usart_data_receive(uint32_t usart_periph);
/* multi-processor communication */
/* configure address of the USART */
void usart_address_config(uint32_t usart_periph, uint8_t addr);
/* enable mute mode */
void usart_mute_mode_enable(uint32_t usart_periph);
/* disable mute mode */
void usart_mute_mode_disable(uint32_t usart_periph);
/* configure wakeup method in mute mode */
void usart_mute_mode_wakeup_config(uint32_t usart_periph, uint32_t wmethod);
/* LIN mode communication */
/* LIN mode enable */
void usart_lin_mode_enable(uint32_t usart_periph);
/* LIN mode disable */
void usart_lin_mode_disable(uint32_t usart_periph);
/* LIN break detection length */
void usart_lin_break_detection_length_config(uint32_t usart_periph, uint32_t lblen);
/* send break frame */
void usart_send_break(uint32_t usart_periph);
/* half-duplex communication */
/* half-duplex enable */
void usart_halfduplex_enable(uint32_t usart_periph);
/* half-duplex disable */
void usart_halfduplex_disable(uint32_t usart_periph);
/* synchronous communication */
/* clock enable */
void usart_synchronous_clock_enable(uint32_t usart_periph);
/* clock disable */
void usart_synchronous_clock_disable(uint32_t usart_periph);
/* configure usart synchronous mode parameters */
void usart_synchronous_clock_config(uint32_t usart_periph, uint32_t clen, uint32_t cph, uint32_t cpl);
/* smartcard communication */
/* guard time value configure in smartcard mode */
void usart_guard_time_config(uint32_t usart_periph, uint32_t gaut);
/* smartcard mode enable */
void usart_smartcard_mode_enable(uint32_t usart_periph);
/* smartcard mode disable */
void usart_smartcard_mode_disable(uint32_t usart_periph);
/* NACK enable in smartcard mode */
void usart_smartcard_mode_nack_enable(uint32_t usart_periph);
/* NACK disable in smartcard mode */
void usart_smartcard_mode_nack_disable(uint32_t usart_periph);
/* IrDA communication */
/* enable IrDA mode */
void usart_irda_mode_enable(uint32_t usart_periph);
/* disable IrDA mode */
void usart_irda_mode_disable(uint32_t usart_periph);
/* configure the peripheral clock prescaler */
void usart_prescaler_config(uint32_t usart_periph, uint8_t psc);
/* configure IrDA low-power */
void usart_irda_lowpower_config(uint32_t usart_periph, uint32_t irlp);
/* hardware flow communication */
/* configure hardware flow control RTS */
void usart_hardware_flow_rts_config(uint32_t usart_periph, uint32_t rtsconfig);
/* configure hardware flow control CTS */
void usart_hardware_flow_cts_config(uint32_t usart_periph, uint32_t ctsconfig);
/* configure USART DMA for reception */
void usart_dma_receive_config(uint32_t usart_periph, uint32_t dmacmd);
/* configure USART DMA for transmission */
void usart_dma_transmit_config(uint32_t usart_periph, uint32_t dmacmd);
/* flag functions */
/* get flag in STAT register */
FlagStatus usart_flag_get(uint32_t usart_periph, usart_flag_enum flag);
/* clear flag in STAT register */
void usart_flag_clear(uint32_t usart_periph, usart_flag_enum flag);
/* interrupt functions */
/* enable USART interrupt */
void usart_interrupt_enable(uint32_t usart_periph, uint32_t int_flag);
/* disable USART interrupt */
void usart_interrupt_disable(uint32_t usart_periph, uint32_t int_flag);
/* get USART interrupt and flag status */
FlagStatus usart_interrupt_flag_get(uint32_t usart_periph, uint32_t int_flag);
/* clear interrupt flag in STAT register */
void usart_interrupt_flag_clear(uint32_t usart_periph, uint32_t flag);
int usart_write(uint32_t usart_periph, int ch);
uint8_t usart_read(uint32_t usart_periph);
#endif /* GD32VF103_USART_H */

View File

@ -0,0 +1,265 @@
/*
* Copyright (c) 2019 Nuclei 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 __NMSIS_GCC_H__
#define __NMSIS_GCC_H__
/*!
* @file nmsis_gcc.h
* @brief NMSIS compiler GCC header file
*/
#include <stdint.h>
#include "riscv_encoding.h"
#ifdef __cplusplus
extern "C" {
#endif
/* ######################### Startup and Lowlevel Init ######################## */
/**
* \defgroup NMSIS_Core_CompilerControl Compiler Control
* \ingroup NMSIS_Core
* \brief Compiler agnostic \#define symbols for generic c/c++ source code
* \details
*
* The NMSIS-Core provides the header file <b>nmsis_compiler.h</b> with consistent \#define symbols for generate C or C++ source files that should be compiler agnostic.
* Each NMSIS compliant compiler should support the functionality described in this section.
*
* The header file <b>nmsis_compiler.h</b> is also included by each Device Header File <device.h> so that these definitions are available.
* @{
*/
/* ignore some GCC warnings */
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wsign-conversion"
#pragma GCC diagnostic ignored "-Wconversion"
#pragma GCC diagnostic ignored "-Wunused-parameter"
/* Fallback for __has_builtin */
#ifndef __has_builtin
#define __has_builtin(x) (0)
#endif
/* NMSIS compiler specific defines */
/** \brief Pass information from the compiler to the assembler. */
#ifndef __ASM
#define __ASM __asm
#endif
/** \brief Recommend that function should be inlined by the compiler. */
#ifndef __INLINE
#define __INLINE inline
#endif
/** \brief Define a static function that may be inlined by the compiler. */
#ifndef __STATIC_INLINE
#define __STATIC_INLINE static inline
#endif
/** \brief Define a static function that should be always inlined by the compiler. */
#ifndef __STATIC_FORCEINLINE
#define __STATIC_FORCEINLINE __attribute__((always_inline)) static inline
#endif
/** \brief Inform the compiler that a function does not return. */
#ifndef __NO_RETURN
#define __NO_RETURN __attribute__((__noreturn__))
#endif
/** \brief Inform that a variable shall be retained in executable image. */
#ifndef __USED
#define __USED __attribute__((used))
#endif
/** \brief restrict pointer qualifier to enable additional optimizations. */
#ifndef __WEAK
#define __WEAK __attribute__((weak))
#endif
/** \brief specified the vector size of the variable, measured in bytes */
#ifndef __VECTOR_SIZE
#define __VECTOR_SIZE(x) __attribute__((vector_size(x)))
#endif
/** \brief Request smallest possible alignment. */
#ifndef __PACKED
#define __PACKED __attribute__((packed, aligned(1)))
#endif
/** \brief Request smallest possible alignment for a structure. */
#ifndef __PACKED_STRUCT
#define __PACKED_STRUCT struct __attribute__((packed, aligned(1)))
#endif
/** \brief Request smallest possible alignment for a union. */
#ifndef __PACKED_UNION
#define __PACKED_UNION union __attribute__((packed, aligned(1)))
#endif
#ifndef __UNALIGNED_UINT16_WRITE
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wpacked"
#pragma GCC diagnostic ignored "-Wattributes"
/** \brief Packed struct for unaligned uint16_t write access */
__PACKED_STRUCT T_UINT16_WRITE {
uint16_t v;
};
#pragma GCC diagnostic pop
/** \brief Pointer for unaligned write of a uint16_t variable. */
#define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void *)(addr))->v) = (val))
#endif
#ifndef __UNALIGNED_UINT16_READ
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wpacked"
#pragma GCC diagnostic ignored "-Wattributes"
/** \brief Packed struct for unaligned uint16_t read access */
__PACKED_STRUCT T_UINT16_READ {
uint16_t v;
};
#pragma GCC diagnostic pop
/** \brief Pointer for unaligned read of a uint16_t variable. */
#define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v)
#endif
#ifndef __UNALIGNED_UINT32_WRITE
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wpacked"
#pragma GCC diagnostic ignored "-Wattributes"
/** \brief Packed struct for unaligned uint32_t write access */
__PACKED_STRUCT T_UINT32_WRITE {
uint32_t v;
};
#pragma GCC diagnostic pop
/** \brief Pointer for unaligned write of a uint32_t variable. */
#define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val))
#endif
#ifndef __UNALIGNED_UINT32_READ
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wpacked"
#pragma GCC diagnostic ignored "-Wattributes"
/** \brief Packed struct for unaligned uint32_t read access */
__PACKED_STRUCT T_UINT32_READ {
uint32_t v;
};
#pragma GCC diagnostic pop
/** \brief Pointer for unaligned read of a uint32_t variable. */
#define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v)
#endif
/** \brief Minimum `x` bytes alignment for a variable. */
#ifndef __ALIGNED
#define __ALIGNED(x) __attribute__((aligned(x)))
#endif
/** \brief restrict pointer qualifier to enable additional optimizations. */
#ifndef __RESTRICT
#define __RESTRICT __restrict
#endif
/** \brief Barrier to prevent compiler from reordering instructions. */
#ifndef __COMPILER_BARRIER
#define __COMPILER_BARRIER() __ASM volatile("":::"memory")
#endif
/** \brief provide the compiler with branch prediction information, the branch is usually true */
#ifndef __USUALLY
#define __USUALLY(exp) __builtin_expect((exp), 1)
#endif
/** \brief provide the compiler with branch prediction information, the branch is rarely true */
#ifndef __RARELY
#define __RARELY(exp) __builtin_expect((exp), 0)
#endif
/** \brief Use this attribute to indicate that the specified function is an interrupt handler. */
#ifndef __INTERRUPT
#define __INTERRUPT __attribute__((interrupt))
#endif
/** @} */ /* End of Doxygen Group NMSIS_Core_CompilerControl */
/* IO definitions (access restrictions to peripheral registers) */
/**
* \defgroup NMSIS_Core_PeriphAccess Peripheral Access
* \brief Naming conventions and optional features for accessing peripherals.
*
* The section below describes the naming conventions, requirements, and optional features
* for accessing device specific peripherals.
* Most of the rules also apply to the core peripherals.
*
* The **Device Header File <device.h>** contains typically these definition
* and also includes the core specific header files.
*
* @{
*/
/** \brief Defines 'read only' permissions */
#ifdef __cplusplus
#define __I volatile
#else
#define __I volatile const
#endif
/** \brief Defines 'write only' permissions */
#define __O volatile
/** \brief Defines 'read / write' permissions */
#define __IO volatile
/* following defines should be used for structure members */
/** \brief Defines 'read only' structure member permissions */
#define __IM volatile const
/** \brief Defines 'write only' structure member permissions */
#define __OM volatile
/** \brief Defines 'read/write' structure member permissions */
#define __IOM volatile
/**
* \brief Mask and shift a bit field value for use in a register bit range.
* \details The macro \ref _VAL2FLD uses the #define's _Pos and _Msk of the related bit
* field to shift bit-field values for assigning to a register.
*
* **Example**:
* \code
* ECLIC->CFG = _VAL2FLD(CLIC_CLICCFG_NLBIT, 3);
* \endcode
* \param[in] field Name of the register bit field.
* \param[in] value Value of the bit field. This parameter is interpreted as an uint32_t type.
* \return Masked and shifted value.
*/
#define _VAL2FLD(field, value) (((uint32_t)(value) << field ## _Pos) & field ## _Msk)
/**
* \brief Mask and shift a register value to extract a bit filed value.
* \details The macro \ref _FLD2VAL uses the #define's _Pos and _Msk of the related bit
* field to extract the value of a bit field from a register.
*
* **Example**:
* \code
* nlbits = _FLD2VAL(CLIC_CLICCFG_NLBIT, ECLIC->CFG);
* \endcode
* \param[in] field Name of the register bit field.
* \param[in] value Value of register. This parameter is interpreted as an uint32_t type.
* \return Masked and shifted bit field value.
*/
#define _FLD2VAL(field, value) (((uint32_t)(value) & field ## _Msk) >> field ## _Pos)
/** @} */ /* end of group NMSIS_Core_PeriphAccess */
#ifdef __cplusplus
}
#endif
#endif /* __NMSIS_GCC_H__ */

View File

@ -0,0 +1,94 @@
/*
* Copyright (c) 2019 Nuclei 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 __RISCV_BITS_H__
#define __RISCV_BITS_H__
#ifdef __cplusplus
extern "C" {
#endif
#if __riscv_xlen == 64
# define SLL32 sllw
# define STORE sd
# define LOAD ld
# define LWU lwu
# define LOG_REGBYTES 3
#else
# define SLL32 sll
# define STORE sw
# define LOAD lw
# define LWU lw
# define LOG_REGBYTES 2
#endif /* __riscv_xlen */
#define REGBYTES (1 << LOG_REGBYTES)
#if defined(__riscv_flen)
#if __riscv_flen == 64
# define FPSTORE fsd
# define FPLOAD fld
# define LOG_FPREGBYTES 3
#else
# define FPSTORE fsw
# define FPLOAD flw
# define LOG_FPREGBYTES 2
#endif /* __riscv_flen == 64 */
#define FPREGBYTES (1 << LOG_FPREGBYTES)
#endif /* __riscv_flen */
#define __rv_likely(x) __builtin_expect((x), 1)
#define __rv_unlikely(x) __builtin_expect((x), 0)
#define __RV_ROUNDUP(a, b) ((((a)-1)/(b)+1)*(b))
#define __RV_ROUNDDOWN(a, b) ((a)/(b)*(b))
#define __RV_MAX(a, b) ((a) > (b) ? (a) : (b))
#define __RV_MIN(a, b) ((a) < (b) ? (a) : (b))
#define __RV_CLAMP(a, lo, hi) MIN(MAX(a, lo), hi)
#define __RV_EXTRACT_FIELD(val, which) (((val) & (which)) / ((which) & ~((which)-1)))
#define __RV_INSERT_FIELD(val, which, fieldval) (((val) & ~(which)) | ((fieldval) * ((which) & ~((which)-1))))
#ifdef __ASSEMBLY__
#define _AC(X,Y) X
#define _AT(T,X) X
#else
#define __AC(X,Y) (X##Y)
#define _AC(X,Y) __AC(X,Y)
#define _AT(T,X) ((T)(X))
#endif /* __ASSEMBLY__ */
#define _UL(x) (_AC(x, UL))
#define _ULL(x) (_AC(x, ULL))
#define _BITUL(x) (_UL(1) << (x))
#define _BITULL(x) (_ULL(1) << (x))
#define UL(x) (_UL(x))
#define ULL(x) (_ULL(x))
#define STR(x) XSTR(x)
#define XSTR(x) #x
#define __STR(s) #s
#define STRINGIFY(s) __STR(s)
#ifdef __cplusplus
}
#endif
#endif /** __RISCV_BITS_H__ */

View File

@ -0,0 +1,690 @@
/*
* Copyright (c) 2019 Nuclei 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 __RISCV_ENCODING_H__
#define __RISCV_ENCODING_H__
#include "riscv_bits.h"
#ifdef __cplusplus
extern "C" {
#endif
/**
* \defgroup NMSIS_Core_CSR_Encoding Core CSR Encodings
* \ingroup NMSIS_Core
* \brief NMSIS Core CSR Encodings
* \details
*
* The following macros are used for CSR encodings
* @{
*/
/* === Standard CSR bit mask === */
#define MSTATUS_UIE 0x00000001
#define MSTATUS_SIE 0x00000002
#define MSTATUS_HIE 0x00000004
#define MSTATUS_MIE 0x00000008
#define MSTATUS_UPIE 0x00000010
#define MSTATUS_SPIE 0x00000020
#define MSTATUS_HPIE 0x00000040
#define MSTATUS_MPIE 0x00000080
#define MSTATUS_SPP 0x00000100
#define MSTATUS_MPP 0x00001800
#define MSTATUS_FS 0x00006000
#define MSTATUS_XS 0x00018000
#define MSTATUS_MPRV 0x00020000
#define MSTATUS_PUM 0x00040000
#define MSTATUS_MXR 0x00080000
#define MSTATUS_VM 0x1F000000
#define MSTATUS32_SD 0x80000000
#define MSTATUS64_SD 0x8000000000000000
#define MSTATUS_FS_INITIAL 0x00002000
#define MSTATUS_FS_CLEAN 0x00004000
#define MSTATUS_FS_DIRTY 0x00006000
#define SSTATUS_UIE 0x00000001
#define SSTATUS_SIE 0x00000002
#define SSTATUS_UPIE 0x00000010
#define SSTATUS_SPIE 0x00000020
#define SSTATUS_SPP 0x00000100
#define SSTATUS_FS 0x00006000
#define SSTATUS_XS 0x00018000
#define SSTATUS_PUM 0x00040000
#define SSTATUS32_SD 0x80000000
#define SSTATUS64_SD 0x8000000000000000
#define CSR_MCACHE_CTL_IE 0x00000001
#define CSR_MCACHE_CTL_DE 0x00010000
#define DCSR_XDEBUGVER (3U<<30)
#define DCSR_NDRESET (1<<29)
#define DCSR_FULLRESET (1<<28)
#define DCSR_EBREAKM (1<<15)
#define DCSR_EBREAKH (1<<14)
#define DCSR_EBREAKS (1<<13)
#define DCSR_EBREAKU (1<<12)
#define DCSR_STOPCYCLE (1<<10)
#define DCSR_STOPTIME (1<<9)
#define DCSR_CAUSE (7<<6)
#define DCSR_DEBUGINT (1<<5)
#define DCSR_HALT (1<<3)
#define DCSR_STEP (1<<2)
#define DCSR_PRV (3<<0)
#define DCSR_CAUSE_NONE 0
#define DCSR_CAUSE_SWBP 1
#define DCSR_CAUSE_HWBP 2
#define DCSR_CAUSE_DEBUGINT 3
#define DCSR_CAUSE_STEP 4
#define DCSR_CAUSE_HALT 5
#define MCONTROL_TYPE(xlen) (0xfULL<<((xlen)-4))
#define MCONTROL_DMODE(xlen) (1ULL<<((xlen)-5))
#define MCONTROL_MASKMAX(xlen) (0x3fULL<<((xlen)-11))
#define MCONTROL_SELECT (1<<19)
#define MCONTROL_TIMING (1<<18)
#define MCONTROL_ACTION (0x3f<<12)
#define MCONTROL_CHAIN (1<<11)
#define MCONTROL_MATCH (0xf<<7)
#define MCONTROL_M (1<<6)
#define MCONTROL_H (1<<5)
#define MCONTROL_S (1<<4)
#define MCONTROL_U (1<<3)
#define MCONTROL_EXECUTE (1<<2)
#define MCONTROL_STORE (1<<1)
#define MCONTROL_LOAD (1<<0)
#define MCONTROL_TYPE_NONE 0
#define MCONTROL_TYPE_MATCH 2
#define MCONTROL_ACTION_DEBUG_EXCEPTION 0
#define MCONTROL_ACTION_DEBUG_MODE 1
#define MCONTROL_ACTION_TRACE_START 2
#define MCONTROL_ACTION_TRACE_STOP 3
#define MCONTROL_ACTION_TRACE_EMIT 4
#define MCONTROL_MATCH_EQUAL 0
#define MCONTROL_MATCH_NAPOT 1
#define MCONTROL_MATCH_GE 2
#define MCONTROL_MATCH_LT 3
#define MCONTROL_MATCH_MASK_LOW 4
#define MCONTROL_MATCH_MASK_HIGH 5
#define MIP_SSIP (1 << IRQ_S_SOFT)
#define MIP_HSIP (1 << IRQ_H_SOFT)
#define MIP_MSIP (1 << IRQ_M_SOFT)
#define MIP_STIP (1 << IRQ_S_TIMER)
#define MIP_HTIP (1 << IRQ_H_TIMER)
#define MIP_MTIP (1 << IRQ_M_TIMER)
#define MIP_SEIP (1 << IRQ_S_EXT)
#define MIP_HEIP (1 << IRQ_H_EXT)
#define MIP_MEIP (1 << IRQ_M_EXT)
#define MIE_SSIE MIP_SSIP
#define MIE_HSIE MIP_HSIP
#define MIE_MSIE MIP_MSIP
#define MIE_STIE MIP_STIP
#define MIE_HTIE MIP_HTIP
#define MIE_MTIE MIP_MTIP
#define MIE_SEIE MIP_SEIP
#define MIE_HEIE MIP_HEIP
#define MIE_MEIE MIP_MEIP
/* === P-ext CSR bit mask === */
#define UCODE_OV (0x1)
/* === Nuclei custom CSR bit mask === */
#define WFE_WFE (0x1)
#define TXEVT_TXEVT (0x1)
#define SLEEPVALUE_SLEEPVALUE (0x1)
#define MCOUNTINHIBIT_IR (1<<2)
#define MCOUNTINHIBIT_CY (1<<0)
#define MILM_CTL_ILM_BPA (((1ULL<<((__riscv_xlen)-10))-1)<<10)
#define MILM_CTL_ILM_RWECC (1<<3)
#define MILM_CTL_ILM_ECC_EXCP_EN (1<<2)
#define MILM_CTL_ILM_ECC_EN (1<<1)
#define MILM_CTL_ILM_EN (1<<0)
#define MDLM_CTL_DLM_BPA (((1ULL<<((__riscv_xlen)-10))-1)<<10)
#define MDLM_CTL_DLM_RWECC (1<<3)
#define MDLM_CTL_DLM_ECC_EXCP_EN (1<<2)
#define MDLM_CTL_DLM_ECC_EN (1<<1)
#define MDLM_CTL_DLM_EN (1<<0)
#define MSUBM_PTYP (0x3<<8)
#define MSUBM_TYP (0x3<<6)
#define MDCAUSE_MDCAUSE (0x3)
#define MMISC_CTL_NMI_CAUSE_FFF (1<<9)
#define MMISC_CTL_MISALIGN (1<<6)
#define MMISC_CTL_BPU (1<<3)
#define MCACHE_CTL_IC_EN (1<<0)
#define MCACHE_CTL_IC_SCPD_MOD (1<<1)
#define MCACHE_CTL_IC_ECC_EN (1<<2)
#define MCACHE_CTL_IC_ECC_EXCP_EN (1<<3)
#define MCACHE_CTL_IC_RWTECC (1<<4)
#define MCACHE_CTL_IC_RWDECC (1<<5)
#define MCACHE_CTL_DC_EN (1<<16)
#define MCACHE_CTL_DC_ECC_EN (1<<17)
#define MCACHE_CTL_DC_ECC_EXCP_EN (1<<18)
#define MCACHE_CTL_DC_RWTECC (1<<19)
#define MCACHE_CTL_DC_RWDECC (1<<20)
#define MTVT2_MTVT2EN (1<<0)
#define MTVT2_COMMON_CODE_ENTRY (((1ULL<<((__riscv_xlen)-2))-1)<<2)
#define MCFG_INFO_TEE (1<<0)
#define MCFG_INFO_ECC (1<<1)
#define MCFG_INFO_CLIC (1<<2)
#define MCFG_INFO_PLIC (1<<3)
#define MCFG_INFO_FIO (1<<4)
#define MCFG_INFO_PPI (1<<5)
#define MCFG_INFO_NICE (1<<6)
#define MCFG_INFO_ILM (1<<7)
#define MCFG_INFO_DLM (1<<8)
#define MCFG_INFO_ICACHE (1<<9)
#define MCFG_INFO_DCACHE (1<<10)
#define MICFG_IC_SET (0xF<<0)
#define MICFG_IC_WAY (0x7<<4)
#define MICFG_IC_LSIZE (0x7<<7)
#define MICFG_IC_ECC (0x1<<10)
#define MICFG_ILM_SIZE (0x1F<<16)
#define MICFG_ILM_XONLY (0x1<<21)
#define MICFG_ILM_ECC (0x1<<22)
#define MDCFG_DC_SET (0xF<<0)
#define MDCFG_DC_WAY (0x7<<4)
#define MDCFG_DC_LSIZE (0x7<<7)
#define MDCFG_DC_ECC (0x1<<10)
#define MDCFG_DLM_SIZE (0x1F<<16)
#define MDCFG_DLM_ECC (0x1<<21)
#define MPPICFG_INFO_PPI_SIZE (0x1F<<1)
#define MPPICFG_INFO_PPI_BPA (((1ULL<<((__riscv_xlen)-10))-1)<<10)
#define MFIOCFG_INFO_FIO_SIZE (0x1F<<1)
#define MFIOCFG_INFO_FIO_BPA (((1ULL<<((__riscv_xlen)-10))-1)<<10)
#define MECC_LOCK_ECC_LOCK (0x1)
#define MECC_CODE_CODE (0x1FF)
#define MECC_CODE_RAMID (0x1F<<16)
#define MECC_CODE_SRAMID (0x1F<<24)
#define CCM_SUEN_SUEN (0x1<<0)
#define CCM_DATA_DATA (0x7<<0)
#define CCM_COMMAND_COMMAND (0x1F<<0)
#define SIP_SSIP MIP_SSIP
#define SIP_STIP MIP_STIP
#define PRV_U 0
#define PRV_S 1
#define PRV_H 2
#define PRV_M 3
#define VM_MBARE 0
#define VM_MBB 1
#define VM_MBBID 2
#define VM_SV32 8
#define VM_SV39 9
#define VM_SV48 10
#define IRQ_S_SOFT 1
#define IRQ_H_SOFT 2
#define IRQ_M_SOFT 3
#define IRQ_S_TIMER 5
#define IRQ_H_TIMER 6
#define IRQ_M_TIMER 7
#define IRQ_S_EXT 9
#define IRQ_H_EXT 10
#define IRQ_M_EXT 11
#define IRQ_COP 12
#define IRQ_HOST 13
/* === FPU FRM Rounding Mode === */
/** FPU Round to Nearest, ties to Even*/
#define FRM_RNDMODE_RNE 0x0
/** FPU Round Towards Zero */
#define FRM_RNDMODE_RTZ 0x1
/** FPU Round Down (towards -inf) */
#define FRM_RNDMODE_RDN 0x2
/** FPU Round Up (towards +inf) */
#define FRM_RNDMODE_RUP 0x3
/** FPU Round to nearest, ties to Max Magnitude */
#define FRM_RNDMODE_RMM 0x4
/**
* In instruction's rm, selects dynamic rounding mode.
* In Rounding Mode register, Invalid */
#define FRM_RNDMODE_DYN 0x7
/* === FPU FFLAGS Accrued Exceptions === */
/** FPU Inexact */
#define FFLAGS_AE_NX (1<<0)
/** FPU Underflow */
#define FFLAGS_AE_UF (1<<1)
/** FPU Overflow */
#define FFLAGS_AE_OF (1<<2)
/** FPU Divide by Zero */
#define FFLAGS_AE_DZ (1<<3)
/** FPU Invalid Operation */
#define FFLAGS_AE_NV (1<<4)
/** Floating Point Register f0-f31, eg. f0 -> FREG(0) */
#define FREG(idx) f##idx
/* === PMP CFG Bits === */
#define PMP_R 0x01
#define PMP_W 0x02
#define PMP_X 0x04
#define PMP_A 0x18
#define PMP_A_TOR 0x08
#define PMP_A_NA4 0x10
#define PMP_A_NAPOT 0x18
#define PMP_L 0x80
#define PMP_SHIFT 2
#define PMP_COUNT 16
// page table entry (PTE) fields
#define PTE_V 0x001 // Valid
#define PTE_R 0x002 // Read
#define PTE_W 0x004 // Write
#define PTE_X 0x008 // Execute
#define PTE_U 0x010 // User
#define PTE_G 0x020 // Global
#define PTE_A 0x040 // Accessed
#define PTE_D 0x080 // Dirty
#define PTE_SOFT 0x300 // Reserved for Software
#define PTE_PPN_SHIFT 10
#define PTE_TABLE(PTE) (((PTE) & (PTE_V | PTE_R | PTE_W | PTE_X)) == PTE_V)
#ifdef __riscv
#ifdef __riscv64
# define MSTATUS_SD MSTATUS64_SD
# define SSTATUS_SD SSTATUS64_SD
# define RISCV_PGLEVEL_BITS 9
#else
# define MSTATUS_SD MSTATUS32_SD
# define SSTATUS_SD SSTATUS32_SD
# define RISCV_PGLEVEL_BITS 10
#endif /* __riscv64 */
#define RISCV_PGSHIFT 12
#define RISCV_PGSIZE (1 << RISCV_PGSHIFT)
#endif /* __riscv */
/**
* \defgroup NMSIS_Core_CSR_Registers Core CSR Registers
* \ingroup NMSIS_Core
* \brief NMSIS Core CSR Register Definitions
* \details
*
* The following macros are used for CSR Register Defintions.
* @{
*/
/* === Standard RISC-V CSR Registers === */
#define CSR_USTATUS 0x0
#define CSR_FFLAGS 0x1
#define CSR_FRM 0x2
#define CSR_FCSR 0x3
#define CSR_CYCLE 0xc00
#define CSR_TIME 0xc01
#define CSR_INSTRET 0xc02
#define CSR_HPMCOUNTER3 0xc03
#define CSR_HPMCOUNTER4 0xc04
#define CSR_HPMCOUNTER5 0xc05
#define CSR_HPMCOUNTER6 0xc06
#define CSR_HPMCOUNTER7 0xc07
#define CSR_HPMCOUNTER8 0xc08
#define CSR_HPMCOUNTER9 0xc09
#define CSR_HPMCOUNTER10 0xc0a
#define CSR_HPMCOUNTER11 0xc0b
#define CSR_HPMCOUNTER12 0xc0c
#define CSR_HPMCOUNTER13 0xc0d
#define CSR_HPMCOUNTER14 0xc0e
#define CSR_HPMCOUNTER15 0xc0f
#define CSR_HPMCOUNTER16 0xc10
#define CSR_HPMCOUNTER17 0xc11
#define CSR_HPMCOUNTER18 0xc12
#define CSR_HPMCOUNTER19 0xc13
#define CSR_HPMCOUNTER20 0xc14
#define CSR_HPMCOUNTER21 0xc15
#define CSR_HPMCOUNTER22 0xc16
#define CSR_HPMCOUNTER23 0xc17
#define CSR_HPMCOUNTER24 0xc18
#define CSR_HPMCOUNTER25 0xc19
#define CSR_HPMCOUNTER26 0xc1a
#define CSR_HPMCOUNTER27 0xc1b
#define CSR_HPMCOUNTER28 0xc1c
#define CSR_HPMCOUNTER29 0xc1d
#define CSR_HPMCOUNTER30 0xc1e
#define CSR_HPMCOUNTER31 0xc1f
#define CSR_SSTATUS 0x100
#define CSR_SIE 0x104
#define CSR_STVEC 0x105
#define CSR_SSCRATCH 0x140
#define CSR_SEPC 0x141
#define CSR_SCAUSE 0x142
#define CSR_SBADADDR 0x143
#define CSR_SIP 0x144
#define CSR_SPTBR 0x180
#define CSR_MSTATUS 0x300
#define CSR_MISA 0x301
#define CSR_MEDELEG 0x302
#define CSR_MIDELEG 0x303
#define CSR_MIE 0x304
#define CSR_MTVEC 0x305
#define CSR_MCOUNTEREN 0x306
#define CSR_MSCRATCH 0x340
#define CSR_MEPC 0x341
#define CSR_MCAUSE 0x342
#define CSR_MBADADDR 0x343
#define CSR_MTVAL 0x343
#define CSR_MIP 0x344
#define CSR_PMPCFG0 0x3a0
#define CSR_PMPCFG1 0x3a1
#define CSR_PMPCFG2 0x3a2
#define CSR_PMPCFG3 0x3a3
#define CSR_PMPADDR0 0x3b0
#define CSR_PMPADDR1 0x3b1
#define CSR_PMPADDR2 0x3b2
#define CSR_PMPADDR3 0x3b3
#define CSR_PMPADDR4 0x3b4
#define CSR_PMPADDR5 0x3b5
#define CSR_PMPADDR6 0x3b6
#define CSR_PMPADDR7 0x3b7
#define CSR_PMPADDR8 0x3b8
#define CSR_PMPADDR9 0x3b9
#define CSR_PMPADDR10 0x3ba
#define CSR_PMPADDR11 0x3bb
#define CSR_PMPADDR12 0x3bc
#define CSR_PMPADDR13 0x3bd
#define CSR_PMPADDR14 0x3be
#define CSR_PMPADDR15 0x3bf
#define CSR_TSELECT 0x7a0
#define CSR_TDATA1 0x7a1
#define CSR_TDATA2 0x7a2
#define CSR_TDATA3 0x7a3
#define CSR_DCSR 0x7b0
#define CSR_DPC 0x7b1
#define CSR_DSCRATCH 0x7b2
#define CSR_MCYCLE 0xb00
#define CSR_MINSTRET 0xb02
#define CSR_MHPMCOUNTER3 0xb03
#define CSR_MHPMCOUNTER4 0xb04
#define CSR_MHPMCOUNTER5 0xb05
#define CSR_MHPMCOUNTER6 0xb06
#define CSR_MHPMCOUNTER7 0xb07
#define CSR_MHPMCOUNTER8 0xb08
#define CSR_MHPMCOUNTER9 0xb09
#define CSR_MHPMCOUNTER10 0xb0a
#define CSR_MHPMCOUNTER11 0xb0b
#define CSR_MHPMCOUNTER12 0xb0c
#define CSR_MHPMCOUNTER13 0xb0d
#define CSR_MHPMCOUNTER14 0xb0e
#define CSR_MHPMCOUNTER15 0xb0f
#define CSR_MHPMCOUNTER16 0xb10
#define CSR_MHPMCOUNTER17 0xb11
#define CSR_MHPMCOUNTER18 0xb12
#define CSR_MHPMCOUNTER19 0xb13
#define CSR_MHPMCOUNTER20 0xb14
#define CSR_MHPMCOUNTER21 0xb15
#define CSR_MHPMCOUNTER22 0xb16
#define CSR_MHPMCOUNTER23 0xb17
#define CSR_MHPMCOUNTER24 0xb18
#define CSR_MHPMCOUNTER25 0xb19
#define CSR_MHPMCOUNTER26 0xb1a
#define CSR_MHPMCOUNTER27 0xb1b
#define CSR_MHPMCOUNTER28 0xb1c
#define CSR_MHPMCOUNTER29 0xb1d
#define CSR_MHPMCOUNTER30 0xb1e
#define CSR_MHPMCOUNTER31 0xb1f
#define CSR_MUCOUNTEREN 0x320
#define CSR_MSCOUNTEREN 0x321
#define CSR_MHPMEVENT3 0x323
#define CSR_MHPMEVENT4 0x324
#define CSR_MHPMEVENT5 0x325
#define CSR_MHPMEVENT6 0x326
#define CSR_MHPMEVENT7 0x327
#define CSR_MHPMEVENT8 0x328
#define CSR_MHPMEVENT9 0x329
#define CSR_MHPMEVENT10 0x32a
#define CSR_MHPMEVENT11 0x32b
#define CSR_MHPMEVENT12 0x32c
#define CSR_MHPMEVENT13 0x32d
#define CSR_MHPMEVENT14 0x32e
#define CSR_MHPMEVENT15 0x32f
#define CSR_MHPMEVENT16 0x330
#define CSR_MHPMEVENT17 0x331
#define CSR_MHPMEVENT18 0x332
#define CSR_MHPMEVENT19 0x333
#define CSR_MHPMEVENT20 0x334
#define CSR_MHPMEVENT21 0x335
#define CSR_MHPMEVENT22 0x336
#define CSR_MHPMEVENT23 0x337
#define CSR_MHPMEVENT24 0x338
#define CSR_MHPMEVENT25 0x339
#define CSR_MHPMEVENT26 0x33a
#define CSR_MHPMEVENT27 0x33b
#define CSR_MHPMEVENT28 0x33c
#define CSR_MHPMEVENT29 0x33d
#define CSR_MHPMEVENT30 0x33e
#define CSR_MHPMEVENT31 0x33f
#define CSR_MVENDORID 0xf11
#define CSR_MARCHID 0xf12
#define CSR_MIMPID 0xf13
#define CSR_MHARTID 0xf14
#define CSR_CYCLEH 0xc80
#define CSR_TIMEH 0xc81
#define CSR_INSTRETH 0xc82
#define CSR_HPMCOUNTER3H 0xc83
#define CSR_HPMCOUNTER4H 0xc84
#define CSR_HPMCOUNTER5H 0xc85
#define CSR_HPMCOUNTER6H 0xc86
#define CSR_HPMCOUNTER7H 0xc87
#define CSR_HPMCOUNTER8H 0xc88
#define CSR_HPMCOUNTER9H 0xc89
#define CSR_HPMCOUNTER10H 0xc8a
#define CSR_HPMCOUNTER11H 0xc8b
#define CSR_HPMCOUNTER12H 0xc8c
#define CSR_HPMCOUNTER13H 0xc8d
#define CSR_HPMCOUNTER14H 0xc8e
#define CSR_HPMCOUNTER15H 0xc8f
#define CSR_HPMCOUNTER16H 0xc90
#define CSR_HPMCOUNTER17H 0xc91
#define CSR_HPMCOUNTER18H 0xc92
#define CSR_HPMCOUNTER19H 0xc93
#define CSR_HPMCOUNTER20H 0xc94
#define CSR_HPMCOUNTER21H 0xc95
#define CSR_HPMCOUNTER22H 0xc96
#define CSR_HPMCOUNTER23H 0xc97
#define CSR_HPMCOUNTER24H 0xc98
#define CSR_HPMCOUNTER25H 0xc99
#define CSR_HPMCOUNTER26H 0xc9a
#define CSR_HPMCOUNTER27H 0xc9b
#define CSR_HPMCOUNTER28H 0xc9c
#define CSR_HPMCOUNTER29H 0xc9d
#define CSR_HPMCOUNTER30H 0xc9e
#define CSR_HPMCOUNTER31H 0xc9f
#define CSR_MCYCLEH 0xb80
#define CSR_MINSTRETH 0xb82
#define CSR_MHPMCOUNTER3H 0xb83
#define CSR_MHPMCOUNTER4H 0xb84
#define CSR_MHPMCOUNTER5H 0xb85
#define CSR_MHPMCOUNTER6H 0xb86
#define CSR_MHPMCOUNTER7H 0xb87
#define CSR_MHPMCOUNTER8H 0xb88
#define CSR_MHPMCOUNTER9H 0xb89
#define CSR_MHPMCOUNTER10H 0xb8a
#define CSR_MHPMCOUNTER11H 0xb8b
#define CSR_MHPMCOUNTER12H 0xb8c
#define CSR_MHPMCOUNTER13H 0xb8d
#define CSR_MHPMCOUNTER14H 0xb8e
#define CSR_MHPMCOUNTER15H 0xb8f
#define CSR_MHPMCOUNTER16H 0xb90
#define CSR_MHPMCOUNTER17H 0xb91
#define CSR_MHPMCOUNTER18H 0xb92
#define CSR_MHPMCOUNTER19H 0xb93
#define CSR_MHPMCOUNTER20H 0xb94
#define CSR_MHPMCOUNTER21H 0xb95
#define CSR_MHPMCOUNTER22H 0xb96
#define CSR_MHPMCOUNTER23H 0xb97
#define CSR_MHPMCOUNTER24H 0xb98
#define CSR_MHPMCOUNTER25H 0xb99
#define CSR_MHPMCOUNTER26H 0xb9a
#define CSR_MHPMCOUNTER27H 0xb9b
#define CSR_MHPMCOUNTER28H 0xb9c
#define CSR_MHPMCOUNTER29H 0xb9d
#define CSR_MHPMCOUNTER30H 0xb9e
#define CSR_MHPMCOUNTER31H 0xb9f
/* === TEE CSR Registers === */
#define CSR_SPMPCFG0 0x1A0
#define CSR_SPMPCFG1 0x1A1
#define CSR_SPMPCFG2 0x1A2
#define CSR_SPMPCFG3 0x1A3
#define CSR_SPMPADDR0 0x1B0
#define CSR_SPMPADDR1 0x1B1
#define CSR_SPMPADDR2 0x1B2
#define CSR_SPMPADDR3 0x1B3
#define CSR_SPMPADDR4 0x1B4
#define CSR_SPMPADDR5 0x1B5
#define CSR_SPMPADDR6 0x1B6
#define CSR_SPMPADDR7 0x1B7
#define CSR_SPMPADDR8 0x1B8
#define CSR_SPMPADDR9 0x1B9
#define CSR_SPMPADDR10 0x1BA
#define CSR_SPMPADDR11 0x1BB
#define CSR_SPMPADDR12 0x1BC
#define CSR_SPMPADDR13 0x1BD
#define CSR_SPMPADDR14 0x1BE
#define CSR_SPMPADDR15 0x1BF
#define CSR_JALSNXTI 0x947
#define CSR_STVT2 0x948
#define CSR_PUSHSCAUSE 0x949
#define CSR_PUSHSEPC 0x94A
/* === CLIC CSR Registers === */
#define CSR_MTVT 0x307
#define CSR_MNXTI 0x345
#define CSR_MINTSTATUS 0x346
#define CSR_MSCRATCHCSW 0x348
#define CSR_MSCRATCHCSWL 0x349
#define CSR_MCLICBASE 0x350
/* === P-Extension Registers === */
#define CSR_UCODE 0x801
/* === Nuclei custom CSR Registers === */
#define CSR_MCOUNTINHIBIT 0x320
#define CSR_MILM_CTL 0x7C0
#define CSR_MDLM_CTL 0x7C1
#define CSR_MECC_CODE 0x7C2
#define CSR_MNVEC 0x7C3
#define CSR_MSUBM 0x7C4
#define CSR_MDCAUSE 0x7C9
#define CSR_MCACHE_CTL 0x7CA
#define CSR_MMISC_CTL 0x7D0
#define CSR_MSAVESTATUS 0x7D6
#define CSR_MSAVEEPC1 0x7D7
#define CSR_MSAVECAUSE1 0x7D8
#define CSR_MSAVEEPC2 0x7D9
#define CSR_MSAVECAUSE2 0x7DA
#define CSR_MSAVEDCAUSE1 0x7DB
#define CSR_MSAVEDCAUSE2 0x7DC
#define CSR_MTLB_CTL 0x7DD
#define CSR_MECC_LOCK 0x7DE
#define CSR_MFP16MODE 0x7E2
#define CSR_LSTEPFORC 0x7E9
#define CSR_PUSHMSUBM 0x7EB
#define CSR_MTVT2 0x7EC
#define CSR_JALMNXTI 0x7ED
#define CSR_PUSHMCAUSE 0x7EE
#define CSR_PUSHMEPC 0x7EF
#define CSR_MPPICFG_INFO 0x7F0
#define CSR_MFIOCFG_INFO 0x7F1
#define CSR_MSMPCFG_INFO 0x7F7
#define CSR_SLEEPVALUE 0x811
#define CSR_TXEVT 0x812
#define CSR_WFE 0x810
#define CSR_MICFG_INFO 0xFC0
#define CSR_MDCFG_INFO 0xFC1
#define CSR_MCFG_INFO 0xFC2
#define CSR_MTLBCFG_INFO 0xFC3
/* === Nuclei CCM Registers === */
#define CSR_CCM_MBEGINADDR 0x7CB
#define CSR_CCM_MCOMMAND 0x7CC
#define CSR_CCM_MDATA 0x7CD
#define CSR_CCM_SUEN 0x7CE
#define CSR_CCM_SBEGINADDR 0x5CB
#define CSR_CCM_SCOMMAND 0x5CC
#define CSR_CCM_SDATA 0x5CD
#define CSR_CCM_UBEGINADDR 0x4CB
#define CSR_CCM_UCOMMAND 0x4CC
#define CSR_CCM_UDATA 0x4CD
#define CSR_CCM_FPIPE 0x4CF
/** @} */ /** End of Doxygen Group NMSIS_Core_CSR_Registers **/
/* Exception Code in MCAUSE CSR */
#define CAUSE_MISALIGNED_FETCH 0x0
#define CAUSE_FAULT_FETCH 0x1
#define CAUSE_ILLEGAL_INSTRUCTION 0x2
#define CAUSE_BREAKPOINT 0x3
#define CAUSE_MISALIGNED_LOAD 0x4
#define CAUSE_FAULT_LOAD 0x5
#define CAUSE_MISALIGNED_STORE 0x6
#define CAUSE_FAULT_STORE 0x7
#define CAUSE_USER_ECALL 0x8
#define CAUSE_SUPERVISOR_ECALL 0x9
#define CAUSE_HYPERVISOR_ECALL 0xa
#define CAUSE_MACHINE_ECALL 0xb
/* Exception Subcode in MDCAUSE CSR */
#define DCAUSE_FAULT_FETCH_PMP 0x1
#define DCAUSE_FAULT_FETCH_INST 0x2
#define DCAUSE_FAULT_LOAD_PMP 0x1
#define DCAUSE_FAULT_LOAD_INST 0x2
#define DCAUSE_FAULT_LOAD_NICE 0x3
#define DCAUSE_FAULT_STORE_PMP 0x1
#define DCAUSE_FAULT_STORE_INST 0x2
/** @} */ /** End of Doxygen Group NMSIS_Core_CSR_Encoding **/
#ifdef __cplusplus
}
#endif
#endif /* __RISCV_ENCODING_H__ */

View File

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

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,60 @@
#include "nuclei_sdk_soc.h"
#include <core_feature_timer.h>
__STATIC_FORCEINLINE uint64_t get_timer_freq(void)
{
return (uint64_t)SOC_TIMER_FREQ;
}
uint32_t measure_cpu_freq(uint32_t n)
{
uint32_t start_mcycle, delta_mcycle;
uint32_t start_mtime, delta_mtime;
uint64_t mtime_freq = get_timer_freq();
// Don't start measuruing until we see an mtime tick
uint32_t tmp = (uint32_t)SysTimer_GetLoadValue();
do {
start_mtime = (uint32_t)SysTimer_GetLoadValue();
start_mcycle = __RV_CSR_READ(CSR_MCYCLE);
} while (start_mtime == tmp);
do {
delta_mtime = (uint32_t)SysTimer_GetLoadValue() - start_mtime;
delta_mcycle = __RV_CSR_READ(CSR_MCYCLE) - start_mcycle;
} while (delta_mtime < n);
return (delta_mcycle / delta_mtime) * mtime_freq
+ ((delta_mcycle % delta_mtime) * mtime_freq) / delta_mtime;
}
uint32_t get_cpu_freq(void)
{
uint32_t cpu_freq;
// warm up
measure_cpu_freq(1);
// measure for real
cpu_freq = measure_cpu_freq(100);
return cpu_freq;
}
/**
* \brief delay a time in milliseconds
* \details
* provide API for delay
* \param[in] count: count in milliseconds
* \remarks
*/
void delay_1ms(uint32_t count)
{
uint64_t start_mtime, delta_mtime;
uint64_t delay_ticks = (SOC_TIMER_FREQ * (uint64_t)count) / 1000;
start_mtime = SysTimer_GetLoadValue();
do {
delta_mtime = SysTimer_GetLoadValue() - start_mtime;
} while (delta_mtime < delay_ticks);
}

View File

@ -0,0 +1,603 @@
/******************************************************************************
* @file system_gd32vf103.c
* @brief NMSIS Nuclei Core Device Peripheral Access Layer Source File for
* Device gd32vf103
* @version V1.00
* @date 22. Nov 2019
******************************************************************************/
/*
* Copyright (c) 2009-2018 Arm Limited. All rights reserved.
* Copyright (c) 2019 Nuclei 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.
*/
#include <stdint.h>
#include <stdio.h>
#include "nuclei_sdk_hal.h"
/*----------------------------------------------------------------------------
Define clocks
*----------------------------------------------------------------------------*/
/* ToDo: add here your necessary defines for device initialization
following is an example for different system frequencies */
#ifndef SYSTEM_CLOCK
#define SYSTEM_CLOCK __SYSTEM_CLOCK_108M_PLL_HXTAL
#endif
/**
* \defgroup NMSIS_Core_SystemAndClock System and Clock Configuration
* \brief Functions for system and clock setup available in system_<device>.c.
* \details
* Nuclei provides a template file **system_Device.c** that must be adapted by
* the silicon vendor to match their actual device. As a <b>minimum requirement</b>,
* this file must provide:
* - A device-specific system configuration function, \ref SystemInit().
* - A global variable that contains the system frequency, \ref SystemCoreClock.
*
* The file configures the device and, typically, initializes the oscillator (PLL) that is part
* of the microcontroller device. This file might export other functions or variables that provide
* a more flexible configuration of the microcontroller system.
*
* \note Please pay special attention to the static variable \c SystemCoreClock. This variable might be
* used throughout the whole system initialization and runtime to calculate frequency/time related values.
* Thus one must assure that the variable always reflects the actual system clock speed.
*
* \attention
* Be aware that a value stored to \c SystemCoreClock during low level initialization (i.e. \c SystemInit()) might get
* overwritten by C libray startup code and/or .bss section initialization.
* Thus its highly recommended to call \ref SystemCoreClockUpdate at the beginning of the user \c main() routine.
*
* @{
*/
/*----------------------------------------------------------------------------
System Core Clock Variable
*----------------------------------------------------------------------------*/
/* ToDo: initialize SystemCoreClock with the system core clock frequency value
achieved after system intitialization.
This means system core clock frequency after call to SystemInit() */
/**
* \brief Variable to hold the system core clock value
* \details
* Holds the system core clock, which is the system clock frequency supplied to the SysTick
* timer and the processor core clock. This variable can be used by debuggers to query the
* frequency of the debug timer or to configure the trace clock speed.
*
* \attention
* Compilers must be configured to avoid removing this variable in case the application
* program is not using it. Debugging systems require the variable to be physically
* present in memory so that it can be examined to configure the debugger.
*/
uint32_t SystemCoreClock = __SYSTEM_CLOCK_108M_PLL_HXTAL; /* System Clock Frequency (Core Clock) */
/*----------------------------------------------------------------------------
Clock functions
*----------------------------------------------------------------------------*/
/*!
\brief configure the system clock to 108M by PLL which selects HXTAL(MD/HD/XD:8M; CL:25M) as its clock source
\param[in] none
\param[out] none
\retval none
*/
static void system_clock_108m_hxtal(void)
{
uint32_t timeout = 0U;
uint32_t stab_flag = 0U;
/* enable HXTAL */
RCU_CTL |= RCU_CTL_HXTALEN;
/* wait until HXTAL is stable or the startup time is longer than
* HXTAL_STARTUP_TIMEOUT */
do {
timeout++;
stab_flag = (RCU_CTL & RCU_CTL_HXTALSTB);
} while ((0U == stab_flag) && (HXTAL_STARTUP_TIMEOUT != timeout));
/* if fail */
if (0U == (RCU_CTL & RCU_CTL_HXTALSTB)) {
while (1) {
}
}
/* HXTAL is stable */
/* AHB = SYSCLK */
RCU_CFG0 |= RCU_AHB_CKSYS_DIV1;
/* APB2 = AHB/1 */
RCU_CFG0 |= RCU_APB2_CKAHB_DIV1;
/* APB1 = AHB/2 */
RCU_CFG0 |= RCU_APB1_CKAHB_DIV2;
/* CK_PLL = (CK_PREDIV0) * 27 = 108 MHz */
RCU_CFG0 &= ~(RCU_CFG0_PLLMF | RCU_CFG0_PLLMF_4);
RCU_CFG0 |= (RCU_PLLSRC_HXTAL | RCU_PLL_MUL27);
if (HXTAL_VALUE == 25000000) {
/* CK_PREDIV0 = (CK_HXTAL)/5 *8 /10 = 4 MHz */
RCU_CFG1 &= ~(RCU_CFG1_PREDV0SEL | RCU_CFG1_PREDV1 | RCU_CFG1_PLL1MF |
RCU_CFG1_PREDV0);
RCU_CFG1 |= (RCU_PREDV0SRC_CKPLL1 | RCU_PREDV1_DIV5 | RCU_PLL1_MUL8 |
RCU_PREDV0_DIV10);
/* enable PLL1 */
RCU_CTL |= RCU_CTL_PLL1EN;
/* wait till PLL1 is ready */
while (0U == (RCU_CTL & RCU_CTL_PLL1STB)) {
}
/* enable PLL1 */
RCU_CTL |= RCU_CTL_PLL2EN;
/* wait till PLL1 is ready */
while (0U == (RCU_CTL & RCU_CTL_PLL2STB)) {
}
} else if (HXTAL_VALUE == 8000000) {
RCU_CFG1 &= ~(RCU_CFG1_PREDV0SEL | RCU_CFG1_PREDV1 | RCU_CFG1_PLL1MF |
RCU_CFG1_PREDV0);
RCU_CFG1 |= (RCU_PREDV0SRC_HXTAL | RCU_PREDV0_DIV2 | RCU_PREDV1_DIV2 |
RCU_PLL1_MUL20 | RCU_PLL2_MUL20);
/* enable PLL1 */
RCU_CTL |= RCU_CTL_PLL1EN;
/* wait till PLL1 is ready */
while (0U == (RCU_CTL & RCU_CTL_PLL1STB)) {
}
/* enable PLL2 */
RCU_CTL |= RCU_CTL_PLL2EN;
/* wait till PLL1 is ready */
while (0U == (RCU_CTL & RCU_CTL_PLL2STB)) {
}
}
/* enable PLL */
RCU_CTL |= RCU_CTL_PLLEN;
/* wait until PLL is stable */
while (0U == (RCU_CTL & RCU_CTL_PLLSTB)) {
}
/* select PLL as system clock */
RCU_CFG0 &= ~RCU_CFG0_SCS;
RCU_CFG0 |= RCU_CKSYSSRC_PLL;
/* wait until PLL is selected as system clock */
while (0U == (RCU_CFG0 & RCU_SCSS_PLL)) {
}
}
/*!
\brief configure the system clock
\param[in] none
\param[out] none
\retval none
*/
static void system_clock_config(void)
{
system_clock_108m_hxtal();
}
/**
* \brief Function to update the variable \ref SystemCoreClock
* \details
* Updates the variable \ref SystemCoreClock and must be called whenever the core clock is changed
* during program execution. The function evaluates the clock register settings and calculates
* the current core clock.
*/
void SystemCoreClockUpdate(void) /* Get Core Clock Frequency */
{
/* ToDo: add code to calculate the system frequency based upon the current
* register settings.
* Note: This function can be used to retrieve the system core clock
* frequeny after user changed register settings.
*/
uint32_t scss;
uint32_t pllsel, predv0sel, pllmf, ck_src;
uint32_t predv0, predv1, pll1mf;
scss = GET_BITS(RCU_CFG0, 2, 3);
switch (scss) {
/* IRC8M is selected as CK_SYS */
case SEL_IRC8M:
SystemCoreClock = IRC8M_VALUE;
break;
/* HXTAL is selected as CK_SYS */
case SEL_HXTAL:
SystemCoreClock = HXTAL_VALUE;
break;
/* PLL is selected as CK_SYS */
case SEL_PLL:
/* PLL clock source selection, HXTAL or IRC8M/2 */
pllsel = (RCU_CFG0 & RCU_CFG0_PLLSEL);
if (RCU_PLLSRC_IRC8M_DIV2 == pllsel) {
/* PLL clock source is IRC8M/2 */
ck_src = IRC8M_VALUE / 2U;
} else {
/* PLL clock source is HXTAL */
ck_src = HXTAL_VALUE;
predv0sel = (RCU_CFG1 & RCU_CFG1_PREDV0SEL);
/* source clock use PLL1 */
if (RCU_PREDV0SRC_CKPLL1 == predv0sel) {
predv1 = ((RCU_CFG1 & RCU_CFG1_PREDV1) >> 4) + 1U;
pll1mf = ((RCU_CFG1 & RCU_CFG1_PLL1MF) >> 8) + 2U;
if (17U == pll1mf) {
pll1mf = 20U;
}
ck_src = (ck_src / predv1) * pll1mf;
}
predv0 = (RCU_CFG1 & RCU_CFG1_PREDV0) + 1U;
ck_src /= predv0;
}
/* PLL multiplication factor */
pllmf = GET_BITS(RCU_CFG0, 18, 21);
if ((RCU_CFG0 & RCU_CFG0_PLLMF_4)) {
pllmf |= 0x10U;
}
if (pllmf >= 15U) {
pllmf += 1U;
} else {
pllmf += 2U;
}
SystemCoreClock = ck_src * pllmf;
if (15U == pllmf) {
/* PLL source clock multiply by 6.5 */
SystemCoreClock = ck_src * 6U + ck_src / 2U;
}
break;
/* IRC8M is selected as CK_SYS */
default:
SystemCoreClock = IRC8M_VALUE;
break;
}
}
/**
* \brief Function to Initialize the system.
* \details
* Initializes the microcontroller system. Typically, this function configures the
* oscillator (PLL) that is part of the microcontroller device. For systems
* with a variable clock speed, it updates the variable \ref SystemCoreClock.
* SystemInit is called from the file <b>startup<i>_device</i></b>.
*/
void SystemInit(void)
{
/* ToDo: add code to initialize the system
* Warn: do not use global variables because this function is called before
* reaching pre-main. RW section maybe overwritten afterwards.
*/
/* reset the RCC clock configuration to the default reset state */
/* enable IRC8M */
RCU_CTL |= RCU_CTL_IRC8MEN;
/* reset SCS, AHBPSC, APB1PSC, APB2PSC, ADCPSC, CKOUT0SEL bits */
RCU_CFG0 &= ~(RCU_CFG0_SCS | RCU_CFG0_AHBPSC | RCU_CFG0_APB1PSC | RCU_CFG0_APB2PSC |
RCU_CFG0_ADCPSC | RCU_CFG0_ADCPSC_2 | RCU_CFG0_CKOUT0SEL);
/* reset HXTALEN, CKMEN, PLLEN bits */
RCU_CTL &= ~(RCU_CTL_HXTALEN | RCU_CTL_CKMEN | RCU_CTL_PLLEN);
/* Reset HXTALBPS bit */
RCU_CTL &= ~(RCU_CTL_HXTALBPS);
/* reset PLLSEL, PREDV0_LSB, PLLMF, USBFSPSC bits */
RCU_CFG0 &= ~(RCU_CFG0_PLLSEL | RCU_CFG0_PREDV0_LSB | RCU_CFG0_PLLMF |
RCU_CFG0_USBFSPSC | RCU_CFG0_PLLMF_4);
RCU_CFG1 = 0x00000000U;
/* Reset HXTALEN, CKMEN, PLLEN, PLL1EN and PLL2EN bits */
RCU_CTL &= ~(RCU_CTL_PLLEN | RCU_CTL_PLL1EN | RCU_CTL_PLL2EN | RCU_CTL_CKMEN | RCU_CTL_HXTALEN);
/* disable all interrupts */
RCU_INT = 0x00FF0000U;
/* Configure the System clock source, PLL Multiplier, AHB/APBx prescalers and Flash settings */
system_clock_config();
}
/**
* \defgroup NMSIS_Core_IntExcNMI_Handling Interrupt and Exception and NMI Handling
* \brief Functions for interrupt, exception and nmi handle available in system_<device>.c.
* \details
* Nuclei provide a template for interrupt, exception and NMI handling. Silicon Vendor could adapat according
* to their requirement. Silicon vendor could implement interface for different exception code and
* replace current implementation.
*
* @{
*/
/** \brief Max exception handler number, don't include the NMI(0xFFF) one */
#define MAX_SYSTEM_EXCEPTION_NUM 12
/**
* \brief Store the exception handlers for each exception ID
* \note
* - This SystemExceptionHandlers are used to store all the handlers for all
* the exception codes Nuclei N/NX core provided.
* - Exception code 0 - 11, totally 12 exceptions are mapped to SystemExceptionHandlers[0:11]
* - Exception for NMI is also re-routed to exception handling(exception code 0xFFF) in startup code configuration, the handler itself is mapped to SystemExceptionHandlers[MAX_SYSTEM_EXCEPTION_NUM]
*/
static unsigned long SystemExceptionHandlers[MAX_SYSTEM_EXCEPTION_NUM + 1];
/**
* \brief Exception Handler Function Typedef
* \note
* This typedef is only used internal in this system_gd32vf103.c file.
* It is used to do type conversion for registered exception handler before calling it.
*/
typedef void (*EXC_HANDLER)(unsigned long mcause, unsigned long sp);
/**
* \brief System Default Exception Handler
* \details
* This function provided a default exception and NMI handling code for all exception ids.
* By default, It will just print some information for debug, Vendor can customize it according to its requirements.
*/
static void system_default_exception_handler(unsigned long mcause, unsigned long sp)
{
/* TODO: Uncomment this if you have implement printf function */
printf("MCAUSE: 0x%lx\r\n", mcause);
printf("MEPC : 0x%lx\r\n", __RV_CSR_READ(CSR_MEPC));
printf("MTVAL : 0x%lx\r\n", __RV_CSR_READ(CSR_MBADADDR));
Exception_DumpFrame(sp);
while (1);
}
/**
* \brief Initialize all the default core exception handlers
* \details
* The core exception handler for each exception id will be initialized to \ref system_default_exception_handler.
* \note
* Called in \ref _init function, used to initialize default exception handlers for all exception IDs
*/
static void Exception_Init(void)
{
for (int i = 0; i < MAX_SYSTEM_EXCEPTION_NUM + 1; i++) {
SystemExceptionHandlers[i] = (unsigned long)system_default_exception_handler;
}
}
/**
* \brief Register an exception handler for exception code EXCn
* \details
* * For EXCn < \ref MAX_SYSTEM_EXCEPTION_NUM, it will be registered into SystemExceptionHandlers[EXCn-1].
* * For EXCn == NMI_EXCn, it will be registered into SystemExceptionHandlers[MAX_SYSTEM_EXCEPTION_NUM].
* \param EXCn See \ref EXCn_Type
* \param exc_handler The exception handler for this exception code EXCn
*/
void Exception_Register_EXC(uint32_t EXCn, unsigned long exc_handler)
{
if ((EXCn < MAX_SYSTEM_EXCEPTION_NUM) && (EXCn >= 0)) {
SystemExceptionHandlers[EXCn] = exc_handler;
} else if (EXCn == NMI_EXCn) {
SystemExceptionHandlers[MAX_SYSTEM_EXCEPTION_NUM] = exc_handler;
}
}
/**
* \brief Get current exception handler for exception code EXCn
* \details
* * For EXCn < \ref MAX_SYSTEM_EXCEPTION_NUM, it will return SystemExceptionHandlers[EXCn-1].
* * For EXCn == NMI_EXCn, it will return SystemExceptionHandlers[MAX_SYSTEM_EXCEPTION_NUM].
* \param EXCn See \ref EXCn_Type
* \return Current exception handler for exception code EXCn, if not found, return 0.
*/
unsigned long Exception_Get_EXC(uint32_t EXCn)
{
if ((EXCn < MAX_SYSTEM_EXCEPTION_NUM) && (EXCn >= 0)) {
return SystemExceptionHandlers[EXCn];
} else if (EXCn == NMI_EXCn) {
return SystemExceptionHandlers[MAX_SYSTEM_EXCEPTION_NUM];
} else {
return 0;
}
}
/**
* \brief Common NMI and Exception handler entry
* \details
* This function provided a command entry for NMI and exception. Silicon Vendor could modify
* this template implementation according to requirement.
* \remarks
* - RISCV provided common entry for all types of exception. This is proposed code template
* for exception entry function, Silicon Vendor could modify the implementation.
* - For the core_exception_handler template, we provided exception register function \ref Exception_Register_EXC
* which can help developer to register your exception handler for specific exception number.
*/
uint32_t core_exception_handler(unsigned long mcause, unsigned long sp)
{
uint32_t EXCn = (uint32_t)(mcause & 0X00000fff);
EXC_HANDLER exc_handler;
if ((EXCn < MAX_SYSTEM_EXCEPTION_NUM) && (EXCn >= 0)) {
exc_handler = (EXC_HANDLER)SystemExceptionHandlers[EXCn];
} else if (EXCn == NMI_EXCn) {
exc_handler = (EXC_HANDLER)SystemExceptionHandlers[MAX_SYSTEM_EXCEPTION_NUM];
} else {
exc_handler = (EXC_HANDLER)system_default_exception_handler;
}
if (exc_handler != NULL) {
exc_handler(mcause, sp);
}
return 0;
}
/** @} */ /* End of Doxygen Group NMSIS_Core_ExceptionAndNMI */
void SystemBannerPrint(void)
{
#if defined(NUCLEI_BANNER) && (NUCLEI_BANNER == 1)
printf("Nuclei SDK Build Time: %s, %s\r\n", __DATE__, __TIME__);
#ifdef DOWNLOAD_MODE_STRING
printf("Download Mode: %s\r\n", DOWNLOAD_MODE_STRING);
#endif
printf("CPU Frequency %d Hz\r\n", SystemCoreClock);
#endif
}
/**
* \brief initialize eclic config
* \details
* Eclic need initialize after boot up, Vendor could also change the initialization
* configuration.
*/
void ECLIC_Init(void)
{
/* TODO: Add your own initialization code here. This function will be called by main */
ECLIC_SetMth(0);
ECLIC_SetCfgNlbits(__ECLIC_INTCTLBITS);
}
/**
* \brief Dump Exception Frame
* \details
* This function provided feature to dump exception frame stored in stack.
*/
void Exception_DumpFrame(unsigned long sp)
{
EXC_Frame_Type *exc_frame = (EXC_Frame_Type *)sp;
#ifndef __riscv_32e
printf("ra: 0x%x, tp: 0x%x, t0: 0x%x, t1: 0x%x, t2: 0x%x, t3: 0x%x, t4: 0x%x, t5: 0x%x, t6: 0x%x\n" \
"a0: 0x%x, a1: 0x%x, a2: 0x%x, a3: 0x%x, a4: 0x%x, a5: 0x%x, a6: 0x%x, a7: 0x%x\n" \
"mcause: 0x%x, mepc: 0x%x, msubm: 0x%x\n", exc_frame->ra, exc_frame->tp, exc_frame->t0, \
exc_frame->t1, exc_frame->t2, exc_frame->t3, exc_frame->t4, exc_frame->t5, exc_frame->t6, \
exc_frame->a0, exc_frame->a1, exc_frame->a2, exc_frame->a3, exc_frame->a4, exc_frame->a5, \
exc_frame->a6, exc_frame->a7, exc_frame->mcause, exc_frame->mepc, exc_frame->msubm);
#else
printf("ra: 0x%x, tp: 0x%x, t0: 0x%x, t1: 0x%x, t2: 0x%x\n" \
"a0: 0x%x, a1: 0x%x, a2: 0x%x, a3: 0x%x, a4: 0x%x, a5: 0x%x\n" \
"mcause: 0x%x, mepc: 0x%x, msubm: 0x%x\n", exc_frame->ra, exc_frame->tp, exc_frame->t0, \
exc_frame->t1, exc_frame->t2, exc_frame->a0, exc_frame->a1, exc_frame->a2, exc_frame->a3, \
exc_frame->a4, exc_frame->a5, exc_frame->mcause, exc_frame->mepc, exc_frame->msubm);
#endif
}
/**
* \brief Initialize a specific IRQ and register the handler
* \details
* This function set vector mode, trigger mode and polarity, interrupt level and priority,
* assign handler for specific IRQn.
* \param [in] IRQn NMI interrupt handler address
* \param [in] shv \ref ECLIC_NON_VECTOR_INTERRUPT means non-vector mode, and \ref ECLIC_VECTOR_INTERRUPT is vector mode
* \param [in] trig_mode see \ref ECLIC_TRIGGER_Type
* \param [in] lvl interupt level
* \param [in] priority interrupt priority
* \param [in] handler interrupt handler, if NULL, handler will not be installed
* \return -1 means invalid input parameter. 0 means successful.
* \remarks
* - This function use to configure specific eclic interrupt and register its interrupt handler and enable its interrupt.
* - If the vector table is placed in read-only section(FLASHXIP mode), handler could not be installed
*/
int32_t ECLIC_Register_IRQ(IRQn_Type IRQn, uint8_t shv, ECLIC_TRIGGER_Type trig_mode, uint8_t lvl, uint8_t priority, void* handler)
{
if ((IRQn > SOC_INT_MAX) || (shv > ECLIC_VECTOR_INTERRUPT) \
|| (trig_mode > ECLIC_NEGTIVE_EDGE_TRIGGER)) {
return -1;
}
/* set interrupt vector mode */
ECLIC_SetShvIRQ(IRQn, shv);
/* set interrupt trigger mode and polarity */
ECLIC_SetTrigIRQ(IRQn, trig_mode);
/* set interrupt level */
ECLIC_SetLevelIRQ(IRQn, lvl);
/* set interrupt priority */
ECLIC_SetPriorityIRQ(IRQn, priority);
if (handler != NULL) {
/* set interrupt handler entry to vector table */
ECLIC_SetVector(IRQn, (rv_csr_t)handler);
}
/* enable interrupt */
ECLIC_EnableIRQ(IRQn);
return 0;
}
/** @} */ /* End of Doxygen Group NMSIS_Core_ExceptionAndNMI */
/**
* \brief early init function before main
* \details
* This function is executed right before main function.
* For RISC-V gnu toolchain, _init function might not be called
* by __libc_init_array function, so we defined a new function
* to do initialization
*/
void _premain_init(void)
{
/* TODO: Add your own initialization code here, called before main */
SystemCoreClock = get_cpu_freq();
/* configure USART */
gd_com_init(SOC_DEBUG_UART);
/* Display banner after UART initialized */
// SystemBannerPrint();
/* Initialize exception default handlers */
Exception_Init();
/* ECLIC initialization, mainly MTH and NLBIT */
ECLIC_Init();
}
/**
* \brief finish function after main
* \param [in] status status code return from main
* \details
* This function is executed right after main function.
* For RISC-V gnu toolchain, _fini function might not be called
* by __libc_fini_array function, so we defined a new function
* to do initialization
*/
void _postmain_fini(int status)
{
/* TODO: Add your own finishing code here, called after main */
}
/**
* \brief _init function called in __libc_init_array()
* \details
* This `__libc_init_array()` function is called during startup code,
* user need to implement this function, otherwise when link it will
* error init.c:(.text.__libc_init_array+0x26): undefined reference to `_init'
* \note
* Please use \ref _premain_init function now
*/
void _init(void)
{
/* Don't put any code here, please use _premain_init now */
}
/**
* \brief _fini function called in __libc_fini_array()
* \details
* This `__libc_fini_array()` function is called when exit main.
* user need to implement this function, otherwise when link it will
* error fini.c:(.text.__libc_fini_array+0x28): undefined reference to `_fini'
* \note
* Please use \ref _postmain_fini function now
*/
void _fini(void)
{
/* Don't put any code here, please use _postmain_fini now */
}
/** @} */ /* End of Doxygen Group NMSIS_Core_SystemAndClock */

View File

@ -0,0 +1,110 @@
/*
* Copyright (c) 2009-2018 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.
*/
/*******************************************************************************
* @file system_gd32vf103.h
* @brief NMSIS Nuclei N/NX Device Peripheral Access Layer Header File for
* Device gd32vf103
* @version V1.00
* @date 7. Jan 2020
******************************************************************************/
#ifndef __SYSTEM_GD32VF103_H__
#define __SYSTEM_GD32VF103_H__
#ifdef __cplusplus
extern "C" {
#endif
#include <stdint.h>
#include "gd32vf103.h"
#include "core_feature_eclic.h"
extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */
typedef struct EXC_Frame {
unsigned long ra; /* ra: x1, return address for jump */
unsigned long tp; /* tp: x4, thread pointer */
unsigned long t0; /* t0: x5, temporary register 0 */
unsigned long t1; /* t1: x6, temporary register 1 */
unsigned long t2; /* t2: x7, temporary register 2 */
unsigned long a0; /* a0: x10, return value or function argument 0 */
unsigned long a1; /* a1: x11, return value or function argument 1 */
unsigned long a2; /* a2: x12, function argument 2 */
unsigned long a3; /* a3: x13, function argument 3 */
unsigned long a4; /* a4: x14, function argument 4 */
unsigned long a5; /* a5: x15, function argument 5 */
unsigned long mcause; /* mcause: machine cause csr register */
unsigned long mepc; /* mepc: machine exception program counter csr register */
unsigned long msubm; /* msubm: machine sub-mode csr register, nuclei customized */
#ifndef __riscv_32e
unsigned long a6; /* a6: x16, function argument 6 */
unsigned long a7; /* a7: x17, function argument 7 */
unsigned long t3; /* t3: x28, temporary register 3 */
unsigned long t4; /* t4: x29, temporary register 4 */
unsigned long t5; /* t5: x30, temporary register 5 */
unsigned long t6; /* t6: x31, temporary register 6 */
#endif
} EXC_Frame_Type;
/**
\brief Setup the microcontroller system.
Initialize the System and update the SystemCoreClock variable.
*/
extern void SystemInit(void);
/**
\brief Update SystemCoreClock variable.
Updates the SystemCoreClock with current core Clock retrieved from cpu registers.
*/
extern void SystemCoreClockUpdate(void);
/**
* \brief Dump Exception Frame
*/
void Exception_DumpFrame(unsigned long sp);
/**
* \brief Register an exception handler for exception code EXCn
*/
extern void Exception_Register_EXC(uint32_t EXCn, unsigned long exc_handler);
/**
* \brief Get current exception handler for exception code EXCn
*/
extern unsigned long Exception_Get_EXC(uint32_t EXCn);
/**
* \brief Initialize eclic config
*/
extern void ECLIC_Init(void);
/**
* \brief Initialize a specific IRQ and register the handler
* \details
* This function set vector mode, trigger mode and polarity, interrupt level and priority,
* assign handler for specific IRQn.
*/
extern int32_t ECLIC_Register_IRQ(IRQn_Type IRQn, uint8_t shv, ECLIC_TRIGGER_Type trig_mode, uint8_t lvl, uint8_t priority, void* handler);
#ifdef __cplusplus
}
#endif
#endif /* __SYSTEM_GD32VF103_H__ */

View File

@ -0,0 +1,14 @@
menuconfig BSP_USING_UART4
bool "Enable UART4"
default y
if BSP_USING_UART4
config SERIAL_BUS_NAME_4
string "serial bus name"
default "uart4"
config SERIAL_DRV_NAME_4
string "serial bus driver name"
default "uart4_drv"
config SERIAL_4_DEVICE_NAME_4
string "serial bus device name"
default "uart4_dev4"
endif

View File

@ -0,0 +1,4 @@
SRC_FILES := connect_uart.c gd32vf103_usart.c
include $(KERNEL_ROOT)/compiler.mk

View File

@ -0,0 +1,378 @@
/*
* 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 connect_usart.c
* @brief support gap8-board uart function and register to bus framework
* @version 1.1
* @author AIIT XUOS Lab
* @date 2021-09-02
*/
#include <xiuos.h>
#include <device.h>
#include "connect_uart.h"
#include "gd32vf103_usart.h"
#include "gd32vf103.h"
#include <board.h>
static void SerialCfgParamCheck(struct SerialCfgParam *serial_cfg_default, struct SerialCfgParam *serial_cfg_new)
{
struct SerialDataCfg *data_cfg_default = &serial_cfg_default->data_cfg;
struct SerialDataCfg *data_cfg_new = &serial_cfg_new->data_cfg;
if ((data_cfg_default->serial_baud_rate != data_cfg_new->serial_baud_rate) && (data_cfg_new->serial_baud_rate)) {
data_cfg_default->serial_baud_rate = data_cfg_new->serial_baud_rate;
}
if ((data_cfg_default->serial_bit_order != data_cfg_new->serial_bit_order) && (data_cfg_new->serial_bit_order)) {
data_cfg_default->serial_bit_order = data_cfg_new->serial_bit_order;
}
if ((data_cfg_default->serial_buffer_size != data_cfg_new->serial_buffer_size) && (data_cfg_new->serial_buffer_size)) {
data_cfg_default->serial_buffer_size = data_cfg_new->serial_buffer_size;
}
if ((data_cfg_default->serial_data_bits != data_cfg_new->serial_data_bits) && (data_cfg_new->serial_data_bits)) {
data_cfg_default->serial_data_bits = data_cfg_new->serial_data_bits;
}
if ((data_cfg_default->serial_invert_mode != data_cfg_new->serial_invert_mode) && (data_cfg_new->serial_invert_mode)) {
data_cfg_default->serial_invert_mode = data_cfg_new->serial_invert_mode;
}
if ((data_cfg_default->serial_parity_mode != data_cfg_new->serial_parity_mode) && (data_cfg_new->serial_parity_mode)) {
data_cfg_default->serial_parity_mode = data_cfg_new->serial_parity_mode;
}
if ((data_cfg_default->serial_stop_bits != data_cfg_new->serial_stop_bits) && (data_cfg_new->serial_stop_bits)) {
data_cfg_default->serial_stop_bits = data_cfg_new->serial_stop_bits;
}
}
static void UartIsr(struct SerialDriver *serial_drv, struct SerialHardwareDevice *serial_dev)
{
struct SerialCfgParam *serial_cfg = (struct SerialCfgParam *)serial_drv->private_data;
if ((usart_interrupt_flag_get(serial_cfg->hw_cfg.serial_register_base, USART_INT_FLAG_RBNE)
!= RESET)
&& (RESET != usart_flag_get(serial_cfg->hw_cfg.serial_register_base, USART_FLAG_RBNE)))
{
SerialSetIsr(serial_dev, SERIAL_EVENT_RX_IND);
usart_interrupt_flag_clear(serial_cfg->hw_cfg.serial_register_base, USART_INT_FLAG_RBNE);
usart_flag_clear(serial_cfg->hw_cfg.serial_register_base, USART_FLAG_RBNE);
}
else
{
if (usart_flag_get(serial_cfg->hw_cfg.serial_register_base, USART_FLAG_CTSF) != RESET)
{
usart_flag_clear(serial_cfg->hw_cfg.serial_register_base, USART_FLAG_CTSF);
}
if (usart_flag_get(serial_cfg->hw_cfg.serial_register_base, USART_FLAG_LBDF) != RESET)
{
usart_flag_clear(serial_cfg->hw_cfg.serial_register_base, USART_FLAG_LBDF);
}
if (usart_flag_get(serial_cfg->hw_cfg.serial_register_base, USART_FLAG_TC) != RESET)
{
usart_flag_clear(serial_cfg->hw_cfg.serial_register_base, USART_FLAG_TC);
}
}
}
static uint32 SerialInit(struct SerialDriver *serial_drv, struct BusConfigureInfo *configure_info)
{
NULL_PARAM_CHECK(serial_drv);
struct SerialCfgParam *serial_cfg = (struct SerialCfgParam *)serial_drv->private_data;
// struct UsartHwCfg *serial_hw_cfg = (struct UsartHwCfg *)serial_cfg->hw_cfg.private_data;
usart_deinit(serial_cfg->hw_cfg.serial_register_base);
usart_baudrate_set(serial_cfg->hw_cfg.serial_register_base, serial_cfg->data_cfg.serial_baud_rate);
switch (serial_cfg->data_cfg.serial_data_bits)
{
case DATA_BITS_8:
usart_word_length_set(serial_cfg->hw_cfg.serial_register_base, USART_WL_8BIT);
break;
case DATA_BITS_9:
usart_word_length_set(serial_cfg->hw_cfg.serial_register_base, USART_WL_9BIT);
break;
default:
usart_word_length_set(serial_cfg->hw_cfg.serial_register_base, USART_WL_8BIT);
break;
}
switch (serial_cfg->data_cfg.serial_stop_bits)
{
case STOP_BITS_1:
usart_stop_bit_set(serial_cfg->hw_cfg.serial_register_base, USART_STB_1BIT);
break;
case STOP_BITS_2:
usart_stop_bit_set(serial_cfg->hw_cfg.serial_register_base, USART_STB_2BIT);
break;
default:
usart_stop_bit_set(serial_cfg->hw_cfg.serial_register_base, USART_STB_1BIT);
break;
}
switch (serial_cfg->data_cfg.serial_parity_mode)
{
case PARITY_NONE:
usart_parity_config(serial_cfg->hw_cfg.serial_register_base, USART_PM_NONE);
break;
case PARITY_ODD:
usart_parity_config(serial_cfg->hw_cfg.serial_register_base, USART_PM_ODD);
break;
case PARITY_EVEN:
usart_parity_config(serial_cfg->hw_cfg.serial_register_base, USART_PM_EVEN);
break;
default:
usart_parity_config(serial_cfg->hw_cfg.serial_register_base, USART_PM_NONE);
break;
}
usart_hardware_flow_rts_config(serial_cfg->hw_cfg.serial_register_base, USART_RTS_DISABLE);
usart_hardware_flow_cts_config(serial_cfg->hw_cfg.serial_register_base, USART_CTS_DISABLE);
usart_receive_config(serial_cfg->hw_cfg.serial_register_base, USART_RECEIVE_ENABLE);
usart_transmit_config(serial_cfg->hw_cfg.serial_register_base, USART_TRANSMIT_ENABLE);
usart_enable(serial_cfg->hw_cfg.serial_register_base);
return EOK;
}
static uint32 SerialConfigure(struct SerialDriver *serial_drv, int serial_operation_cmd)
{
NULL_PARAM_CHECK(serial_drv);
struct SerialCfgParam *serial_cfg = (struct SerialCfgParam *)serial_drv->private_data;
switch (serial_operation_cmd)
{
case OPER_CLR_INT:
ECLIC_DisableIRQ(serial_cfg->hw_cfg.serial_irq_interrupt);
usart_interrupt_disable(serial_cfg->hw_cfg.serial_register_base, USART_INT_RBNE);
break;
case OPER_SET_INT:
ECLIC_EnableIRQ(serial_cfg->hw_cfg.serial_irq_interrupt);
/* enable USART0 receive interrupt */
usart_interrupt_enable(serial_cfg->hw_cfg.serial_register_base, USART_INT_RBNE);
break;
}
return EOK;
}
static uint32 SerialDrvConfigure(void *drv, struct BusConfigureInfo *configure_info)
{
NULL_PARAM_CHECK(drv);
NULL_PARAM_CHECK(configure_info);
x_err_t ret = EOK;
int serial_operation_cmd;
struct SerialDriver *serial_drv = (struct SerialDriver *)drv;
switch (configure_info->configure_cmd)
{
case OPE_INT:
ret = SerialInit(serial_drv, configure_info);
break;
case OPE_CFG:
serial_operation_cmd = *(int *)configure_info->private_data;
ret = SerialConfigure(serial_drv, serial_operation_cmd);
break;
default:
break;
}
return ret;
}
static int SerialPutChar(struct SerialHardwareDevice *serial_dev, char c)
{
struct SerialCfgParam *serial_cfg = (struct SerialCfgParam *)serial_dev->private_data;
// struct UsartHwCfg *serial_hw_cfg = (struct UsartHwCfg *)serial_cfg->hw_cfg.private_data;
usart_data_transmit(serial_cfg->hw_cfg.serial_register_base, (uint8_t) c);
while (usart_flag_get(serial_cfg->hw_cfg.serial_register_base, USART_FLAG_TBE) == RESET);
return 0;
}
static int SerialGetChar(struct SerialHardwareDevice *serial_dev)
{
char ch = -1;
struct SerialCfgParam *serial_cfg = (struct SerialCfgParam *)serial_dev->private_data;
// struct UsartHwCfg *serial_hw_cfg = (struct UsartHwCfg *)serial_cfg->hw_cfg.private_data;
if (RESET != usart_flag_get(serial_cfg->hw_cfg.serial_register_base, USART_FLAG_RBNE))
{
ch = usart_data_receive(serial_cfg->hw_cfg.serial_register_base) & 0xff;
}
return ch;
}
static const struct SerialDataCfg data_cfg_init =
{
.serial_baud_rate = BAUD_RATE_115200,
.serial_data_bits = DATA_BITS_8,
.serial_stop_bits = STOP_BITS_1,
.serial_parity_mode = PARITY_NONE,
.serial_bit_order = BIT_ORDER_LSB,
.serial_invert_mode = NRZ_NORMAL,
.serial_buffer_size = SERIAL_RB_BUFSZ,
};
/*manage the serial device operations*/
static const struct SerialDrvDone drv_done =
{
.init = SerialInit,
.configure = SerialConfigure,
};
/*manage the serial device hal operations*/
static struct SerialHwDevDone hwdev_done =
{
.put_char = SerialPutChar,
.get_char = SerialGetChar,
};
static int BoardSerialBusInit(struct SerialBus *serial_bus, struct SerialDriver *serial_driver, const char *bus_name, const char *drv_name)
{
x_err_t ret = EOK;
/*Init the serial bus */
ret = SerialBusInit(serial_bus, bus_name);
if (EOK != ret) {
KPrintf("InitHwUart SerialBusInit error %d\n", ret);
return ERROR;
}
/*Init the serial driver*/
ret = SerialDriverInit(serial_driver, drv_name);
if (EOK != ret) {
KPrintf("InitHwUart SerialDriverInit error %d\n", ret);
return ERROR;
}
/*Attach the serial driver to the serial bus*/
ret = SerialDriverAttachToBus(drv_name, bus_name);
if (EOK != ret) {
KPrintf("InitHwUart SerialDriverAttachToBus error %d\n", ret);
return ERROR;
}
return ret;
}
/*Attach the serial device to the serial bus*/
static int BoardSerialDevBend(struct SerialHardwareDevice *serial_device, void *serial_param, const char *bus_name, const char *dev_name)
{
x_err_t ret = EOK;
ret = SerialDeviceRegister(serial_device, serial_param, dev_name);
if (EOK != ret) {
KPrintf("InitHwUart SerialDeviceInit device %s error %d\n", dev_name, ret);
return ERROR;
}
ret = SerialDeviceAttachToBus(dev_name, bus_name);
if (EOK != ret) {
KPrintf("InitHwUart SerialDeviceAttachToBus device %s error %d\n", dev_name, ret);
return ERROR;
}
return ret;
}
#ifdef BSP_USING_UART4
struct SerialDriver serial_driver_4;
struct SerialHardwareDevice serial_device_4;
void UART4_IRQHandler(int irq_num, void *arg)
{
UartIsr(&serial_driver_4, &serial_device_4);
}
// DECLARE_HW_IRQ(UART4_IRQn, UART4_IRQHandler, NONE);
#endif
int InitHwUart(void)
{
x_err_t ret = EOK;
// #ifdef BSP_USING_UART0
// rcu_periph_clock_enable(RCU_USART0);
// #endif
// #ifdef BSP_USING_UART1
// rcu_periph_clock_enable(RCU_USART1);
// #endif
// #ifdef BSP_USING_UART2
// rcu_periph_clock_enable(RCU_USART2);
// #endif
// #ifdef BSP_USING_UART3
// rcu_periph_clock_enable(RCU_UART3);
// #endif
#ifdef BSP_USING_UART4
rcu_periph_clock_enable(RCU_UART4);
#endif
#ifdef BSP_USING_UART4
static struct SerialBus serial_bus;
memset(&serial_bus, 0, sizeof(struct SerialBus));
memset(&serial_driver_4, 0, sizeof(struct SerialDriver));
memset(&serial_device_4, 0, sizeof(struct SerialHardwareDevice));
static struct SerialCfgParam serial_cfg;
memset(&serial_cfg, 0, sizeof(struct SerialCfgParam));
static struct SerialDevParam serial_dev_param;
memset(&serial_dev_param, 0, sizeof(struct SerialDevParam));
serial_driver_4.drv_done = &drv_done;
serial_driver_4.configure = &SerialDrvConfigure;
serial_device_4.hwdev_done = &hwdev_done;
serial_cfg.data_cfg = data_cfg_init;
serial_cfg.hw_cfg.serial_register_base = UART4;
serial_cfg.hw_cfg.serial_irq_interrupt = UART4_IRQn;
serial_driver_4.private_data = (void *)&serial_cfg;
serial_dev_param.serial_work_mode = SIGN_OPER_INT_RX;
serial_device_4.haldev.private_data = (void *)&serial_dev_param;
ret = BoardSerialBusInit(&serial_bus, &serial_driver_4, SERIAL_BUS_NAME_4, SERIAL_DRV_NAME_4);
if (EOK != ret) {
KPrintf("InitHwUart uarths error ret %u\n", ret);
return ERROR;
}
ret = BoardSerialDevBend(&serial_device_4, (void *)&serial_cfg, SERIAL_BUS_NAME_4, SERIAL_4_DEVICE_NAME_4);
if (EOK != ret) {
KPrintf("InitHwUart uarths error ret %u\n", ret);
return ERROR;
}
#endif
return ret;
}

View File

@ -0,0 +1,781 @@
/*!
\file gd32vf103_usart.c
\brief USART driver
\version 2019-6-5, V1.0.0, firmware for GD32VF103
*/
/*
Copyright (c) 2019, GigaDevice Semiconductor Inc.
Redistribution and use in source and binary forms, with or without modification,
are permitted provided that the following conditions are met:
1. Redistributions of source code must retain the above copyright notice, this
list of conditions and the following disclaimer.
2. Redistributions in binary form must reproduce the above copyright notice,
this list of conditions and the following disclaimer in the documentation
and/or other materials provided with the distribution.
3. Neither the name of the copyright holder nor the names of its contributors
may be used to endorse or promote products derived from this software without
specific prior written permission.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED.
IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT,
INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT
NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY
OF SUCH DAMAGE.
*/
#include "gd32vf103_usart.h"
/*!
\brief reset USART/UART
\param[in] usart_periph: USARTx(x=0,1,2)/UARTx(x=3,4)
\param[out] none
\retval none
*/
void usart_deinit(uint32_t usart_periph)
{
switch (usart_periph) {
case USART0:
/* reset USART0 */
rcu_periph_reset_enable(RCU_USART0RST);
rcu_periph_reset_disable(RCU_USART0RST);
break;
case USART1:
/* reset USART1 */
rcu_periph_reset_enable(RCU_USART1RST);
rcu_periph_reset_disable(RCU_USART1RST);
break;
case USART2:
/* reset USART2 */
rcu_periph_reset_enable(RCU_USART2RST);
rcu_periph_reset_disable(RCU_USART2RST);
break;
case UART3:
/* reset UART3 */
rcu_periph_reset_enable(RCU_UART3RST);
rcu_periph_reset_disable(RCU_UART3RST);
break;
case UART4:
/* reset UART4 */
rcu_periph_reset_enable(RCU_UART4RST);
rcu_periph_reset_disable(RCU_UART4RST);
break;
default:
break;
}
}
/*!
\brief configure USART baud rate value
\param[in] usart_periph: USARTx(x=0,1,2)/UARTx(x=3,4)
\param[in] baudval: baud rate value
\param[out] none
\retval none
*/
void usart_baudrate_set(uint32_t usart_periph, uint32_t baudval)
{
uint32_t uclk = 0U, intdiv = 0U, fradiv = 0U, udiv = 0U;
switch (usart_periph) {
/* get clock frequency */
case USART0:
/* get USART0 clock */
uclk = rcu_clock_freq_get(CK_APB2);
break;
case USART1:
/* get USART1 clock */
uclk = rcu_clock_freq_get(CK_APB1);
break;
case USART2:
/* get USART2 clock */
uclk = rcu_clock_freq_get(CK_APB1);
break;
case UART3:
/* get UART3 clock */
uclk = rcu_clock_freq_get(CK_APB1);
break;
case UART4:
/* get UART4 clock */
uclk = rcu_clock_freq_get(CK_APB1);
break;
default:
break;
}
/* oversampling by 16, configure the value of USART_BAUD */
udiv = (uclk + baudval / 2U) / baudval;
intdiv = udiv & (0x0000fff0U);
fradiv = udiv & (0x0000000fU);
USART_BAUD(usart_periph) = ((USART_BAUD_FRADIV | USART_BAUD_INTDIV) & (intdiv | fradiv));
}
/*!
\brief configure USART parity
\param[in] usart_periph: USARTx(x=0,1,2)/UARTx(x=3,4)
\param[in] paritycfg: configure USART parity
only one parameter can be selected which is shown as below:
\arg USART_PM_NONE: no parity
\arg USART_PM_ODD: odd parity
\arg USART_PM_EVEN: even parity
\param[out] none
\retval none
*/
void usart_parity_config(uint32_t usart_periph, uint32_t paritycfg)
{
/* clear USART_CTL0 PM,PCEN bits */
USART_CTL0(usart_periph) &= ~(USART_CTL0_PM | USART_CTL0_PCEN);
/* configure USART parity mode */
USART_CTL0(usart_periph) |= paritycfg ;
}
/*!
\brief configure USART word length
\param[in] usart_periph: USARTx(x=0,1,2)/UARTx(x=3,4)
\param[in] wlen: USART word length configure
only one parameter can be selected which is shown as below:
\arg USART_WL_8BIT: 8 bits
\arg USART_WL_9BIT: 9 bits
\param[out] none
\retval none
*/
void usart_word_length_set(uint32_t usart_periph, uint32_t wlen)
{
/* clear USART_CTL0 WL bit */
USART_CTL0(usart_periph) &= ~USART_CTL0_WL;
/* configure USART word length */
USART_CTL0(usart_periph) |= wlen;
}
/*!
\brief configure USART stop bit length
\param[in] usart_periph: USARTx(x=0,1,2)/UARTx(x=3,4)
\param[in] stblen: USART stop bit configure
only one parameter can be selected which is shown as below:
\arg USART_STB_1BIT: 1 bit
\arg USART_STB_0_5BIT: 0.5 bit, not available for UARTx(x=3,4)
\arg USART_STB_2BIT: 2 bits
\arg USART_STB_1_5BIT: 1.5 bits, not available for UARTx(x=3,4)
\param[out] none
\retval none
*/
void usart_stop_bit_set(uint32_t usart_periph, uint32_t stblen)
{
/* clear USART_CTL1 STB bits */
USART_CTL1(usart_periph) &= ~USART_CTL1_STB;
/* configure USART stop bits */
USART_CTL1(usart_periph) |= stblen;
}
/*!
\brief enable USART
\param[in] usart_periph: USARTx(x=0,1,2)/UARTx(x=3,4)
\param[out] none
\retval none
*/
void usart_enable(uint32_t usart_periph)
{
USART_CTL0(usart_periph) |= USART_CTL0_UEN;
}
/*!
\brief disable USART
\param[in] usart_periph: USARTx(x=0,1,2)/UARTx(x=3,4)
\param[out] none
\retval none
*/
void usart_disable(uint32_t usart_periph)
{
USART_CTL0(usart_periph) &= ~(USART_CTL0_UEN);
}
/*!
\brief configure USART transmitter
\param[in] usart_periph: USARTx(x=0,1,2)/UARTx(x=3,4)
\param[in] txconfig: enable or disable USART transmitter
only one parameter can be selected which is shown as below:
\arg USART_TRANSMIT_ENABLE: enable USART transmission
\arg USART_TRANSMIT_DISABLE: disable USART transmission
\param[out] none
\retval none
*/
void usart_transmit_config(uint32_t usart_periph, uint32_t txconfig)
{
uint32_t ctl = 0U;
ctl = USART_CTL0(usart_periph);
ctl &= ~USART_CTL0_TEN;
ctl |= txconfig;
/* configure transfer mode */
USART_CTL0(usart_periph) = ctl;
}
/*!
\brief configure USART receiver
\param[in] usart_periph: USARTx(x=0,1,2)/UARTx(x=3,4)
\param[in] rxconfig: enable or disable USART receiver
only one parameter can be selected which is shown as below:
\arg USART_RECEIVE_ENABLE: enable USART reception
\arg USART_RECEIVE_DISABLE: disable USART reception
\param[out] none
\retval none
*/
void usart_receive_config(uint32_t usart_periph, uint32_t rxconfig)
{
uint32_t ctl = 0U;
ctl = USART_CTL0(usart_periph);
ctl &= ~USART_CTL0_REN;
ctl |= rxconfig;
/* configure receiver mode */
USART_CTL0(usart_periph) = ctl;
}
/*!
\brief USART transmit data function
\param[in] usart_periph: USARTx(x=0,1,2)/UARTx(x=3,4)
\param[in] data: data of transmission
\param[out] none
\retval none
*/
void usart_data_transmit(uint32_t usart_periph, uint32_t data)
{
USART_DATA(usart_periph) = USART_DATA_DATA & data;
}
/*!
\brief USART receive data function
\param[in] usart_periph: USARTx(x=0,1,2)/UARTx(x=3,4)
\param[out] none
\retval data of received
*/
uint16_t usart_data_receive(uint32_t usart_periph)
{
return (uint16_t)(GET_BITS(USART_DATA(usart_periph), 0U, 8U));
}
/*!
\brief configure the address of the USART in wake up by address match mode
\param[in] usart_periph: USARTx(x=0,1,2)/UARTx(x=3,4)
\param[in] addr: address of USART/UART
\param[out] none
\retval none
*/
void usart_address_config(uint32_t usart_periph, uint8_t addr)
{
USART_CTL1(usart_periph) &= ~(USART_CTL1_ADDR);
USART_CTL1(usart_periph) |= (USART_CTL1_ADDR & addr);
}
/*!
\brief receiver in mute mode
\param[in] usart_periph: USARTx(x=0,1,2)/UARTx(x=3,4)
\param[out] none
\retval none
*/
void usart_mute_mode_enable(uint32_t usart_periph)
{
USART_CTL0(usart_periph) |= USART_CTL0_RWU;
}
/*!
\brief receiver in active mode
\param[in] usart_periph: USARTx(x=0,1,2)/UARTx(x=3,4)
\param[out] none
\retval none
*/
void usart_mute_mode_disable(uint32_t usart_periph)
{
USART_CTL0(usart_periph) &= ~(USART_CTL0_RWU);
}
/*!
\brief configure wakeup method in mute mode
\param[in] usart_periph: USARTx(x=0,1,2)/UARTx(x=3,4)
\param[in] wmethod: two methods be used to enter or exit the mute mode
only one parameter can be selected which is shown as below:
\arg USART_WM_IDLE: idle line
\arg USART_WM_ADDR: address mask
\param[out] none
\retval none
*/
void usart_mute_mode_wakeup_config(uint32_t usart_periph, uint32_t wmethod)
{
USART_CTL0(usart_periph) &= ~(USART_CTL0_WM);
USART_CTL0(usart_periph) |= wmethod;
}
/*!
\brief enable LIN mode
\param[in] usart_periph: USARTx(x=0,1,2)/UARTx(x=3,4)
\param[out] none
\retval none
*/
void usart_lin_mode_enable(uint32_t usart_periph)
{
USART_CTL1(usart_periph) |= USART_CTL1_LMEN;
}
/*!
\brief disable LIN mode
\param[in] usart_periph: USARTx(x=0,1,2)/UARTx(x=3,4)
\param[out] none
\retval none
*/
void usart_lin_mode_disable(uint32_t usart_periph)
{
USART_CTL1(usart_periph) &= ~(USART_CTL1_LMEN);
}
/*!
\brief configure lin break frame length
\param[in] usart_periph: USARTx(x=0,1,2)/UARTx(x=3,4)
\param[in] lblen: lin break frame length
only one parameter can be selected which is shown as below:
\arg USART_LBLEN_10B: 10 bits
\arg USART_LBLEN_11B: 11 bits
\param[out] none
\retval none
*/
void usart_lin_break_detection_length_config(uint32_t usart_periph, uint32_t lblen)
{
USART_CTL1(usart_periph) &= ~(USART_CTL1_LBLEN);
USART_CTL1(usart_periph) |= (USART_CTL1_LBLEN & lblen);
}
/*!
\brief send break frame
\param[in] usart_periph: USARTx(x=0,1,2)/UARTx(x=3,4)
\param[out] none
\retval none
*/
void usart_send_break(uint32_t usart_periph)
{
USART_CTL0(usart_periph) |= USART_CTL0_SBKCMD;
}
/*!
\brief enable half duplex mode
\param[in] usart_periph: USARTx(x=0,1,2)/UARTx(x=3,4)
\param[out] none
\retval none
*/
void usart_halfduplex_enable(uint32_t usart_periph)
{
USART_CTL2(usart_periph) |= USART_CTL2_HDEN;
}
/*!
\brief disable half duplex mode
\param[in] usart_periph: USARTx(x=0,1,2)/UARTx(x=3,4)
\param[out] none
\retval none
*/
void usart_halfduplex_disable(uint32_t usart_periph)
{
USART_CTL2(usart_periph) &= ~(USART_CTL2_HDEN);
}
/*!
\brief enable CK pin in synchronous mode
\param[in] usart_periph: USARTx(x=0,1,2)
\param[out] none
\retval none
*/
void usart_synchronous_clock_enable(uint32_t usart_periph)
{
USART_CTL1(usart_periph) |= USART_CTL1_CKEN;
}
/*!
\brief disable CK pin in synchronous mode
\param[in] usart_periph: USARTx(x=0,1,2)
\param[out] none
\retval none
*/
void usart_synchronous_clock_disable(uint32_t usart_periph)
{
USART_CTL1(usart_periph) &= ~(USART_CTL1_CKEN);
}
/*!
\brief configure USART synchronous mode parameters
\param[in] usart_periph: USARTx(x=0,1,2)
\param[in] clen: CK length
only one parameter can be selected which is shown as below:
\arg USART_CLEN_NONE: there are 7 CK pulses for an 8 bit frame and 8 CK pulses for a 9 bit frame
\arg USART_CLEN_EN: there are 8 CK pulses for an 8 bit frame and 9 CK pulses for a 9 bit frame
\param[in] cph: clock phase
only one parameter can be selected which is shown as below:
\arg USART_CPH_1CK: first clock transition is the first data capture edge
\arg USART_CPH_2CK: second clock transition is the first data capture edge
\param[in] cpl: clock polarity
only one parameter can be selected which is shown as below:
\arg USART_CPL_LOW: steady low value on CK pin
\arg USART_CPL_HIGH: steady high value on CK pin
\param[out] none
\retval none
*/
void usart_synchronous_clock_config(uint32_t usart_periph, uint32_t clen, uint32_t cph, uint32_t cpl)
{
uint32_t ctl = 0U;
/* read USART_CTL1 register */
ctl = USART_CTL1(usart_periph);
ctl &= ~(USART_CTL1_CLEN | USART_CTL1_CPH | USART_CTL1_CPL);
/* set CK length, CK phase, CK polarity */
ctl |= (USART_CTL1_CLEN & clen) | (USART_CTL1_CPH & cph) | (USART_CTL1_CPL & cpl);
USART_CTL1(usart_periph) = ctl;
}
/*!
\brief configure guard time value in smartcard mode
\param[in] usart_periph: USARTx(x=0,1,2)
\param[in] gaut: guard time value
\param[out] none
\retval none
*/
void usart_guard_time_config(uint32_t usart_periph, uint32_t gaut)
{
USART_GP(usart_periph) &= ~(USART_GP_GUAT);
USART_GP(usart_periph) |= (USART_GP_GUAT & ((gaut) << 8));
}
/*!
\brief enable smartcard mode
\param[in] usart_periph: USARTx(x=0,1,2)
\param[out] none
\retval none
*/
void usart_smartcard_mode_enable(uint32_t usart_periph)
{
USART_CTL2(usart_periph) |= USART_CTL2_SCEN;
}
/*!
\brief disable smartcard mode
\param[in] usart_periph: USARTx(x=0,1,2)
\param[out] none
\retval none
*/
void usart_smartcard_mode_disable(uint32_t usart_periph)
{
USART_CTL2(usart_periph) &= ~(USART_CTL2_SCEN);
}
/*!
\brief enable NACK in smartcard mode
\param[in] usart_periph: USARTx(x=0,1,2)
\param[out] none
\retval none
*/
void usart_smartcard_mode_nack_enable(uint32_t usart_periph)
{
USART_CTL2(usart_periph) |= USART_CTL2_NKEN;
}
/*!
\brief disable NACK in smartcard mode
\param[in] usart_periph: USARTx(x=0,1,2)
\param[out] none
\retval none
*/
void usart_smartcard_mode_nack_disable(uint32_t usart_periph)
{
USART_CTL2(usart_periph) &= ~(USART_CTL2_NKEN);
}
/*!
\brief enable IrDA mode
\param[in] usart_periph: USARTx(x=0,1,2)/UARTx(x=3,4)
\param[out] none
\retval none
*/
void usart_irda_mode_enable(uint32_t usart_periph)
{
USART_CTL2(usart_periph) |= USART_CTL2_IREN;
}
/*!
\brief disable IrDA mode
\param[in] usart_periph: USARTx(x=0,1,2)/UARTx(x=3,4)
\param[out] none
\retval none
*/
void usart_irda_mode_disable(uint32_t usart_periph)
{
USART_CTL2(usart_periph) &= ~(USART_CTL2_IREN);
}
/*!
\brief configure the peripheral clock prescaler in USART IrDA low-power mode
\param[in] usart_periph: USARTx(x=0,1,2)/UARTx(x=3,4)
\param[in] psc: 0x00-0xFF
\param[out] none
\retval none
*/
void usart_prescaler_config(uint32_t usart_periph, uint8_t psc)
{
USART_GP(usart_periph) &= ~(USART_GP_PSC);
USART_GP(usart_periph) |= psc;
}
/*!
\brief configure IrDA low-power
\param[in] usart_periph: USARTx(x=0,1,2)/UARTx(x=3,4)
\param[in] irlp: IrDA low-power or normal
only one parameter can be selected which is shown as below:
\arg USART_IRLP_LOW: low-power
\arg USART_IRLP_NORMAL: normal
\param[out] none
\retval none
*/
void usart_irda_lowpower_config(uint32_t usart_periph, uint32_t irlp)
{
USART_CTL2(usart_periph) &= ~(USART_CTL2_IRLP);
USART_CTL2(usart_periph) |= (USART_CTL2_IRLP & irlp);
}
/*!
\brief configure hardware flow control RTS
\param[in] usart_periph: USARTx(x=0,1,2)
\param[in] rtsconfig: enable or disable RTS
only one parameter can be selected which is shown as below:
\arg USART_RTS_ENABLE: enable RTS
\arg USART_RTS_DISABLE: disable RTS
\param[out] none
\retval none
*/
void usart_hardware_flow_rts_config(uint32_t usart_periph, uint32_t rtsconfig)
{
uint32_t ctl = 0U;
ctl = USART_CTL2(usart_periph);
ctl &= ~USART_CTL2_RTSEN;
ctl |= rtsconfig;
/* configure RTS */
USART_CTL2(usart_periph) = ctl;
}
/*!
\brief configure hardware flow control CTS
\param[in] usart_periph: USARTx(x=0,1,2)
\param[in] ctsconfig: enable or disable CTS
only one parameter can be selected which is shown as below:
\arg USART_CTS_ENABLE: enable CTS
\arg USART_CTS_DISABLE: disable CTS
\param[out] none
\retval none
*/
void usart_hardware_flow_cts_config(uint32_t usart_periph, uint32_t ctsconfig)
{
uint32_t ctl = 0U;
ctl = USART_CTL2(usart_periph);
ctl &= ~USART_CTL2_CTSEN;
ctl |= ctsconfig;
/* configure CTS */
USART_CTL2(usart_periph) = ctl;
}
/*!
\brief configure USART DMA reception
\param[in] usart_periph: USARTx(x=0,1,2)/UARTx(x=3)
\param[in] dmacmd: enable or disable DMA for reception
only one parameter can be selected which is shown as below:
\arg USART_DENR_ENABLE: DMA enable for reception
\arg USART_DENR_DISABLE: DMA disable for reception
\param[out] none
\retval none
*/
void usart_dma_receive_config(uint32_t usart_periph, uint32_t dmacmd)
{
uint32_t ctl = 0U;
ctl = USART_CTL2(usart_periph);
ctl &= ~USART_CTL2_DENR;
ctl |= dmacmd;
/* configure DMA reception */
USART_CTL2(usart_periph) = ctl;
}
/*!
\brief configure USART DMA transmission
\param[in] usart_periph: USARTx(x=0,1,2)/UARTx(x=3)
\param[in] dmacmd: enable or disable DMA for transmission
only one parameter can be selected which is shown as below:
\arg USART_DENT_ENABLE: DMA enable for transmission
\arg USART_DENT_DISABLE: DMA disable for transmission
\param[out] none
\retval none
*/
void usart_dma_transmit_config(uint32_t usart_periph, uint32_t dmacmd)
{
uint32_t ctl = 0U;
ctl = USART_CTL2(usart_periph);
ctl &= ~USART_CTL2_DENT;
ctl |= dmacmd;
/* configure DMA transmission */
USART_CTL2(usart_periph) = ctl;
}
/*!
\brief get flag in STAT register
\param[in] usart_periph: USARTx(x=0,1,2)/UARTx(x=3,4)
\param[in] flag: USART flags, refer to usart_flag_enum
only one parameter can be selected which is shown as below:
\arg USART_FLAG_CTSF: CTS change flag
\arg USART_FLAG_LBDF: LIN break detected flag
\arg USART_FLAG_TBE: transmit data buffer empty
\arg USART_FLAG_TC: transmission complete
\arg USART_FLAG_RBNE: read data buffer not empty
\arg USART_FLAG_IDLEF: IDLE frame detected flag
\arg USART_FLAG_ORERR: overrun error
\arg USART_FLAG_NERR: noise error flag
\arg USART_FLAG_FERR: frame error flag
\arg USART_FLAG_PERR: parity error flag
\param[out] none
\retval FlagStatus: SET or RESET
*/
FlagStatus usart_flag_get(uint32_t usart_periph, usart_flag_enum flag)
{
if (RESET != (USART_REG_VAL(usart_periph, flag) & BIT(USART_BIT_POS(flag)))) {
return SET;
} else {
return RESET;
}
}
/*!
\brief clear flag in STAT register
\param[in] usart_periph: USARTx(x=0,1,2)/UARTx(x=3,4)
\param[in] flag: USART flags, refer to usart_flag_enum
only one parameter can be selected which is shown as below:
\arg USART_FLAG_CTSF: CTS change flag
\arg USART_FLAG_LBDF: LIN break detected flag
\arg USART_FLAG_TC: transmission complete
\arg USART_FLAG_RBNE: read data buffer not empty
\param[out] none
\retval none
*/
void usart_flag_clear(uint32_t usart_periph, usart_flag_enum flag)
{
USART_REG_VAL(usart_periph, flag) &= ~BIT(USART_BIT_POS(flag));
}
/*!
\brief enable USART interrupt
\param[in] usart_periph: USARTx(x=0,1,2)/UARTx(x=3,4)
\param[in] int_flag
only one parameter can be selected which is shown as below:
\arg USART_INT_PERR: parity error interrupt
\arg USART_INT_TBE: transmitter buffer empty interrupt
\arg USART_INT_TC: transmission complete interrupt
\arg USART_INT_RBNE: read data buffer not empty interrupt and overrun error interrupt
\arg USART_INT_IDLE: IDLE line detected interrupt
\arg USART_INT_LBD: LIN break detected interrupt
\arg USART_INT_ERR: error interrupt
\arg USART_INT_CTS: CTS interrupt
\param[out] none
\retval none
*/
void usart_interrupt_enable(uint32_t usart_periph, uint32_t int_flag)
{
USART_REG_VAL(usart_periph, int_flag) |= BIT(USART_BIT_POS(int_flag));
}
/*!
\brief disable USART interrupt
\param[in] usart_periph: USARTx(x=0,1,2)/UARTx(x=3,4)
\param[in] int_flag
only one parameter can be selected which is shown as below:
\arg USART_INT_PERR: parity error interrupt
\arg USART_INT_TBE: transmitter buffer empty interrupt
\arg USART_INT_TC: transmission complete interrupt
\arg USART_INT_RBNE: read data buffer not empty interrupt and overrun error interrupt
\arg USART_INT_IDLE: IDLE line detected interrupt
\arg USART_INT_LBD: LIN break detected interrupt
\arg USART_INT_ERR: error interrupt
\arg USART_INT_CTS: CTS interrupt
\param[out] none
\retval none
*/
void usart_interrupt_disable(uint32_t usart_periph, uint32_t int_flag)
{
USART_REG_VAL(usart_periph, int_flag) &= ~BIT(USART_BIT_POS(int_flag));
}
/*!
\brief get USART interrupt and flag status
\param[in] usart_periph: USARTx(x=0,1,2)/UARTx(x=3,4)
\param[in] int_flag
only one parameter can be selected which is shown as below:
\arg USART_INT_FLAG_PERR: parity error interrupt and flag
\arg USART_INT_FLAG_TBE: transmitter buffer empty interrupt and flag
\arg USART_INT_FLAG_TC: transmission complete interrupt and flag
\arg USART_INT_FLAG_RBNE: read data buffer not empty interrupt and flag
\arg USART_INT_FLAG_RBNE_ORERR: read data buffer not empty interrupt and overrun error flag
\arg USART_INT_FLAG_IDLE: IDLE line detected interrupt and flag
\arg USART_INT_FLAG_LBD: LIN break detected interrupt and flag
\arg USART_INT_FLAG_CTS: CTS interrupt and flag
\arg USART_INT_FLAG_ERR_ORERR: error interrupt and overrun error
\arg USART_INT_FLAG_ERR_NERR: error interrupt and noise error flag
\arg USART_INT_FLAG_ERR_FERR: error interrupt and frame error flag
\param[out] none
\retval FlagStatus: SET or RESET
*/
FlagStatus usart_interrupt_flag_get(uint32_t usart_periph, uint32_t int_flag)
{
uint32_t intenable = 0U, flagstatus = 0U;
/* get the interrupt enable bit status */
intenable = (USART_REG_VAL(usart_periph, int_flag) & BIT(USART_BIT_POS(int_flag)));
/* get the corresponding flag bit status */
flagstatus = (USART_REG_VAL2(usart_periph, int_flag) & BIT(USART_BIT_POS2(int_flag)));
if (flagstatus && intenable) {
return SET;
} else {
return RESET;
}
}
/*!
\brief clear USART interrupt flag in STAT register
\param[in] usart_periph: USARTx(x=0,1,2)/UARTx(x=3,4)
\param[in] flag: USART interrupt flag
only one parameter can be selected which is shown as below:
\arg USART_INT_FLAG_CTS: CTS change flag
\arg USART_INT_FLAG_LBD: LIN break detected flag
\arg USART_INT_FLAG_TC: transmission complete
\arg USART_INT_FLAG_RBNE: read data buffer not empty
\param[out] none
\retval none
*/
void usart_interrupt_flag_clear(uint32_t usart_periph, uint32_t flag)
{
USART_REG_VAL2(usart_periph, flag) &= ~BIT(USART_BIT_POS2(flag));
}
int usart_write(uint32_t usart_periph, int ch)
{
usart_data_transmit(usart_periph, (uint8_t) ch);
while (usart_flag_get(usart_periph, USART_FLAG_TBE) == RESET) {
}
return ch;
}
uint8_t usart_read(uint32_t usart_periph)
{
/* loop until RBNE = 1 */
while (usart_flag_get(usart_periph, USART_FLAG_RBNE) == RESET);
return (usart_data_receive(usart_periph));
}

View File

@ -80,6 +80,15 @@ KERNELPATHS :=-I$(BSP_ROOT) \
-I$(KERNEL_ROOT)/include #
endif
ifeq ($(BSP_ROOT),$(KERNEL_ROOT)/board/gd32vf103_rvstar)
KERNELPATHS :=-I$(BSP_ROOT) \
-I$(KERNEL_ROOT)/arch/risc-v/gd32vf103_rvstar \
-I$(BSP_ROOT)/include \
-I$(BSP_ROOT)/third_party_driver \
-I$(BSP_ROOT)/third_party_driver/include \
-I$(KERNEL_ROOT)/include #
endif
ifeq ($(BSP_ROOT),$(KERNEL_ROOT)/board/hifive1-rev-B)
KERNELPATHS :=-I$(BSP_ROOT) \
-I$(BSP_ROOT)/third_party_driver \
@ -254,6 +263,9 @@ endif
ifeq ($(MCU), GAP8)
KERNELPATHS +=-I$(KERNEL_ROOT)/arch/risc-v/gap8
endif
ifeq ($(MCU), GD32VF103)
KERNELPATHS +=-I$(KERNEL_ROOT)/arch/risc-v/gd32vf103
endif
endif