1
0
forked from me/IronOS

The basic NMSIS port

This commit is contained in:
Ben V. Brown
2020-12-10 16:18:44 +11:00
parent 6f3a7c1b90
commit 120a0502d6
198 changed files with 45413 additions and 13961 deletions

1
workspace/TS100/Core/BSP/Pine64/BSP.cpp Normal file → Executable file
View File

@@ -7,7 +7,6 @@
#include "gd32vf103_timer.h"
#include "history.hpp"
#include "main.hpp"
#include "systick.h"
#include <IRQ.h>
const uint16_t powerPWM = 255;

0
workspace/TS100/Core/BSP/Pine64/BSP_PD.c Normal file → Executable file
View File

14
workspace/TS100/Core/BSP/Pine64/FreeRTOSConfig.h Normal file → Executable file
View File

@@ -1,21 +1,18 @@
#ifndef FREERTOS_CONFIG_H
#define FREERTOS_CONFIG_H
/* Ensure stdint is only used by the compiler, and not the assembler. */
#if defined(__ICCARM__) || defined(__CC_ARM) || defined(__GNUC__)
#include <stdint.h>
extern uint32_t SystemCoreClock;
#endif
#include "nuclei_sdk_soc.h"
//RISC-V configuration
#include "n200_timer.h"
#define USER_MODE_TASKS 0
#define configUSE_PREEMPTION 1
#define configUSE_PORT_OPTIMISED_TASK_SELECTION 0
#define configUSE_TICKLESS_IDLE 0
#define configCPU_CLOCK_HZ ((uint32_t)SystemCoreClock)
#define configRTC_CLOCK_HZ ((uint32_t)TIMER_FREQ)
#define configRTC_CLOCK_HZ ((uint32_t)32768)
#define configTICK_RATE_HZ ((TickType_t)1000)
#define configMAX_PRIORITIES (4) //0 - 3 å…±6等级,idleç¬å<C2AC> 0,Tmr_svcç¬å<C2AC> 3
#define configMAX_PRIORITIES (4)
#define configMINIMAL_STACK_SIZE ((unsigned short)128)
#define configMAX_TASK_NAME_LEN 24
#define configUSE_16_BIT_TICKS 0
@@ -30,12 +27,13 @@ extern uint32_t SystemCoreClock;
#define configUSE_NEWLIB_REENTRANT 0
#define configENABLE_BACKWARD_COMPATIBILITY 0
#define configNUM_THREAD_LOCAL_STORAGE_POINTERS 5
#define INCLUDE_uxTaskGetStackHighWaterMark 1
#define INCLUDE_xTaskGetSchedulerState 1
#define INCLUDE_vTaskDelay 1
/* Memory allocation related definitions. */
#define configSUPPORT_STATIC_ALLOCATION 1
#define configSUPPORT_DYNAMIC_ALLOCATION 1
#define configSUPPORT_DYNAMIC_ALLOCATION 0
#define configTOTAL_HEAP_SIZE 1024
#define configAPPLICATION_ALLOCATED_HEAP 0
@@ -57,7 +55,7 @@ extern uint32_t SystemCoreClock;
/* Software timer related definitions. */
#define configUSE_TIMERS 0
#define configTIMER_TASK_PRIORITY (configMAX_PRIORITIES - 1) //Tmr_svc ç¬å<C2AC> æœ€é«˜ä¼˜å…ˆçº§
#define configTIMER_TASK_PRIORITY3
#define configTIMER_QUEUE_LENGTH 5
#define configTIMER_TASK_STACK_DEPTH configMINIMAL_STACK_SIZE

4
workspace/TS100/Core/BSP/Pine64/I2C_Wrapper.cpp Normal file → Executable file
View File

@@ -10,7 +10,7 @@
#include <I2C_Wrapper.hpp>
SemaphoreHandle_t FRToSI2C::I2CSemaphore = nullptr;
StaticSemaphore_t FRToSI2C::xSemaphoreBuffer;
#define I2C_TIME_OUT (uint16_t)(5000)
#define I2C_TIME_OUT (uint16_t)(12000)
void FRToSI2C::CpltCallback() {
// TODO
}
@@ -353,7 +353,7 @@ bool FRToSI2C::Mem_Write(uint16_t DevAddress, uint16_t MemAddress,
dma_channel_enable(DMA0, DMA_CH5);
/* wait until BTC bit is set */
while (!dma_flag_get(DMA0, DMA_CH5, DMA_FLAG_FTF)) {
osDelay(1);
osDelay(2);
}
/* wait until BTC bit is set */
while (!i2c_flag_get(I2C0, I2C_FLAG_BTC))

141
workspace/TS100/Core/BSP/Pine64/IRQ.cpp Normal file → Executable file
View File

@@ -20,102 +20,107 @@ volatile uint16_t i2c_read_dress;
volatile uint8_t i2c_process_flag = 0;
void ADC0_1_IRQHandler(void) {
adc_interrupt_flag_clear(ADC0, ADC_INT_FLAG_EOIC);
// unblock the PID controller thread
BaseType_t xHigherPriorityTaskWoken = pdFALSE;
if (pidTaskNotification) {
vTaskNotifyGiveFromISR(pidTaskNotification, &xHigherPriorityTaskWoken);
portYIELD_FROM_ISR(xHigherPriorityTaskWoken);
}
adc_interrupt_flag_clear(ADC0, ADC_INT_FLAG_EOIC);
// unblock the PID controller thread
if (xTaskGetSchedulerState() != taskSCHEDULER_NOT_STARTED) {
BaseType_t xHigherPriorityTaskWoken = pdFALSE;
if (pidTaskNotification) {
vTaskNotifyGiveFromISR(pidTaskNotification, &xHigherPriorityTaskWoken);
portYIELD_FROM_ISR(xHigherPriorityTaskWoken);
}
}
}
volatile uint16_t PWMSafetyTimer = 0;
volatile uint8_t pendingPWM = 0;
void TIMER1_IRQHandler(void) {
if (timer_interrupt_flag_get(TIMER1, TIMER_INT_UP) == SET) {
timer_interrupt_flag_clear(TIMER1, TIMER_INT_UP);
// rollover turn on output if required
if (PWMSafetyTimer && pendingPWM) {
timer_channel_output_pulse_value_config(TIMER2, TIMER_CH_0, 50);
}
if (PWMSafetyTimer) {
PWMSafetyTimer--;
}
}
if (timer_interrupt_flag_get(TIMER1, TIMER_INT_CH1) == SET) {
timer_interrupt_flag_clear(TIMER1, TIMER_INT_CH1);
// This is triggered on pwm setpoint trigger; we want to copy the pending
// PWM value into the output control reg
if (timer_interrupt_flag_get(TIMER1, TIMER_INT_UP) == SET) {
timer_interrupt_flag_clear(TIMER1, TIMER_INT_UP);
// rollover turn on output if required
if (PWMSafetyTimer && pendingPWM) {
timer_channel_output_pulse_value_config(TIMER2, TIMER_CH_0, 50);
}
if (PWMSafetyTimer) {
PWMSafetyTimer--;
}
}
if (timer_interrupt_flag_get(TIMER1, TIMER_INT_CH1) == SET) {
timer_interrupt_flag_clear(TIMER1, TIMER_INT_CH1);
// This is triggered on pwm setpoint trigger; we want to copy the pending
// PWM value into the output control reg
timer_channel_output_pulse_value_config(TIMER2, TIMER_CH_0, 0);
if (pendingPWM) {
timer_channel_output_pulse_value_config(TIMER1, TIMER_CH_1, pendingPWM);
}
}
timer_channel_output_pulse_value_config(TIMER2, TIMER_CH_0, 0);
if (pendingPWM) {
timer_channel_output_pulse_value_config(TIMER1, TIMER_CH_1, pendingPWM);
}
}
}
void setTipPWM(uint8_t pulse) {
PWMSafetyTimer =
10; // This is decremented in the handler for PWM so that the tip pwm is
// disabled if the PID task is not scheduled often enough.
pendingPWM = pulse;
PWMSafetyTimer = 10; // This is decremented in the handler for PWM so that the tip pwm is
// disabled if the PID task is not scheduled often enough.
pendingPWM = pulse;
}
static bool fastPWM;
static void switchToFastPWM(void) {
fastPWM = true;
totalPWM = powerPWM + tempMeasureTicks * 2;
TIMER_CAR(TIMER1) = (uint32_t)totalPWM;
fastPWM = true;
totalPWM = powerPWM + tempMeasureTicks * 2;
TIMER_CAR(TIMER1) = (uint32_t) totalPWM;
// ~3.5 Hz rate
TIMER_CH0CV(TIMER1) = powerPWM + holdoffTicks * 2;
// 1 kHz tick rate
TIMER_PSC(TIMER1) = 12000;
/* generate an update event */
TIMER_SWEVG(TIMER1) |= (uint32_t)TIMER_SWEVG_UPG;
// ~3.5 Hz rate
TIMER_CH0CV(TIMER1) = powerPWM + holdoffTicks * 2;
// 1 kHz tick rate
TIMER_PSC(TIMER1) = 12000;
/* generate an update event */
TIMER_SWEVG(TIMER1) |= (uint32_t) TIMER_SWEVG_UPG;
}
static void switchToSlowPWM(void) {
fastPWM = false;
totalPWM = powerPWM + tempMeasureTicks;
TIMER_CAR(TIMER1) = (uint32_t)totalPWM;
// ~1.84 Hz rate
TIMER_CH0CV(TIMER1) = powerPWM + holdoffTicks;
// 500 Hz tick rate
TIMER_PSC(TIMER1) = 24000;
/* generate an update event */
TIMER_SWEVG(TIMER1) |= (uint32_t)TIMER_SWEVG_UPG;
fastPWM = false;
totalPWM = powerPWM + tempMeasureTicks;
TIMER_CAR(TIMER1) = (uint32_t) totalPWM;
// ~1.84 Hz rate
TIMER_CH0CV(TIMER1) = powerPWM + holdoffTicks;
// 500 Hz tick rate
TIMER_PSC(TIMER1) = 24000;
/* generate an update event */
TIMER_SWEVG(TIMER1) |= (uint32_t) TIMER_SWEVG_UPG;
}
bool tryBetterPWM(uint8_t pwm) {
if (fastPWM && pwm == powerPWM) {
// maximum power for fast PWM reached, need to go slower to get more
switchToSlowPWM();
return true;
} else if (!fastPWM && pwm < 230) {
// 254 in fast PWM mode gives the same power as 239 in slow
// allow for some reasonable hysteresis by switching only when it goes
// below 230 (equivalent to 245 in fast mode)
switchToFastPWM();
return true;
}
return false;
if (fastPWM && pwm == powerPWM) {
// maximum power for fast PWM reached, need to go slower to get more
switchToSlowPWM();
return true;
} else if (!fastPWM && pwm < 230) {
// 254 in fast PWM mode gives the same power as 239 in slow
// allow for some reasonable hysteresis by switching only when it goes
// below 230 (equivalent to 245 in fast mode)
switchToFastPWM();
return true;
}
return false;
}
void EXTI5_9_IRQHandler(void) {
#ifdef POW_PD
if (RESET != exti_interrupt_flag_get(EXTI_5)) {
exti_interrupt_flag_clear(EXTI_5);
if (RESET != exti_interrupt_flag_get(EXTI_5)) {
exti_interrupt_flag_clear(EXTI_5);
if (RESET == gpio_input_bit_get(FUSB302_IRQ_GPIO_Port, FUSB302_IRQ_Pin)) {
InterruptHandler::irqCallback();
}
}
if (RESET == gpio_input_bit_get(FUSB302_IRQ_GPIO_Port, FUSB302_IRQ_Pin)) {
if (xTaskGetSchedulerState() != taskSCHEDULER_NOT_STARTED) {
InterruptHandler::irqCallback();
}
}
}
#endif
}
// These are unused for now
void I2C0_EV_IRQHandler(void) {}
void I2C0_EV_IRQHandler(void) {
}
void I2C0_ER_IRQHandler(void) {}
void I2C0_ER_IRQHandler(void) {
}

0
workspace/TS100/Core/BSP/Pine64/IRQ.h Normal file → Executable file
View File

0
workspace/TS100/Core/BSP/Pine64/Model_Config.h Normal file → Executable file
View File

View File

@@ -1,318 +0,0 @@
#include "FreeRTOSConfig.h"
//
#include "FreeRTOS.h"
#include "gd32vf103.h"
#include "n200_eclic.h"
#include "n200_func.h"
#include "n200_timer.h"
#include "portmacro.h"
#include "riscv_encoding.h"
#include "task.h"
/* Standard Includes */
#include <stdio.h>
#include <stdlib.h>
#include <unistd.h>
/* Each task maintains its own interrupt status in the critical nesting variable. */
UBaseType_t uxCriticalNesting = 0xaaaaaaaa;
#if USER_MODE_TASKS
#ifdef __riscv_flen
unsigned long MSTATUS_INIT = (MSTATUS_MPIE | (0x1 << 13));
#else
unsigned long MSTATUS_INIT = (MSTATUS_MPIE);
#endif
#else
#ifdef __riscv_flen
unsigned long MSTATUS_INIT = (MSTATUS_MPP | MSTATUS_MPIE | (0x1 << 13));
#else
unsigned long MSTATUS_INIT = (MSTATUS_MPP | MSTATUS_MPIE);
#endif
#endif
/*
* Used to catch tasks that attempt to return from their implementing function.
*/
static void prvTaskExitError(void);
/**
* @brief System Call Trap
*
* @param mcause csr
* @param sp 触发系统调用时的栈地址
* @param arg1 ECALL macro stores argument in a2
* @return unsigned long 传入的sp
*/
unsigned long ulSynchTrap(unsigned long mcause, unsigned long sp, unsigned long arg1) {
switch (mcause & 0X00000fff) {
//on User and Machine ECALL, handler the request
case 8:
case 11: {
if (arg1 == IRQ_DISABLE) {
//zero out mstatus.mpie
clear_csr(mstatus, MSTATUS_MPIE);
} else if (arg1 == IRQ_ENABLE) {
//set mstatus.mpie
set_csr(mstatus, MSTATUS_MPIE);
} else if (arg1 == PORT_YIELD) {
//always yield from machine mode
//fix up mepc on sync trap
unsigned long epc = read_csr(mepc);
vPortYield_from_ulSynchTrap(sp, epc + 4);
} else if (arg1 == PORT_YIELD_TO_RA) {
vPortYield_from_ulSynchTrap(sp, (*(unsigned long *)(sp + 1 * sizeof(sp))));
}
break;
}
default: {
/* 异常处理 */
extern uintptr_t handle_trap(uintptr_t mcause, uintptr_t sp);
handle_trap(mcause, sp);
}
}
//fix mepc and return
unsigned long epc = read_csr(mepc);
write_csr(mepc, epc + 4);
return sp;
}
/*-----------------------------------------------------------*/
/**
* @brief 设置触发软中断
* @note 目的是在软中断内进行任务上下文切换
*
*/
void vPortSetMSIPInt(void) {
*(volatile uint8_t *)(TIMER_CTRL_ADDR + TIMER_MSIP) |= 0x01;
__asm volatile("fence");
__asm volatile("fence.i");
}
/*-----------------------------------------------------------*/
/**
* @brief 清除软中断
*
*/
void vPortClearMSIPInt(void) {
*(volatile uint8_t *)(TIMER_CTRL_ADDR + TIMER_MSIP) &= ~0x01;
}
/*-----------------------------------------------------------*/
/**
* @brief 执行任务上下文切换,在portasm.S中被调用
*
* @param sp 触发任务切换时的栈地址
* @param arg1
* @return unsigned long sp地址
*/
unsigned long taskswitch(unsigned long sp, unsigned long arg1) {
//always yield from machine mode
//fix up mepc on
unsigned long epc = read_csr(mepc);
vPortYield(sp, epc); //never returns
return sp;
}
/*-----------------------------------------------------------*/
/**
* @brief 调研freertos内建函数vTaskSwitchContext,在portasm.S中被调用
*
*/
void vDoTaskSwitchContext(void) {
portDISABLE_INTERRUPTS();
vTaskSwitchContext();
portENABLE_INTERRUPTS();
}
/*-----------------------------------------------------------*/
/**
* @brief 进入临界段
*
*/
void vPortEnterCritical(void) {
#if USER_MODE_TASKS
ECALL(IRQ_DISABLE);
#else
portDISABLE_INTERRUPTS();
#endif
uxCriticalNesting++;
}
/*-----------------------------------------------------------*/
/**
* @brief 退出临界段
*
*/
void vPortExitCritical(void) {
configASSERT(uxCriticalNesting);
uxCriticalNesting--;
if (uxCriticalNesting == 0) {
#if USER_MODE_TASKS
ECALL(IRQ_ENABLE);
#else
portENABLE_INTERRUPTS();
#endif
}
return;
}
/*-----------------------------------------------------------*/
/**
* @brief Clear current interrupt mask and set given mask
*
* @param int_mask mth值
*/
void vPortClearInterruptMask(int int_mask) {
eclic_set_mth(int_mask);
}
/*-----------------------------------------------------------*/
/**
* @brief Set interrupt mask and return current interrupt enable register
*
* @return int
*/
int xPortSetInterruptMask(void) {
int int_mask = 0;
int_mask = eclic_get_mth();
portDISABLE_INTERRUPTS();
return int_mask;
}
/*-----------------------------------------------------------*/
/**
* @brief 初始化任务栈帧
*
* @param pxTopOfStack 栈顶
* @param pxCode 任务入口
* @param pvParameters 任务参数
* @return StackType_t* 完成初始化后的栈顶
*/
StackType_t *pxPortInitialiseStack(StackType_t *pxTopOfStack, TaskFunction_t pxCode, void *pvParameters) {
/* Simulate the stack frame as it would be created by a context switch
interrupt. */
#ifdef __riscv_flen
pxTopOfStack -= 32; /* 浮点寄存器 */
#endif
pxTopOfStack--;
*pxTopOfStack = 0xb8000000; /* CSR_MCAUSE */
pxTopOfStack--;
*pxTopOfStack = 0x40; /* CSR_SUBM */
pxTopOfStack--;
*pxTopOfStack = (portSTACK_TYPE)pxCode; /* Start address */
pxTopOfStack--;
*pxTopOfStack = MSTATUS_INIT; /* CSR_MSTATUS */
pxTopOfStack -= 22;
*pxTopOfStack = (portSTACK_TYPE)pvParameters; /* Register a0 */
pxTopOfStack -= 9;
*pxTopOfStack = (portSTACK_TYPE)prvTaskExitError; /* Register ra */
pxTopOfStack--;
return pxTopOfStack;
}
/*-----------------------------------------------------------*/
/**
* @brief 任务退出函数
*
*/
void prvTaskExitError(void) {
/* A function that implements a task must not exit or attempt to return to
its caller as there is nothing to return to. If a task wants to exit it
should instead call vTaskDelete( NULL ).
Artificially force an assert() to be triggered if configASSERT() is
defined, then stop here so application writers can catch the error. */
configASSERT(uxCriticalNesting == ~0UL);
portDISABLE_INTERRUPTS();
for (;;)
;
}
/*-----------------------------------------------------------*/
/**
* @brief tick中断
* @note 由于该中断配置为向量模式则中断到来会调用portasm.S的MTIME_HANDLER,进行栈帧保存之后该函数会调用vPortSysTickHandler
*
*/
void vPortSysTickHandler(void) {
volatile uint64_t *mtime = (uint64_t *)(TIMER_CTRL_ADDR + TIMER_MTIME);
volatile uint64_t *mtimecmp = (uint64_t *)(TIMER_CTRL_ADDR + TIMER_MTIMECMP);
UBaseType_t uxSavedInterruptStatus = portSET_INTERRUPT_MASK_FROM_ISR();
#if CONFIG_SYSTEMVIEW_EN
traceISR_ENTER();
#endif
uint64_t now = *mtime;
now += (configRTC_CLOCK_HZ / configTICK_RATE_HZ);
*mtimecmp = now;
/* 调用freertos的tick增加接口 */
if (xTaskIncrementTick() != pdFALSE) {
#if CONFIG_SYSTEMVIEW_EN
traceISR_EXIT_TO_SCHEDULER();
#endif
portYIELD();
}
#if CONFIG_SYSTEMVIEW_EN
else {
traceISR_EXIT();
}
#endif
portCLEAR_INTERRUPT_MASK_FROM_ISR(uxSavedInterruptStatus);
}
/*-----------------------------------------------------------*/
/**
* @brief 初始化tick
*
*/
void vPortSetupTimer(void) {
/* 内核timer定时器使用64位的计数器来实现 */
volatile uint64_t *mtime = (uint64_t *)(TIMER_CTRL_ADDR + TIMER_MTIME);
volatile uint64_t *mtimecmp = (uint64_t *)(TIMER_CTRL_ADDR + TIMER_MTIMECMP);
portENTER_CRITICAL();
uint64_t now = *mtime;
now += (configRTC_CLOCK_HZ / configTICK_RATE_HZ);
*mtimecmp = now;
portEXIT_CRITICAL();
eclic_set_vmode(CLIC_INT_TMR);
eclic_irq_enable(CLIC_INT_TMR, configKERNEL_INTERRUPT_PRIORITY >> configPRIO_BITS, 0);
}
/*-----------------------------------------------------------*/
/**
* @brief 初始化软中断
*
*/
void vPortSetupMSIP(void) {
eclic_set_vmode(CLIC_INT_SFT);
eclic_irq_enable(CLIC_INT_SFT, configKERNEL_INTERRUPT_PRIORITY >> configPRIO_BITS, 0);
}
/*-----------------------------------------------------------*/
/**
* @brief 调度启动前的初始化准备
*
*/
void vPortSetup(void) {
vPortSetupTimer();
vPortSetupMSIP();
uxCriticalNesting = 0;
}
/*-----------------------------------------------------------*/

View File

@@ -1,730 +0,0 @@
#include "riscv_encoding.h"
#include "riscv_bits.h"
#include "n200_timer.h"
#include "n200_eclic.h"
#define USE_MSP 1 //
.section .text.entry
.align 4
.global vPortYield
.global vPortYield_from_ulSynchTrap
.global xPortStartScheduler
.global vPortEndScheduler
.global vPortAsmAssertSP
.section .init
.weak eclic_msip_handler //bin0
.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
vector_base: //
j _start //_start
.align 2
.word 0
.word 0
.word eclic_msip_handler
.word 0
.word 0
.word 0
.word eclic_mtip_handler
.word 0
.word 0
.word 0
.word 0
.word 0
.word 0
.word 0
.word 0
.word 0
.word eclic_bwei_handler
.word eclic_pmovi_handler
.word WWDGT_IRQHandler
.word LVD_IRQHandler
.word TAMPER_IRQHandler
.word RTC_IRQHandler
.word FMC_IRQHandler
.word RCU_IRQHandler
.word EXTI0_IRQHandler
.word EXTI1_IRQHandler
.word EXTI2_IRQHandler
.word EXTI3_IRQHandler
.word EXTI4_IRQHandler
.word DMA0_Channel0_IRQHandler
.word DMA0_Channel1_IRQHandler
.word DMA0_Channel2_IRQHandler
.word DMA0_Channel3_IRQHandler
.word DMA0_Channel4_IRQHandler
.word DMA0_Channel5_IRQHandler
.word DMA0_Channel6_IRQHandler
.word ADC0_1_IRQHandler
.word CAN0_TX_IRQHandler
.word CAN0_RX0_IRQHandler
.word CAN0_RX1_IRQHandler
.word CAN0_EWMC_IRQHandler
.word EXTI5_9_IRQHandler
.word TIMER0_BRK_IRQHandler
.word TIMER0_UP_IRQHandler
.word TIMER0_TRG_CMT_IRQHandler
.word TIMER0_Channel_IRQHandler
.word TIMER1_IRQHandler
.word TIMER2_IRQHandler
.word TIMER3_IRQHandler
.word I2C0_EV_IRQHandler
.word I2C0_ER_IRQHandler
.word I2C1_EV_IRQHandler
.word I2C1_ER_IRQHandler
.word SPI0_IRQHandler
.word SPI1_IRQHandler
.word USART0_IRQHandler
.word USART1_IRQHandler
.word USART2_IRQHandler
.word EXTI10_15_IRQHandler
.word RTC_Alarm_IRQHandler
.word USBFS_WKUP_IRQHandler
.word 0
.word 0
.word 0
.word 0
.word 0
.word EXMC_IRQHandler
.word 0
.word TIMER4_IRQHandler
.word SPI2_IRQHandler
.word UART3_IRQHandler
.word UART4_IRQHandler
.word TIMER5_IRQHandler
.word TIMER6_IRQHandler
.word DMA1_Channel0_IRQHandler
.word DMA1_Channel1_IRQHandler
.word DMA1_Channel2_IRQHandler
.word DMA1_Channel3_IRQHandler
.word DMA1_Channel4_IRQHandler
.word 0
.word 0
.word CAN1_TX_IRQHandler
.word CAN1_RX0_IRQHandler
.word CAN1_RX1_IRQHandler
.word CAN1_EWMC_IRQHandler
.word USBFS_IRQHandler
.globl _start
.type _start,@function
_start:
csrc CSR_MSTATUS, MSTATUS_MIE //CSR_MSTATUS &= ~0x8 mstatus[3]:0 1
/* Jump to logical address first to ensure correct operation of RAM region */
la a0, _start //a0 = _start
li a1, 1 //a1 = 1
slli a1, a1, 29 //a1 = 0x20000000 raw
bleu a1, a0, _start0800 //if( a1 <= a0 ) JUMP _start0800
srli a1, a1, 2 //a1 = 0x08000000 flash
bleu a1, a0, _start0800 //if( a1 <= a0 ) JUMP _start0800
la a0, _start0800 //a0 = _start0800
add a0, a0, a1 //a0 = a0+a1
jr a0 //JUMP a0
_start0800:
/* Set the the NMI base to share with mtvec by setting CSR_MMISC_CTL */
li t0, 0x200 //t0 = 0x200
csrs CSR_MMISC_CTL, t0 //mmisc_ctl |= 0x200 CSR_MMISC_CTL[9]NMImtvecmcause.EXCCODE = 0xfff
//cs12
/* Intial the mtvt*/
la t0, vector_base //t0 = vector_base
csrw CSR_MTVT, t0 //mtvt = vector_base
/* Intial the mtvt2 and enable it*/
la t0, irq_entry //t0 = irq_entry irq_entryentry.S,freertosportasm.S
csrw CSR_MTVT2, t0 //mtvt2 = irq_entry mtvt2[31:2]:
csrs CSR_MTVT2, 0x1 //mtvt2 |= 0x1 mtvt2[0]: 1mtvt20mtvec
/* Intial the CSR MTVEC for the Trap ane NMI base addr*/
la t0, trap_entry //t0 = trap_entry trap_entryentry.S,freertosportasm.S
csrw CSR_MTVEC, t0 //mtvec = trap_entry mtvec[31:6]
// mtvec[5:0]0B00011 -- ECLIC
//
// trap_entryarmhard/mem/use/svcfault
// freertos使 ecall trap_entry armPendSVC
/* OS启动前配置中断栈为FHEAP的end地址 */
la t0, ucHeap
csrw CSR_MSCRATCH, t0
#ifdef __riscv_flen //
/* Enable FPU */
li t0, MSTATUS_FS //t0 = 0x6000
csrs mstatus, t0 //mstatus |= 0x6000 mstatus[14:13]:12使33
csrw fcsr, x0 //fcsr = x0 = 0 ??x0zero? 0-45-7
#endif
.option push
.option norelax
la gp, __global_pointer$ //__global_pointer$link.data0x800,0x8002K
//gp global pointer
//访4KB
//使__global_pointer$
///pcgp使-Wl,--no-relax使
//.option norelax-Wl,--no-relax
//https://gnu-mcu-eclipse.github.io/arch/riscv/programmer/#the-gp-global-pointer-register
// relaxing -msmall-data-limit=n
// n .sdata .sdata.*
// __global_pointer$ +/- 2K
//https://blog.csdn.net/zoomdy/article/details/100703451
.option pop
la sp, _sp //sp = _splink
/* Load data section */
la a0, _data_lma //a0 = dataLoad Memory Address _data_lmalink
la a1, _data //a1 = dataRun Memory Address _datalink
la a2, _edata //a2 = dataRun Memory Address _edatalink
bgeu a1, a2, 2f //if( a1 >= a2 ) JUMP 2f _data_edata
// 2f 2
1:
lw t0, (a0) //t0 = _data_lma
sw t0, (a1) //*_data = t0 *_data_lmaword
addi a0, a0, 4 //a0 = a0 + 4 ward
addi a1, a1, 4 //a1 = a1 + 4
bltu a1, a2, 1b //if( a1 < a2 ) JUMP 1b _edata 1b 1
2:
/* Clear bss section */
la a0, __bss_start //a0 = __bss_start 0 __bss_startlink
la a1, _end //a1 = _end 0 _endlink
bgeu a0, a1, 2f //if( a0 >= a1 ) JUMP 2f __bss_start_end
// 2f 2
1:
sw zero, (a0) //*__bss_start = zero = 0 bss0
addi a0, a0, 4 //a0 = a0 + 4 ward
bltu a0, a1, 1b //if( a0 < a1 ) JUMP 1b _end 1b 1
//
2:
/*enable mcycle_minstret*/
csrci CSR_MCOUNTINHIBIT, 0x5 //CSR_MCOUNTINHIBIT &= ~0x5 0bit1bit使mcycleminstret
//csrci5bit0x50B00101
/*
* Call vendor defined SystemInit to
* initialize the micro-controller system
*/
call SystemInit
/* Call global constructors */
la a0, __libc_fini_array //a0 = __libc_fini_array newlibatexit
call atexit //newlib void atexit(void (*func)(void))
//main__libc_fini_array
call __libc_init_array //newlib void __libc_init_array (void)
//__libc_init_array_initc
//_initinit.c
//C/C++main
/* argc = argv = 0 */
li a0, 0 //a0 = 0 mainargc = 0
li a1, 0 //a1 = 0 mainargv = 0
call main // int main(int argc,char **argv)
tail exit //mainnewlibexit, tail
1:
j 1b //1b 1
.global disable_mcycle_minstret
disable_mcycle_minstret:
csrsi CSR_MCOUNTINHIBIT, 0x5 //mcycleminstret
ret
.global enable_mcycle_minstret
enable_mcycle_minstret:
csrci CSR_MCOUNTINHIBIT, 0x5 //使mcycleminstret
ret
/**
* @brief 压栈通用寄存器
* @param x 目标sp寄存器
*/
.macro pushREGFILE x
#ifdef __riscv_flen
addi \x, \x, -REGBYTES * 68 //36+32
#else
addi \x, \x, -REGBYTES * 36
#endif
STORE x1, 1 * REGBYTES(\x)
STORE x2, 2 * REGBYTES(\x)
#STORE x3, 3 * REGBYTES(\x)
#STORE x4, 4 * REGBYTES(\x)
STORE x5, 5 * REGBYTES(\x)
STORE x6, 6 * REGBYTES(\x)
STORE x7, 7 * REGBYTES(\x)
STORE x8, 8 * REGBYTES(\x)
STORE x9, 9 * REGBYTES(\x)
STORE x10, 10 * REGBYTES(\x)
STORE x11, 11 * REGBYTES(\x)
STORE x12, 12 * REGBYTES(\x)
STORE x13, 13 * REGBYTES(\x)
STORE x14, 14 * REGBYTES(\x)
STORE x15, 15 * REGBYTES(\x)
#ifndef __riscv_32e
STORE x16, 16 * REGBYTES(\x)
STORE x17, 17 * REGBYTES(\x)
STORE x18, 18 * REGBYTES(\x)
STORE x19, 19 * REGBYTES(\x)
STORE x20, 20 * REGBYTES(\x)
STORE x21, 21 * REGBYTES(\x)
STORE x22, 22 * REGBYTES(\x)
STORE x23, 23 * REGBYTES(\x)
STORE x24, 24 * REGBYTES(\x)
STORE x25, 25 * REGBYTES(\x)
STORE x26, 26 * REGBYTES(\x)
STORE x27, 27 * REGBYTES(\x)
STORE x28, 28 * REGBYTES(\x)
STORE x29, 29 * REGBYTES(\x)
STORE x30, 30 * REGBYTES(\x)
STORE x31, 31 * REGBYTES(\x)
#endif
.endm
/**
* @brief 压栈csr寄存器CSR_MSTATUS、CSR_MEPC、CSR_MSUBM、CSR_MCAUSE
* @param x 目标sp寄存器
*/
.macro portSAVE_CONTEXT_EXCP x
csrr t0, CSR_MSTATUS
STORE t0, 32 * REGBYTES(\x)
csrr t0, CSR_MEPC
STORE t0, 33 * REGBYTES(\x)
csrr t0, CSR_MSUBM
STORE t0, 34 * REGBYTES(\x)
csrr t0, CSR_MCAUSE
STORE t0, 35 * REGBYTES(\x)
.endm
/**
* @brief 压栈浮点寄存器
* @param x 目标sp寄存器
*/
.macro popVFPREGFILE x
flw f0, 36 * REGBYTES(\x)
flw f1, 37 * REGBYTES(\x)
flw f2, 38 * REGBYTES(\x)
flw f3, 39 * REGBYTES(\x)
flw f4, 40 * REGBYTES(\x)
flw f5, 41 * REGBYTES(\x)
flw f6, 42 * REGBYTES(\x)
flw f7, 43 * REGBYTES(\x)
flw f8, 44 * REGBYTES(\x)
flw f9, 45 * REGBYTES(\x)
flw f10,46 * REGBYTES(\x)
flw f11, 47 * REGBYTES(\x)
flw f12, 48 * REGBYTES(\x)
flw f13, 49 * REGBYTES(\x)
flw f14, 50 * REGBYTES(\x)
flw f15, 51 * REGBYTES(\x)
flw f16, 52 * REGBYTES(\x)
flw f17, 53 * REGBYTES(\x)
flw f18, 54 * REGBYTES(\x)
flw f19, 55 * REGBYTES(\x)
flw f20, 56 * REGBYTES(\x)
flw f21, 57 * REGBYTES(\x)
flw f22, 58 * REGBYTES(\x)
flw f23, 59 * REGBYTES(\x)
flw f24, 60 * REGBYTES(\x)
flw f25, 61 * REGBYTES(\x)
flw f26, 62 * REGBYTES(\x)
flw f27, 63 * REGBYTES(\x)
flw f28, 64 * REGBYTES(\x)
flw f29, 65 * REGBYTES(\x)
flw f30, 66 * REGBYTES(\x)
flw f31, 67 * REGBYTES(\x)
.endm
/**
* @brief 出栈通用寄存器
* @param x 目标sp寄存器
*/
.macro popREGFILE x
LOAD x1, 1 * REGBYTES(\x)
#LOAD x2, 2 * REGBYTES(\x)
#LOAD x3, 3 * REGBYTES(\x)
#LOAD x4, 4 * REGBYTES(\x)
LOAD x5, 5 * REGBYTES(\x)
LOAD x6, 6 * REGBYTES(\x)
LOAD x7, 7 * REGBYTES(\x)
LOAD x8, 8 * REGBYTES(\x)
LOAD x9, 9 * REGBYTES(\x)
LOAD x10, 10 * REGBYTES(\x)
LOAD x11, 11 * REGBYTES(\x)
LOAD x12, 12 * REGBYTES(\x)
LOAD x13, 13 * REGBYTES(\x)
LOAD x14, 14 * REGBYTES(\x)
LOAD x15, 15 * REGBYTES(\x)
#ifndef __riscv_32e
LOAD x16, 16 * REGBYTES(\x)
LOAD x17, 17 * REGBYTES(\x)
LOAD x18, 18 * REGBYTES(\x)
LOAD x19, 19 * REGBYTES(\x)
LOAD x20, 20 * REGBYTES(\x)
LOAD x21, 21 * REGBYTES(\x)
LOAD x22, 22 * REGBYTES(\x)
LOAD x23, 23 * REGBYTES(\x)
LOAD x24, 24 * REGBYTES(\x)
LOAD x25, 25 * REGBYTES(\x)
LOAD x26, 26 * REGBYTES(\x)
LOAD x27, 27 * REGBYTES(\x)
LOAD x28, 28 * REGBYTES(\x)
LOAD x29, 29 * REGBYTES(\x)
LOAD x30, 30 * REGBYTES(\x)
LOAD x31, 31 * REGBYTES(\x)
#endif
#ifdef __riscv_flen
addi \x, \x, REGBYTES * 68 //36+32
#else
addi \x, \x, REGBYTES * 36
#endif
.endm
/**
* @brief 出栈csr寄存器CSR_MSTATUS、CSR_MEPC、CSR_MSUBM、CSR_MCAUSE
* @param x 目标sp寄存器
*/
.macro portRESTORE_CONTEXT_EXCP x
LOAD t0, 35*REGBYTES(\x)
csrw CSR_MCAUSE, t0
LOAD t0, 34*REGBYTES(\x)
csrw CSR_MSUBM, t0
LOAD t0, 33*REGBYTES(\x)
csrw CSR_MEPC, t0
LOAD t0, 32*REGBYTES(\x)
csrw CSR_MSTATUS, t0
.endm
/**
* @brief 出栈浮点寄存器
* @param x 目标sp寄存器
*/
.macro pushVFPREGFILE x
fsw f0, 36 * REGBYTES(\x)
fsw f1, 37 * REGBYTES(\x)
fsw f2, 38 * REGBYTES(\x)
fsw f3, 39 * REGBYTES(\x)
fsw f4, 40 * REGBYTES(\x)
fsw f5, 41 * REGBYTES(\x)
fsw f6, 42 * REGBYTES(\x)
fsw f7, 43 * REGBYTES(\x)
fsw f8, 44 * REGBYTES(\x)
fsw f9, 45 * REGBYTES(\x)
fsw f10, 46 * REGBYTES(\x)
fsw f11, 47 * REGBYTES(\x)
fsw f12, 48 * REGBYTES(\x)
fsw f13, 49 * REGBYTES(\x)
fsw f14, 50 * REGBYTES(\x)
fsw f15, 51 * REGBYTES(\x)
fsw f16, 52 * REGBYTES(\x)
fsw f17, 53 * REGBYTES(\x)
fsw f18, 54 * REGBYTES(\x)
fsw f19, 55 * REGBYTES(\x)
fsw f20, 56 * REGBYTES(\x)
fsw f21, 57 * REGBYTES(\x)
fsw f22, 58 * REGBYTES(\x)
fsw f23, 59 * REGBYTES(\x)
fsw f24, 60 * REGBYTES(\x)
fsw f25, 61 * REGBYTES(\x)
fsw f26, 62 * REGBYTES(\x)
fsw f27, 63 * REGBYTES(\x)
fsw f28, 64 * REGBYTES(\x)
fsw f29, 65 * REGBYTES(\x)
fsw f30, 66 * REGBYTES(\x)
fsw f31, 67 * REGBYTES(\x)
.endm
/**
* @brief 清理fpu状态寄存器
*/
.macro CONFIG_FS_CLEAN
li t0, (0x1 << 13) //FSclean
csrc mstatus, t0
li t0, (0x1 << 14)
csrs mstatus, t0
.endm
/* -------------------------------------------------------------------------------------------------------- */
/**
* @brief trap入口函数
*/
.section .text.trap
.align 6// In CLIC mode, the trap entry must be 64bytes aligned
.global trap_entry
.weak trap_entry
trap_entry:
pushREGFILE sp //trap使便
//(//)便
portSAVE_CONTEXT_EXCP sp
csrr a0, mcause
mv a1, sp
jal ulSynchTrap
mv sp, a0
portRESTORE_CONTEXT_EXCP sp
popREGFILE sp
mret
/* -------------------------------------------------------------------------------------------------------- */
/**
* @brife trq入口函数
*/
.align 2
.global irq_entry
irq_entry:
#if USE_MSP
csrrw sp, CSR_MSCRATCHCSWL, sp
#endif
pushREGFILE sp
portSAVE_CONTEXT_EXCP sp
#ifdef __riscv_flen
csrr t2, mstatus
li t0, (0x3 << 13)
and t1,t2,t0
bne t1,t0,1f
pushVFPREGFILE sp
1:
CONFIG_FS_CLEAN
#endif
int_loop:
csrrw ra, CSR_JALMNXTI, ra
csrrsi a0, CSR_MNXTI, MSTATUS_MIE
bnez a0, int_loop
csrc CSR_MSTATUS, MSTATUS_MIE
#ifdef __riscv_flen
csrr t2, mstatus
li t0, (0x3 << 13)
and t1,t2, t0
bne t1,t0, 2f
popVFPREGFILE sp
2:
#endif
portRESTORE_CONTEXT_EXCP sp
#ifdef __riscv_flen
CONFIG_FS_CLEAN
#endif
popREGFILE sp
#if USE_MSP
csrrw sp, CSR_MSCRATCHCSWL, sp
#endif
mret
/* -------------------------------------------------------------------------------------------------------- */
/**
* @brife MTIME入口函数
*/
.align 2
.globl MTIME_HANDLER
MTIME_HANDLER:
#if USE_MSP
csrrw sp, CSR_MSCRATCHCSWL, sp
#endif
pushREGFILE sp
portSAVE_CONTEXT_EXCP sp
csrs CSR_MSTATUS, MSTATUS_MIE
jal vPortSysTickHandler
csrc CSR_MSTATUS, MSTATUS_MIE
portRESTORE_CONTEXT_EXCP sp
popREGFILE sp
#if USE_MSP
csrrw sp, CSR_MSCRATCHCSWL, sp
#endif
mret
/* -------------------------------------------------------------------------------------------------------- */
/**
* @brife MSIP入口函数
*/
.align 2
.globl MSIP_HANDLER
MSIP_HANDLER:
pushREGFILE sp
portSAVE_CONTEXT_EXCP sp
mv a0,sp
call vPortClearMSIPInt
jal taskswitch
portRESTORE_CONTEXT_EXCP sp
popREGFILE sp
mret
/* -------------------------------------------------------------------------------------------------------- */
/**
* @brife Trap模式请求切换任务函数
*/
.align 6
vPortYield_from_ulSynchTrap:
mv sp, a0
portSAVE_CONTEXT_EXCP sp
j _vPortYield
/* -------------------------------------------------------------------------------------------------------- */
/**
* @brife MSIP模式请求切换任务函数
*/
.align 6
vPortYield:
mv sp, a0
_vPortYield:
LOAD t0, pxCurrentTCB
STORE sp, 0x0(t0)
#ifdef __riscv_flen
csrr t2, mstatus
li t0, (0x3 << 13)
and t1,t2,t0
bne t1,t0,1f
pushVFPREGFILE sp
1:
CONFIG_FS_CLEAN
#endif
STORE a1, 33 * REGBYTES(sp)
#if USE_MSP
csrr sp, CSR_MSCRATCH
#endif
csrs CSR_MSTATUS, MSTATUS_MIE
jal vDoTaskSwitchContext
csrc CSR_MSTATUS, MSTATUS_MIE
LOAD sp, pxCurrentTCB
LOAD sp, 0x0(sp)
portRESTORE_CONTEXT_EXCP sp
#ifdef __riscv_flen
csrr t2, mstatus
li t0, (0x3 << 13)
and t1, t2, t0
bne t1, t0, 2f
popVFPREGFILE sp
2:
CONFIG_FS_CLEAN
#endif
popREGFILE sp
mret
/* -------------------------------------------------------------------------------------------------------- */
/**
* @brife freertos启动调度函数
*/
xPortStartScheduler:
jal vPortSetup
csrc CSR_MSTATUS, MSTATUS_MIE
#if USE_MSP
la t0, _sp
csrw CSR_MSCRATCH, t0
#endif
LOAD sp, pxCurrentTCB
LOAD sp, 0x0(sp)
portRESTORE_CONTEXT_EXCP sp
popREGFILE sp
mret
/* -------------------------------------------------------------------------------------------------------- */
/**
* @brife MSIP模式请求切换任务函数
*/
vPortEndScheduler:
j vPortEndScheduler
/* Default Handler for Exceptions / Interrupts */
.global default_intexc_handler
.weak default_intexc_handler
Undef_Handler:
default_intexc_handler:
1:
j 1b

View File

@@ -1,143 +0,0 @@
#ifndef PORTMACRO_H
#define PORTMACRO_H
#ifdef __cplusplus
extern "C" {
#endif
#include "n200_func.h"
#include "riscv_encoding.h"
/*-----------------------------------------------------------
* Port specific definitions.
*
* The settings in this file configure FreeRTOS correctly for the
* given hardware and compiler.
*
* These settings should not be altered.
*-----------------------------------------------------------
*/
/* Type definitions. */
#define portCHAR char
#define portFLOAT float
#define portDOUBLE double
#define portLONG long
#define portSHORT short
#define portSTACK_TYPE uint32_t
#define portBASE_TYPE long
typedef portSTACK_TYPE StackType_t;
typedef long BaseType_t;
typedef unsigned long UBaseType_t;
#if (configUSE_16_BIT_TICKS == 1)
typedef uint16_t TickType_t;
#define portMAX_DELAY (TickType_t)0xffff
#else
typedef uint32_t TickType_t;
#define portMAX_DELAY (TickType_t)0xffffffffUL
#endif
/*-----------------------------------------------------------*/
/* Architecture specifics. */
#define portSTACK_GROWTH (-1)
#define portTICK_PERIOD_MS ((TickType_t)1000 / configTICK_RATE_HZ)
#define portBYTE_ALIGNMENT 8
/*-----------------------------------------------------------*/
/* Architecture specifics. */
extern void vPortYield(unsigned long, unsigned long);
extern void vPortYield_from_ulSynchTrap(unsigned long, unsigned long);
extern int xPortSetInterruptMask(void);
extern void vPortClearInterruptMask(int uxSavedStatusValue);
/*-----------------------------------------------------------*/
/*System Calls */
/*-----------------------------------------------------------*/
//ecall macro used to store argument in a3
#define ECALL(arg) ({ \
register uintptr_t a2 asm("a2") = (uintptr_t)(arg); \
asm volatile("ecall" \
: "+r"(a2) \
: \
: "memory"); \
a2; \
})
extern void vPortSetMSIPInt(void);
#define port_MSIPSET_BIT vPortSetMSIPInt()
#define IRQ_DISABLE 20
#define IRQ_ENABLE 30
#define PORT_YIELD 40
#define PORT_YIELD_TO_RA 50
/*-----------------------------------------------------------*/
/* Scheduler utilities. */
/* the return after the ECALL is VERY important */
//#define portYIELD() ECALL(PORT_YIELD);
#define portYIELD() port_MSIPSET_BIT;
#ifdef CONFIG_SYSTEMVIEW_EN
#define portEND_SWITCHING_ISR(xSwitchRequired) \
{ \
if (xSwitchRequired != pdFALSE) { \
traceISR_EXIT_TO_SCHEDULER(); \
portYIELD(); \
} else { \
traceISR_EXIT(); \
} \
}
#else
#define portEND_SWITCHING_ISR(xSwitchRequired) \
if (xSwitchRequired != pdFALSE) \
portYIELD()
#endif
#define portYIELD_FROM_ISR(x) portEND_SWITCHING_ISR(x)
/* Critical section management. */
extern void vPortEnterCritical(void);
extern void vPortExitCritical(void);
extern void eclic_set_mth(uint8_t mth);
#define portDISABLE_INTERRUPTS() \
{ \
eclic_set_mth((configMAX_SYSCALL_INTERRUPT_PRIORITY) | 0x1f); \
__asm volatile("fence"); \
__asm volatile("fence.i"); \
}
#define portENABLE_INTERRUPTS() eclic_set_mth(0)
#define portSET_INTERRUPT_MASK_FROM_ISR() xPortSetInterruptMask()
#define portCLEAR_INTERRUPT_MASK_FROM_ISR(uxSavedStatusValue) vPortClearInterruptMask(uxSavedStatusValue)
#define portENTER_CRITICAL() vPortEnterCritical()
#define portEXIT_CRITICAL() vPortExitCritical()
/*-----------------------------------------------------------*/
/* Task function macros as described on the FreeRTOS.org WEB site. These are
not necessary for to use this port. They are defined so the common demo files
(which build with all the ports) will build. */
#define portTASK_FUNCTION_PROTO(vFunction, pvParameters) void vFunction(void *pvParameters)
#define portTASK_FUNCTION(vFunction, pvParameters) void vFunction(void *pvParameters)
/*-----------------------------------------------------------*/
/* Tickless idle/low power functionality. */
#ifndef portSUPPRESS_TICKS_AND_SLEEP
extern void vPortSuppressTicksAndSleep(TickType_t xExpectedIdleTime);
#define portSUPPRESS_TICKS_AND_SLEEP(xExpectedIdleTime) vPortSuppressTicksAndSleep(xExpectedIdleTime)
#endif
/*-----------------------------------------------------------*/
#define portINLINE __inline
#ifndef portFORCE_INLINE
#define portFORCE_INLINE inline __attribute__((always_inline))
#endif
#ifdef __cplusplus
}
#endif
#endif /* PORTMACRO_H */

0
workspace/TS100/Core/BSP/Pine64/NOTES.md Normal file → Executable file
View File

4
workspace/TS100/Core/BSP/Pine64/Pins.h Normal file → Executable file
View File

@@ -7,8 +7,8 @@
#ifndef BSP_MINIWARE_PINS_H_
#define BSP_MINIWARE_PINS_H_
#include "Vendor/Lib/gd32vf103_gpio.h"
//TODO
#include "gd32vf103_gpio.h"
#define KEY_B_Pin BIT(1)
#define KEY_B_GPIO_Port GPIOB
#define TMP36_INPUT_Pin BIT(4)

0
workspace/TS100/Core/BSP/Pine64/Power.cpp Normal file → Executable file
View File

3
workspace/TS100/Core/BSP/Pine64/QC_GPIO.cpp Normal file → Executable file
View File

@@ -4,11 +4,12 @@
* Created on: 29 May 2020
* Author: Ralim
*/
#include "gd32vf103_libopt.h"
#include "BSP.h"
#include "Pins.h"
#include "QC3.h"
#include "Settings.h"
#include "gd32vf103.h"
#ifdef POW_QC
void QC_DPlusZero_Six() {
// pull down D+

0
workspace/TS100/Core/BSP/Pine64/README.md Normal file → Executable file
View File

View File

@@ -8,7 +8,6 @@
#include "BSP.h"
#include "Pins.h"
#include "gd32vf103.h"
#include "systick.h"
#include <string.h>
#define ADC_NORM_CHANNELS 2
#define ADC_NORM_SAMPLES 32
@@ -40,8 +39,6 @@ void hardware_init() {
/* enable TIMER1 - PWM control timing*/
timer_enable(TIMER1);
timer_enable(TIMER2);
eclic_priority_group_set(ECLIC_PRIGROUP_LEVEL4_PRIO0);
eclic_global_interrupt_enable();
}
// channel 0 -> temperature sensor, 1-> VIN
uint16_t getADC(uint8_t channel) {
@@ -135,7 +132,7 @@ void setup_adc() {
/* config ADC clock */
rcu_adc_clock_config(RCU_CKADC_CKAPB2_DIV16);
// Run in normal parallel + inserted parallel
adc_mode_config(ADC_DAUL_REGULAL_PARALLEL_INSERTED_PARALLEL);
adc_mode_config(ADC0,ADC_DAUL_REGULAL_PARALLEL_INSERTED_PARALLEL);
adc_special_function_config(ADC0, ADC_CONTINUOUS_MODE, ENABLE);
adc_special_function_config(ADC0, ADC_SCAN_MODE, ENABLE);
adc_special_function_config(ADC1, ADC_CONTINUOUS_MODE, ENABLE);
@@ -214,7 +211,7 @@ void setup_timers() {
/* initialize TIMER init parameter struct */
timer_struct_para_init(&timer_initpara);
/* TIMER1 configuration */
timer_initpara.prescaler = 24000;
timer_initpara.prescaler = 5000;
timer_initpara.alignedmode = TIMER_COUNTER_EDGE;
timer_initpara.counterdirection = TIMER_COUNTER_UP;
timer_initpara.period = powerPWM + tempMeasureTicks;

2
workspace/TS100/Core/BSP/Pine64/Setup.h Normal file → Executable file
View File

@@ -7,7 +7,7 @@
#ifndef SETUP_H_
#define SETUP_H_
#include "Vendor/Lib/gd32vf103_libopt.h"
#include "gd32vf103_libopt.h"
#include <stdint.h>
#ifdef __cplusplus

0
workspace/TS100/Core/BSP/Pine64/UnitSettings.h Normal file → Executable file
View File

View File

@@ -1,13 +0,0 @@
/* See LICENSE of license details. */
#include <errno.h>
#include <time.h>
#include <stdint.h>
#include "system_gd32vf103.h"
/* Get resolution of clock. */
int clock_getres(clockid_t clock_id, struct timespec *res)
{
res->tv_sec = 0;
res->tv_nsec = 1000000000 / SystemCoreClock;
return 0;
}

View File

@@ -1,20 +0,0 @@
/* See LICENSE of license details. */
#include <errno.h>
#include <time.h>
#include <sys/time.h>
extern int _gettimeofday(struct timeval *tp, void *tzp);
/* Get current value of CLOCK and store it in tp. */
int clock_gettime(clockid_t clock_id, struct timespec *tp)
{
struct timeval tv;
int retval = -1;
retval = _gettimeofday(&tv, NULL);
if (retval == 0) {
TIMEVAL_TO_TIMESPEC(&tv, tp);
}
return retval;
}

View File

@@ -1,9 +0,0 @@
/* See LICENSE of license details. */
#include <errno.h>
#include <time.h>
/* Set CLOCK to value TP. */
int clock_settime(clockid_t clock_id, const struct timespec *tp)
{
return -1;
}

View File

@@ -1,11 +0,0 @@
/* See LICENSE of license details. */
#include <errno.h>
#undef errno
extern int errno;
int _close(int fd)
{
errno = EBADF;
return -1;
}

View File

@@ -1,11 +0,0 @@
/* See LICENSE of license details. */
#include <errno.h>
#undef errno
extern int errno;
int _execve(char *name, char **argv, char **env)
{
errno = ENOMEM;
return -1;
}

View File

@@ -1,9 +0,0 @@
/* See LICENSE of license details. */
#include "n200_func.h"
void _exit(int fd)
{
while(1) {
__WFI();
}
}

View File

@@ -1,11 +0,0 @@
/* See LICENSE of license details. */
#include <errno.h>
#undef errno
extern int errno;
int fork(void)
{
errno = EAGAIN;
return -1;
}

View File

@@ -1,18 +0,0 @@
/* See LICENSE of license details. */
#include <errno.h>
#include <sys/stat.h>
#include <unistd.h>
#undef errno
extern int errno;
int _fstat(int file, struct stat *st)
{
if ((STDOUT_FILENO == file) || (STDERR_FILENO == file)) {
st->st_mode = S_IFCHR;
return 0;
} else {
errno = EBADF;
return -1;
}
}

View File

@@ -1,7 +0,0 @@
/* See LICENSE of license details. */
#include <errno.h>
int getpid(void)
{
return 1;
}

View File

@@ -1,7 +0,0 @@
/* See LICENSE of license details. */
#include <unistd.h>
int _isatty(int fd)
{
return 1;
}

View File

@@ -1,10 +0,0 @@
/* See LICENSE of license details. */
#include <errno.h>
#undef errno
extern int errno;
int _kill(int pid, int sig)
{
errno = EINVAL;
return -1;
}

View File

@@ -1,11 +0,0 @@
/* See LICENSE of license details. */
#include <errno.h>
#undef errno
extern int errno;
int _link(char *old, char *new)
{
errno = EMLINK;
return -1;
}

View File

@@ -1,10 +0,0 @@
/* See LICENSE of license details. */
#include <errno.h>
#undef errno
extern int errno;
int _lseek(int file, int offset, int whence)
{
return 0;
}

View File

@@ -1,11 +0,0 @@
/* See LICENSE of license details. */
#include <errno.h>
#undef errno
extern int errno;
int _open(const char *name, int flags, int mode)
{
errno = ENOSYS;
return -1;
}

View File

@@ -1,9 +0,0 @@
/* See LICENSE of license details. */
#include <stdint.h>
#include <stddef.h>
#include <unistd.h>
void *_sbrk(ptrdiff_t incr)
{
return (void *)0;
}

View File

@@ -1,8 +0,0 @@
/* See LICENSE of license details. */
#include <sys/stat.h>
int _stat(char *file, struct stat *st)
{
st->st_mode = S_IFCHR;
return 0;
}

View File

@@ -1,26 +0,0 @@
/* See LICENSE of license details. */
#include <sys/times.h>
#include <sys/time.h>
#include <time.h>
extern int _gettimeofday(struct timeval *, void *);
clock_t _times(struct tms *buf)
{
static struct timeval t0;
struct timeval t;
long long utime;
/* When called for the first time, initialize t0. */
if (t0.tv_sec == 0 && t0.tv_usec == 0) {
_gettimeofday(&t0, 0);
}
_gettimeofday(&t, 0);
utime = (t.tv_sec - t0.tv_sec) * 1000000 + (t.tv_usec - t0.tv_usec);
buf->tms_utime = utime * CLOCKS_PER_SEC / 1000000;
buf->tms_stime = buf->tms_cstime = buf->tms_cutime = 0;
return buf->tms_utime;
}

View File

@@ -1,11 +0,0 @@
/* See LICENSE of license details. */
#include <errno.h>
#undef errno
extern int errno;
int _unlink(const char *name)
{
return -1;
}

View File

@@ -1,12 +0,0 @@
/* See LICENSE of license details. */
#include <sys/stat.h>
#include <errno.h>
#undef errno
extern int errno;
int _wait(int *status)
{
errno = ECHILD;
return -1;
}

View File

@@ -1,246 +0,0 @@
/*!
\file gd32vf103.h
\brief general definitions for GD32VF103
\version 2019-06-05, 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_H
#define GD32VF103_H
#ifdef cplusplus
extern "C" {
#endif
/* IO definitions (access restrictions to peripheral registers) */
/**
<strong>IO Type Qualifiers</strong> are used
\li to specify the access to peripheral variables.
\li for automatic generation of peripheral register debug information.
*/
#ifdef __cplusplus
#define __I volatile /*!< Defines 'read only' permissions */
#else
#define __I volatile const /*!< Defines 'read only' permissions */
#endif
#define __O volatile /*!< Defines 'write only' permissions */
#define __IO volatile /*!< Defines 'read / write' permissions */
#define GD32VF103V_EVAL
/* define value of high speed crystal oscillator (HXTAL) in Hz */
#if !defined HXTAL_VALUE
#ifdef GD32VF103R_START
#define HXTAL_VALUE ((uint32_t)25000000) /*!< value of the external oscillator in Hz */
#define HXTAL_VALUE_8M HXTAL_VALUE
#elif defined(GD32VF103V_EVAL) || defined(GD32VF103C_START) || defined(GD32VF103T_START)
#define HXTAL_VALUE ((uint32_t)8000000) /*!< value of the external oscillator in Hz */
#define HXTAL_VALUE_25M HXTAL_VALUE
#else
#error "Please select the target board type used in your application (in gd32vf103.h file)"
#endif
#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 interrupt number */
typedef enum IRQn {
CLIC_INT_RESERVED = 0, /*!< RISC-V reserved */
CLIC_INT_SFT = 3, /*!< Software interrupt */
CLIC_INT_TMR = 7, /*!< CPU Timer interrupt */
CLIC_INT_BWEI = 17, /*!< Bus Error interrupt */
CLIC_INT_PMOVI = 18, /*!< Performance Monitor */
/* interrupt 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 */
ECLIC_NUM_INTERRUPTS
} IRQn_Type;
/* includes */
#include "system_gd32vf103.h"
#include <stdint.h>
/* 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 { ERROR = 0,
SUCCESS = !ERROR } ErrStatus;
/* bit operations */
#define REG32(addr) (*(volatile uint32_t *)(uint32_t)(addr))
#define REG16(addr) (*(volatile uint16_t *)(uint32_t)(addr))
#define REG8(addr) (*(volatile uint8_t *)(uint32_t)(addr))
#define BIT(x) ((uint32_t)((uint32_t)0x01U << (x)))
#define BITS(start, end) ((0xFFFFFFFFUL << (start)) & (0xFFFFFFFFUL >> (31U - (uint32_t)(end))))
#define GET_BITS(regval, start, end) (((regval)&BITS((start), (end))) >> (start))
/* 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 */
/* define marco USE_STDPERIPH_DRIVER */
#if !defined USE_STDPERIPH_DRIVER
#define USE_STDPERIPH_DRIVER
#endif
#ifdef USE_STDPERIPH_DRIVER
#include "gd32vf103_libopt.h"
#endif /* USE_STDPERIPH_DRIVER */
#ifdef cplusplus
}
#endif
#endif

View File

@@ -1,401 +0,0 @@
/*!
\file gd32vf103_adc.h
\brief definitions for the ADC
\version 2019-06-05, 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.
*/
#ifdef __cplusplus
extern "C" {
#endif
#ifndef GD32VF103_ADC_H
#define GD32VF103_ADC_H
#include "gd32vf103.h"
/* ADC definitions */
#define ADC0 ADC_BASE
#define ADC1 (ADC_BASE + 0x400U)
/* registers definitions */
#define ADC_STAT(adcx) REG32((adcx) + 0x00U) /*!< ADC status register */
#define ADC_CTL0(adcx) REG32((adcx) + 0x04U) /*!< ADC control register 0 */
#define ADC_CTL1(adcx) REG32((adcx) + 0x08U) /*!< ADC control register 1 */
#define ADC_SAMPT0(adcx) REG32((adcx) + 0x0CU) /*!< ADC sampling time register 0 */
#define ADC_SAMPT1(adcx) REG32((adcx) + 0x10U) /*!< ADC sampling time register 1 */
#define ADC_IOFF0(adcx) REG32((adcx) + 0x14U) /*!< ADC inserted channel data offset register 0 */
#define ADC_IOFF1(adcx) REG32((adcx) + 0x18U) /*!< ADC inserted channel data offset register 1 */
#define ADC_IOFF2(adcx) REG32((adcx) + 0x1CU) /*!< ADC inserted channel data offset register 2 */
#define ADC_IOFF3(adcx) REG32((adcx) + 0x20U) /*!< ADC inserted channel data offset register 3 */
#define ADC_WDHT(adcx) REG32((adcx) + 0x24U) /*!< ADC watchdog high threshold register */
#define ADC_WDLT(adcx) REG32((adcx) + 0x28U) /*!< ADC watchdog low threshold register */
#define ADC_RSQ0(adcx) REG32((adcx) + 0x2CU) /*!< ADC regular sequence register 0 */
#define ADC_RSQ1(adcx) REG32((adcx) + 0x30U) /*!< ADC regular sequence register 1 */
#define ADC_RSQ2(adcx) REG32((adcx) + 0x34U) /*!< ADC regular sequence register 2 */
#define ADC_ISQ(adcx) REG32((adcx) + 0x38U) /*!< ADC inserted sequence register */
#define ADC_IDATA0(adcx) REG32((adcx) + 0x3CU) /*!< ADC inserted data register 0 */
#define ADC_IDATA1(adcx) REG32((adcx) + 0x40U) /*!< ADC inserted data register 1 */
#define ADC_IDATA2(adcx) REG32((adcx) + 0x44U) /*!< ADC inserted data register 2 */
#define ADC_IDATA3(adcx) REG32((adcx) + 0x48U) /*!< ADC inserted data register 3 */
#define ADC_RDATA(adcx) REG32((adcx) + 0x4CU) /*!< ADC regular data register */
#define ADC_OVSCR(adcx) REG32((adcx) + 0x80U) /*!< ADC oversample control register */
/* bits definitions */
/* ADC_STAT */
#define ADC_STAT_WDE BIT(0) /*!< analog watchdog event flag */
#define ADC_STAT_EOC BIT(1) /*!< end of conversion */
#define ADC_STAT_EOIC BIT(2) /*!< inserted channel end of conversion */
#define ADC_STAT_STIC BIT(3) /*!< inserted channel start flag */
#define ADC_STAT_STRC BIT(4) /*!< regular channel start flag */
/* ADC_CTL0 */
#define ADC_CTL0_WDCHSEL BITS(0, 4) /*!< analog watchdog channel select bits */
#define ADC_CTL0_EOCIE BIT(5) /*!< interrupt enable for EOC */
#define ADC_CTL0_WDEIE BIT(6) /*!< analog watchdog interrupt enable */
#define ADC_CTL0_EOICIE BIT(7) /*!< interrupt enable for inserted channels */
#define ADC_CTL0_SM BIT(8) /*!< scan mode */
#define ADC_CTL0_WDSC BIT(9) /*!< when in scan mode, analog watchdog is effective on a single channel */
#define ADC_CTL0_ICA BIT(10) /*!< automatic inserted group conversion */
#define ADC_CTL0_DISRC BIT(11) /*!< discontinuous mode on regular channels */
#define ADC_CTL0_DISIC BIT(12) /*!< discontinuous mode on inserted channels */
#define ADC_CTL0_DISNUM BITS(13, 15) /*!< discontinuous mode channel count */
#define ADC_CTL0_SYNCM BITS(16, 19) /*!< sync mode selection */
#define ADC_CTL0_IWDEN BIT(22) /*!< analog watchdog enable on inserted channels */
#define ADC_CTL0_RWDEN BIT(23) /*!< analog watchdog enable on regular channels */
/* ADC_CTL1 */
#define ADC_CTL1_ADCON BIT(0) /*!< ADC converter on */
#define ADC_CTL1_CTN BIT(1) /*!< continuous conversion */
#define ADC_CTL1_CLB BIT(2) /*!< ADC calibration */
#define ADC_CTL1_RSTCLB BIT(3) /*!< reset calibration */
#define ADC_CTL1_DMA BIT(8) /*!< direct memory access mode */
#define ADC_CTL1_DAL BIT(11) /*!< data alignment */
#define ADC_CTL1_ETSIC BITS(12, 14) /*!< external trigger select for inserted channel */
#define ADC_CTL1_ETEIC BIT(15) /*!< external trigger enable for inserted channel */
#define ADC_CTL1_ETSRC BITS(17, 19) /*!< external trigger select for regular channel */
#define ADC_CTL1_ETERC BIT(20) /*!< external trigger conversion mode for inserted channels */
#define ADC_CTL1_SWICST BIT(21) /*!< start on inserted channel */
#define ADC_CTL1_SWRCST BIT(22) /*!< start on regular channel */
#define ADC_CTL1_TSVREN BIT(23) /*!< channel 16 and 17 enable of ADC0 */
/* ADC_SAMPTx x=0..1 */
#define ADC_SAMPTX_SPTN BITS(0, 2) /*!< channel n sample time selection */
/* ADC_IOFFx x=0..3 */
#define ADC_IOFFX_IOFF BITS(0, 11) /*!< data offset for inserted channel x */
/* ADC_WDHT */
#define ADC_WDHT_WDHT BITS(0, 11) /*!< analog watchdog high threshold */
/* ADC_WDLT */
#define ADC_WDLT_WDLT BITS(0, 11) /*!< analog watchdog low threshold */
/* ADC_RSQx x=0..2 */
#define ADC_RSQX_RSQN BITS(0, 4) /*!< nth conversion in regular sequence */
#define ADC_RSQ0_RL BITS(20, 23) /*!< regular channel sequence length */
/* ADC_ISQ */
#define ADC_ISQ_ISQN BITS(0, 4) /*!< nth conversion in inserted sequence */
#define ADC_ISQ_IL BITS(20, 21) /*!< inserted sequence length */
/* ADC_IDATAx x=0..3*/
#define ADC_IDATAX_IDATAN BITS(0, 15) /*!< inserted data n */
/* ADC_RDATA */
#define ADC_RDATA_RDATA BITS(0, 15) /*!< regular data */
#define ADC_RDATA_ADC1RDTR BITS(16, 31) /*!< ADC1 regular channel data */
/* ADC_OVSCR */
#define ADC_OVSCR_OVSEN BIT(0) /*!< oversampling enable */
#define ADC_OVSCR_OVSR BITS(2, 4) /*!< oversampling ratio */
#define ADC_OVSCR_OVSS BITS(5, 8) /*!< oversampling shift */
#define ADC_OVSCR_TOVS BIT(9) /*!< triggered oversampling */
#define ADC_OVSCR_DRES BITS(12, 13) /*!< ADC data resolution */
/* constants definitions */
/* adc_stat register value */
#define ADC_FLAG_WDE ADC_STAT_WDE /*!< analog watchdog event flag */
#define ADC_FLAG_EOC ADC_STAT_EOC /*!< end of conversion */
#define ADC_FLAG_EOIC ADC_STAT_EOIC /*!< inserted channel end of conversion */
#define ADC_FLAG_STIC ADC_STAT_STIC /*!< inserted channel start flag */
#define ADC_FLAG_STRC ADC_STAT_STRC /*!< regular channel start flag */
/* adc_ctl0 register value */
#define CTL0_DISNUM(regval) (BITS(13, 15) & ((uint32_t)(regval) << 13)) /*!< write value to ADC_CTL0_DISNUM bit field */
/* scan mode */
#define ADC_SCAN_MODE ADC_CTL0_SM /*!< scan mode */
/* inserted channel group convert automatically */
#define ADC_INSERTED_CHANNEL_AUTO ADC_CTL0_ICA /*!< inserted channel group convert automatically */
/* ADC sync mode */
#define CTL0_SYNCM(regval) (BITS(16, 19) & ((uint32_t)(regval) << 16)) /*!< write value to ADC_CTL0_SYNCM bit field */
#define ADC_MODE_FREE CTL0_SYNCM(0) /*!< all the ADCs work independently */
#define ADC_DAUL_REGULAL_PARALLEL_INSERTED_PARALLEL CTL0_SYNCM(1) /*!< ADC0 and ADC1 work in combined regular parallel + inserted parallel mode */
#define ADC_DAUL_REGULAL_PARALLEL_INSERTED_ROTATION CTL0_SYNCM(2) /*!< ADC0 and ADC1 work in combined regular parallel + trigger rotation mode */
#define ADC_DAUL_INSERTED_PARALLEL_REGULAL_FOLLOWUP_FAST CTL0_SYNCM(3) /*!< ADC0 and ADC1 work in combined inserted parallel + follow-up fast mode */
#define ADC_DAUL_INSERTED_PARALLEL_REGULAL_FOLLOWUP_SLOW CTL0_SYNCM(4) /*!< ADC0 and ADC1 work in combined inserted parallel + follow-up slow mode */
#define ADC_DAUL_INSERTED_PARALLEL CTL0_SYNCM(5) /*!< ADC0 and ADC1 work in inserted parallel mode only */
#define ADC_DAUL_REGULAL_PARALLEL CTL0_SYNCM(6) /*!< ADC0 and ADC1 work in regular parallel mode only */
#define ADC_DAUL_REGULAL_FOLLOWUP_FAST CTL0_SYNCM(7) /*!< ADC0 and ADC1 work in follow-up fast mode only */
#define ADC_DAUL_REGULAL_FOLLOWUP_SLOW CTL0_SYNCM(8) /*!< ADC0 and ADC1 work in follow-up slow mode only */
#define ADC_DAUL_INSERTED_TRIGGER_ROTATION CTL0_SYNCM(9) /*!< ADC0 and ADC1 work in trigger rotation mode only */
/* adc_ctl1 register value */
#define ADC_DATAALIGN_RIGHT ((uint32_t)0x00000000U) /*!< LSB alignment */
#define ADC_DATAALIGN_LEFT ADC_CTL1_DAL /*!< MSB alignment */
/* continuous mode */
#define ADC_CONTINUOUS_MODE ADC_CTL1_CTN /*!< continuous mode */
/* external trigger select for regular channel */
#define CTL1_ETSRC(regval) (BITS(17, 19) & ((uint32_t)(regval) << 17)) /*!< write value to ADC_CTL1_ETSRC bit field */
/* for ADC0 and ADC1 regular channel */
#define ADC0_1_EXTTRIG_REGULAR_T0_CH0 CTL1_ETSRC(0) /*!< TIMER0 CH0 event select */
#define ADC0_1_EXTTRIG_REGULAR_T0_CH1 CTL1_ETSRC(1) /*!< TIMER0 CH1 event select */
#define ADC0_1_EXTTRIG_REGULAR_T0_CH2 CTL1_ETSRC(2) /*!< TIMER0 CH2 event select */
#define ADC0_1_EXTTRIG_REGULAR_T1_CH1 CTL1_ETSRC(3) /*!< TIMER1 CH1 event select */
#define ADC0_1_EXTTRIG_REGULAR_T2_TRGO CTL1_ETSRC(4) /*!< TIMER2 TRGO event select */
#define ADC0_1_EXTTRIG_REGULAR_T3_CH3 CTL1_ETSRC(5) /*!< TIMER3 CH3 event select */
#define ADC0_1_EXTTRIG_REGULAR_EXTI_11 CTL1_ETSRC(6) /*!< external interrupt line 11 */
#define ADC0_1_EXTTRIG_REGULAR_NONE CTL1_ETSRC(7) /*!< software trigger */
/* external trigger mode for inserted channel */
#define CTL1_ETSIC(regval) (BITS(12, 14) & ((uint32_t)(regval) << 12)) /*!< write value to ADC_CTL1_ETSIC bit field */
/* for ADC0 and ADC1 inserted channel */
#define ADC0_1_EXTTRIG_INSERTED_T0_TRGO CTL1_ETSIC(0) /*!< TIMER0 TRGO event select */
#define ADC0_1_EXTTRIG_INSERTED_T0_CH3 CTL1_ETSIC(1) /*!< TIMER0 CH3 event select */
#define ADC0_1_EXTTRIG_INSERTED_T1_TRGO CTL1_ETSIC(2) /*!< TIMER1 TRGO event select */
#define ADC0_1_EXTTRIG_INSERTED_T1_CH0 CTL1_ETSIC(3) /*!< TIMER1 CH0 event select */
#define ADC0_1_EXTTRIG_INSERTED_T2_CH3 CTL1_ETSIC(4) /*!< TIMER2 CH3 event select */
#define ADC0_1_EXTTRIG_INSERTED_T3_TRGO CTL1_ETSIC(5) /*!< TIMER3 TRGO event select */
#define ADC0_1_EXTTRIG_INSERTED_EXTI_15 CTL1_ETSIC(6) /*!< external interrupt line 15 */
#define ADC0_1_EXTTRIG_INSERTED_NONE CTL1_ETSIC(7) /*!< software trigger */
/* adc_samptx register value */
#define SAMPTX_SPT(regval) (BITS(0, 2) & ((uint32_t)(regval) << 0)) /*!< write value to ADC_SAMPTX_SPT bit field */
#define ADC_SAMPLETIME_1POINT5 SAMPTX_SPT(0) /*!< 1.5 sampling cycles */
#define ADC_SAMPLETIME_7POINT5 SAMPTX_SPT(1) /*!< 7.5 sampling cycles */
#define ADC_SAMPLETIME_13POINT5 SAMPTX_SPT(2) /*!< 13.5 sampling cycles */
#define ADC_SAMPLETIME_28POINT5 SAMPTX_SPT(3) /*!< 28.5 sampling cycles */
#define ADC_SAMPLETIME_41POINT5 SAMPTX_SPT(4) /*!< 41.5 sampling cycles */
#define ADC_SAMPLETIME_55POINT5 SAMPTX_SPT(5) /*!< 55.5 sampling cycles */
#define ADC_SAMPLETIME_71POINT5 SAMPTX_SPT(6) /*!< 71.5 sampling cycles */
#define ADC_SAMPLETIME_239POINT5 SAMPTX_SPT(7) /*!< 239.5 sampling cycles */
/* adc_ioffx register value */
#define IOFFX_IOFF(regval) (BITS(0, 11) & ((uint32_t)(regval) << 0)) /*!< write value to ADC_IOFFX_IOFF bit field */
/* adc_wdht register value */
#define WDHT_WDHT(regval) (BITS(0, 11) & ((uint32_t)(regval) << 0)) /*!< write value to ADC_WDHT_WDHT bit field */
/* adc_wdlt register value */
#define WDLT_WDLT(regval) (BITS(0, 11) & ((uint32_t)(regval) << 0)) /*!< write value to ADC_WDLT_WDLT bit field */
/* adc_rsqx register value */
#define RSQ0_RL(regval) (BITS(20, 23) & ((uint32_t)(regval) << 20)) /*!< write value to ADC_RSQ0_RL bit field */
/* adc_isq register value */
#define ISQ_IL(regval) (BITS(20, 21) & ((uint32_t)(regval) << 20)) /*!< write value to ADC_ISQ_IL bit field */
/* ADC channel group definitions */
#define ADC_REGULAR_CHANNEL ((uint8_t)0x01U) /*!< adc regular channel group */
#define ADC_INSERTED_CHANNEL ((uint8_t)0x02U) /*!< adc inserted channel group */
#define ADC_REGULAR_INSERTED_CHANNEL ((uint8_t)0x03U) /*!< both regular and inserted channel group */
#define ADC_CHANNEL_DISCON_DISABLE ((uint8_t)0x04U) /*!< disable discontinuous mode of regular & inserted channel */
/* ADC inserted channel definitions */
#define ADC_INSERTED_CHANNEL_0 ((uint8_t)0x00U) /*!< adc inserted channel 0 */
#define ADC_INSERTED_CHANNEL_1 ((uint8_t)0x01U) /*!< adc inserted channel 1 */
#define ADC_INSERTED_CHANNEL_2 ((uint8_t)0x02U) /*!< adc inserted channel 2 */
#define ADC_INSERTED_CHANNEL_3 ((uint8_t)0x03U) /*!< adc inserted channel 3 */
/* ADC channel definitions */
#define ADC_CHANNEL_0 ((uint8_t)0x00U) /*!< ADC channel 0 */
#define ADC_CHANNEL_1 ((uint8_t)0x01U) /*!< ADC channel 1 */
#define ADC_CHANNEL_2 ((uint8_t)0x02U) /*!< ADC channel 2 */
#define ADC_CHANNEL_3 ((uint8_t)0x03U) /*!< ADC channel 3 */
#define ADC_CHANNEL_4 ((uint8_t)0x04U) /*!< ADC channel 4 */
#define ADC_CHANNEL_5 ((uint8_t)0x05U) /*!< ADC channel 5 */
#define ADC_CHANNEL_6 ((uint8_t)0x06U) /*!< ADC channel 6 */
#define ADC_CHANNEL_7 ((uint8_t)0x07U) /*!< ADC channel 7 */
#define ADC_CHANNEL_8 ((uint8_t)0x08U) /*!< ADC channel 8 */
#define ADC_CHANNEL_9 ((uint8_t)0x09U) /*!< ADC channel 9 */
#define ADC_CHANNEL_10 ((uint8_t)0x0AU) /*!< ADC channel 10 */
#define ADC_CHANNEL_11 ((uint8_t)0x0BU) /*!< ADC channel 11 */
#define ADC_CHANNEL_12 ((uint8_t)0x0CU) /*!< ADC channel 12 */
#define ADC_CHANNEL_13 ((uint8_t)0x0DU) /*!< ADC channel 13 */
#define ADC_CHANNEL_14 ((uint8_t)0x0EU) /*!< ADC channel 14 */
#define ADC_CHANNEL_15 ((uint8_t)0x0FU) /*!< ADC channel 15 */
#define ADC_CHANNEL_16 ((uint8_t)0x10U) /*!< ADC channel 16 */
#define ADC_CHANNEL_17 ((uint8_t)0x11U) /*!< ADC channel 17 */
/* ADC interrupt */
#define ADC_INT_WDE ADC_STAT_WDE /*!< analog watchdog event interrupt */
#define ADC_INT_EOC ADC_STAT_EOC /*!< end of group conversion interrupt */
#define ADC_INT_EOIC ADC_STAT_EOIC /*!< end of inserted group conversion interrupt */
/* ADC interrupt flag */
#define ADC_INT_FLAG_WDE ADC_STAT_WDE /*!< analog watchdog event interrupt flag */
#define ADC_INT_FLAG_EOC ADC_STAT_EOC /*!< end of group conversion interrupt flag */
#define ADC_INT_FLAG_EOIC ADC_STAT_EOIC /*!< end of inserted group conversion interrupt flag */
/* ADC resolution definitions */
#define OVSCR_DRES(regval) (BITS(12, 13) & ((uint32_t)(regval) << 12))
#define ADC_RESOLUTION_12B OVSCR_DRES(0) /*!< 12-bit ADC resolution */
#define ADC_RESOLUTION_10B OVSCR_DRES(1) /*!< 10-bit ADC resolution */
#define ADC_RESOLUTION_8B OVSCR_DRES(2) /*!< 8-bit ADC resolution */
#define ADC_RESOLUTION_6B OVSCR_DRES(3) /*!< 6-bit ADC resolution */
/* ADC oversampling mode */
#define ADC_OVERSAMPLING_ALL_CONVERT 0 /*!< all oversampled conversions for a channel are done consecutively after a trigger */
#define ADC_OVERSAMPLING_ONE_CONVERT 1 /*!< each oversampled conversion for a channel needs a trigger */
/* ADC oversampling shift */
#define OVSCR_OVSS(regval) (BITS(5, 8) & ((uint32_t)(regval) << 5))
#define ADC_OVERSAMPLING_SHIFT_NONE OVSCR_OVSS(0) /*!< no oversampling shift */
#define ADC_OVERSAMPLING_SHIFT_1B OVSCR_OVSS(1) /*!< 1-bit oversampling shift */
#define ADC_OVERSAMPLING_SHIFT_2B OVSCR_OVSS(2) /*!< 2-bit oversampling shift */
#define ADC_OVERSAMPLING_SHIFT_3B OVSCR_OVSS(3) /*!< 3-bit oversampling shift */
#define ADC_OVERSAMPLING_SHIFT_4B OVSCR_OVSS(4) /*!< 4-bit oversampling shift */
#define ADC_OVERSAMPLING_SHIFT_5B OVSCR_OVSS(5) /*!< 5-bit oversampling shift */
#define ADC_OVERSAMPLING_SHIFT_6B OVSCR_OVSS(6) /*!< 6-bit oversampling shift */
#define ADC_OVERSAMPLING_SHIFT_7B OVSCR_OVSS(7) /*!< 7-bit oversampling shift */
#define ADC_OVERSAMPLING_SHIFT_8B OVSCR_OVSS(8) /*!< 8-bit oversampling shift */
/* ADC oversampling ratio */
#define OVSCR_OVSR(regval) (BITS(2, 4) & ((uint32_t)(regval) << 2))
#define ADC_OVERSAMPLING_RATIO_MUL2 OVSCR_OVSR(0) /*!< oversampling ratio X2 */
#define ADC_OVERSAMPLING_RATIO_MUL4 OVSCR_OVSR(1) /*!< oversampling ratio X4 */
#define ADC_OVERSAMPLING_RATIO_MUL8 OVSCR_OVSR(2) /*!< oversampling ratio X8 */
#define ADC_OVERSAMPLING_RATIO_MUL16 OVSCR_OVSR(3) /*!< oversampling ratio X16 */
#define ADC_OVERSAMPLING_RATIO_MUL32 OVSCR_OVSR(4) /*!< oversampling ratio X32 */
#define ADC_OVERSAMPLING_RATIO_MUL64 OVSCR_OVSR(5) /*!< oversampling ratio X64 */
#define ADC_OVERSAMPLING_RATIO_MUL128 OVSCR_OVSR(6) /*!< oversampling ratio X128 */
#define ADC_OVERSAMPLING_RATIO_MUL256 OVSCR_OVSR(7) /*!< oversampling ratio X256 */
/* function declarations */
/* initialization config */
/* reset ADC */
void adc_deinit(uint32_t adc_periph);
/* configure the ADC sync mode */
void adc_mode_config(uint32_t mode);
/* enable or disable ADC special function */
void adc_special_function_config(uint32_t adc_periph, uint32_t function, ControlStatus newvalue);
/* configure ADC data alignment */
void adc_data_alignment_config(uint32_t adc_periph, uint32_t data_alignment);
/* enable ADC interface */
void adc_enable(uint32_t adc_periph);
/* disable ADC interface */
void adc_disable(uint32_t adc_periph);
/* ADC calibration and reset calibration */
void adc_calibration_enable(uint32_t adc_periph);
/* enable the temperature sensor and Vrefint channel */
void adc_tempsensor_vrefint_enable(void);
/* disable the temperature sensor and Vrefint channel */
void adc_tempsensor_vrefint_disable(void);
/* DMA config */
/* enable DMA request */
void adc_dma_mode_enable(uint32_t adc_periph);
/* disable DMA request */
void adc_dma_mode_disable(uint32_t adc_periph);
/* regular group and inserted group config */
/* configure ADC discontinuous mode */
void adc_discontinuous_mode_config(uint32_t adc_periph, uint8_t adc_channel_group, uint8_t length);
/* configure the length of regular channel group or inserted channel group */
void adc_channel_length_config(uint32_t adc_periph, uint8_t adc_channel_group, uint32_t length);
/* configure ADC regular channel */
void adc_regular_channel_config(uint32_t adc_periph, uint8_t rank, uint8_t adc_channel, uint32_t sample_time);
/* configure ADC inserted channel */
void adc_inserted_channel_config(uint32_t adc_periph, uint8_t rank, uint8_t adc_channel, uint32_t sample_time);
/* configure ADC inserted channel offset */
void adc_inserted_channel_offset_config(uint32_t adc_periph, uint8_t inserted_channel, uint16_t offset);
/* configure ADC external trigger source */
void adc_external_trigger_source_config(uint32_t adc_periph, uint8_t adc_channel_group, uint32_t external_trigger_source);
/* configure ADC external trigger */
void adc_external_trigger_config(uint32_t adc_periph, uint8_t adc_channel_group, ControlStatus newvalue);
/* enable ADC software trigger */
void adc_software_trigger_enable(uint32_t adc_periph, uint8_t adc_channel_group);
/* get channel data */
/* read ADC regular group data register */
uint16_t adc_regular_data_read(uint32_t adc_periph);
/* read ADC inserted group data register */
uint16_t adc_inserted_data_read(uint32_t adc_periph, uint8_t inserted_channel);
/* read the last ADC0 and ADC1 conversion result data in sync mode */
uint32_t adc_sync_mode_convert_value_read(void);
/* watchdog config */
/* configure ADC analog watchdog single channel */
void adc_watchdog_single_channel_enable(uint32_t adc_periph, uint8_t adc_channel);
/* configure ADC analog watchdog group channel */
void adc_watchdog_group_channel_enable(uint32_t adc_periph, uint8_t adc_channel_group);
/* disable ADC analog watchdog */
void adc_watchdog_disable(uint32_t adc_periph);
/* configure ADC analog watchdog threshold */
void adc_watchdog_threshold_config(uint32_t adc_periph, uint16_t low_threshold, uint16_t high_threshold);
/* interrupt & flag functions */
/* get the ADC flag bits */
FlagStatus adc_flag_get(uint32_t adc_periph, uint32_t adc_flag);
/* clear the ADC flag bits */
void adc_flag_clear(uint32_t adc_periph, uint32_t adc_flag);
/* get the bit state of ADCx software start conversion */
FlagStatus adc_regular_software_startconv_flag_get(uint32_t adc_periph);
/* get the bit state of ADCx software inserted channel start conversion */
FlagStatus adc_inserted_software_startconv_flag_get(uint32_t adc_periph);
/* get the ADC interrupt bits */
FlagStatus adc_interrupt_flag_get(uint32_t adc_periph, uint32_t adc_interrupt);
/* clear the ADC flag */
void adc_interrupt_flag_clear(uint32_t adc_periph, uint32_t adc_interrupt);
/* enable ADC interrupt */
void adc_interrupt_enable(uint32_t adc_periph, uint32_t adc_interrupt);
/* disable ADC interrupt */
void adc_interrupt_disable(uint32_t adc_periph, uint32_t adc_interrupt);
/* ADC resolution & oversample */
/* ADC resolution config */
void adc_resolution_config(uint32_t adc_periph, uint32_t resolution);
/* ADC oversample mode config */
void adc_oversample_mode_config(uint32_t adc_periph, uint8_t mode, uint16_t shift, uint8_t ratio);
/* enable ADC oversample mode */
void adc_oversample_mode_enable(uint32_t adc_periph);
/* disable ADC oversample mode */
void adc_oversample_mode_disable(uint32_t adc_periph);
#endif /* GD32VF103_ADC_H */
#ifdef __cplusplus
}
#endif

View File

@@ -1,231 +0,0 @@
/*!
\file gd32vf103_bkp.h
\brief definitions for the BKP
\version 2019-06-05, 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.
*/
#ifdef __cplusplus
extern "C" {
#endif
#ifndef GD32VF103_BKP_H
#define GD32VF103_BKP_H
#include "gd32vf103.h"
/* BKP definitions */
#define BKP BKP_BASE /*!< BKP base address */
/* registers definitions */
#define BKP_DATA0 REG16((BKP) + 0x04U) /*!< BKP data register 0 */
#define BKP_DATA1 REG16((BKP) + 0x08U) /*!< BKP data register 1 */
#define BKP_DATA2 REG16((BKP) + 0x0CU) /*!< BKP data register 2 */
#define BKP_DATA3 REG16((BKP) + 0x10U) /*!< BKP data register 3 */
#define BKP_DATA4 REG16((BKP) + 0x14U) /*!< BKP data register 4 */
#define BKP_DATA5 REG16((BKP) + 0x18U) /*!< BKP data register 5 */
#define BKP_DATA6 REG16((BKP) + 0x1CU) /*!< BKP data register 6 */
#define BKP_DATA7 REG16((BKP) + 0x20U) /*!< BKP data register 7 */
#define BKP_DATA8 REG16((BKP) + 0x24U) /*!< BKP data register 8 */
#define BKP_DATA9 REG16((BKP) + 0x28U) /*!< BKP data register 9 */
#define BKP_DATA10 REG16((BKP) + 0x40U) /*!< BKP data register 10 */
#define BKP_DATA11 REG16((BKP) + 0x44U) /*!< BKP data register 11 */
#define BKP_DATA12 REG16((BKP) + 0x48U) /*!< BKP data register 12 */
#define BKP_DATA13 REG16((BKP) + 0x4CU) /*!< BKP data register 13 */
#define BKP_DATA14 REG16((BKP) + 0x50U) /*!< BKP data register 14 */
#define BKP_DATA15 REG16((BKP) + 0x54U) /*!< BKP data register 15 */
#define BKP_DATA16 REG16((BKP) + 0x58U) /*!< BKP data register 16 */
#define BKP_DATA17 REG16((BKP) + 0x5CU) /*!< BKP data register 17 */
#define BKP_DATA18 REG16((BKP) + 0x60U) /*!< BKP data register 18 */
#define BKP_DATA19 REG16((BKP) + 0x64U) /*!< BKP data register 19 */
#define BKP_DATA20 REG16((BKP) + 0x68U) /*!< BKP data register 20 */
#define BKP_DATA21 REG16((BKP) + 0x6CU) /*!< BKP data register 21 */
#define BKP_DATA22 REG16((BKP) + 0x70U) /*!< BKP data register 22 */
#define BKP_DATA23 REG16((BKP) + 0x74U) /*!< BKP data register 23 */
#define BKP_DATA24 REG16((BKP) + 0x78U) /*!< BKP data register 24 */
#define BKP_DATA25 REG16((BKP) + 0x7CU) /*!< BKP data register 25 */
#define BKP_DATA26 REG16((BKP) + 0x80U) /*!< BKP data register 26 */
#define BKP_DATA27 REG16((BKP) + 0x84U) /*!< BKP data register 27 */
#define BKP_DATA28 REG16((BKP) + 0x88U) /*!< BKP data register 28 */
#define BKP_DATA29 REG16((BKP) + 0x8CU) /*!< BKP data register 29 */
#define BKP_DATA30 REG16((BKP) + 0x90U) /*!< BKP data register 30 */
#define BKP_DATA31 REG16((BKP) + 0x94U) /*!< BKP data register 31 */
#define BKP_DATA32 REG16((BKP) + 0x98U) /*!< BKP data register 32 */
#define BKP_DATA33 REG16((BKP) + 0x9CU) /*!< BKP data register 33 */
#define BKP_DATA34 REG16((BKP) + 0xA0U) /*!< BKP data register 34 */
#define BKP_DATA35 REG16((BKP) + 0xA4U) /*!< BKP data register 35 */
#define BKP_DATA36 REG16((BKP) + 0xA8U) /*!< BKP data register 36 */
#define BKP_DATA37 REG16((BKP) + 0xACU) /*!< BKP data register 37 */
#define BKP_DATA38 REG16((BKP) + 0xB0U) /*!< BKP data register 38 */
#define BKP_DATA39 REG16((BKP) + 0xB4U) /*!< BKP data register 39 */
#define BKP_DATA40 REG16((BKP) + 0xB8U) /*!< BKP data register 40 */
#define BKP_DATA41 REG16((BKP) + 0xBCU) /*!< BKP data register 41 */
#define BKP_OCTL REG16((BKP) + 0x2CU) /*!< RTC signal output control register */
#define BKP_TPCTL REG16((BKP) + 0x30U) /*!< tamper pin control register */
#define BKP_TPCS REG16((BKP) + 0x34U) /*!< tamper control and status register */
/* bits definitions */
/* BKP_DATA */
#define BKP_DATA BITS(0, 15) /*!< backup data */
/* BKP_OCTL */
#define BKP_OCTL_RCCV BITS(0, 6) /*!< RTC clock calibration value */
#define BKP_OCTL_COEN BIT(7) /*!< RTC clock calibration output enable */
#define BKP_OCTL_ASOEN BIT(8) /*!< RTC alarm or second signal output enable */
#define BKP_OCTL_ROSEL BIT(9) /*!< RTC output selection */
/* BKP_TPCTL */
#define BKP_TPCTL_TPEN BIT(0) /*!< tamper detection enable */
#define BKP_TPCTL_TPAL BIT(1) /*!< tamper pin active level */
/* BKP_TPCS */
#define BKP_TPCS_TER BIT(0) /*!< tamper event reset */
#define BKP_TPCS_TIR BIT(1) /*!< tamper interrupt reset */
#define BKP_TPCS_TPIE BIT(2) /*!< tamper interrupt enable */
#define BKP_TPCS_TEF BIT(8) /*!< tamper event flag */
#define BKP_TPCS_TIF BIT(9) /*!< tamper interrupt flag */
/* constants definitions */
/* BKP data register number */
typedef enum {
BKP_DATA_0 = 1, /*!< BKP data register 0 */
BKP_DATA_1, /*!< BKP data register 1 */
BKP_DATA_2, /*!< BKP data register 2 */
BKP_DATA_3, /*!< BKP data register 3 */
BKP_DATA_4, /*!< BKP data register 4 */
BKP_DATA_5, /*!< BKP data register 5 */
BKP_DATA_6, /*!< BKP data register 6 */
BKP_DATA_7, /*!< BKP data register 7 */
BKP_DATA_8, /*!< BKP data register 8 */
BKP_DATA_9, /*!< BKP data register 9 */
BKP_DATA_10, /*!< BKP data register 10 */
BKP_DATA_11, /*!< BKP data register 11 */
BKP_DATA_12, /*!< BKP data register 12 */
BKP_DATA_13, /*!< BKP data register 13 */
BKP_DATA_14, /*!< BKP data register 14 */
BKP_DATA_15, /*!< BKP data register 15 */
BKP_DATA_16, /*!< BKP data register 16 */
BKP_DATA_17, /*!< BKP data register 17 */
BKP_DATA_18, /*!< BKP data register 18 */
BKP_DATA_19, /*!< BKP data register 19 */
BKP_DATA_20, /*!< BKP data register 20 */
BKP_DATA_21, /*!< BKP data register 21 */
BKP_DATA_22, /*!< BKP data register 22 */
BKP_DATA_23, /*!< BKP data register 23 */
BKP_DATA_24, /*!< BKP data register 24 */
BKP_DATA_25, /*!< BKP data register 25 */
BKP_DATA_26, /*!< BKP data register 26 */
BKP_DATA_27, /*!< BKP data register 27 */
BKP_DATA_28, /*!< BKP data register 28 */
BKP_DATA_29, /*!< BKP data register 29 */
BKP_DATA_30, /*!< BKP data register 30 */
BKP_DATA_31, /*!< BKP data register 31 */
BKP_DATA_32, /*!< BKP data register 32 */
BKP_DATA_33, /*!< BKP data register 33 */
BKP_DATA_34, /*!< BKP data register 34 */
BKP_DATA_35, /*!< BKP data register 35 */
BKP_DATA_36, /*!< BKP data register 36 */
BKP_DATA_37, /*!< BKP data register 37 */
BKP_DATA_38, /*!< BKP data register 38 */
BKP_DATA_39, /*!< BKP data register 39 */
BKP_DATA_40, /*!< BKP data register 40 */
BKP_DATA_41, /*!< BKP data register 41 */
} bkp_data_register_enum;
/* BKP register */
#define BKP_DATA0_9(number) REG16((BKP) + 0x04U + (number)*0x04U)
#define BKP_DATA10_41(number) REG16((BKP) + 0x40U + ((number)-10U) * 0x04U)
/* get data of BKP data register */
#define BKP_DATA_GET(regval) GET_BITS((uint32_t)(regval), 0, 15)
/* RTC clock calibration value */
#define OCTL_RCCV(regval) (BITS(0, 6) & ((uint32_t)(regval) << 0))
/* RTC output selection */
#define RTC_OUTPUT_ALARM_PULSE ((uint16_t)0x0000U) /*!< RTC alarm pulse is selected as the RTC output */
#define RTC_OUTPUT_SECOND_PULSE ((uint16_t)0x0200U) /*!< RTC second pulse is selected as the RTC output */
/* tamper pin active level */
#define TAMPER_PIN_ACTIVE_HIGH ((uint16_t)0x0000U) /*!< the tamper pin is active high */
#define TAMPER_PIN_ACTIVE_LOW ((uint16_t)0x0002U) /*!< the tamper pin is active low */
/* tamper flag */
#define BKP_FLAG_TAMPER BKP_TPCS_TEF /*!< tamper event flag */
/* tamper interrupt flag */
#define BKP_INT_FLAG_TAMPER BKP_TPCS_TIF /*!< tamper interrupt flag */
/* function declarations */
/* reset BKP registers */
void bkp_deinit(void);
/* write BKP data register */
void bkp_data_write(bkp_data_register_enum register_number, uint16_t data);
/* read BKP data register */
uint16_t bkp_data_read(bkp_data_register_enum register_number);
/* RTC related functions */
/* enable RTC clock calibration output */
void bkp_rtc_calibration_output_enable(void);
/* disable RTC clock calibration output */
void bkp_rtc_calibration_output_disable(void);
/* enable RTC alarm or second signal output */
void bkp_rtc_signal_output_enable(void);
/* disable RTC alarm or second signal output */
void bkp_rtc_signal_output_disable(void);
/* select RTC output */
void bkp_rtc_output_select(uint16_t outputsel);
/* set RTC clock calibration value */
void bkp_rtc_calibration_value_set(uint8_t value);
/* tamper pin related functions */
/* enable tamper pin detection */
void bkp_tamper_detection_enable(void);
/* disable tamper pin detection */
void bkp_tamper_detection_disable(void);
/* set tamper pin active level */
void bkp_tamper_active_level_set(uint16_t level);
/* interrupt & flag functions */
/* enable tamper interrupt */
void bkp_interrupt_enable(void);
/* disable tamper interrupt */
void bkp_interrupt_disable(void);
/* get tamper flag state */
FlagStatus bkp_flag_get(void);
/* clear tamper flag state */
void bkp_flag_clear(void);
/* get tamper interrupt flag state */
FlagStatus bkp_interrupt_flag_get(void);
/* clear tamper interrupt flag state */
void bkp_interrupt_flag_clear(void);
#endif /* GD32VF103_BKP_H */
#ifdef __cplusplus
}
#endif

View File

@@ -1,113 +0,0 @@
/*!
\file gd32vf103_dbg.h
\brief definitions for the DBG
\version 2019-06-05, 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.
*/
#ifdef __cplusplus
extern "C" {
#endif
#ifndef GD32VF103_DBG_H
#define GD32VF103_DBG_H
#include "gd32vf103.h"
/* DBG definitions */
#define DBG DBG_BASE
/* registers definitions */
#define DBG_ID REG32(DBG + 0x00U) /*!< DBG_ID code register */
#define DBG_CTL REG32(DBG + 0x04U) /*!< DBG control register */
/* bits definitions */
/* DBG_ID */
#define DBG_ID_ID_CODE BITS(0, 31) /*!< DBG ID code values */
/* DBG_CTL */
#define DBG_CTL_SLP_HOLD BIT(0) /*!< keep debugger connection during sleep mode */
#define DBG_CTL_DSLP_HOLD BIT(1) /*!< keep debugger connection during deepsleep mode */
#define DBG_CTL_STB_HOLD BIT(2) /*!< keep debugger connection during standby mode */
#define DBG_CTL_FWDGT_HOLD BIT(8) /*!< debug FWDGT kept when core is halted */
#define DBG_CTL_WWDGT_HOLD BIT(9) /*!< debug WWDGT kept when core is halted */
#define DBG_CTL_TIMER0_HOLD BIT(10) /*!< hold TIMER0 counter when core is halted */
#define DBG_CTL_TIMER1_HOLD BIT(11) /*!< hold TIMER1 counter when core is halted */
#define DBG_CTL_TIMER2_HOLD BIT(12) /*!< hold TIMER2 counter when core is halted */
#define DBG_CTL_TIMER3_HOLD BIT(13) /*!< hold TIMER3 counter when core is halted */
#define DBG_CTL_CAN0_HOLD BIT(14) /*!< debug CAN0 kept when core is halted */
#define DBG_CTL_I2C0_HOLD BIT(15) /*!< hold I2C0 smbus when core is halted */
#define DBG_CTL_I2C1_HOLD BIT(16) /*!< hold I2C1 smbus when core is halted */
#define DBG_CTL_TIMER4_HOLD BIT(18) /*!< hold TIMER4 counter when core is halted */
#define DBG_CTL_TIMER5_HOLD BIT(19) /*!< hold TIMER5 counter when core is halted */
#define DBG_CTL_TIMER6_HOLD BIT(20) /*!< hold TIMER6 counter when core is halted */
#define DBG_CTL_CAN1_HOLD BIT(21) /*!< debug CAN1 kept when core is halted */
/* constants definitions */
/* debug hold when core is halted */
typedef enum {
DBG_FWDGT_HOLD = BIT(8), /*!< debug FWDGT kept when core is halted */
DBG_WWDGT_HOLD = BIT(9), /*!< debug WWDGT kept when core is halted */
DBG_TIMER0_HOLD = BIT(10), /*!< hold TIMER0 counter when core is halted */
DBG_TIMER1_HOLD = BIT(11), /*!< hold TIMER1 counter when core is halted */
DBG_TIMER2_HOLD = BIT(12), /*!< hold TIMER2 counter when core is halted */
DBG_TIMER3_HOLD = BIT(13), /*!< hold TIMER3 counter when core is halted */
DBG_CAN0_HOLD = BIT(14), /*!< debug CAN0 kept when core is halted */
DBG_I2C0_HOLD = BIT(15), /*!< hold I2C0 smbus when core is halted */
DBG_I2C1_HOLD = BIT(16), /*!< hold I2C1 smbus when core is halted */
DBG_TIMER4_HOLD = BIT(17), /*!< hold TIMER4 counter when core is halted */
DBG_TIMER5_HOLD = BIT(18), /*!< hold TIMER5 counter when core is halted */
DBG_TIMER6_HOLD = BIT(19), /*!< hold TIMER6 counter when core is halted */
DBG_CAN1_HOLD = BIT(21), /*!< debug CAN1 kept when core is halted */
} dbg_periph_enum;
/* DBG low power mode configurations */
#define DBG_LOW_POWER_SLEEP DBG_CTL_SLP_HOLD /*!< keep debugger connection during sleep mode */
#define DBG_LOW_POWER_DEEPSLEEP DBG_CTL_DSLP_HOLD /*!< keep debugger connection during deepsleep mode */
#define DBG_LOW_POWER_STANDBY DBG_CTL_STB_HOLD /*!< keep debugger connection during standby mode */
/* function declarations */
/* read DBG_ID code register */
uint32_t dbg_id_get(void);
/* low power behavior configuration */
/* enable low power behavior when the MCU is in debug mode */
void dbg_low_power_enable(uint32_t dbg_low_power);
/* disable low power behavior when the MCU is in debug mode */
void dbg_low_power_disable(uint32_t dbg_low_power);
/* peripheral behavior configuration */
/* enable peripheral behavior when the MCU is in debug mode */
void dbg_periph_enable(dbg_periph_enum dbg_periph);
/* disable peripheral behavior when the MCU is in debug mode */
void dbg_periph_disable(dbg_periph_enum dbg_periph);
#endif /* GD32VF103_DBG_H */
#ifdef __cplusplus
}
#endif

View File

@@ -1,287 +0,0 @@
/*!
\file gd32vf103_dma.h
\brief definitions for the DMA
\version 2019-06-05, V1.0.0, firmware for GD32VF103
\version 2019-10-30, V1.0.1, 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.
*/
#ifdef __cplusplus
extern "C" {
#endif
#ifndef GD32VF103_DMA_H
#define GD32VF103_DMA_H
#include "gd32vf103.h"
/* DMA definitions */
#define DMA0 (DMA_BASE) /*!< DMA0 base address */
#define DMA1 (DMA_BASE + 0x0400U) /*!< DMA1 base address */
/* registers definitions */
#define DMA_INTF(dmax) REG32((dmax) + 0x00U) /*!< DMA interrupt flag register */
#define DMA_INTC(dmax) REG32((dmax) + 0x04U) /*!< DMA interrupt flag clear register */
#define DMA_CH0CTL(dmax) REG32((dmax) + 0x08U) /*!< DMA channel 0 control register */
#define DMA_CH0CNT(dmax) REG32((dmax) + 0x0CU) /*!< DMA channel 0 counter register */
#define DMA_CH0PADDR(dmax) REG32((dmax) + 0x10U) /*!< DMA channel 0 peripheral base address register */
#define DMA_CH0MADDR(dmax) REG32((dmax) + 0x14U) /*!< DMA channel 0 memory base address register */
#define DMA_CH1CTL(dmax) REG32((dmax) + 0x1CU) /*!< DMA channel 1 control register */
#define DMA_CH1CNT(dmax) REG32((dmax) + 0x20U) /*!< DMA channel 1 counter register */
#define DMA_CH1PADDR(dmax) REG32((dmax) + 0x24U) /*!< DMA channel 1 peripheral base address register */
#define DMA_CH1MADDR(dmax) REG32((dmax) + 0x28U) /*!< DMA channel 1 memory base address register */
#define DMA_CH2CTL(dmax) REG32((dmax) + 0x30U) /*!< DMA channel 2 control register */
#define DMA_CH2CNT(dmax) REG32((dmax) + 0x34U) /*!< DMA channel 2 counter register */
#define DMA_CH2PADDR(dmax) REG32((dmax) + 0x38U) /*!< DMA channel 2 peripheral base address register */
#define DMA_CH2MADDR(dmax) REG32((dmax) + 0x3CU) /*!< DMA channel 2 memory base address register */
#define DMA_CH3CTL(dmax) REG32((dmax) + 0x44U) /*!< DMA channel 3 control register */
#define DMA_CH3CNT(dmax) REG32((dmax) + 0x48U) /*!< DMA channel 3 counter register */
#define DMA_CH3PADDR(dmax) REG32((dmax) + 0x4CU) /*!< DMA channel 3 peripheral base address register */
#define DMA_CH3MADDR(dmax) REG32((dmax) + 0x50U) /*!< DMA channel 3 memory base address register */
#define DMA_CH4CTL(dmax) REG32((dmax) + 0x58U) /*!< DMA channel 4 control register */
#define DMA_CH4CNT(dmax) REG32((dmax) + 0x5CU) /*!< DMA channel 4 counter register */
#define DMA_CH4PADDR(dmax) REG32((dmax) + 0x60U) /*!< DMA channel 4 peripheral base address register */
#define DMA_CH4MADDR(dmax) REG32((dmax) + 0x64U) /*!< DMA channel 4 memory base address register */
#define DMA_CH5CTL(dmax) REG32((dmax) + 0x6CU) /*!< DMA channel 5 control register */
#define DMA_CH5CNT(dmax) REG32((dmax) + 0x70U) /*!< DMA channel 5 counter register */
#define DMA_CH5PADDR(dmax) REG32((dmax) + 0x74U) /*!< DMA channel 5 peripheral base address register */
#define DMA_CH5MADDR(dmax) REG32((dmax) + 0x78U) /*!< DMA channel 5 memory base address register */
#define DMA_CH6CTL(dmax) REG32((dmax) + 0x80U) /*!< DMA channel 6 control register */
#define DMA_CH6CNT(dmax) REG32((dmax) + 0x84U) /*!< DMA channel 6 counter register */
#define DMA_CH6PADDR(dmax) REG32((dmax) + 0x88U) /*!< DMA channel 6 peripheral base address register */
#define DMA_CH6MADDR(dmax) REG32((dmax) + 0x8CU) /*!< DMA channel 6 memory base address register */
/* bits definitions */
/* DMA_INTF */
#define DMA_INTF_GIF BIT(0) /*!< global interrupt flag of channel */
#define DMA_INTF_FTFIF BIT(1) /*!< full transfer finish flag of channel */
#define DMA_INTF_HTFIF BIT(2) /*!< half transfer finish flag of channel */
#define DMA_INTF_ERRIF BIT(3) /*!< error flag of channel */
/* DMA_INTC */
#define DMA_INTC_GIFC BIT(0) /*!< clear global interrupt flag of channel */
#define DMA_INTC_FTFIFC BIT(1) /*!< clear transfer finish flag of channel */
#define DMA_INTC_HTFIFC BIT(2) /*!< clear half transfer finish flag of channel */
#define DMA_INTC_ERRIFC BIT(3) /*!< clear error flag of channel */
/* DMA_CHxCTL, x=0..6 */
#define DMA_CHXCTL_CHEN BIT(0) /*!< channel enable */
#define DMA_CHXCTL_FTFIE BIT(1) /*!< enable bit for channel full transfer finish interrupt */
#define DMA_CHXCTL_HTFIE BIT(2) /*!< enable bit for channel half transfer finish interrupt */
#define DMA_CHXCTL_ERRIE BIT(3) /*!< enable bit for channel error interrupt */
#define DMA_CHXCTL_DIR BIT(4) /*!< transfer direction */
#define DMA_CHXCTL_CMEN BIT(5) /*!< circular mode enable */
#define DMA_CHXCTL_PNAGA BIT(6) /*!< next address generation algorithm of peripheral */
#define DMA_CHXCTL_MNAGA BIT(7) /*!< next address generation algorithm of memory */
#define DMA_CHXCTL_PWIDTH BITS(8, 9) /*!< transfer data width of peripheral */
#define DMA_CHXCTL_MWIDTH BITS(10, 11) /*!< transfer data width of memory */
#define DMA_CHXCTL_PRIO BITS(12, 13) /*!< priority level */
#define DMA_CHXCTL_M2M BIT(14) /*!< memory to memory mode */
/* DMA_CHxCNT, x=0..6 */
#define DMA_CHXCNT_CNT BITS(0, 15) /*!< transfer counter */
/* DMA_CHxPADDR, x=0..6 */
#define DMA_CHXPADDR_PADDR BITS(0, 31) /*!< peripheral base address */
/* DMA_CHxMADDR, x=0..6 */
#define DMA_CHXMADDR_MADDR BITS(0, 31) /*!< memory base address */
/* constants definitions */
/* DMA channel select */
typedef enum {
DMA_CH0 = 0, /*!< DMA Channel0 */
DMA_CH1, /*!< DMA Channel1 */
DMA_CH2, /*!< DMA Channel2 */
DMA_CH3, /*!< DMA Channel3 */
DMA_CH4, /*!< DMA Channel4 */
DMA_CH5, /*!< DMA Channel5 */
DMA_CH6 /*!< DMA Channel6 */
} dma_channel_enum;
/* DMA initialize struct */
typedef struct
{
uint32_t periph_addr; /*!< peripheral base address */
uint32_t periph_width; /*!< transfer data size of peripheral */
uint32_t memory_addr; /*!< memory base address */
uint32_t memory_width; /*!< transfer data size of memory */
uint32_t number; /*!< channel transfer number */
uint32_t priority; /*!< channel priority level */
uint8_t periph_inc; /*!< peripheral increasing mode */
uint8_t memory_inc; /*!< memory increasing mode */
uint8_t direction; /*!< channel data transfer direction */
} dma_parameter_struct;
#define DMA_FLAG_ADD(flag, shift) ((flag) << ((shift)*4U)) /*!< DMA channel flag shift */
/* DMA_register address */
#define DMA_CHCTL(dma, channel) REG32(((dma) + 0x08U) + 0x14U * (uint32_t)(channel)) /*!< the address of DMA channel CHXCTL register */
#define DMA_CHCNT(dma, channel) REG32(((dma) + 0x0CU) + 0x14U * (uint32_t)(channel)) /*!< the address of DMA channel CHXCNT register */
#define DMA_CHPADDR(dma, channel) REG32(((dma) + 0x10U) + 0x14U * (uint32_t)(channel)) /*!< the address of DMA channel CHXPADDR register */
#define DMA_CHMADDR(dma, channel) REG32(((dma) + 0x14U) + 0x14U * (uint32_t)(channel)) /*!< the address of DMA channel CHXMADDR register */
/* DMA reset value */
#define DMA_CHCTL_RESET_VALUE ((uint32_t)0x00000000U) /*!< the reset value of DMA channel CHXCTL register */
#define DMA_CHCNT_RESET_VALUE ((uint32_t)0x00000000U) /*!< the reset value of DMA channel CHXCNT register */
#define DMA_CHPADDR_RESET_VALUE ((uint32_t)0x00000000U) /*!< the reset value of DMA channel CHXPADDR register */
#define DMA_CHMADDR_RESET_VALUE ((uint32_t)0x00000000U) /*!< the reset value of DMA channel CHXMADDR register */
#define DMA_CHINTF_RESET_VALUE (DMA_INTF_GIF | DMA_INTF_FTFIF | \
DMA_INTF_HTFIF | DMA_INTF_ERRIF) /*!< clear DMA channel DMA_INTF register */
/* DMA_INTF register */
/* interrupt flag bits */
#define DMA_INT_FLAG_G DMA_INTF_GIF /*!< global interrupt flag of channel */
#define DMA_INT_FLAG_FTF DMA_INTF_FTFIF /*!< full transfer finish interrupt flag of channel */
#define DMA_INT_FLAG_HTF DMA_INTF_HTFIF /*!< half transfer finish interrupt flag of channel */
#define DMA_INT_FLAG_ERR DMA_INTF_ERRIF /*!< error interrupt flag of channel */
/* flag bits */
#define DMA_FLAG_G DMA_INTF_GIF /*!< global interrupt flag of channel */
#define DMA_FLAG_FTF DMA_INTF_FTFIF /*!< full transfer finish flag of channel */
#define DMA_FLAG_HTF DMA_INTF_HTFIF /*!< half transfer finish flag of channel */
#define DMA_FLAG_ERR DMA_INTF_ERRIF /*!< error flag of channel */
/* DMA_CHxCTL register */
/* interrupt enable bits */
#define DMA_INT_FTF DMA_CHXCTL_FTFIE /*!< enable bit for channel full transfer finish interrupt */
#define DMA_INT_HTF DMA_CHXCTL_HTFIE /*!< enable bit for channel half transfer finish interrupt */
#define DMA_INT_ERR DMA_CHXCTL_ERRIE /*!< enable bit for channel error interrupt */
/* transfer direction */
#define DMA_PERIPHERAL_TO_MEMORY ((uint8_t)0x00U) /*!< read from peripheral and write to memory */
#define DMA_MEMORY_TO_PERIPHERAL ((uint8_t)0x01U) /*!< read from memory and write to peripheral */
/* peripheral increasing mode */
#define DMA_PERIPH_INCREASE_DISABLE ((uint8_t)0x00U) /*!< next address of peripheral is fixed address mode */
#define DMA_PERIPH_INCREASE_ENABLE ((uint8_t)0x01U) /*!< next address of peripheral is increasing address mode */
/* memory increasing mode */
#define DMA_MEMORY_INCREASE_DISABLE ((uint8_t)0x00U) /*!< next address of memory is fixed address mode */
#define DMA_MEMORY_INCREASE_ENABLE ((uint8_t)0x01U) /*!< next address of memory is increasing address mode */
/* transfer data size of peripheral */
#define CHCTL_PWIDTH(regval) (BITS(8, 9) & ((uint32_t)(regval) << 8)) /*!< transfer data size of peripheral */
#define DMA_PERIPHERAL_WIDTH_8BIT CHCTL_PWIDTH(0U) /*!< transfer data size of peripheral is 8-bit */
#define DMA_PERIPHERAL_WIDTH_16BIT CHCTL_PWIDTH(1U) /*!< transfer data size of peripheral is 16-bit */
#define DMA_PERIPHERAL_WIDTH_32BIT CHCTL_PWIDTH(2U) /*!< transfer data size of peripheral is 32-bit */
/* transfer data size of memory */
#define CHCTL_MWIDTH(regval) (BITS(10, 11) & ((uint32_t)(regval) << 10)) /*!< transfer data size of memory */
#define DMA_MEMORY_WIDTH_8BIT CHCTL_MWIDTH(0U) /*!< transfer data size of memory is 8-bit */
#define DMA_MEMORY_WIDTH_16BIT CHCTL_MWIDTH(1U) /*!< transfer data size of memory is 16-bit */
#define DMA_MEMORY_WIDTH_32BIT CHCTL_MWIDTH(2U) /*!< transfer data size of memory is 32-bit */
/* channel priority level */
#define CHCTL_PRIO(regval) (BITS(12, 13) & ((uint32_t)(regval) << 12)) /*!< DMA channel priority level */
#define DMA_PRIORITY_LOW CHCTL_PRIO(0U) /*!< low priority */
#define DMA_PRIORITY_MEDIUM CHCTL_PRIO(1U) /*!< medium priority */
#define DMA_PRIORITY_HIGH CHCTL_PRIO(2U) /*!< high priority */
#define DMA_PRIORITY_ULTRA_HIGH CHCTL_PRIO(3U) /*!< ultra high priority */
/* memory to memory mode */
#define DMA_MEMORY_TO_MEMORY_DISABLE ((uint32_t)0x00000000U) /*!< disable memory to memory mode */
#define DMA_MEMORY_TO_MEMORY_ENABLE ((uint32_t)0x00000001U) /*!< enable memory to memory mode */
/* DMA_CHxCNT register */
/* transfer counter */
#define DMA_CHANNEL_CNT_MASK DMA_CHXCNT_CNT /*!< transfer counter mask */
/* function declarations */
/* DMA deinitialization and initialization functions */
/* deinitialize DMA a channel registers */
void dma_deinit(uint32_t dma_periph, dma_channel_enum channelx);
/* initialize the parameters of DMA struct with the default values */
void dma_struct_para_init(dma_parameter_struct *init_struct);
/* initialize DMA channel */
void dma_init(uint32_t dma_periph, dma_channel_enum channelx, dma_parameter_struct *init_struct);
/* enable DMA circulation mode */
void dma_circulation_enable(uint32_t dma_periph, dma_channel_enum channelx);
/* disable DMA circulation mode */
void dma_circulation_disable(uint32_t dma_periph, dma_channel_enum channelx);
/* enable memory to memory mode */
void dma_memory_to_memory_enable(uint32_t dma_periph, dma_channel_enum channelx);
/* disable memory to memory mode */
void dma_memory_to_memory_disable(uint32_t dma_periph, dma_channel_enum channelx);
/* enable DMA channel */
void dma_channel_enable(uint32_t dma_periph, dma_channel_enum channelx);
/* disable DMA channel */
void dma_channel_disable(uint32_t dma_periph, dma_channel_enum channelx);
/* DMA configuration functions */
/* set DMA peripheral base address */
void dma_periph_address_config(uint32_t dma_periph, dma_channel_enum channelx, uint32_t address);
/* set DMA memory base address */
void dma_memory_address_config(uint32_t dma_periph, dma_channel_enum channelx, uint32_t address);
/* set the number of remaining data to be transferred by the DMA */
void dma_transfer_number_config(uint32_t dma_periph, dma_channel_enum channelx, uint32_t number);
/* get the number of remaining data to be transferred by the DMA */
uint32_t dma_transfer_number_get(uint32_t dma_periph, dma_channel_enum channelx);
/* configure priority level of DMA channel */
void dma_priority_config(uint32_t dma_periph, dma_channel_enum channelx, uint32_t priority);
/* configure transfer data size of memory */
void dma_memory_width_config(uint32_t dma_periph, dma_channel_enum channelx, uint32_t mwidth);
/* configure transfer data size of peripheral */
void dma_periph_width_config(uint32_t dma_periph, dma_channel_enum channelx, uint32_t pwidth);
/* enable next address increasement algorithm of memory */
void dma_memory_increase_enable(uint32_t dma_periph, dma_channel_enum channelx);
/* disable next address increasement algorithm of memory */
void dma_memory_increase_disable(uint32_t dma_periph, dma_channel_enum channelx);
/* enable next address increasement algorithm of peripheral */
void dma_periph_increase_enable(uint32_t dma_periph, dma_channel_enum channelx);
/* disable next address increasement algorithm of peripheral */
void dma_periph_increase_disable(uint32_t dma_periph, dma_channel_enum channelx);
/* configure the direction of data transfer on the channel */
void dma_transfer_direction_config(uint32_t dma_periph, dma_channel_enum channelx, uint8_t direction);
/* flag and interrupt functions */
/* check DMA flag is set or not */
FlagStatus dma_flag_get(uint32_t dma_periph, dma_channel_enum channelx, uint32_t flag);
/* clear the flag of a DMA channel */
void dma_flag_clear(uint32_t dma_periph, dma_channel_enum channelx, uint32_t flag);
/* check DMA flag and interrupt enable bit is set or not */
FlagStatus dma_interrupt_flag_get(uint32_t dma_periph, dma_channel_enum channelx, uint32_t flag);
/* clear the interrupt flag of a DMA channel */
void dma_interrupt_flag_clear(uint32_t dma_periph, dma_channel_enum channelx, uint32_t flag);
/* enable DMA interrupt */
void dma_interrupt_enable(uint32_t dma_periph, dma_channel_enum channelx, uint32_t source);
/* disable DMA interrupt */
void dma_interrupt_disable(uint32_t dma_periph, dma_channel_enum channelx, uint32_t source);
#endif /* GD32VF103_DMA_H */
#ifdef __cplusplus
}
#endif

View File

@@ -1,250 +0,0 @@
/*!
\file gd32vf103_exti.h
\brief definitions for the EXTI
\version 2019-06-05, 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.
*/
#ifdef __cplusplus
extern "C" {
#endif
#ifndef GD32VF103_EXTI_H
#define GD32VF103_EXTI_H
#include "gd32vf103.h"
/* EXTI definitions */
#define EXTI EXTI_BASE
/* registers definitions */
#define EXTI_INTEN REG32(EXTI + 0x00U) /*!< interrupt enable register */
#define EXTI_EVEN REG32(EXTI + 0x04U) /*!< event enable register */
#define EXTI_RTEN REG32(EXTI + 0x08U) /*!< rising edge trigger enable register */
#define EXTI_FTEN REG32(EXTI + 0x0CU) /*!< falling trigger enable register */
#define EXTI_SWIEV REG32(EXTI + 0x10U) /*!< software interrupt event register */
#define EXTI_PD REG32(EXTI + 0x14U) /*!< pending register */
/* bits definitions */
/* EXTI_INTEN */
#define EXTI_INTEN_INTEN0 BIT(0) /*!< interrupt from line 0 */
#define EXTI_INTEN_INTEN1 BIT(1) /*!< interrupt from line 1 */
#define EXTI_INTEN_INTEN2 BIT(2) /*!< interrupt from line 2 */
#define EXTI_INTEN_INTEN3 BIT(3) /*!< interrupt from line 3 */
#define EXTI_INTEN_INTEN4 BIT(4) /*!< interrupt from line 4 */
#define EXTI_INTEN_INTEN5 BIT(5) /*!< interrupt from line 5 */
#define EXTI_INTEN_INTEN6 BIT(6) /*!< interrupt from line 6 */
#define EXTI_INTEN_INTEN7 BIT(7) /*!< interrupt from line 7 */
#define EXTI_INTEN_INTEN8 BIT(8) /*!< interrupt from line 8 */
#define EXTI_INTEN_INTEN9 BIT(9) /*!< interrupt from line 9 */
#define EXTI_INTEN_INTEN10 BIT(10) /*!< interrupt from line 10 */
#define EXTI_INTEN_INTEN11 BIT(11) /*!< interrupt from line 11 */
#define EXTI_INTEN_INTEN12 BIT(12) /*!< interrupt from line 12 */
#define EXTI_INTEN_INTEN13 BIT(13) /*!< interrupt from line 13 */
#define EXTI_INTEN_INTEN14 BIT(14) /*!< interrupt from line 14 */
#define EXTI_INTEN_INTEN15 BIT(15) /*!< interrupt from line 15 */
#define EXTI_INTEN_INTEN16 BIT(16) /*!< interrupt from line 16 */
#define EXTI_INTEN_INTEN17 BIT(17) /*!< interrupt from line 17 */
#define EXTI_INTEN_INTEN18 BIT(18) /*!< interrupt from line 18 */
/* EXTI_EVEN */
#define EXTI_EVEN_EVEN0 BIT(0) /*!< event from line 0 */
#define EXTI_EVEN_EVEN1 BIT(1) /*!< event from line 1 */
#define EXTI_EVEN_EVEN2 BIT(2) /*!< event from line 2 */
#define EXTI_EVEN_EVEN3 BIT(3) /*!< event from line 3 */
#define EXTI_EVEN_EVEN4 BIT(4) /*!< event from line 4 */
#define EXTI_EVEN_EVEN5 BIT(5) /*!< event from line 5 */
#define EXTI_EVEN_EVEN6 BIT(6) /*!< event from line 6 */
#define EXTI_EVEN_EVEN7 BIT(7) /*!< event from line 7 */
#define EXTI_EVEN_EVEN8 BIT(8) /*!< event from line 8 */
#define EXTI_EVEN_EVEN9 BIT(9) /*!< event from line 9 */
#define EXTI_EVEN_EVEN10 BIT(10) /*!< event from line 10 */
#define EXTI_EVEN_EVEN11 BIT(11) /*!< event from line 11 */
#define EXTI_EVEN_EVEN12 BIT(12) /*!< event from line 12 */
#define EXTI_EVEN_EVEN13 BIT(13) /*!< event from line 13 */
#define EXTI_EVEN_EVEN14 BIT(14) /*!< event from line 14 */
#define EXTI_EVEN_EVEN15 BIT(15) /*!< event from line 15 */
#define EXTI_EVEN_EVEN16 BIT(16) /*!< event from line 16 */
#define EXTI_EVEN_EVEN17 BIT(17) /*!< event from line 17 */
#define EXTI_EVEN_EVEN18 BIT(18) /*!< event from line 18 */
/* EXTI_RTEN */
#define EXTI_RTEN_RTEN0 BIT(0) /*!< rising edge from line 0 */
#define EXTI_RTEN_RTEN1 BIT(1) /*!< rising edge from line 1 */
#define EXTI_RTEN_RTEN2 BIT(2) /*!< rising edge from line 2 */
#define EXTI_RTEN_RTEN3 BIT(3) /*!< rising edge from line 3 */
#define EXTI_RTEN_RTEN4 BIT(4) /*!< rising edge from line 4 */
#define EXTI_RTEN_RTEN5 BIT(5) /*!< rising edge from line 5 */
#define EXTI_RTEN_RTEN6 BIT(6) /*!< rising edge from line 6 */
#define EXTI_RTEN_RTEN7 BIT(7) /*!< rising edge from line 7 */
#define EXTI_RTEN_RTEN8 BIT(8) /*!< rising edge from line 8 */
#define EXTI_RTEN_RTEN9 BIT(9) /*!< rising edge from line 9 */
#define EXTI_RTEN_RTEN10 BIT(10) /*!< rising edge from line 10 */
#define EXTI_RTEN_RTEN11 BIT(11) /*!< rising edge from line 11 */
#define EXTI_RTEN_RTEN12 BIT(12) /*!< rising edge from line 12 */
#define EXTI_RTEN_RTEN13 BIT(13) /*!< rising edge from line 13 */
#define EXTI_RTEN_RTEN14 BIT(14) /*!< rising edge from line 14 */
#define EXTI_RTEN_RTEN15 BIT(15) /*!< rising edge from line 15 */
#define EXTI_RTEN_RTEN16 BIT(16) /*!< rising edge from line 16 */
#define EXTI_RTEN_RTEN17 BIT(17) /*!< rising edge from line 17 */
#define EXTI_RTEN_RTEN18 BIT(18) /*!< rising edge from line 18 */
/* EXTI_FTEN */
#define EXTI_FTEN_FTEN0 BIT(0) /*!< falling edge from line 0 */
#define EXTI_FTEN_FTEN1 BIT(1) /*!< falling edge from line 1 */
#define EXTI_FTEN_FTEN2 BIT(2) /*!< falling edge from line 2 */
#define EXTI_FTEN_FTEN3 BIT(3) /*!< falling edge from line 3 */
#define EXTI_FTEN_FTEN4 BIT(4) /*!< falling edge from line 4 */
#define EXTI_FTEN_FTEN5 BIT(5) /*!< falling edge from line 5 */
#define EXTI_FTEN_FTEN6 BIT(6) /*!< falling edge from line 6 */
#define EXTI_FTEN_FTEN7 BIT(7) /*!< falling edge from line 7 */
#define EXTI_FTEN_FTEN8 BIT(8) /*!< falling edge from line 8 */
#define EXTI_FTEN_FTEN9 BIT(9) /*!< falling edge from line 9 */
#define EXTI_FTEN_FTEN10 BIT(10) /*!< falling edge from line 10 */
#define EXTI_FTEN_FTEN11 BIT(11) /*!< falling edge from line 11 */
#define EXTI_FTEN_FTEN12 BIT(12) /*!< falling edge from line 12 */
#define EXTI_FTEN_FTEN13 BIT(13) /*!< falling edge from line 13 */
#define EXTI_FTEN_FTEN14 BIT(14) /*!< falling edge from line 14 */
#define EXTI_FTEN_FTEN15 BIT(15) /*!< falling edge from line 15 */
#define EXTI_FTEN_FTEN16 BIT(16) /*!< falling edge from line 16 */
#define EXTI_FTEN_FTEN17 BIT(17) /*!< falling edge from line 17 */
#define EXTI_FTEN_FTEN18 BIT(18) /*!< falling edge from line 18 */
/* EXTI_SWIEV */
#define EXTI_SWIEV_SWIEV0 BIT(0) /*!< software interrupt/event request from line 0 */
#define EXTI_SWIEV_SWIEV1 BIT(1) /*!< software interrupt/event request from line 1 */
#define EXTI_SWIEV_SWIEV2 BIT(2) /*!< software interrupt/event request from line 2 */
#define EXTI_SWIEV_SWIEV3 BIT(3) /*!< software interrupt/event request from line 3 */
#define EXTI_SWIEV_SWIEV4 BIT(4) /*!< software interrupt/event request from line 4 */
#define EXTI_SWIEV_SWIEV5 BIT(5) /*!< software interrupt/event request from line 5 */
#define EXTI_SWIEV_SWIEV6 BIT(6) /*!< software interrupt/event request from line 6 */
#define EXTI_SWIEV_SWIEV7 BIT(7) /*!< software interrupt/event request from line 7 */
#define EXTI_SWIEV_SWIEV8 BIT(8) /*!< software interrupt/event request from line 8 */
#define EXTI_SWIEV_SWIEV9 BIT(9) /*!< software interrupt/event request from line 9 */
#define EXTI_SWIEV_SWIEV10 BIT(10) /*!< software interrupt/event request from line 10 */
#define EXTI_SWIEV_SWIEV11 BIT(11) /*!< software interrupt/event request from line 11 */
#define EXTI_SWIEV_SWIEV12 BIT(12) /*!< software interrupt/event request from line 12 */
#define EXTI_SWIEV_SWIEV13 BIT(13) /*!< software interrupt/event request from line 13 */
#define EXTI_SWIEV_SWIEV14 BIT(14) /*!< software interrupt/event request from line 14 */
#define EXTI_SWIEV_SWIEV15 BIT(15) /*!< software interrupt/event request from line 15 */
#define EXTI_SWIEV_SWIEV16 BIT(16) /*!< software interrupt/event request from line 16 */
#define EXTI_SWIEV_SWIEV17 BIT(17) /*!< software interrupt/event request from line 17 */
#define EXTI_SWIEV_SWIEV18 BIT(18) /*!< software interrupt/event request from line 18 */
/* EXTI_PD */
#define EXTI_PD_PD0 BIT(0) /*!< interrupt/event pending status from line 0 */
#define EXTI_PD_PD1 BIT(1) /*!< interrupt/event pending status from line 1 */
#define EXTI_PD_PD2 BIT(2) /*!< interrupt/event pending status from line 2 */
#define EXTI_PD_PD3 BIT(3) /*!< interrupt/event pending status from line 3 */
#define EXTI_PD_PD4 BIT(4) /*!< interrupt/event pending status from line 4 */
#define EXTI_PD_PD5 BIT(5) /*!< interrupt/event pending status from line 5 */
#define EXTI_PD_PD6 BIT(6) /*!< interrupt/event pending status from line 6 */
#define EXTI_PD_PD7 BIT(7) /*!< interrupt/event pending status from line 7 */
#define EXTI_PD_PD8 BIT(8) /*!< interrupt/event pending status from line 8 */
#define EXTI_PD_PD9 BIT(9) /*!< interrupt/event pending status from line 9 */
#define EXTI_PD_PD10 BIT(10) /*!< interrupt/event pending status from line 10 */
#define EXTI_PD_PD11 BIT(11) /*!< interrupt/event pending status from line 11 */
#define EXTI_PD_PD12 BIT(12) /*!< interrupt/event pending status from line 12 */
#define EXTI_PD_PD13 BIT(13) /*!< interrupt/event pending status from line 13 */
#define EXTI_PD_PD14 BIT(14) /*!< interrupt/event pending status from line 14 */
#define EXTI_PD_PD15 BIT(15) /*!< interrupt/event pending status from line 15 */
#define EXTI_PD_PD16 BIT(16) /*!< interrupt/event pending status from line 16 */
#define EXTI_PD_PD17 BIT(17) /*!< interrupt/event pending status from line 17 */
#define EXTI_PD_PD18 BIT(18) /*!< interrupt/event pending status from line 18 */
/* constants definitions */
/* EXTI line number */
typedef enum {
EXTI_0 = BIT(0), /*!< EXTI line 0 */
EXTI_1 = BIT(1), /*!< EXTI line 1 */
EXTI_2 = BIT(2), /*!< EXTI line 2 */
EXTI_3 = BIT(3), /*!< EXTI line 3 */
EXTI_4 = BIT(4), /*!< EXTI line 4 */
EXTI_5 = BIT(5), /*!< EXTI line 5 */
EXTI_6 = BIT(6), /*!< EXTI line 6 */
EXTI_7 = BIT(7), /*!< EXTI line 7 */
EXTI_8 = BIT(8), /*!< EXTI line 8 */
EXTI_9 = BIT(9), /*!< EXTI line 9 */
EXTI_10 = BIT(10), /*!< EXTI line 10 */
EXTI_11 = BIT(11), /*!< EXTI line 11 */
EXTI_12 = BIT(12), /*!< EXTI line 12 */
EXTI_13 = BIT(13), /*!< EXTI line 13 */
EXTI_14 = BIT(14), /*!< EXTI line 14 */
EXTI_15 = BIT(15), /*!< EXTI line 15 */
EXTI_16 = BIT(16), /*!< EXTI line 16 */
EXTI_17 = BIT(17), /*!< EXTI line 17 */
EXTI_18 = BIT(18), /*!< EXTI line 18 */
} exti_line_enum;
/* external interrupt and event */
typedef enum {
EXTI_INTERRUPT = 0, /*!< EXTI interrupt mode */
EXTI_EVENT /*!< EXTI event mode */
} exti_mode_enum;
/* interrupt trigger mode */
typedef enum {
EXTI_TRIG_RISING = 0, /*!< EXTI rising edge trigger */
EXTI_TRIG_FALLING, /*!< EXTI falling edge trigger */
EXTI_TRIG_BOTH, /*!< EXTI rising edge and falling edge trigger */
EXTI_TRIG_NONE /*!< without rising edge or falling edge trigger */
} exti_trig_type_enum;
/* function declarations */
/* initialization, EXTI lines configuration functions */
/* deinitialize the EXTI */
void exti_deinit(void);
/* enable the configuration of EXTI initialize */
void exti_init(exti_line_enum linex, exti_mode_enum mode, exti_trig_type_enum trig_type);
/* enable the interrupts from EXTI line x */
void exti_interrupt_enable(exti_line_enum linex);
/* enable the events from EXTI line x */
void exti_event_enable(exti_line_enum linex);
/* disable the interrupts from EXTI line x */
void exti_interrupt_disable(exti_line_enum linex);
/* disable the events from EXTI line x */
void exti_event_disable(exti_line_enum linex);
/* interrupt & flag functions */
/* get EXTI lines pending flag */
FlagStatus exti_flag_get(exti_line_enum linex);
/* clear EXTI lines pending flag */
void exti_flag_clear(exti_line_enum linex);
/* get EXTI lines flag when the interrupt flag is set */
FlagStatus exti_interrupt_flag_get(exti_line_enum linex);
/* clear EXTI lines pending flag */
void exti_interrupt_flag_clear(exti_line_enum linex);
/* enable the EXTI software interrupt event */
void exti_software_interrupt_enable(exti_line_enum linex);
/* disable the EXTI software interrupt event */
void exti_software_interrupt_disable(exti_line_enum linex);
#endif /* GD32VF103_EXTI_H */
#ifdef __cplusplus
}
#endif

View File

@@ -1,313 +0,0 @@
/*!
\file gd32vf103_fmc.h
\brief definitions for the FMC
\version 2019-06-05, V1.0.0, firmware for GD32VF103
\version 2019-09-18, V1.0.1, 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.
*/
#ifdef __cplusplus
extern "C" {
#endif
#ifndef GD32VF103_FMC_H
#define GD32VF103_FMC_H
#include "gd32vf103.h"
/* FMC and option byte definition */
#define FMC FMC_BASE /*!< FMC register base address */
#define OB OB_BASE /*!< option bytes base address */
/* registers definitions */
#define FMC_WS REG32((FMC) + 0x00U) /*!< FMC wait state register */
#define FMC_KEY REG32((FMC) + 0x04U) /*!< FMC unlock key register */
#define FMC_OBKEY REG32((FMC) + 0x08U) /*!< FMC option bytes unlock key register */
#define FMC_STAT REG32((FMC) + 0x0CU) /*!< FMC status register */
#define FMC_CTL REG32((FMC) + 0x10U) /*!< FMC control register */
#define FMC_ADDR REG32((FMC) + 0x14U) /*!< FMC address register */
#define FMC_OBSTAT REG32((FMC) + 0x1CU) /*!< FMC option bytes status register */
#define FMC_WP REG32((FMC) + 0x20U) /*!< FMC erase/program protection register */
#define FMC_PID REG32((FMC) + 0x100U) /*!< FMC product ID register */
#define OB_SPC REG16((OB) + 0x00U) /*!< option byte security protection value */
#define OB_USER REG16((OB) + 0x02U) /*!< option byte user value*/
#define OB_WP0 REG16((OB) + 0x08U) /*!< option byte write protection 0 */
#define OB_WP1 REG16((OB) + 0x0AU) /*!< option byte write protection 1 */
#define OB_WP2 REG16((OB) + 0x0CU) /*!< option byte write protection 2 */
#define OB_WP3 REG16((OB) + 0x0EU) /*!< option byte write protection 3 */
/* bits definitions */
/* FMC_WS */
#define FMC_WS_WSCNT BITS(0, 2) /*!< wait state counter */
/* FMC_KEY */
#define FMC_KEY_KEY BITS(0, 31) /*!< FMC_CTL unlock key bits */
/* FMC_OBKEY */
#define FMC_OBKEY_OBKEY BITS(0, 31) /*!< option bytes unlock key bits */
/* FMC_STAT */
#define FMC_STAT_BUSY BIT(0) /*!< flash busy flag bit */
#define FMC_STAT_PGERR BIT(2) /*!< flash program error flag bit */
#define FMC_STAT_WPERR BIT(4) /*!< erase/program protection error flag bit */
#define FMC_STAT_ENDF BIT(5) /*!< end of operation flag bit */
/* FMC_CTL */
#define FMC_CTL_PG BIT(0) /*!< main flash program command bit */
#define FMC_CTL_PER BIT(1) /*!< main flash page erase command bit */
#define FMC_CTL_MER BIT(2) /*!< main flash mass erase command bit */
#define FMC_CTL_OBPG BIT(4) /*!< option bytes program command bit */
#define FMC_CTL_OBER BIT(5) /*!< option bytes erase command bit */
#define FMC_CTL_START BIT(6) /*!< send erase command to FMC bit */
#define FMC_CTL_LK BIT(7) /*!< FMC_CTL lock bit */
#define FMC_CTL_OBWEN BIT(9) /*!< option bytes erase/program enable bit */
#define FMC_CTL_ERRIE BIT(10) /*!< error interrupt enable bit */
#define FMC_CTL_ENDIE BIT(12) /*!< end of operation interrupt enable bit */
/* FMC_ADDR */
#define FMC_ADDR0_ADDR BITS(0, 31) /*!< Flash erase/program command address bits */
/* FMC_OBSTAT */
#define FMC_OBSTAT_OBERR BIT(0) /*!< option bytes read error bit. */
#define FMC_OBSTAT_SPC BIT(1) /*!< option bytes security protection code */
#define FMC_OBSTAT_USER BITS(2, 9) /*!< store USER of option bytes block after system reset */
#define FMC_OBSTAT_DATA BITS(10, 25) /*!< store DATA of option bytes block after system reset. */
/* FMC_WP */
#define FMC_WP_WP BITS(0, 31) /*!< store WP of option bytes block after system reset */
/* FMC_WSEN */
#define FMC_WSEN_WSEN BIT(0) /*!< FMC wait state enable bit */
/* FMC_PID */
#define FMC_PID_PID BITS(0, 31) /*!< product ID bits */
/* constants definitions */
/* define the FMC bit position and its register index offset */
#define FMC_REGIDX_BIT(regidx, bitpos) (((uint32_t)(regidx) << 6) | (uint32_t)(bitpos))
#define FMC_REG_VAL(offset) (REG32(FMC + ((uint32_t)(offset) >> 6)))
#define FMC_BIT_POS(val) ((uint32_t)(val)&0x1FU)
#define FMC_REGIDX_BITS(regidx, bitpos0, bitpos1) (((uint32_t)(regidx) << 12) | ((uint32_t)(bitpos0) << 6) | (uint32_t)(bitpos1))
#define FMC_REG_VALS(offset) (REG32(FMC + ((uint32_t)(offset) >> 12)))
#define FMC_BIT_POS0(val) (((uint32_t)(val) >> 6) & 0x1FU)
#define FMC_BIT_POS1(val) ((uint32_t)(val)&0x1FU)
#define FMC_REG_OFFSET_GET(flag) ((uint32_t)(flag) >> 12)
/* configuration register */
#define FMC_STAT_REG_OFFSET 0x0CU /*!< status register offset */
#define FMC_CTL_REG_OFFSET 0x10U /*!< control register offset */
#define FMC_OBSTAT_REG_OFFSET 0x1CU /*!< option byte status register offset */
/* fmc state */
typedef enum {
FMC_READY, /*!< the operation has been completed */
FMC_BUSY, /*!< the operation is in progress */
FMC_PGERR, /*!< program error */
FMC_WPERR, /*!< erase/program protection error */
FMC_TOERR, /*!< timeout error */
} fmc_state_enum;
/* FMC interrupt enable */
typedef enum {
FMC_INT_END = FMC_REGIDX_BIT(FMC_CTL_REG_OFFSET, 12U), /*!< enable FMC end of program interrupt */
FMC_INT_ERR = FMC_REGIDX_BIT(FMC_CTL_REG_OFFSET, 10U), /*!< enable FMC error interrupt */
} fmc_int_enum;
/* FMC flags */
typedef enum {
FMC_FLAG_BUSY = FMC_REGIDX_BIT(FMC_STAT_REG_OFFSET, 0U), /*!< FMC busy flag */
FMC_FLAG_PGERR = FMC_REGIDX_BIT(FMC_STAT_REG_OFFSET, 2U), /*!< FMC operation error flag bit */
FMC_FLAG_WPERR = FMC_REGIDX_BIT(FMC_STAT_REG_OFFSET, 4U), /*!< FMC erase/program protection error flag bit */
FMC_FLAG_END = FMC_REGIDX_BIT(FMC_STAT_REG_OFFSET, 5U), /*!< FMC end of operation flag bit */
FMC_FLAG_OBERR = FMC_REGIDX_BIT(FMC_OBSTAT_REG_OFFSET, 0U), /*!< FMC option bytes read error flag */
} fmc_flag_enum;
/* FMC interrupt flags */
typedef enum {
FMC_INT_FLAG_PGERR = FMC_REGIDX_BITS(FMC_STAT_REG_OFFSET, 2U, 10U), /*!< FMC operation error interrupt flag bit */
FMC_INT_FLAG_WPERR = FMC_REGIDX_BITS(FMC_STAT_REG_OFFSET, 4U, 10U), /*!< FMC erase/program protection error interrupt flag bit */
FMC_INT_FLAG_END = FMC_REGIDX_BITS(FMC_STAT_REG_OFFSET, 5U, 12U), /*!< FMC end of operation interrupt flag bit */
} fmc_interrupt_flag_enum;
/* unlock key */
#define UNLOCK_KEY0 ((uint32_t)0x45670123U) /*!< unlock key 0 */
#define UNLOCK_KEY1 ((uint32_t)0xCDEF89ABU) /*!< unlock key 1 */
/* FMC wait state counter */
#define WS_WSCNT(regval) (BITS(0, 2) & ((uint32_t)(regval)))
#define WS_WSCNT_0 WS_WSCNT(0) /*!< FMC 0 wait */
#define WS_WSCNT_1 WS_WSCNT(1) /*!< FMC 1 wait */
#define WS_WSCNT_2 WS_WSCNT(2) /*!< FMC 2 wait */
/* option bytes software/hardware free watch dog timer */
#define OB_FWDGT_SW ((uint8_t)0x01U) /*!< software free watchdog */
#define OB_FWDGT_HW ((uint8_t)0x00U) /*!< hardware free watchdog */
/* option bytes reset or not entering deep sleep mode */
#define OB_DEEPSLEEP_NRST ((uint8_t)0x02U) /*!< no reset when entering deepsleep mode */
#define OB_DEEPSLEEP_RST ((uint8_t)0x00U) /*!< generate a reset instead of entering deepsleep mode */
/* option bytes reset or not entering standby mode */
#define OB_STDBY_NRST ((uint8_t)0x04U) /*!< no reset when entering deepsleep mode */
#define OB_STDBY_RST ((uint8_t)0x00U) /*!< generate a reset instead of entering standby mode */
/* option bytes boot bank value */
#define OB_BOOT_B0 ((uint8_t)0x08U) /*!< boot from bank0 */
#define OB_USER_MASK ((uint8_t)0xF0U) /*!< MASK value */
/* read protect configure */
#define FMC_NSPC ((uint8_t)0xA5U) /*!< no security protection */
#define FMC_USPC ((uint8_t)0xBBU) /*!< under security protection */
/* OB_SPC */
#define OB_SPC_SPC ((uint32_t)0x000000FFU) /*!< option byte security protection value */
#define OB_SPC_SPC_N ((uint32_t)0x0000FF00U) /*!< option byte security protection complement value */
/* OB_USER */
#define OB_USER_USER ((uint32_t)0x00FF0000U) /*!< user option value */
#define OB_USER_USER_N ((uint32_t)0xFF000000U) /*!< user option complement value */
/* OB_WP0 */
#define OB_WP0_WP0 ((uint32_t)0x000000FFU) /*!< FMC write protection option value */
/* OB_WP1 */
#define OB_WP1_WP1 ((uint32_t)0x0000FF00U) /*!< FMC write protection option complement value */
/* OB_WP2 */
#define OB_WP2_WP2 ((uint32_t)0x00FF0000U) /*!< FMC write protection option value */
/* OB_WP3 */
#define OB_WP3_WP3 ((uint32_t)0xFF000000U) /*!< FMC write protection option complement value */
/* option bytes write protection */
#define OB_WP_0 ((uint32_t)0x00000001U) /*!< erase/program protection of sector 0 */
#define OB_WP_1 ((uint32_t)0x00000002U) /*!< erase/program protection of sector 1 */
#define OB_WP_2 ((uint32_t)0x00000004U) /*!< erase/program protection of sector 2 */
#define OB_WP_3 ((uint32_t)0x00000008U) /*!< erase/program protection of sector 3 */
#define OB_WP_4 ((uint32_t)0x00000010U) /*!< erase/program protection of sector 4 */
#define OB_WP_5 ((uint32_t)0x00000020U) /*!< erase/program protection of sector 5 */
#define OB_WP_6 ((uint32_t)0x00000040U) /*!< erase/program protection of sector 6 */
#define OB_WP_7 ((uint32_t)0x00000080U) /*!< erase/program protection of sector 7 */
#define OB_WP_8 ((uint32_t)0x00000100U) /*!< erase/program protection of sector 8 */
#define OB_WP_9 ((uint32_t)0x00000200U) /*!< erase/program protection of sector 9 */
#define OB_WP_10 ((uint32_t)0x00000400U) /*!< erase/program protection of sector 10 */
#define OB_WP_11 ((uint32_t)0x00000800U) /*!< erase/program protection of sector 11 */
#define OB_WP_12 ((uint32_t)0x00001000U) /*!< erase/program protection of sector 12 */
#define OB_WP_13 ((uint32_t)0x00002000U) /*!< erase/program protection of sector 13 */
#define OB_WP_14 ((uint32_t)0x00004000U) /*!< erase/program protection of sector 14 */
#define OB_WP_15 ((uint32_t)0x00008000U) /*!< erase/program protection of sector 15 */
#define OB_WP_16 ((uint32_t)0x00010000U) /*!< erase/program protection of sector 16 */
#define OB_WP_17 ((uint32_t)0x00020000U) /*!< erase/program protection of sector 17 */
#define OB_WP_18 ((uint32_t)0x00040000U) /*!< erase/program protection of sector 18 */
#define OB_WP_19 ((uint32_t)0x00080000U) /*!< erase/program protection of sector 19 */
#define OB_WP_20 ((uint32_t)0x00100000U) /*!< erase/program protection of sector 20 */
#define OB_WP_21 ((uint32_t)0x00200000U) /*!< erase/program protection of sector 21 */
#define OB_WP_22 ((uint32_t)0x00400000U) /*!< erase/program protection of sector 22 */
#define OB_WP_23 ((uint32_t)0x00800000U) /*!< erase/program protection of sector 23 */
#define OB_WP_24 ((uint32_t)0x01000000U) /*!< erase/program protection of sector 24 */
#define OB_WP_25 ((uint32_t)0x02000000U) /*!< erase/program protection of sector 25 */
#define OB_WP_26 ((uint32_t)0x04000000U) /*!< erase/program protection of sector 26 */
#define OB_WP_27 ((uint32_t)0x08000000U) /*!< erase/program protection of sector 27 */
#define OB_WP_28 ((uint32_t)0x10000000U) /*!< erase/program protection of sector 28 */
#define OB_WP_29 ((uint32_t)0x20000000U) /*!< erase/program protection of sector 29 */
#define OB_WP_30 ((uint32_t)0x40000000U) /*!< erase/program protection of sector 30 */
#define OB_WP_31 ((uint32_t)0x80000000U) /*!< erase/program protection of sector 31 */
#define OB_WP_ALL ((uint32_t)0xFFFFFFFFU) /*!< erase/program protection of all sectors */
/* FMC timeout */
#define FMC_TIMEOUT_COUNT ((uint32_t)0x000F0000U) /*!< FMC timeout count value */
/* FMC BANK address */
#define FMC_SIZE (*(uint16_t *)0x1FFFF7E0U) /*!< FMC size */
#define SRAM_SIZE (*(uint16_t *)0x1FFFF7E2U) /*!< SRAM size*/
/* function declarations */
/* FMC main memory programming functions */
/* set the FMC wait state counter */
void fmc_wscnt_set(uint32_t wscnt);
/* unlock the main FMC operation */
void fmc_unlock(void);
/* lock the main FMC operation */
void fmc_lock(void);
/* FMC erase page */
fmc_state_enum fmc_page_erase(uint32_t page_address);
/* FMC erase whole chip */
fmc_state_enum fmc_mass_erase(void);
/* FMC program a word at the corresponding address */
fmc_state_enum fmc_word_program(uint32_t address, uint32_t data);
/* FMC program a half word at the corresponding address */
fmc_state_enum fmc_halfword_program(uint32_t address, uint16_t data);
/* FMC option bytes programming functions */
/* unlock the option byte operation */
void ob_unlock(void);
/* lock the option byte operation */
void ob_lock(void);
/* erase the FMC option byte */
fmc_state_enum ob_erase(void);
/* enable write protection */
fmc_state_enum ob_write_protection_enable(uint32_t ob_wp);
/* configure security protection */
fmc_state_enum ob_security_protection_config(uint8_t ob_spc);
/* program the FMC user option byte */
fmc_state_enum ob_user_write(uint8_t ob_fwdgt, uint8_t ob_deepsleep, uint8_t ob_stdby, uint8_t ob_boot);
/* program the FMC data option byte */
fmc_state_enum ob_data_program(uint32_t address, uint8_t data);
/* get OB_USER in register FMC_OBSTAT */
uint8_t ob_user_get(void);
/* get OB_DATA in register FMC_OBSTAT */
uint16_t ob_data_get(void);
/* get the FMC option byte write protection */
uint32_t ob_write_protection_get(void);
/* get FMC option byte security protection state */
FlagStatus ob_spc_get(void);
/* FMC interrupts and flags management functions */
/* enable FMC interrupt */
void fmc_interrupt_enable(uint32_t interrupt);
/* disable FMC interrupt */
void fmc_interrupt_disable(uint32_t interrupt);
/* check flag is set or not */
FlagStatus fmc_flag_get(uint32_t flag);
/* clear the FMC flag */
void fmc_flag_clear(uint32_t flag);
/* get FMC interrupt flag state */
FlagStatus fmc_interrupt_flag_get(fmc_interrupt_flag_enum flag);
/* clear FMC interrupt flag state */
void fmc_interrupt_flag_clear(fmc_interrupt_flag_enum flag);
/* return the FMC state */
fmc_state_enum fmc_state_get(void);
/* check FMC ready or not */
fmc_state_enum fmc_ready_wait(uint32_t timeout);
#endif /* GD32VF103_FMC_H */
#ifdef __cplusplus
}
#endif

View File

@@ -1,109 +0,0 @@
/*!
\file gd32vf103_fwdgt.h
\brief definitions for the FWDGT
\version 2019-06-05, 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.
*/
#ifdef __cplusplus
extern "C" {
#endif
#ifndef GD32VF103_FWDGT_H
#define GD32VF103_FWDGT_H
#include "gd32vf103.h"
/* FWDGT definitions */
#define FWDGT FWDGT_BASE /*!< FWDGT base address */
/* registers definitions */
#define FWDGT_CTL REG32((FWDGT) + 0x00000000U) /*!< FWDGT control register */
#define FWDGT_PSC REG32((FWDGT) + 0x00000004U) /*!< FWDGT prescaler register */
#define FWDGT_RLD REG32((FWDGT) + 0x00000008U) /*!< FWDGT reload register */
#define FWDGT_STAT REG32((FWDGT) + 0x0000000CU) /*!< FWDGT status register */
/* bits definitions */
/* FWDGT_CTL */
#define FWDGT_CTL_CMD BITS(0, 15) /*!< FWDGT command value */
/* FWDGT_PSC */
#define FWDGT_PSC_PSC BITS(0, 2) /*!< FWDGT prescaler divider value */
/* FWDGT_RLD */
#define FWDGT_RLD_RLD BITS(0, 11) /*!< FWDGT counter reload value */
/* FWDGT_STAT */
#define FWDGT_STAT_PUD BIT(0) /*!< FWDGT prescaler divider value update */
#define FWDGT_STAT_RUD BIT(1) /*!< FWDGT counter reload value update */
/* constants definitions */
/* psc register value */
#define PSC_PSC(regval) (BITS(0, 2) & ((uint32_t)(regval) << 0))
#define FWDGT_PSC_DIV4 ((uint8_t)PSC_PSC(0)) /*!< FWDGT prescaler set to 4 */
#define FWDGT_PSC_DIV8 ((uint8_t)PSC_PSC(1)) /*!< FWDGT prescaler set to 8 */
#define FWDGT_PSC_DIV16 ((uint8_t)PSC_PSC(2)) /*!< FWDGT prescaler set to 16 */
#define FWDGT_PSC_DIV32 ((uint8_t)PSC_PSC(3)) /*!< FWDGT prescaler set to 32 */
#define FWDGT_PSC_DIV64 ((uint8_t)PSC_PSC(4)) /*!< FWDGT prescaler set to 64 */
#define FWDGT_PSC_DIV128 ((uint8_t)PSC_PSC(5)) /*!< FWDGT prescaler set to 128 */
#define FWDGT_PSC_DIV256 ((uint8_t)PSC_PSC(6)) /*!< FWDGT prescaler set to 256 */
/* control value */
#define FWDGT_WRITEACCESS_ENABLE ((uint16_t)0x5555U) /*!< FWDGT_CTL bits write access enable value */
#define FWDGT_WRITEACCESS_DISABLE ((uint16_t)0x0000U) /*!< FWDGT_CTL bits write access disable value */
#define FWDGT_KEY_RELOAD ((uint16_t)0xAAAAU) /*!< FWDGT_CTL bits fwdgt counter reload value */
#define FWDGT_KEY_ENABLE ((uint16_t)0xCCCCU) /*!< FWDGT_CTL bits fwdgt counter enable value */
/* FWDGT timeout value */
#define FWDGT_PSC_TIMEOUT ((uint32_t)0x000FFFFFU) /*!< FWDGT_PSC register write operation state flag timeout */
#define FWDGT_RLD_TIMEOUT ((uint32_t)0x000FFFFFU) /*!< FWDGT_RLD register write operation state flag timeout */
/* FWDGT flag definitions */
#define FWDGT_FLAG_PUD FWDGT_STAT_PUD /*!< FWDGT prescaler divider value update flag */
#define FWDGT_FLAG_RUD FWDGT_STAT_RUD /*!< FWDGT counter reload value update flag */
/* function declarations */
/* enable write access to FWDGT_PSC and FWDGT_RLD */
void fwdgt_write_enable(void);
/* disable write access to FWDGT_PSC and FWDGT_RLD */
void fwdgt_write_disable(void);
/* start the free watchdog timer counter */
void fwdgt_enable(void);
/* reload the counter of FWDGT */
void fwdgt_counter_reload(void);
/* configure counter reload value, and prescaler divider value */
ErrStatus fwdgt_config(uint16_t reload_value, uint8_t prescaler_div);
/* get flag state of FWDGT */
FlagStatus fwdgt_flag_get(uint16_t flag);
#endif /* GD32VF103_FWDGT_H */
#ifdef __cplusplus
}
#endif

View File

@@ -1,426 +0,0 @@
/*!
\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.
*/
#ifdef __cplusplus
extern "C" {
#endif
#ifndef GD32VF103_GPIO_H
#define GD32VF103_GPIO_H
#include "gd32vf103.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 */
#ifdef __cplusplus
}
#endif

View File

@@ -1,195 +0,0 @@
/*!
\file gd32vf103_hw.c
\brief USB hardware configuration for GD32VF103
\version 2019-06-05, 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_timer.h"
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#define TIM_MSEC_DELAY 0x01
#define TIM_USEC_DELAY 0x02
__IO uint32_t delay_time = 0;
__IO uint32_t timer_prescaler;
__IO uint32_t usbfs_prescaler = 0;
static void hw_time_set(uint8_t unit);
static void hw_delay(uint32_t ntime, uint8_t unit);
/*!
\brief configure USB clock
\param[in] none
\param[out] none
\retval none
*/
void usb_rcu_config(void) {
uint32_t system_clock = rcu_clock_freq_get(CK_SYS);
if (system_clock == 48000000) {
usbfs_prescaler = RCU_CKUSB_CKPLL_DIV1;
timer_prescaler = 3;
} else if (system_clock == 72000000) {
usbfs_prescaler = RCU_CKUSB_CKPLL_DIV1_5;
timer_prescaler = 5;
} else if (system_clock == 96000000) {
usbfs_prescaler = RCU_CKUSB_CKPLL_DIV2;
timer_prescaler = 7;
} else {
/* reserved */
}
rcu_usb_clock_config(usbfs_prescaler);
rcu_periph_clock_enable(RCU_USBFS);
}
/*!
\brief configure USB interrupt
\param[in] none
\param[out] none
\retval none
*/
void usb_intr_config(void) {
eclic_irq_enable((uint8_t)USBFS_IRQn, 1, 0);
/* enable the power module clock */
rcu_periph_clock_enable(RCU_PMU);
/* USB wakeup EXTI line configuration */
exti_interrupt_flag_clear(EXTI_18);
exti_init(EXTI_18, EXTI_INTERRUPT, EXTI_TRIG_RISING);
exti_interrupt_enable(EXTI_18);
eclic_irq_enable((uint8_t)USBFS_WKUP_IRQn, 3, 0);
}
/*!
\brief initializes delay unit using Timer2
\param[in] none
\param[out] none
\retval none
*/
void usb_timer_init(void) {
rcu_periph_clock_enable(RCU_TIMER2);
eclic_irq_enable(TIMER2_IRQn, 2, 0);
}
/*!
\brief delay in micro seconds
\param[in] usec: value of delay required in micro seconds
\param[out] none
\retval none
*/
void usb_udelay(const uint32_t usec) {
hw_delay(usec, TIM_USEC_DELAY);
}
/*!
\brief delay in milli seconds
\param[in] msec: value of delay required in milli seconds
\param[out] none
\retval none
*/
void usb_mdelay(const uint32_t msec) {
hw_delay(msec, TIM_MSEC_DELAY);
}
/*!
\brief time base IRQ
\param[in] none
\param[out] none
\retval none
*/
void usb_timer_irq(void) {
if (RESET != timer_flag_get(TIMER2, TIMER_FLAG_UP)) {
timer_flag_clear(TIMER2, TIMER_FLAG_UP);
if (delay_time > 0x00U) {
delay_time--;
} else {
timer_disable(TIMER2);
}
}
}
/*!
\brief delay routine based on TIM0
\param[in] nTime: delay Time
\param[in] unit: delay Time unit = mili sec / micro sec
\param[out] none
\retval none
*/
static void hw_delay(uint32_t ntime, uint8_t unit) {
delay_time = ntime;
hw_time_set(unit);
while (0U != delay_time) {
}
timer_disable(TIMER2);
}
/*!
\brief configures TIM0 for delay routine based on TIM0
\param[in] unit: msec /usec
\param[out] none
\retval none
*/
static void hw_time_set(uint8_t unit) {
timer_parameter_struct timer_initpara;
rcu_periph_clock_enable(RCU_TIMER2);
timer_deinit(TIMER2);
if (TIM_USEC_DELAY == unit) {
timer_initpara.period = 11;
} else if (TIM_MSEC_DELAY == unit) {
timer_initpara.period = 11999;
}
timer_initpara.prescaler = timer_prescaler;
timer_initpara.alignedmode = TIMER_COUNTER_EDGE;
timer_initpara.counterdirection = TIMER_COUNTER_UP;
timer_initpara.clockdivision = TIMER_CKDIV_DIV1;
timer_initpara.repetitioncounter = 0;
timer_init(TIMER2, &timer_initpara);
timer_update_event_enable(TIMER2);
timer_interrupt_enable(TIMER2, TIMER_INT_UP);
timer_flag_clear(TIMER2, TIMER_FLAG_UP);
timer_update_source_config(TIMER2, TIMER_UPDATE_SRC_GLOBAL);
/* TIMER2 counter enable */
timer_enable(TIMER2);
}

View File

@@ -1,700 +0,0 @@
/*!
\file gd32vf103_i2c.c
\brief I2C driver
\version 2019-06-05, V1.0.0, firmware for GD32VF103
\version 2019-09-18, V1.0.1, 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_i2c.h"
/* I2C register bit mask */
#define I2CCLK_MAX ((uint32_t)0x00000036U) /*!< i2cclk maximum value */
#define I2CCLK_MIN ((uint32_t)0x00000002U) /*!< i2cclk minimum value */
#define I2C_FLAG_MASK ((uint32_t)0x0000FFFFU) /*!< i2c flag mask */
#define I2C_ADDRESS_MASK ((uint32_t)0x000003FFU) /*!< i2c address mask */
#define I2C_ADDRESS2_MASK ((uint32_t)0x000000FEU) /*!< the second i2c address mask */
/* I2C register bit offset */
#define STAT1_PECV_OFFSET ((uint32_t)8U) /* bit offset of PECV in I2C_STAT1 */
/*!
\brief reset I2C
\param[in] i2c_periph: I2Cx(x=0,1)
\param[out] none
\retval none
*/
void i2c_deinit(uint32_t i2c_periph) {
switch (i2c_periph) {
case I2C0:
/* reset I2C0 */
rcu_periph_reset_enable(RCU_I2C0RST);
rcu_periph_reset_disable(RCU_I2C0RST);
break;
case I2C1:
/* reset I2C1 */
rcu_periph_reset_enable(RCU_I2C1RST);
rcu_periph_reset_disable(RCU_I2C1RST);
break;
default:
break;
}
}
/*!
\brief configure I2C clock
\param[in] i2c_periph: I2Cx(x=0,1)
\param[in] clkspeed: I2C clock speed, supports standard mode (up to 100 kHz), fast mode (up to 400 kHz)
and fast mode plus (up to 1MHz)
\param[in] dutycyc: duty cycle in fast mode or fast mode plus
only one parameter can be selected which is shown as below:
\arg I2C_DTCY_2: T_low/T_high=2
\arg I2C_DTCY_16_9: T_low/T_high=16/9
\param[out] none
\retval none
*/
void i2c_clock_config(uint32_t i2c_periph, uint32_t clkspeed, uint32_t dutycyc) {
uint32_t pclk1, clkc, freq, risetime;
uint32_t temp;
pclk1 = rcu_clock_freq_get(CK_APB1);
/* I2C peripheral clock frequency */
freq = (uint32_t) (pclk1 / 1000000U);
if (freq >= I2CCLK_MAX) {
freq = I2CCLK_MAX;
}
temp = I2C_CTL1(i2c_periph);
temp &= ~I2C_CTL1_I2CCLK;
temp |= freq;
I2C_CTL1(i2c_periph) = temp;
if (100000U >= clkspeed) {
/* the maximum SCL rise time is 1000ns in standard mode */
risetime = (uint32_t) ((pclk1 / 1000000U) + 1U);
if (risetime >= I2CCLK_MAX) {
I2C_RT(i2c_periph) = I2CCLK_MAX;
} else if (risetime <= I2CCLK_MIN) {
I2C_RT(i2c_periph) = I2CCLK_MIN;
} else {
I2C_RT(i2c_periph) = risetime;
}
clkc = (uint32_t) (pclk1 / (clkspeed * 2U));
if (clkc < 0x04U) {
/* the CLKC in standard mode minmum value is 4 */
clkc = 0x04U;
}
I2C_CKCFG(i2c_periph) |= (I2C_CKCFG_CLKC & clkc);
} else if (400000U >= clkspeed) {
/* the maximum SCL rise time is 300ns in fast mode */
I2C_RT(i2c_periph) = (uint32_t) (((freq * (uint32_t) 300U) / (uint32_t) 1000U) + (uint32_t) 1U);
if (I2C_DTCY_2 == dutycyc) {
/* I2C duty cycle is 2 */
clkc = (uint32_t) (pclk1 / (clkspeed * 3U));
I2C_CKCFG(i2c_periph) &= ~I2C_CKCFG_DTCY;
} else {
/* I2C duty cycle is 16/9 */
clkc = (uint32_t) (pclk1 / (clkspeed * 25U));
I2C_CKCFG(i2c_periph) |= I2C_CKCFG_DTCY;
}
if (0U == (clkc & I2C_CKCFG_CLKC)) {
/* the CLKC in fast mode minmum value is 1 */
clkc |= 0x0001U;
}
I2C_CKCFG(i2c_periph) |= I2C_CKCFG_FAST;
I2C_CKCFG(i2c_periph) |= clkc;
} else {
/* fast mode plus, the maximum SCL rise time is 120ns */
I2C_RT (i2c_periph) = (uint32_t) (((freq * (uint32_t) 120U) / (uint32_t) 1000U) + (uint32_t) 1U);
if (I2C_DTCY_2 == dutycyc) {
/* I2C duty cycle is 2 */
clkc = (uint32_t) (pclk1 / (clkspeed * 3U));
I2C_CKCFG(i2c_periph) &= ~I2C_CKCFG_DTCY;
} else {
/* I2C duty cycle is 16/9 */
clkc = (uint32_t) (pclk1 / (clkspeed * 25U));
I2C_CKCFG(i2c_periph) |= I2C_CKCFG_DTCY;
}
/* enable fast mode */
I2C_CKCFG(i2c_periph) |= I2C_CKCFG_FAST;
I2C_CKCFG(i2c_periph) |= clkc;
/* enable I2C fast mode plus */
I2C_FMPCFG(i2c_periph) |= I2C_FMPCFG_FMPEN;
}
}
/*!
\brief configure I2C address
\param[in] i2c_periph: I2Cx(x=0,1)
\param[in] mode:
only one parameter can be selected which is shown as below:
\arg I2C_I2CMODE_ENABLE: I2C mode
\arg I2C_SMBUSMODE_ENABLE: SMBus mode
\param[in] addformat: 7bits or 10bits
only one parameter can be selected which is shown as below:
\arg I2C_ADDFORMAT_7BITS: 7bits
\arg I2C_ADDFORMAT_10BITS: 10bits
\param[in] addr: I2C address
\param[out] none
\retval none
*/
void i2c_mode_addr_config(uint32_t i2c_periph, uint32_t mode, uint32_t addformat, uint32_t addr) {
/* SMBus/I2C mode selected */
uint32_t ctl = 0U;
ctl = I2C_CTL0(i2c_periph);
ctl &= ~(I2C_CTL0_SMBEN);
ctl |= mode;
I2C_CTL0(i2c_periph) = ctl;
/* configure address */
addr = addr & I2C_ADDRESS_MASK;
I2C_SADDR0(i2c_periph) = (addformat | addr);
}
/*!
\brief SMBus type selection
\param[in] i2c_periph: I2Cx(x=0,1)
\param[in] type:
only one parameter can be selected which is shown as below:
\arg I2C_SMBUS_DEVICE: device
\arg I2C_SMBUS_HOST: host
\param[out] none
\retval none
*/
void i2c_smbus_type_config(uint32_t i2c_periph, uint32_t type) {
if (I2C_SMBUS_HOST == type) {
I2C_CTL0(i2c_periph) |= I2C_CTL0_SMBSEL;
} else {
I2C_CTL0(i2c_periph) &= ~(I2C_CTL0_SMBSEL);
}
}
/*!
\brief whether or not to send an ACK
\param[in] i2c_periph: I2Cx(x=0,1)
\param[in] ack:
only one parameter can be selected which is shown as below:
\arg I2C_ACK_ENABLE: ACK will be sent
\arg I2C_ACK_DISABLE: ACK will not be sent
\param[out] none
\retval none
*/
void i2c_ack_config(uint32_t i2c_periph, uint32_t ack) {
if (I2C_ACK_ENABLE == ack) {
I2C_CTL0(i2c_periph) |= I2C_CTL0_ACKEN;
} else {
I2C_CTL0(i2c_periph) &= ~(I2C_CTL0_ACKEN);
}
}
/*!
\brief configure I2C POAP position
\param[in] i2c_periph: I2Cx(x=0,1)
\param[in] pos:
only one parameter can be selected which is shown as below:
\arg I2C_ACKPOS_CURRENT: whether to send ACK or not for the current
\arg I2C_ACKPOS_NEXT: whether to send ACK or not for the next byte
\param[out] none
\retval none
*/
void i2c_ackpos_config(uint32_t i2c_periph, uint32_t pos) {
/* configure I2C POAP position */
if (I2C_ACKPOS_NEXT == pos) {
I2C_CTL0(i2c_periph) |= I2C_CTL0_POAP;
} else {
I2C_CTL0(i2c_periph) &= ~(I2C_CTL0_POAP);
}
}
/*!
\brief master sends slave address
\param[in] i2c_periph: I2Cx(x=0,1)
\param[in] addr: slave address
\param[in] trandirection: transmitter or receiver
only one parameter can be selected which is shown as below:
\arg I2C_TRANSMITTER: transmitter
\arg I2C_RECEIVER: receiver
\param[out] none
\retval none
*/
void i2c_master_addressing(uint32_t i2c_periph, uint32_t addr, uint32_t trandirection) {
/* master is a transmitter or a receiver */
if (I2C_TRANSMITTER == trandirection) {
addr = addr & I2C_TRANSMITTER;
} else {
addr = addr | I2C_RECEIVER;
}
/* send slave address */
I2C_DATA(i2c_periph) = addr;
}
/*!
\brief enable dual-address mode
\param[in] i2c_periph: I2Cx(x=0,1)
\param[in] addr: the second address in dual-address mode
\param[out] none
\retval none
*/
void i2c_dualaddr_enable(uint32_t i2c_periph, uint32_t addr) {
/* configure address */
addr = addr & I2C_ADDRESS2_MASK;
I2C_SADDR1(i2c_periph) = (I2C_SADDR1_DUADEN | addr);
}
/*!
\brief disable dual-address mode
\param[in] i2c_periph: I2Cx(x=0,1)
\param[out] none
\retval none
*/
void i2c_dualaddr_disable(uint32_t i2c_periph) {
I2C_SADDR1(i2c_periph) &= ~(I2C_SADDR1_DUADEN);
}
/*!
\brief enable I2C
\param[in] i2c_periph: I2Cx(x=0,1)
\param[out] none
\retval none
*/
void i2c_enable(uint32_t i2c_periph) {
I2C_CTL0(i2c_periph) |= I2C_CTL0_I2CEN;
}
/*!
\brief disable I2C
\param[in] i2c_periph: I2Cx(x=0,1)
\param[out] none
\retval none
*/
void i2c_disable(uint32_t i2c_periph) {
I2C_CTL0(i2c_periph) &= ~(I2C_CTL0_I2CEN);
}
/*!
\brief generate a START condition on I2C bus
\param[in] i2c_periph: I2Cx(x=0,1)
\param[out] none
\retval none
*/
void i2c_start_on_bus(uint32_t i2c_periph) {
I2C_CTL0(i2c_periph) |= I2C_CTL0_START;
}
/*!
\brief generate a STOP condition on I2C bus
\param[in] i2c_periph: I2Cx(x=0,1)
\param[out] none
\retval none
*/
void i2c_stop_on_bus(uint32_t i2c_periph) {
I2C_CTL0(i2c_periph) |= I2C_CTL0_STOP;
}
/*!
\brief I2C transmit data function
\param[in] i2c_periph: I2Cx(x=0,1)
\param[in] data: data of transmission
\param[out] none
\retval none
*/
void i2c_data_transmit(uint32_t i2c_periph, uint8_t data) {
I2C_DATA(i2c_periph) = DATA_TRANS(data);
}
/*!
\brief I2C receive data function
\param[in] i2c_periph: I2Cx(x=0,1)
\param[out] none
\retval data of received
*/
uint8_t i2c_data_receive(uint32_t i2c_periph) {
return (uint8_t) DATA_RECV(I2C_DATA(i2c_periph));
}
/*!
\brief enable I2C DMA mode
\param[in] i2c_periph: I2Cx(x=0,1)
\param[in] dmastate:
only one parameter can be selected which is shown as below:
\arg I2C_DMA_ON: DMA mode enable
\arg I2C_DMA_OFF: DMA mode disable
\param[out] none
\retval none
*/
void i2c_dma_enable(uint32_t i2c_periph, uint32_t dmastate) {
/* configure I2C DMA function */
uint32_t ctl = 0U;
ctl = I2C_CTL1(i2c_periph);
ctl &= ~(I2C_CTL1_DMAON);
ctl |= dmastate;
I2C_CTL1(i2c_periph) = ctl;
}
/*!
\brief configure whether next DMA EOT is DMA last transfer or not
\param[in] i2c_periph: I2Cx(x=0,1)
\param[in] dmalast:
only one parameter can be selected which is shown as below:
\arg I2C_DMALST_ON: next DMA EOT is the last transfer
\arg I2C_DMALST_OFF: next DMA EOT is not the last transfer
\param[out] none
\retval none
*/
void i2c_dma_last_transfer_config(uint32_t i2c_periph, uint32_t dmalast) {
/* configure DMA last transfer */
uint32_t ctl = 0U;
ctl = I2C_CTL1(i2c_periph);
ctl &= ~(I2C_CTL1_DMALST);
ctl |= dmalast;
I2C_CTL1(i2c_periph) = ctl;
}
/*!
\brief whether to stretch SCL low when data is not ready in slave mode
\param[in] i2c_periph: I2Cx(x=0,1)
\param[in] stretchpara:
only one parameter can be selected which is shown as below:
\arg I2C_SCLSTRETCH_ENABLE: SCL stretching is enabled
\arg I2C_SCLSTRETCH_DISABLE: SCL stretching is disabled
\param[out] none
\retval none
*/
void i2c_stretch_scl_low_config(uint32_t i2c_periph, uint32_t stretchpara) {
/* configure I2C SCL strerching enable or disable */
uint32_t ctl = 0U;
ctl = I2C_CTL0(i2c_periph);
ctl &= ~(I2C_CTL0_SS);
ctl |= stretchpara;
I2C_CTL0(i2c_periph) = ctl;
}
/*!
\brief whether or not to response to a general call
\param[in] i2c_periph: I2Cx(x=0,1)
\param[in] gcallpara:
only one parameter can be selected which is shown as below:
\arg I2C_GCEN_ENABLE: slave will response to a general call
\arg I2C_GCEN_DISABLE: slave will not response to a general call
\param[out] none
\retval none
*/
void i2c_slave_response_to_gcall_config(uint32_t i2c_periph, uint32_t gcallpara) {
/* configure slave response to a general call enable or disable */
uint32_t ctl = 0U;
ctl = I2C_CTL0(i2c_periph);
ctl &= ~(I2C_CTL0_GCEN);
ctl |= gcallpara;
I2C_CTL0(i2c_periph) = ctl;
}
/*!
\brief software reset I2C
\param[in] i2c_periph: I2Cx(x=0,1)
\param[in] sreset:
only one parameter can be selected which is shown as below:
\arg I2C_SRESET_SET: I2C is under reset
\arg I2C_SRESET_RESET: I2C is not under reset
\param[out] none
\retval none
*/
void i2c_software_reset_config(uint32_t i2c_periph, uint32_t sreset) {
/* modify CTL0 and configure software reset I2C state */
uint32_t ctl = 0U;
ctl = I2C_CTL0(i2c_periph);
ctl &= ~(I2C_CTL0_SRESET);
ctl |= sreset;
I2C_CTL0(i2c_periph) = ctl;
}
/*!
\brief I2C PEC calculation on or off
\param[in] i2c_periph: I2Cx(x=0,1)
\param[in] pecpara:
only one parameter can be selected which is shown as below:
\arg I2C_PEC_ENABLE: PEC calculation on
\arg I2C_PEC_DISABLE: PEC calculation off
\param[out] none
\retval none
*/
void i2c_pec_enable(uint32_t i2c_periph, uint32_t pecstate) {
/* on/off PEC calculation */
uint32_t ctl = 0U;
ctl = I2C_CTL0(i2c_periph);
ctl &= ~(I2C_CTL0_PECEN);
ctl |= pecstate;
I2C_CTL0(i2c_periph) = ctl;
}
/*!
\brief I2C whether to transfer PEC value
\param[in] i2c_periph: I2Cx(x=0,1)
\param[in] pecpara:
only one parameter can be selected which is shown as below:
\arg I2C_PECTRANS_ENABLE: transfer PEC
\arg I2C_PECTRANS_DISABLE: not transfer PEC
\param[out] none
\retval none
*/
void i2c_pec_transfer_enable(uint32_t i2c_periph, uint32_t pecpara) {
/* whether to transfer PEC */
uint32_t ctl = 0U;
ctl = I2C_CTL0(i2c_periph);
ctl &= ~(I2C_CTL0_PECTRANS);
ctl |= pecpara;
I2C_CTL0(i2c_periph) = ctl;
}
/*!
\brief get packet error checking value
\param[in] i2c_periph: I2Cx(x=0,1)
\param[out] none
\retval PEC value
*/
uint8_t i2c_pec_value_get(uint32_t i2c_periph) {
return (uint8_t) ((I2C_STAT1(i2c_periph) & I2C_STAT1_PECV) >> STAT1_PECV_OFFSET);
}
/*!
\brief I2C issue alert through SMBA pin
\param[in] i2c_periph: I2Cx(x=0,1)
\param[in] smbuspara:
only one parameter can be selected which is shown as below:
\arg I2C_SALTSEND_ENABLE: issue alert through SMBA pin
\arg I2C_SALTSEND_DISABLE: not issue alert through SMBA pin
\param[out] none
\retval none
*/
void i2c_smbus_issue_alert(uint32_t i2c_periph, uint32_t smbuspara) {
/* issue alert through SMBA pin configure*/
uint32_t ctl = 0U;
ctl = I2C_CTL0(i2c_periph);
ctl &= ~(I2C_CTL0_SALT);
ctl |= smbuspara;
I2C_CTL0(i2c_periph) = ctl;
}
/*!
\brief enable or disable I2C ARP protocol in SMBus switch
\param[in] i2c_periph: I2Cx(x=0,1)
\param[in] arpstate:
only one parameter can be selected which is shown as below:
\arg I2C_ARP_ENABLE: enable ARP
\arg I2C_ARP_DISABLE: disable ARP
\param[out] none
\retval none
*/
void i2c_smbus_arp_enable(uint32_t i2c_periph, uint32_t arpstate) {
/* enable or disable I2C ARP protocol*/
uint32_t ctl = 0U;
ctl = I2C_CTL0(i2c_periph);
ctl &= ~(I2C_CTL0_ARPEN);
ctl |= arpstate;
I2C_CTL0(i2c_periph) = ctl;
}
/*!
\brief check I2C flag is set or not
\param[in] i2c_periph: I2Cx(x=0,1)
\param[in] flag: I2C flags, refer to i2c_flag_enum
only one parameter can be selected which is shown as below:
\arg I2C_FLAG_SBSEND: start condition send out
\arg I2C_FLAG_ADDSEND: address is sent in master mode or received and matches in slave mode
\arg I2C_FLAG_BTC: byte transmission finishes
\arg I2C_FLAG_ADD10SEND: header of 10-bit address is sent in master mode
\arg I2C_FLAG_STPDET: stop condition detected in slave mode
\arg I2C_FLAG_RBNE: I2C_DATA is not Empty during receiving
\arg I2C_FLAG_TBE: I2C_DATA is empty during transmitting
\arg I2C_FLAG_BERR: a bus error occurs indication a unexpected start or stop condition on I2C bus
\arg I2C_FLAG_LOSTARB: arbitration lost in master mode
\arg I2C_FLAG_AERR: acknowledge error
\arg I2C_FLAG_OUERR: overrun or underrun situation occurs in slave mode
\arg I2C_FLAG_PECERR: PEC error when receiving data
\arg I2C_FLAG_SMBTO: timeout signal in SMBus mode
\arg I2C_FLAG_SMBALT: SMBus alert status
\arg I2C_FLAG_MASTER: a flag indicating whether I2C block is in master or slave mode
\arg I2C_FLAG_I2CBSY: busy flag
\arg I2C_FLAG_TR: whether the I2C is a transmitter or a receiver
\arg I2C_FLAG_RXGC: general call address (00h) received
\arg I2C_FLAG_DEFSMB: default address of SMBus device
\arg I2C_FLAG_HSTSMB: SMBus host header detected in slave mode
\arg I2C_FLAG_DUMODF: dual flag in slave mode indicating which address is matched in dual-address mode
\param[out] none
\retval FlagStatus: SET or RESET
*/
FlagStatus i2c_flag_get(uint32_t i2c_periph, i2c_flag_enum flag) {
if (RESET != (I2C_REG_VAL(i2c_periph, flag) & BIT(I2C_BIT_POS(flag)))) {
return SET;
} else {
return RESET;
}
}
/*!
\brief clear I2C flag
\param[in] i2c_periph: I2Cx(x=0,1)
\param[in] flag: I2C flags, refer to i2c_flag_enum
only one parameter can be selected which is shown as below:
\arg I2C_FLAG_SMBALT: SMBus Alert status
\arg I2C_FLAG_SMBTO: timeout signal in SMBus mode
\arg I2C_FLAG_PECERR: PEC error when receiving data
\arg I2C_FLAG_OUERR: over-run or under-run situation occurs in slave mode
\arg I2C_FLAG_AERR: acknowledge error
\arg I2C_FLAG_LOSTARB: arbitration lost in master mode
\arg I2C_FLAG_BERR: a bus error
\arg I2C_FLAG_ADDSEND: cleared by reading I2C_STAT0 and reading I2C_STAT1
\param[out] none
\retval none
*/
void i2c_flag_clear(uint32_t i2c_periph, i2c_flag_enum flag) {
uint32_t temp;
if (I2C_FLAG_ADDSEND == flag) {
/* read I2C_STAT0 and then read I2C_STAT1 to clear ADDSEND */
temp = I2C_STAT0(i2c_periph);
temp = I2C_STAT1(i2c_periph);
} else {
I2C_REG_VAL(i2c_periph, flag) &= ~BIT(I2C_BIT_POS(flag));
}
}
/*!
\brief enable I2C interrupt
\param[in] i2c_periph: I2Cx(x=0,1)
\param[in] interrupt: I2C interrupts, refer to i2c_interrupt_enum
only one parameter can be selected which is shown as below:
\arg I2C_INT_ERR: error interrupt enable
\arg I2C_INT_EV: event interrupt enable
\arg I2C_INT_BUF: buffer interrupt enable
\param[out] none
\retval none
*/
void i2c_interrupt_enable(uint32_t i2c_periph, i2c_interrupt_enum interrupt) {
I2C_REG_VAL(i2c_periph, interrupt) |= BIT(I2C_BIT_POS(interrupt));
}
/*!
\brief disable I2C interrupt
\param[in] i2c_periph: I2Cx(x=0,1)
\param[in] interrupt: I2C interrupts, refer to i2c_flag_enum
only one parameter can be selected which is shown as below:
\arg I2C_INT_ERR: error interrupt enable
\arg I2C_INT_EV: event interrupt enable
\arg I2C_INT_BUF: buffer interrupt enable
\param[out] none
\retval none
*/
void i2c_interrupt_disable(uint32_t i2c_periph, i2c_interrupt_enum interrupt) {
I2C_REG_VAL(i2c_periph, interrupt) &= ~BIT(I2C_BIT_POS(interrupt));
}
/*!
\brief check I2C interrupt flag
\param[in] i2c_periph: I2Cx(x=0,1)
\param[in] int_flag: I2C interrupt flags, refer to i2c_interrupt_flag_enum
only one parameter can be selected which is shown as below:
\arg I2C_INT_FLAG_SBSEND: start condition sent out in master mode interrupt flag
\arg I2C_INT_FLAG_ADDSEND: address is sent in master mode or received and matches in slave mode interrupt flag
\arg I2C_INT_FLAG_BTC: byte transmission finishes
\arg I2C_INT_FLAG_ADD10SEND: header of 10-bit address is sent in master mode interrupt flag
\arg I2C_INT_FLAG_STPDET: etop condition detected in slave mode interrupt flag
\arg I2C_INT_FLAG_RBNE: I2C_DATA is not Empty during receiving interrupt flag
\arg I2C_INT_FLAG_TBE: I2C_DATA is empty during transmitting interrupt flag
\arg I2C_INT_FLAG_BERR: a bus error occurs indication a unexpected start or stop condition on I2C bus interrupt flag
\arg I2C_INT_FLAG_LOSTARB: arbitration lost in master mode interrupt flag
\arg I2C_INT_FLAG_AERR: acknowledge error interrupt flag
\arg I2C_INT_FLAG_OUERR: over-run or under-run situation occurs in slave mode interrupt flag
\arg I2C_INT_FLAG_PECERR: PEC error when receiving data interrupt flag
\arg I2C_INT_FLAG_SMBTO: timeout signal in SMBus mode interrupt flag
\arg I2C_INT_FLAG_SMBALT: SMBus Alert status interrupt flag
\param[out] none
\retval FlagStatus: SET or RESET
*/
FlagStatus i2c_interrupt_flag_get(uint32_t i2c_periph, i2c_interrupt_flag_enum int_flag) {
uint32_t intenable = 0U, flagstatus = 0U, bufie;
/* check BUFIE */
bufie = I2C_CTL1(i2c_periph) & I2C_CTL1_BUFIE;
/* get the interrupt enable bit status */
intenable = (I2C_REG_VAL(i2c_periph, int_flag) & BIT(I2C_BIT_POS(int_flag)));
/* get the corresponding flag bit status */
volatile uint32_t reg = I2C_REG_VAL2(i2c_periph, int_flag);
flagstatus = (reg & BIT(I2C_BIT_POS2(int_flag)));
if ((I2C_INT_FLAG_RBNE == int_flag) || (I2C_INT_FLAG_TBE == int_flag)) {
if (intenable && bufie) {
intenable = 1U;
} else {
intenable = 0U;
}
}
if ((0U != flagstatus) && (0U != intenable)) {
return SET;
} else {
return RESET;
}
}
/*!
\brief clear I2C interrupt flag
\param[in] i2c_periph: I2Cx(x=0,1)
\param[in] int_flag: I2C interrupt flags, refer to i2c_interrupt_flag_enum
only one parameter can be selected which is shown as below:
\arg I2C_INT_FLAG_ADDSEND: address is sent in master mode or received and matches in slave mode interrupt flag
\arg I2C_INT_FLAG_BERR: a bus error occurs indication a unexpected start or stop condition on I2C bus interrupt flag
\arg I2C_INT_FLAG_LOSTARB: arbitration lost in master mode interrupt flag
\arg I2C_INT_FLAG_AERR: acknowledge error interrupt flag
\arg I2C_INT_FLAG_OUERR: over-run or under-run situation occurs in slave mode interrupt flag
\arg I2C_INT_FLAG_PECERR: PEC error when receiving data interrupt flag
\arg I2C_INT_FLAG_SMBTO: timeout signal in SMBus mode interrupt flag
\arg I2C_INT_FLAG_SMBALT: SMBus Alert status interrupt flag
\param[out] none
\retval none
*/
void i2c_interrupt_flag_clear(uint32_t i2c_periph, i2c_interrupt_flag_enum int_flag) {
uint32_t temp;
if (I2C_INT_FLAG_ADDSEND == int_flag) {
/* read I2C_STAT0 and then read I2C_STAT1 to clear ADDSEND */
temp = I2C_STAT0(i2c_periph);
temp = I2C_STAT1(i2c_periph);
} else {
I2C_REG_VAL2(i2c_periph, int_flag) &= ~BIT(I2C_BIT_POS2(int_flag));
}
}

View File

@@ -1,347 +0,0 @@
/*!
\file gd32vf103_i2c.h
\brief definitions for the I2C
\version 2019-06-05, V1.0.1, 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.
*/
#ifdef __cplusplus
extern "C" {
#endif
#ifndef GD32VF103_I2C_H
#define GD32VF103_I2C_H
#include "gd32vf103.h"
/* I2Cx(x=0,1) definitions */
#define I2C0 I2C_BASE /*!< I2C0 base address */
#define I2C1 (I2C_BASE + 0x00000400U) /*!< I2C1 base address */
/* registers definitions */
#define I2C_CTL0(i2cx) REG32((i2cx) + 0x00U) /*!< I2C control register 0 */
#define I2C_CTL1(i2cx) REG32((i2cx) + 0x04U) /*!< I2C control register 1 */
#define I2C_SADDR0(i2cx) REG32((i2cx) + 0x08U) /*!< I2C slave address register 0*/
#define I2C_SADDR1(i2cx) REG32((i2cx) + 0x0CU) /*!< I2C slave address register */
#define I2C_DATA(i2cx) REG32((i2cx) + 0x10U) /*!< I2C transfer buffer register */
#define I2C_STAT0(i2cx) REG32((i2cx) + 0x14U) /*!< I2C transfer status register 0 */
#define I2C_STAT1(i2cx) REG32((i2cx) + 0x18U) /*!< I2C transfer status register */
#define I2C_CKCFG(i2cx) REG32((i2cx) + 0x1CU) /*!< I2C clock configure register */
#define I2C_RT(i2cx) REG32((i2cx) + 0x20U) /*!< I2C rise time register */
#define I2C_FMPCFG(i2cx) REG32((i2cx) + 0x90U) /*!< I2C fast-mode-plus configure register */
/* bits definitions */
/* I2Cx_CTL0 */
#define I2C_CTL0_I2CEN BIT(0) /*!< peripheral enable */
#define I2C_CTL0_SMBEN BIT(1) /*!< SMBus mode */
#define I2C_CTL0_SMBSEL BIT(3) /*!< SMBus type */
#define I2C_CTL0_ARPEN BIT(4) /*!< ARP enable */
#define I2C_CTL0_PECEN BIT(5) /*!< PEC enable */
#define I2C_CTL0_GCEN BIT(6) /*!< general call enable */
#define I2C_CTL0_SS BIT(7) /*!< clock stretching disable (slave mode) */
#define I2C_CTL0_START BIT(8) /*!< start generation */
#define I2C_CTL0_STOP BIT(9) /*!< stop generation */
#define I2C_CTL0_ACKEN BIT(10) /*!< acknowledge enable */
#define I2C_CTL0_POAP BIT(11) /*!< acknowledge/PEC position (for data reception) */
#define I2C_CTL0_PECTRANS BIT(12) /*!< packet error checking */
#define I2C_CTL0_SALT BIT(13) /*!< SMBus alert */
#define I2C_CTL0_SRESET BIT(15) /*!< software reset */
/* I2Cx_CTL1 */
#define I2C_CTL1_I2CCLK BITS(0, 5) /*!< I2CCLK[5:0] bits (peripheral clock frequency) */
#define I2C_CTL1_ERRIE BIT(8) /*!< error interrupt enable */
#define I2C_CTL1_EVIE BIT(9) /*!< event interrupt enable */
#define I2C_CTL1_BUFIE BIT(10) /*!< buffer interrupt enable */
#define I2C_CTL1_DMAON BIT(11) /*!< DMA requests enable */
#define I2C_CTL1_DMALST BIT(12) /*!< DMA last transfer */
/* I2Cx_SADDR0 */
#define I2C_SADDR0_ADDRESS0 BIT(0) /*!< bit 0 of a 10-bit address */
#define I2C_SADDR0_ADDRESS BITS(1, 7) /*!< 7-bit address or bits 7:1 of a 10-bit address */
#define I2C_SADDR0_ADDRESS_H BITS(8, 9) /*!< highest two bits of a 10-bit address */
#define I2C_SADDR0_ADDFORMAT BIT(15) /*!< address mode for the I2C slave */
/* I2Cx_SADDR1 */
#define I2C_SADDR1_DUADEN BIT(0) /*!< aual-address mode switch */
#define I2C_SADDR1_ADDRESS2 BITS(1, 7) /*!< second I2C address for the slave in dual-address mode */
/* I2Cx_DATA */
#define I2C_DATA_TRB BITS(0, 7) /*!< 8-bit data register */
/* I2Cx_STAT0 */
#define I2C_STAT0_SBSEND BIT(0) /*!< start bit (master mode) */
#define I2C_STAT0_ADDSEND BIT(1) /*!< address sent (master mode)/matched (slave mode) */
#define I2C_STAT0_BTC BIT(2) /*!< byte transfer finished */
#define I2C_STAT0_ADD10SEND BIT(3) /*!< 10-bit header sent (master mode) */
#define I2C_STAT0_STPDET BIT(4) /*!< stop detection (slave mode) */
#define I2C_STAT0_RBNE BIT(6) /*!< data register not empty (receivers) */
#define I2C_STAT0_TBE BIT(7) /*!< data register empty (transmitters) */
#define I2C_STAT0_BERR BIT(8) /*!< bus error */
#define I2C_STAT0_LOSTARB BIT(9) /*!< arbitration lost (master mode) */
#define I2C_STAT0_AERR BIT(10) /*!< acknowledge failure */
#define I2C_STAT0_OUERR BIT(11) /*!< overrun/underrun */
#define I2C_STAT0_PECERR BIT(12) /*!< PEC error in reception */
#define I2C_STAT0_SMBTO BIT(14) /*!< timeout signal in SMBus mode */
#define I2C_STAT0_SMBALT BIT(15) /*!< SMBus alert status */
/* I2Cx_STAT1 */
#define I2C_STAT1_MASTER BIT(0) /*!< master/slave */
#define I2C_STAT1_I2CBSY BIT(1) /*!< bus busy */
#define I2C_STAT1_TR BIT(2) /*!< transmitter/receiver */
#define I2C_STAT1_RXGC BIT(4) /*!< general call address (slave mode) */
#define I2C_STAT1_DEFSMB BIT(5) /*!< SMBus device default address (slave mode) */
#define I2C_STAT1_HSTSMB BIT(6) /*!< SMBus host header (slave mode) */
#define I2C_STAT1_DUMODF BIT(7) /*!< dual flag (slave mode) */
#define I2C_STAT1_PECV BITS(8, 15) /*!< packet error checking value */
/* I2Cx_CKCFG */
#define I2C_CKCFG_CLKC BITS(0, 11) /*!< clock control register in fast/standard mode (master mode) */
#define I2C_CKCFG_DTCY BIT(14) /*!< fast mode duty cycle */
#define I2C_CKCFG_FAST BIT(15) /*!< I2C speed selection in master mode */
/* I2Cx_RT */
#define I2C_RT_RISETIME BITS(0, 5) /*!< maximum rise time in fast/standard mode (Master mode) */
/* I2Cx_FMPCFG */
#define I2C_FMPCFG_FMPEN BIT(0) /*!< fast mode plus enable bit */
/* constants definitions */
/* define the I2C bit position and its register index offset */
#define I2C_REGIDX_BIT(regidx, bitpos) (((uint32_t)(regidx) << 6) | (uint32_t)(bitpos))
#define I2C_REG_VAL(i2cx, offset) (REG32((i2cx) + (((uint32_t)(offset)&0xFFFFU) >> 6)))
#define I2C_BIT_POS(val) ((uint32_t)(val)&0x1FU)
#define I2C_REGIDX_BIT2(regidx, bitpos, regidx2, bitpos2) (((uint32_t)(regidx2) << 22) | (uint32_t)((bitpos2) << 16) | (((uint32_t)(regidx) << 6) | (uint32_t)(bitpos)))
#define I2C_REG_VAL2(i2cx, offset) (REG32((i2cx) + ((uint32_t)(offset) >> 22)))
#define I2C_BIT_POS2(val) (((uint32_t)(val)&0x1F0000U) >> 16)
/* register offset */
#define I2C_CTL1_REG_OFFSET 0x04U /*!< CTL1 register offset */
#define I2C_STAT0_REG_OFFSET 0x14U /*!< STAT0 register offset */
#define I2C_STAT1_REG_OFFSET 0x18U /*!< STAT1 register offset */
/* I2C flags */
typedef enum {
/* flags in STAT0 register */
I2C_FLAG_SBSEND = I2C_REGIDX_BIT(I2C_STAT0_REG_OFFSET, 0U), /*!< start condition sent out in master mode */
I2C_FLAG_ADDSEND = I2C_REGIDX_BIT(I2C_STAT0_REG_OFFSET, 1U), /*!< address is sent in master mode or received and matches in slave mode */
I2C_FLAG_BTC = I2C_REGIDX_BIT(I2C_STAT0_REG_OFFSET, 2U), /*!< byte transmission finishes */
I2C_FLAG_ADD10SEND = I2C_REGIDX_BIT(I2C_STAT0_REG_OFFSET, 3U), /*!< header of 10-bit address is sent in master mode */
I2C_FLAG_STPDET = I2C_REGIDX_BIT(I2C_STAT0_REG_OFFSET, 4U), /*!< stop condition detected in slave mode */
I2C_FLAG_RBNE = I2C_REGIDX_BIT(I2C_STAT0_REG_OFFSET, 6U), /*!< I2C_DATA is not Empty during receiving */
I2C_FLAG_TBE = I2C_REGIDX_BIT(I2C_STAT0_REG_OFFSET, 7U), /*!< I2C_DATA is empty during transmitting */
I2C_FLAG_BERR = I2C_REGIDX_BIT(I2C_STAT0_REG_OFFSET, 8U), /*!< a bus error occurs indication a unexpected start or stop condition on I2C bus */
I2C_FLAG_LOSTARB = I2C_REGIDX_BIT(I2C_STAT0_REG_OFFSET, 9U), /*!< arbitration lost in master mode */
I2C_FLAG_AERR = I2C_REGIDX_BIT(I2C_STAT0_REG_OFFSET, 10U), /*!< acknowledge error */
I2C_FLAG_OUERR = I2C_REGIDX_BIT(I2C_STAT0_REG_OFFSET, 11U), /*!< over-run or under-run situation occurs in slave mode */
I2C_FLAG_PECERR = I2C_REGIDX_BIT(I2C_STAT0_REG_OFFSET, 12U), /*!< PEC error when receiving data */
I2C_FLAG_SMBTO = I2C_REGIDX_BIT(I2C_STAT0_REG_OFFSET, 14U), /*!< timeout signal in SMBus mode */
I2C_FLAG_SMBALT = I2C_REGIDX_BIT(I2C_STAT0_REG_OFFSET, 15U), /*!< SMBus alert status */
/* flags in STAT1 register */
I2C_FLAG_MASTER = I2C_REGIDX_BIT(I2C_STAT1_REG_OFFSET, 0U), /*!< a flag indicating whether I2C block is in master or slave mode */
I2C_FLAG_I2CBSY = I2C_REGIDX_BIT(I2C_STAT1_REG_OFFSET, 1U), /*!< busy flag */
I2C_FLAG_TR = I2C_REGIDX_BIT(I2C_STAT1_REG_OFFSET, 2U), /*!< whether the I2C is a transmitter or a receiver */
I2C_FLAG_RXGC = I2C_REGIDX_BIT(I2C_STAT1_REG_OFFSET, 4U), /*!< general call address (00h) received */
I2C_FLAG_DEFSMB = I2C_REGIDX_BIT(I2C_STAT1_REG_OFFSET, 5U), /*!< default address of SMBus device */
I2C_FLAG_HSTSMB = I2C_REGIDX_BIT(I2C_STAT1_REG_OFFSET, 6U), /*!< SMBus host header detected in slave mode */
I2C_FLAG_DUMODF = I2C_REGIDX_BIT(I2C_STAT1_REG_OFFSET, 7U), /*!< dual flag in slave mode indicating which address is matched in dual-address mode */
} i2c_flag_enum;
/* I2C interrupt flags */
typedef enum {
/* interrupt flags in CTL1 register */
I2C_INT_FLAG_SBSEND = I2C_REGIDX_BIT2(I2C_CTL1_REG_OFFSET, 9U, I2C_STAT0_REG_OFFSET, 0U), /*!< start condition sent out in master mode interrupt flag */
I2C_INT_FLAG_ADDSEND = I2C_REGIDX_BIT2(I2C_CTL1_REG_OFFSET, 9U, I2C_STAT0_REG_OFFSET, 1U), /*!< address is sent in master mode or received and matches in slave mode interrupt flag */
I2C_INT_FLAG_BTC = I2C_REGIDX_BIT2(I2C_CTL1_REG_OFFSET, 9U, I2C_STAT0_REG_OFFSET, 2U), /*!< byte transmission finishes */
I2C_INT_FLAG_ADD10SEND = I2C_REGIDX_BIT2(I2C_CTL1_REG_OFFSET, 9U, I2C_STAT0_REG_OFFSET, 3U), /*!< header of 10-bit address is sent in master mode interrupt flag */
I2C_INT_FLAG_STPDET = I2C_REGIDX_BIT2(I2C_CTL1_REG_OFFSET, 9U, I2C_STAT0_REG_OFFSET, 4U), /*!< stop condition detected in slave mode interrupt flag */
I2C_INT_FLAG_RBNE = I2C_REGIDX_BIT2(I2C_CTL1_REG_OFFSET, 9U, I2C_STAT0_REG_OFFSET, 6U), /*!< I2C_DATA is not Empty during receiving interrupt flag */
I2C_INT_FLAG_TBE = I2C_REGIDX_BIT2(I2C_CTL1_REG_OFFSET, 9U, I2C_STAT0_REG_OFFSET, 7U), /*!< I2C_DATA is empty during transmitting interrupt flag */
I2C_INT_FLAG_BERR = I2C_REGIDX_BIT2(I2C_CTL1_REG_OFFSET, 8U, I2C_STAT0_REG_OFFSET, 8U), /*!< a bus error occurs indication a unexpected start or stop condition on I2C bus interrupt flag */
I2C_INT_FLAG_LOSTARB = I2C_REGIDX_BIT2(I2C_CTL1_REG_OFFSET, 8U, I2C_STAT0_REG_OFFSET, 9U), /*!< arbitration lost in master mode interrupt flag */
I2C_INT_FLAG_AERR = I2C_REGIDX_BIT2(I2C_CTL1_REG_OFFSET, 8U, I2C_STAT0_REG_OFFSET, 10U), /*!< acknowledge error interrupt flag */
I2C_INT_FLAG_OUERR = I2C_REGIDX_BIT2(I2C_CTL1_REG_OFFSET, 8U, I2C_STAT0_REG_OFFSET, 11U), /*!< over-run or under-run situation occurs in slave mode interrupt flag */
I2C_INT_FLAG_PECERR = I2C_REGIDX_BIT2(I2C_CTL1_REG_OFFSET, 8U, I2C_STAT0_REG_OFFSET, 12U), /*!< PEC error when receiving data interrupt flag */
I2C_INT_FLAG_SMBTO = I2C_REGIDX_BIT2(I2C_CTL1_REG_OFFSET, 8U, I2C_STAT0_REG_OFFSET, 14U), /*!< timeout signal in SMBus mode interrupt flag */
I2C_INT_FLAG_SMBALT = I2C_REGIDX_BIT2(I2C_CTL1_REG_OFFSET, 8U, I2C_STAT0_REG_OFFSET, 15U), /*!< SMBus Alert status interrupt flag */
} i2c_interrupt_flag_enum;
/* I2C interrupt enable or disable */
typedef enum {
/* interrupt in CTL1 register */
I2C_INT_ERR = I2C_REGIDX_BIT(I2C_CTL1_REG_OFFSET, 8U), /*!< error interrupt enable */
I2C_INT_EV = I2C_REGIDX_BIT(I2C_CTL1_REG_OFFSET, 9U), /*!< event interrupt enable */
I2C_INT_BUF = I2C_REGIDX_BIT(I2C_CTL1_REG_OFFSET, 10U), /*!< buffer interrupt enable */
} i2c_interrupt_enum;
/* SMBus/I2C mode switch and SMBus type selection */
#define I2C_I2CMODE_ENABLE ((uint32_t)0x00000000U) /*!< I2C mode */
#define I2C_SMBUSMODE_ENABLE I2C_CTL0_SMBEN /*!< SMBus mode */
/* SMBus/I2C mode switch and SMBus type selection */
#define I2C_SMBUS_DEVICE ((uint32_t)0x00000000U) /*!< SMBus mode device type */
#define I2C_SMBUS_HOST I2C_CTL0_SMBSEL /*!< SMBus mode host type */
/* I2C transfer direction */
#define I2C_RECEIVER ((uint32_t)0x00000001U) /*!< receiver */
#define I2C_TRANSMITTER ((uint32_t)0xFFFFFFFEU) /*!< transmitter */
/* whether or not to send an ACK */
#define I2C_ACK_DISABLE ((uint32_t)0x00000000U) /*!< ACK will be not sent */
#define I2C_ACK_ENABLE ((uint32_t)0x00000001U) /*!< ACK will be sent */
/* I2C POAP position*/
#define I2C_ACKPOS_NEXT ((uint32_t)0x00000000U) /*!< ACKEN bit decides whether or not to send ACK for the next byte */
#define I2C_ACKPOS_CURRENT ((uint32_t)0x00000001U) /*!< ACKEN bit decides whether or not to send ACK or not for the current byte */
/* I2C dual-address mode switch */
#define I2C_DUADEN_DISABLE ((uint32_t)0x00000000U) /*!< dual-address mode disabled */
#define I2C_DUADEN_ENABLE ((uint32_t)0x00000001U) /*!< dual-address mode enabled */
/* whether or not to stretch SCL low */
#define I2C_SCLSTRETCH_ENABLE ((uint32_t)0x00000000U) /*!< SCL stretching is enabled */
#define I2C_SCLSTRETCH_DISABLE I2C_CTL0_SS /*!< SCL stretching is disabled */
/* whether or not to response to a general call */
#define I2C_GCEN_ENABLE I2C_CTL0_GCEN /*!< slave will response to a general call */
#define I2C_GCEN_DISABLE ((uint32_t)0x00000000U) /*!< slave will not response to a general call */
/* software reset I2C */
#define I2C_SRESET_SET I2C_CTL0_SRESET /*!< I2C is under reset */
#define I2C_SRESET_RESET ((uint32_t)0x00000000U) /*!< I2C is not under reset */
/* I2C DMA mode configure */
/* DMA mode switch */
#define I2C_DMA_ON I2C_CTL1_DMAON /*!< DMA mode enabled */
#define I2C_DMA_OFF ((uint32_t)0x00000000U) /*!< DMA mode disabled */
/* flag indicating DMA last transfer */
#define I2C_DMALST_ON I2C_CTL1_DMALST /*!< next DMA EOT is the last transfer */
#define I2C_DMALST_OFF ((uint32_t)0x00000000U) /*!< next DMA EOT is not the last transfer */
/* I2C PEC configure */
/* PEC enable */
#define I2C_PEC_ENABLE I2C_CTL0_PECEN /*!< PEC calculation on */
#define I2C_PEC_DISABLE ((uint32_t)0x00000000U) /*!< PEC calculation off */
/* PEC transfer */
#define I2C_PECTRANS_ENABLE I2C_CTL0_PECTRANS /*!< transfer PEC */
#define I2C_PECTRANS_DISABLE ((uint32_t)0x00000000U) /*!< not transfer PEC value */
/* I2C SMBus configure */
/* issue or not alert through SMBA pin */
#define I2C_SALTSEND_ENABLE I2C_CTL0_SALT /*!< issue alert through SMBA pin */
#define I2C_SALTSEND_DISABLE ((uint32_t)0x00000000U) /*!< not issue alert through SMBA */
/* ARP protocol in SMBus switch */
#define I2C_ARP_ENABLE I2C_CTL0_ARPEN /*!< ARP enable */
#define I2C_ARP_DISABLE ((uint32_t)0x00000000U) /*!< ARP disable */
/* transmit I2C data */
#define DATA_TRANS(regval) (BITS(0, 7) & ((uint32_t)(regval) << 0))
/* receive I2C data */
#define DATA_RECV(regval) GET_BITS((uint32_t)(regval), 0, 7)
/* I2C duty cycle in fast mode */
#define I2C_DTCY_2 ((uint32_t)0x00000000U) /*!< I2C fast mode Tlow/Thigh = 2 */
#define I2C_DTCY_16_9 I2C_CKCFG_DTCY /*!< I2C fast mode Tlow/Thigh = 16/9 */
/* address mode for the I2C slave */
#define I2C_ADDFORMAT_7BITS ((uint32_t)0x00000000U) /*!< address:7 bits */
#define I2C_ADDFORMAT_10BITS I2C_SADDR0_ADDFORMAT /*!< address:10 bits */
/* function declarations */
/* reset I2C */
void i2c_deinit(uint32_t i2c_periph);
/* configure I2C clock */
void i2c_clock_config(uint32_t i2c_periph, uint32_t clkspeed, uint32_t dutycyc);
/* configure I2C address */
void i2c_mode_addr_config(uint32_t i2c_periph, uint32_t mode, uint32_t addformat, uint32_t addr);
/* SMBus type selection */
void i2c_smbus_type_config(uint32_t i2c_periph, uint32_t type);
/* whether or not to send an ACK */
void i2c_ack_config(uint32_t i2c_periph, uint32_t ack);
/* configure I2C POAP position */
void i2c_ackpos_config(uint32_t i2c_periph, uint32_t pos);
/* master sends slave address */
void i2c_master_addressing(uint32_t i2c_periph, uint32_t addr, uint32_t trandirection);
/* enable dual-address mode */
void i2c_dualaddr_enable(uint32_t i2c_periph, uint32_t dualaddr);
/* disable dual-address mode */
void i2c_dualaddr_disable(uint32_t i2c_periph);
/* enable I2C */
void i2c_enable(uint32_t i2c_periph);
/* disable I2C */
void i2c_disable(uint32_t i2c_periph);
/* generate a START condition on I2C bus */
void i2c_start_on_bus(uint32_t i2c_periph);
/* generate a STOP condition on I2C bus */
void i2c_stop_on_bus(uint32_t i2c_periph);
/* I2C transmit data function */
void i2c_data_transmit(uint32_t i2c_periph, uint8_t data);
/* I2C receive data function */
uint8_t i2c_data_receive(uint32_t i2c_periph);
/* enable I2C DMA mode */
void i2c_dma_enable(uint32_t i2c_periph, uint32_t dmastate);
/* configure whether next DMA EOT is DMA last transfer or not */
void i2c_dma_last_transfer_config(uint32_t i2c_periph, uint32_t dmalast);
/* whether to stretch SCL low when data is not ready in slave mode */
void i2c_stretch_scl_low_config(uint32_t i2c_periph, uint32_t stretchpara);
/* whether or not to response to a general call */
void i2c_slave_response_to_gcall_config(uint32_t i2c_periph, uint32_t gcallpara);
/* software reset I2C */
void i2c_software_reset_config(uint32_t i2c_periph, uint32_t sreset);
/* I2C PEC calculation on or off */
void i2c_pec_enable(uint32_t i2c_periph, uint32_t pecstate);
/* I2C whether to transfer PEC value */
void i2c_pec_transfer_enable(uint32_t i2c_periph, uint32_t pecpara);
/* packet error checking value */
uint8_t i2c_pec_value_get(uint32_t i2c_periph);
/* I2C issue alert through SMBA pin */
void i2c_smbus_issue_alert(uint32_t i2c_periph, uint32_t smbuspara);
/* I2C ARP protocol in SMBus switch */
void i2c_smbus_arp_enable(uint32_t i2c_periph, uint32_t arpstate);
/* check I2C flag is set or not */
FlagStatus i2c_flag_get(uint32_t i2c_periph, i2c_flag_enum flag);
/* clear I2C flag */
void i2c_flag_clear(uint32_t i2c_periph, i2c_flag_enum flag);
/* enable I2C interrupt */
void i2c_interrupt_enable(uint32_t i2c_periph, i2c_interrupt_enum interrupt);
/* disable I2C interrupt */
void i2c_interrupt_disable(uint32_t i2c_periph, i2c_interrupt_enum interrupt);
/* check I2C interrupt flag */
FlagStatus i2c_interrupt_flag_get(uint32_t i2c_periph, i2c_interrupt_flag_enum int_flag);
/* clear I2C interrupt flag */
void i2c_interrupt_flag_clear(uint32_t i2c_periph, i2c_interrupt_flag_enum int_flag);
#endif /* GD32VF103_I2C_H */
#ifdef __cplusplus
}
#endif

View File

@@ -1,130 +0,0 @@
/*!
\file gd32vf103_pmu.h
\brief definitions for the PMU
\version 2019-06-05, 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.
*/
#ifdef __cplusplus
extern "C" {
#endif
#ifndef GD32VF103_PMU_H
#define GD32VF103_PMU_H
#include "gd32vf103.h"
/* PMU definitions */
#define PMU PMU_BASE /*!< PMU base address */
/* registers definitions */
#define PMU_CTL REG32((PMU) + 0x00U) /*!< PMU control register */
#define PMU_CS REG32((PMU) + 0x04U) /*!< PMU control and status register */
/* bits definitions */
/* PMU_CTL */
#define PMU_CTL_LDOLP BIT(0) /*!< LDO low power mode */
#define PMU_CTL_STBMOD BIT(1) /*!< standby mode */
#define PMU_CTL_WURST BIT(2) /*!< wakeup flag reset */
#define PMU_CTL_STBRST BIT(3) /*!< standby flag reset */
#define PMU_CTL_LVDEN BIT(4) /*!< low voltage detector enable */
#define PMU_CTL_LVDT BITS(5, 7) /*!< low voltage detector threshold */
#define PMU_CTL_BKPWEN BIT(8) /*!< backup domain write enable */
/* PMU_CS */
#define PMU_CS_WUF BIT(0) /*!< wakeup flag */
#define PMU_CS_STBF BIT(1) /*!< standby flag */
#define PMU_CS_LVDF BIT(2) /*!< low voltage detector status flag */
#define PMU_CS_WUPEN BIT(8) /*!< wakeup pin enable */
/* constants definitions */
/* PMU low voltage detector threshold definitions */
#define CTL_LVDT(regval) (BITS(5, 7) & ((uint32_t)(regval) << 5))
#define PMU_LVDT_0 CTL_LVDT(0) /*!< voltage threshold is 2.2V */
#define PMU_LVDT_1 CTL_LVDT(1) /*!< voltage threshold is 2.3V */
#define PMU_LVDT_2 CTL_LVDT(2) /*!< voltage threshold is 2.4V */
#define PMU_LVDT_3 CTL_LVDT(3) /*!< voltage threshold is 2.5V */
#define PMU_LVDT_4 CTL_LVDT(4) /*!< voltage threshold is 2.6V */
#define PMU_LVDT_5 CTL_LVDT(5) /*!< voltage threshold is 2.7V */
#define PMU_LVDT_6 CTL_LVDT(6) /*!< voltage threshold is 2.8V */
#define PMU_LVDT_7 CTL_LVDT(7) /*!< voltage threshold is 2.9V */
/* PMU flag definitions */
#define PMU_FLAG_WAKEUP PMU_CS_WUF /*!< wakeup flag status */
#define PMU_FLAG_STANDBY PMU_CS_STBF /*!< standby flag status */
#define PMU_FLAG_LVD PMU_CS_LVDF /*!< lvd flag status */
/* PMU ldo definitions */
#define PMU_LDO_NORMAL ((uint32_t)0x00000000U) /*!< LDO normal work when PMU enter deepsleep mode */
#define PMU_LDO_LOWPOWER PMU_CTL_LDOLP /*!< LDO work at low power status when PMU enter deepsleep mode */
/* PMU flag reset definitions */
#define PMU_FLAG_RESET_WAKEUP ((uint8_t)0x00U) /*!< wakeup flag reset */
#define PMU_FLAG_RESET_STANDBY ((uint8_t)0x01U) /*!< standby flag reset */
/* PMU command constants definitions */
#define WFI_CMD ((uint8_t)0x00U) /*!< use WFI command */
#define WFE_CMD ((uint8_t)0x01U) /*!< use WFE command */
/* function declarations */
/* reset PMU registers */
void pmu_deinit(void);
/* select low voltage detector threshold */
void pmu_lvd_select(uint32_t lvdt_n);
/* disable PMU lvd */
void pmu_lvd_disable(void);
/* set PMU mode */
/* PMU work at sleep mode */
void pmu_to_sleepmode(uint8_t sleepmodecmd);
/* PMU work at deepsleep mode */
void pmu_to_deepsleepmode(uint32_t ldo, uint8_t deepsleepmodecmd);
/* PMU work at standby mode */
void pmu_to_standbymode(uint8_t standbymodecmd);
/* enable PMU wakeup pin */
void pmu_wakeup_pin_enable(void);
/* disable PMU wakeup pin */
void pmu_wakeup_pin_disable(void);
/* backup related functions */
/* enable write access to the registers in backup domain */
void pmu_backup_write_enable(void);
/* disable write access to the registers in backup domain */
void pmu_backup_write_disable(void);
/* flag functions */
/* get flag state */
FlagStatus pmu_flag_get(uint32_t flag);
/* clear flag bit */
void pmu_flag_clear(uint32_t flag_reset);
#endif /* GD32VF103_PMU_H */
#ifdef __cplusplus
}
#endif

View File

@@ -1,721 +0,0 @@
/*!
\file gd32vf103_rcu.h
\brief definitions for the RCU
\version 2019-06-05, 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.
*/
#ifdef __cplusplus
extern "C" {
#endif
#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 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 */
#ifdef __cplusplus
}
#endif

View File

@@ -1,153 +0,0 @@
/*!
\file gd32vf103_rtc.h
\brief definitions for the RTC
\version 2019-06-05, 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.
*/
#ifdef __cplusplus
extern "C" {
#endif
#ifndef GD32VF103_RTC_H
#define GD32VF103_RTC_H
#include "gd32vf103.h"
/* RTC definitions */
#define RTC RTC_BASE
/* registers definitions */
#define RTC_INTEN REG32(RTC + 0x00U) /*!< interrupt enable register */
#define RTC_CTL REG32(RTC + 0x04U) /*!< control register */
#define RTC_PSCH REG32(RTC + 0x08U) /*!< prescaler high register */
#define RTC_PSCL REG32(RTC + 0x0CU) /*!< prescaler low register */
#define RTC_DIVH REG32(RTC + 0x10U) /*!< divider high register */
#define RTC_DIVL REG32(RTC + 0x14U) /*!< divider low register */
#define RTC_CNTH REG32(RTC + 0x18U) /*!< counter high register */
#define RTC_CNTL REG32(RTC + 0x1CU) /*!< counter low register */
#define RTC_ALRMH REG32(RTC + 0x20U) /*!< alarm high register */
#define RTC_ALRML REG32(RTC + 0x24U) /*!< alarm low register */
/* bits definitions */
/* RTC_INTEN */
#define RTC_INTEN_SCIE BIT(0) /*!< second interrupt enable */
#define RTC_INTEN_ALRMIE BIT(1) /*!< alarm interrupt enable */
#define RTC_INTEN_OVIE BIT(2) /*!< overflow interrupt enable */
/* RTC_CTL */
#define RTC_CTL_SCIF BIT(0) /*!< second interrupt flag */
#define RTC_CTL_ALRMIF BIT(1) /*!< alarm interrupt flag */
#define RTC_CTL_OVIF BIT(2) /*!< overflow interrupt flag */
#define RTC_CTL_RSYNF BIT(3) /*!< registers synchronized flag */
#define RTC_CTL_CMF BIT(4) /*!< configuration mode flag */
#define RTC_CTL_LWOFF BIT(5) /*!< last write operation finished flag */
/* RTC_PSCH */
#define RTC_PSCH_PSC BITS(0, 3) /*!< prescaler high value */
/* RTC_PSCL */
#define RTC_PSCL_PSC BITS(0, 15) /*!< prescaler low value */
/* RTC_DIVH */
#define RTC_DIVH_DIV BITS(0, 3) /*!< divider high value */
/* RTC_DIVL */
#define RTC_DIVL_DIV BITS(0, 15) /*!< divider low value */
/* RTC_CNTH */
#define RTC_CNTH_CNT BITS(0, 15) /*!< counter high value */
/* RTC_CNTL */
#define RTC_CNTL_CNT BITS(0, 15) /*!< counter low value */
/* RTC_ALRMH */
#define RTC_ALRMH_ALRM BITS(0, 15) /*!< alarm high value */
/* RTC_ALRML */
#define RTC_ALRML_ALRM BITS(0, 15) /*!< alarm low value */
/* constants definitions */
/* RTC interrupt enable or disable definitions */
#define RTC_INT_SECOND RTC_INTEN_SCIE /*!< second interrupt enable */
#define RTC_INT_ALARM RTC_INTEN_ALRMIE /*!< alarm interrupt enable */
#define RTC_INT_OVERFLOW RTC_INTEN_OVIE /*!< overflow interrupt enable */
/* RTC interrupt flag definitions */
#define RTC_INT_FLAG_SECOND RTC_CTL_SCIF /*!< second interrupt flag */
#define RTC_INT_FLAG_ALARM RTC_CTL_ALRMIF /*!< alarm interrupt flag */
#define RTC_INT_FLAG_OVERFLOW RTC_CTL_OVIF /*!< overflow interrupt flag */
/* RTC flag definitions */
#define RTC_FLAG_SECOND RTC_CTL_SCIF /*!< second interrupt flag */
#define RTC_FLAG_ALARM RTC_CTL_ALRMIF /*!< alarm interrupt flag */
#define RTC_FLAG_OVERFLOW RTC_CTL_OVIF /*!< overflow interrupt flag */
#define RTC_FLAG_RSYN RTC_CTL_RSYNF /*!< registers synchronized flag */
#define RTC_FLAG_LWOF RTC_CTL_LWOFF /*!< last write operation finished flag */
/* function declarations */
/* initialization functions */
/* enter RTC configuration mode */
void rtc_configuration_mode_enter(void);
/* exit RTC configuration mode */
void rtc_configuration_mode_exit(void);
/* set RTC counter value */
void rtc_counter_set(uint32_t cnt);
/* set RTC prescaler value */
void rtc_prescaler_set(uint32_t psc);
/* operation functions */
/* wait RTC last write operation finished flag set */
void rtc_lwoff_wait(void);
/* wait RTC registers synchronized flag set */
void rtc_register_sync_wait(void);
/* set RTC alarm value */
void rtc_alarm_config(uint32_t alarm);
/* get RTC counter value */
uint32_t rtc_counter_get(void);
/* get RTC divider value */
uint32_t rtc_divider_get(void);
/* flag & interrupt functions */
/* get RTC flag status */
FlagStatus rtc_flag_get(uint32_t flag);
/* clear RTC flag status */
void rtc_flag_clear(uint32_t flag);
/* get RTC interrupt flag status */
FlagStatus rtc_interrupt_flag_get(uint32_t flag);
/* clear RTC interrupt flag status */
void rtc_interrupt_flag_clear(uint32_t flag);
/* enable RTC interrupt */
void rtc_interrupt_enable(uint32_t interrupt);
/* disable RTC interrupt */
void rtc_interrupt_disable(uint32_t interrupt);
#endif /* GD32VF103_RTC_H */
#ifdef __cplusplus
}
#endif

View File

@@ -1,346 +0,0 @@
/*!
\file gd32vf103_spi.h
\brief definitions for the SPI
\version 2019-06-05, 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.
*/
#ifdef __cplusplus
extern "C" {
#endif
#ifndef GD32VF103_SPI_H
#define GD32VF103_SPI_H
#include "gd32vf103.h"
/* SPIx(x=0,1,2) definitions */
#define SPI0 (SPI_BASE + 0x0000F800U)
#define SPI1 SPI_BASE
#define SPI2 (SPI_BASE + 0x00000400U)
/* SPI registers definitions */
#define SPI_CTL0(spix) REG32((spix) + 0x00U) /*!< SPI control register 0 */
#define SPI_CTL1(spix) REG32((spix) + 0x04U) /*!< SPI control register 1*/
#define SPI_STAT(spix) REG32((spix) + 0x08U) /*!< SPI status register */
#define SPI_DATA(spix) REG32((spix) + 0x0CU) /*!< SPI data register */
#define SPI_CRCPOLY(spix) REG32((spix) + 0x10U) /*!< SPI CRC polynomial register */
#define SPI_RCRC(spix) REG32((spix) + 0x14U) /*!< SPI receive CRC register */
#define SPI_TCRC(spix) REG32((spix) + 0x18U) /*!< SPI transmit CRC register */
#define SPI_I2SCTL(spix) REG32((spix) + 0x1CU) /*!< SPI I2S control register */
#define SPI_I2SPSC(spix) REG32((spix) + 0x20U) /*!< SPI I2S clock prescaler register */
/* bits definitions */
/* SPI_CTL0 */
#define SPI_CTL0_CKPH BIT(0) /*!< clock phase selection*/
#define SPI_CTL0_CKPL BIT(1) /*!< clock polarity selection */
#define SPI_CTL0_MSTMOD BIT(2) /*!< master mode enable */
#define SPI_CTL0_PSC BITS(3, 5) /*!< master clock prescaler selection */
#define SPI_CTL0_SPIEN BIT(6) /*!< SPI enable*/
#define SPI_CTL0_LF BIT(7) /*!< LSB first mode */
#define SPI_CTL0_SWNSS BIT(8) /*!< NSS pin selection in NSS software mode */
#define SPI_CTL0_SWNSSEN BIT(9) /*!< NSS software mode selection */
#define SPI_CTL0_RO BIT(10) /*!< receive only */
#define SPI_CTL0_FF16 BIT(11) /*!< data frame size */
#define SPI_CTL0_CRCNT BIT(12) /*!< CRC next transfer */
#define SPI_CTL0_CRCEN BIT(13) /*!< CRC calculation enable */
#define SPI_CTL0_BDOEN BIT(14) /*!< bidirectional transmit output enable*/
#define SPI_CTL0_BDEN BIT(15) /*!< bidirectional enable */
/* SPI_CTL1 */
#define SPI_CTL1_DMAREN BIT(0) /*!< receive buffer dma enable */
#define SPI_CTL1_DMATEN BIT(1) /*!< transmit buffer dma enable */
#define SPI_CTL1_NSSDRV BIT(2) /*!< drive NSS output */
#define SPI_CTL1_NSSP BIT(3) /*!< SPI NSS pulse mode enable */
#define SPI_CTL1_TMOD BIT(4) /*!< SPI TI mode enable */
#define SPI_CTL1_ERRIE BIT(5) /*!< errors interrupt enable */
#define SPI_CTL1_RBNEIE BIT(6) /*!< receive buffer not empty interrupt enable */
#define SPI_CTL1_TBEIE BIT(7) /*!< transmit buffer empty interrupt enable */
/* SPI_STAT */
#define SPI_STAT_RBNE BIT(0) /*!< receive buffer not empty */
#define SPI_STAT_TBE BIT(1) /*!< transmit buffer empty */
#define SPI_STAT_I2SCH BIT(2) /*!< I2S channel side */
#define SPI_STAT_TXURERR BIT(3) /*!< I2S transmission underrun error bit */
#define SPI_STAT_CRCERR BIT(4) /*!< SPI CRC error bit */
#define SPI_STAT_CONFERR BIT(5) /*!< SPI configuration error bit */
#define SPI_STAT_RXORERR BIT(6) /*!< SPI reception overrun error bit */
#define SPI_STAT_TRANS BIT(7) /*!< transmitting on-going bit */
#define SPI_STAT_FERR BIT(8) /*!< format error bit */
/* SPI_DATA */
#define SPI_DATA_DATA BITS(0, 15) /*!< data transfer register */
/* SPI_CRCPOLY */
#define SPI_CRCPOLY_CRCPOLY BITS(0, 15) /*!< CRC polynomial value */
/* SPI_RCRC */
#define SPI_RCRC_RCRC BITS(0, 15) /*!< RX CRC value */
/* SPI_TCRC */
#define SPI_TCRC_TCRC BITS(0, 15) /*!< TX CRC value */
/* SPI_I2SCTL */
#define SPI_I2SCTL_CHLEN BIT(0) /*!< channel length */
#define SPI_I2SCTL_DTLEN BITS(1, 2) /*!< data length */
#define SPI_I2SCTL_CKPL BIT(3) /*!< idle state clock polarity */
#define SPI_I2SCTL_I2SSTD BITS(4, 5) /*!< I2S standard selection */
#define SPI_I2SCTL_PCMSMOD BIT(7) /*!< PCM frame synchronization mode */
#define SPI_I2SCTL_I2SOPMOD BITS(8, 9) /*!< I2S operation mode */
#define SPI_I2SCTL_I2SEN BIT(10) /*!< I2S enable */
#define SPI_I2SCTL_I2SSEL BIT(11) /*!< I2S mode selection */
/* SPI_I2SPSC */
#define SPI_I2SPSC_DIV BITS(0, 7) /*!< dividing factor for the prescaler */
#define SPI_I2SPSC_OF BIT(8) /*!< odd factor for the prescaler */
#define SPI_I2SPSC_MCKOEN BIT(9) /*!< I2S MCK output enable */
/* constants definitions */
/* SPI and I2S parameter struct definitions */
typedef struct
{
uint32_t device_mode; /*!< SPI master or slave */
uint32_t trans_mode; /*!< SPI transtype */
uint32_t frame_size; /*!< SPI frame size */
uint32_t nss; /*!< SPI NSS control by handware or software */
uint32_t endian; /*!< SPI big endian or little endian */
uint32_t clock_polarity_phase; /*!< SPI clock phase and polarity */
uint32_t prescale; /*!< SPI prescale factor */
} spi_parameter_struct;
/* SPI mode definitions */
#define SPI_MASTER (SPI_CTL0_MSTMOD | SPI_CTL0_SWNSS) /*!< SPI as master */
#define SPI_SLAVE ((uint32_t)0x00000000U) /*!< SPI as slave */
/* SPI bidirectional transfer direction */
#define SPI_BIDIRECTIONAL_TRANSMIT SPI_CTL0_BDOEN /*!< SPI work in transmit-only mode */
#define SPI_BIDIRECTIONAL_RECEIVE (~SPI_CTL0_BDOEN) /*!< SPI work in receive-only mode */
/* SPI transmit type */
#define SPI_TRANSMODE_FULLDUPLEX ((uint32_t)0x00000000U) /*!< SPI receive and send data at fullduplex communication */
#define SPI_TRANSMODE_RECEIVEONLY SPI_CTL0_RO /*!< SPI only receive data */
#define SPI_TRANSMODE_BDRECEIVE SPI_CTL0_BDEN /*!< bidirectional receive data */
#define SPI_TRANSMODE_BDTRANSMIT (SPI_CTL0_BDEN | SPI_CTL0_BDOEN) /*!< bidirectional transmit data*/
/* SPI frame size */
#define SPI_FRAMESIZE_16BIT SPI_CTL0_FF16 /*!< SPI frame size is 16 bits */
#define SPI_FRAMESIZE_8BIT ((uint32_t)0x00000000U) /*!< SPI frame size is 8 bits */
/* SPI NSS control mode */
#define SPI_NSS_SOFT SPI_CTL0_SWNSSEN /*!< SPI NSS control by software */
#define SPI_NSS_HARD ((uint32_t)0x00000000U) /*!< SPI NSS control by hardware */
/* SPI transmit way */
#define SPI_ENDIAN_MSB ((uint32_t)0x00000000U) /*!< SPI transmit way is big endian: transmit MSB first */
#define SPI_ENDIAN_LSB SPI_CTL0_LF /*!< SPI transmit way is little endian: transmit LSB first */
/* SPI clock phase and polarity */
#define SPI_CK_PL_LOW_PH_1EDGE ((uint32_t)0x00000000U) /*!< SPI clock polarity is low level and phase is first edge */
#define SPI_CK_PL_HIGH_PH_1EDGE SPI_CTL0_CKPL /*!< SPI clock polarity is high level and phase is first edge */
#define SPI_CK_PL_LOW_PH_2EDGE SPI_CTL0_CKPH /*!< SPI clock polarity is low level and phase is second edge */
#define SPI_CK_PL_HIGH_PH_2EDGE (SPI_CTL0_CKPL | SPI_CTL0_CKPH) /*!< SPI clock polarity is high level and phase is second edge */
/* SPI clock prescale factor */
#define CTL0_PSC(regval) (BITS(3, 5) & ((uint32_t)(regval) << 3))
#define SPI_PSC_2 CTL0_PSC(0) /*!< SPI clock prescale factor is 2 */
#define SPI_PSC_4 CTL0_PSC(1) /*!< SPI clock prescale factor is 4 */
#define SPI_PSC_8 CTL0_PSC(2) /*!< SPI clock prescale factor is 8 */
#define SPI_PSC_16 CTL0_PSC(3) /*!< SPI clock prescale factor is 16 */
#define SPI_PSC_32 CTL0_PSC(4) /*!< SPI clock prescale factor is 32 */
#define SPI_PSC_64 CTL0_PSC(5) /*!< SPI clock prescale factor is 64 */
#define SPI_PSC_128 CTL0_PSC(6) /*!< SPI clock prescale factor is 128 */
#define SPI_PSC_256 CTL0_PSC(7) /*!< SPI clock prescale factor is 256 */
/* I2S audio sample rate */
#define I2S_AUDIOSAMPLE_8K ((uint32_t)8000U) /*!< I2S audio sample rate is 8KHz */
#define I2S_AUDIOSAMPLE_11K ((uint32_t)11025U) /*!< I2S audio sample rate is 11KHz */
#define I2S_AUDIOSAMPLE_16K ((uint32_t)16000U) /*!< I2S audio sample rate is 16KHz */
#define I2S_AUDIOSAMPLE_22K ((uint32_t)22050U) /*!< I2S audio sample rate is 22KHz */
#define I2S_AUDIOSAMPLE_32K ((uint32_t)32000U) /*!< I2S audio sample rate is 32KHz */
#define I2S_AUDIOSAMPLE_44K ((uint32_t)44100U) /*!< I2S audio sample rate is 44KHz */
#define I2S_AUDIOSAMPLE_48K ((uint32_t)48000U) /*!< I2S audio sample rate is 48KHz */
#define I2S_AUDIOSAMPLE_96K ((uint32_t)96000U) /*!< I2S audio sample rate is 96KHz */
#define I2S_AUDIOSAMPLE_192K ((uint32_t)192000U) /*!< I2S audio sample rate is 192KHz */
/* I2S frame format */
#define I2SCTL_DTLEN(regval) (BITS(1, 2) & ((uint32_t)(regval) << 1))
#define I2S_FRAMEFORMAT_DT16B_CH16B I2SCTL_DTLEN(0) /*!< I2S data length is 16 bit and channel length is 16 bit */
#define I2S_FRAMEFORMAT_DT16B_CH32B (I2SCTL_DTLEN(0) | SPI_I2SCTL_CHLEN) /*!< I2S data length is 16 bit and channel length is 32 bit */
#define I2S_FRAMEFORMAT_DT24B_CH32B (I2SCTL_DTLEN(1) | SPI_I2SCTL_CHLEN) /*!< I2S data length is 24 bit and channel length is 32 bit */
#define I2S_FRAMEFORMAT_DT32B_CH32B (I2SCTL_DTLEN(2) | SPI_I2SCTL_CHLEN) /*!< I2S data length is 32 bit and channel length is 32 bit */
/* I2S master clock output */
#define I2S_MCKOUT_DISABLE ((uint32_t)0x00000000U) /*!< I2S master clock output disable */
#define I2S_MCKOUT_ENABLE SPI_I2SPSC_MCKOEN /*!< I2S master clock output enable */
/* I2S operation mode */
#define I2SCTL_I2SOPMOD(regval) (BITS(8, 9) & ((uint32_t)(regval) << 8))
#define I2S_MODE_SLAVETX I2SCTL_I2SOPMOD(0) /*!< I2S slave transmit mode */
#define I2S_MODE_SLAVERX I2SCTL_I2SOPMOD(1) /*!< I2S slave receive mode */
#define I2S_MODE_MASTERTX I2SCTL_I2SOPMOD(2) /*!< I2S master transmit mode */
#define I2S_MODE_MASTERRX I2SCTL_I2SOPMOD(3) /*!< I2S master receive mode */
/* I2S standard */
#define I2SCTL_I2SSTD(regval) (BITS(4, 5) & ((uint32_t)(regval) << 4))
#define I2S_STD_PHILLIPS I2SCTL_I2SSTD(0) /*!< I2S phillips standard */
#define I2S_STD_MSB I2SCTL_I2SSTD(1) /*!< I2S MSB standard */
#define I2S_STD_LSB I2SCTL_I2SSTD(2) /*!< I2S LSB standard */
#define I2S_STD_PCMSHORT I2SCTL_I2SSTD(3) /*!< I2S PCM short standard */
#define I2S_STD_PCMLONG (I2SCTL_I2SSTD(3) | SPI_I2SCTL_PCMSMOD) /*!< I2S PCM long standard */
/* I2S clock polarity */
#define I2S_CKPL_LOW ((uint32_t)0x00000000U) /*!< I2S clock polarity low level */
#define I2S_CKPL_HIGH SPI_I2SCTL_CKPL /*!< I2S clock polarity high level */
/* SPI DMA constants definitions */
#define SPI_DMA_TRANSMIT ((uint8_t)0x00U) /*!< SPI transmit data use DMA */
#define SPI_DMA_RECEIVE ((uint8_t)0x01U) /*!< SPI receive data use DMA */
/* SPI CRC constants definitions */
#define SPI_CRC_TX ((uint8_t)0x00U) /*!< SPI transmit CRC value */
#define SPI_CRC_RX ((uint8_t)0x01U) /*!< SPI receive CRC value */
/* SPI/I2S interrupt enable/disable constants definitions */
#define SPI_I2S_INT_TBE ((uint8_t)0x00U) /*!< transmit buffer empty interrupt */
#define SPI_I2S_INT_RBNE ((uint8_t)0x01U) /*!< receive buffer not empty interrupt */
#define SPI_I2S_INT_ERR ((uint8_t)0x02U) /*!< error interrupt */
/* SPI/I2S interrupt flag constants definitions */
#define SPI_I2S_INT_FLAG_TBE ((uint8_t)0x00U) /*!< transmit buffer empty interrupt flag */
#define SPI_I2S_INT_FLAG_RBNE ((uint8_t)0x01U) /*!< receive buffer not empty interrupt flag */
#define SPI_I2S_INT_FLAG_RXORERR ((uint8_t)0x02U) /*!< overrun interrupt flag */
#define SPI_INT_FLAG_CONFERR ((uint8_t)0x03U) /*!< config error interrupt flag */
#define SPI_INT_FLAG_CRCERR ((uint8_t)0x04U) /*!< CRC error interrupt flag */
#define I2S_INT_FLAG_TXURERR ((uint8_t)0x05U) /*!< underrun error interrupt flag */
#define SPI_I2S_INT_FLAG_FERR ((uint8_t)0x06U) /*!< format error interrupt flag */
/* SPI/I2S flag definitions */
#define SPI_FLAG_RBNE SPI_STAT_RBNE /*!< receive buffer not empty flag */
#define SPI_FLAG_TBE SPI_STAT_TBE /*!< transmit buffer empty flag */
#define SPI_FLAG_CRCERR SPI_STAT_CRCERR /*!< CRC error flag */
#define SPI_FLAG_CONFERR SPI_STAT_CONFERR /*!< mode config error flag */
#define SPI_FLAG_RXORERR SPI_STAT_RXORERR /*!< receive overrun error flag */
#define SPI_FLAG_TRANS SPI_STAT_TRANS /*!< transmit on-going flag */
#define SPI_FLAG_FERR SPI_STAT_FERR /*!< format error interrupt flag */
#define I2S_FLAG_RBNE SPI_STAT_RBNE /*!< receive buffer not empty flag */
#define I2S_FLAG_TBE SPI_STAT_TBE /*!< transmit buffer empty flag */
#define I2S_FLAG_CH SPI_STAT_I2SCH /*!< channel side flag */
#define I2S_FLAG_TXURERR SPI_STAT_TXURERR /*!< underrun error flag */
#define I2S_FLAG_RXORERR SPI_STAT_RXORERR /*!< overrun error flag */
#define I2S_FLAG_TRANS SPI_STAT_TRANS /*!< transmit on-going flag */
#define I2S_FLAG_FERR SPI_STAT_FERR /*!< format error interrupt flag */
/* function declarations */
/* SPI/I2S deinitialization and initialization functions */
/* reset SPI and I2S */
void spi_i2s_deinit(uint32_t spi_periph);
/* initialize the parameters of SPI struct with the default values */
void spi_struct_para_init(spi_parameter_struct *spi_struct);
/* initialize SPI parameter */
void spi_init(uint32_t spi_periph, spi_parameter_struct *spi_struct);
/* enable SPI */
void spi_enable(uint32_t spi_periph);
/* disable SPI */
void spi_disable(uint32_t spi_periph);
/* initialize I2S parameter */
void i2s_init(uint32_t spi_periph, uint32_t mode, uint32_t standard, uint32_t ckpl);
/* configure I2S prescaler */
void i2s_psc_config(uint32_t spi_periph, uint32_t audiosample, uint32_t frameformat, uint32_t mckout);
/* enable I2S */
void i2s_enable(uint32_t spi_periph);
/* disable I2S */
void i2s_disable(uint32_t spi_periph);
/* NSS functions */
/* enable SPI NSS output */
void spi_nss_output_enable(uint32_t spi_periph);
/* disable SPI NSS output */
void spi_nss_output_disable(uint32_t spi_periph);
/* SPI NSS pin high level in software mode */
void spi_nss_internal_high(uint32_t spi_periph);
/* SPI NSS pin low level in software mode */
void spi_nss_internal_low(uint32_t spi_periph);
/* DMA communication */
/* enable SPI DMA */
void spi_dma_enable(uint32_t spi_periph, uint8_t dma);
/* disable SPI DMA */
void spi_dma_disable(uint32_t spi_periph, uint8_t dma);
/* normal mode communication */
/* configure SPI/I2S data frame format */
void spi_i2s_data_frame_format_config(uint32_t spi_periph, uint16_t frame_format);
/* SPI transmit data */
void spi_i2s_data_transmit(uint32_t spi_periph, uint16_t data);
/* SPI receive data */
uint16_t spi_i2s_data_receive(uint32_t spi_periph);
/* configure SPI bidirectional transfer direction */
void spi_bidirectional_transfer_config(uint32_t spi_periph, uint32_t transfer_direction);
/* SPI CRC functions */
/* set SPI CRC polynomial */
void spi_crc_polynomial_set(uint32_t spi_periph, uint16_t crc_poly);
/* get SPI CRC polynomial */
uint16_t spi_crc_polynomial_get(uint32_t spi_periph);
/* turn on SPI CRC function */
void spi_crc_on(uint32_t spi_periph);
/* turn off SPI CRC function */
void spi_crc_off(uint32_t spi_periph);
/* SPI next data is CRC value */
void spi_crc_next(uint32_t spi_periph);
/* get SPI CRC send value or receive value */
uint16_t spi_crc_get(uint32_t spi_periph, uint8_t crc);
/* SPI TI mode functions */
/* enable SPI TI mode */
void spi_ti_mode_enable(uint32_t spi_periph);
/* disable SPI TI mode */
void spi_ti_mode_disable(uint32_t spi_periph);
/* SPI NSS pulse mode functions */
/* enable SPI NSS pulse mode */
void spi_nssp_mode_enable(uint32_t spi_periph);
/* disable SPI NSS pulse mode */
void spi_nssp_mode_disable(uint32_t spi_periph);
/* flag and interrupt functions */
/* enable SPI and I2S interrupt */
void spi_i2s_interrupt_enable(uint32_t spi_periph, uint8_t interrupt);
/* disable SPI and I2S interrupt */
void spi_i2s_interrupt_disable(uint32_t spi_periph, uint8_t interrupt);
/* get SPI and I2S interrupt status */
FlagStatus spi_i2s_interrupt_flag_get(uint32_t spi_periph, uint8_t interrupt);
/* get SPI and I2S flag status */
FlagStatus spi_i2s_flag_get(uint32_t spi_periph, uint32_t flag);
/* clear SPI CRC error flag status */
void spi_crc_error_clear(uint32_t spi_periph);
#endif /* GD32VF103_SPI_H */
#ifdef __cplusplus
}
#endif

View File

@@ -1,726 +0,0 @@
/*!
\file gd32vf103_timer.h
\brief definitions for the TIMER
\version 2019-06-05, V1.0.1, 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.
*/
#ifdef __cplusplus
extern "C" {
#endif
#ifndef GD32VF103_TIMER_H
#define GD32VF103_TIMER_H
#include "gd32vf103.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 */
#ifdef __cplusplus
}
#endif

View File

@@ -1,376 +0,0 @@
/*!
\file gd32vf103_usart.h
\brief definitions for the USART
\version 2019-06-05, V1.0.0, firmware for GD32VF103
\version 2019-09-18, V1.0.1, 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.
*/
#ifdef __cplusplus
extern "C" {
#endif
#ifndef GD32VF103_USART_H
#define GD32VF103_USART_H
#include "gd32vf103.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_CTS = USART_REGIDX_BIT(USART_STAT_REG_OFFSET, 9U), /*!< CTS change flag */
USART_FLAG_LBD = 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_IDLE = 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 interrupt);
/* disable USART interrupt */
void usart_interrupt_disable(uint32_t usart_periph, uint32_t interrupt);
/* 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 int_flag);
#endif /* GD32VF103_USART_H */
#ifdef __cplusplus
}
#endif

View File

@@ -1,20 +0,0 @@
//See LICENSE for license details.
#include <stdint.h>
#include <stdio.h>
#include <unistd.h>
#include "riscv_encoding.h"
#include "n200_func.h"
__attribute__((weak)) uintptr_t handle_nmi() {
_exit(1);
return 0;
}
__attribute__((weak)) uintptr_t handle_trap(uintptr_t mcause, uintptr_t sp) {
if ((mcause & 0xFFF) == 0xFFF) {
handle_nmi();
}
_exit(mcause);
return 0;
}

View File

@@ -1,15 +0,0 @@
#ifndef HANDLERS_H_
#define HANDLERS_H_
#include <stdint.h>
#ifdef __cplusplus
extern "C" {
#endif
uintptr_t handle_trap(uintptr_t mcause, uintptr_t sp);
unsigned long ulSynchTrap(unsigned long mcause, unsigned long sp, unsigned long arg1);
#ifdef __cplusplus
}
#endif
#endif

View File

@@ -1,36 +0,0 @@
//See LICENSE for license details.
#include <gd32vf103.h>
#include <stdint.h>
#include <stdio.h>
#include <unistd.h>
#include "riscv_encoding.h"
#include "n200_func.h"
extern uint32_t disable_mcycle_minstret();
void _init()
{
SystemInit();
//ECLIC init
eclic_init(ECLIC_NUM_INTERRUPTS);
eclic_mode_enable();
//printf("After ECLIC mode enabled, the mtvec value is %x \n\n\r", read_csr(mtvec));
// // It must be NOTED:
// // * In the RISC-V arch, if user mode and PMP supported, then by default if PMP is not configured
// // with valid entries, then user mode cannot access any memory, and cannot execute any instructions.
// // * So if switch to user-mode and still want to continue, then you must configure PMP first
//pmp_open_all_space();
//switch_m2u_mode();
/* Before enter into main, add the cycle/instret disable by default to save power,
only use them when needed to measure the cycle/instret */
disable_mcycle_minstret();
}
void _fini()
{
}

View File

@@ -1,50 +0,0 @@
/*-------------------------------------------*/
/* Integer type definitions for FatFs module */
/*-------------------------------------------*/
#ifdef __cplusplus
extern "C" {
#endif
#ifndef _INTEGER
#if 0
#include <windows.h>
#else
#include "usb_conf.h"
/* These types must be 16-bit, 32-bit or larger integer */
typedef int INT;
typedef unsigned int UINT;
/* These types must be 8-bit integer */
typedef signed char CHAR;
typedef unsigned char UCHAR;
typedef unsigned char BYTE;
/* These types must be 16-bit integer */
typedef short SHORT;
typedef unsigned short USHORT;
typedef unsigned short WORD;
typedef unsigned short WCHAR;
/* These types must be 32-bit integer */
typedef long LONG;
typedef unsigned long ULONG;
typedef unsigned long DWORD;
/* Boolean type */
// typedef enum { FALSE = 0, TRUE } BOOL;
#include <stdbool.h>
//typedef bool BOOL;
#ifndef FALSE
#define FALSE false
#define TRUE true
#endif
#endif
#define _INTEGER
#endif
#ifdef __cplusplus
}
#endif

View File

@@ -1,205 +0,0 @@
/*!
\file rtc.c
\brief RTC check and config,time_show and time_adjust function
\version 2019-06-05, 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 "rtc.h"
/* enter the second interruption,set the second interrupt flag to 1 */
__IO uint32_t timedisplay;
/*!
\brief configure the RTC
\param[in] none
\param[out] none
\retval none
*/
void rtc_configuration(void)
{
/* enable PMU and BKPI clocks */
rcu_periph_clock_enable(RCU_BKPI);
rcu_periph_clock_enable(RCU_PMU);
/* allow access to BKP domain */
pmu_backup_write_enable();
/* reset backup domain */
bkp_deinit();
/* enable LXTAL */
rcu_osci_on(RCU_LXTAL);
/* wait till LXTAL is ready */
rcu_osci_stab_wait(RCU_LXTAL);
/* select RCU_LXTAL as RTC clock source */
rcu_rtc_clock_config(RCU_RTCSRC_LXTAL);
/* enable RTC Clock */
rcu_periph_clock_enable(RCU_RTC);
/* wait for RTC registers synchronization */
rtc_register_sync_wait();
/* wait until last write operation on RTC registers has finished */
rtc_lwoff_wait();
/* enable the RTC second interrupt*/
rtc_interrupt_enable(RTC_INT_SECOND);
/* wait until last write operation on RTC registers has finished */
rtc_lwoff_wait();
/* set RTC prescaler: set RTC period to 1s */
rtc_prescaler_set(32767);
/* wait until last write operation on RTC registers has finished */
rtc_lwoff_wait();
}
/*!
\brief return the time entered by user, using Hyperterminal
\param[in] none
\param[out] none
\retval current time of RTC counter value
*/
uint32_t time_regulate(void)
{
uint32_t tmp_hh = 0xFF, tmp_mm = 0xFF, tmp_ss = 0xFF;
printf("\r\n==============Time Settings=====================================");
printf("\r\n Please Set Hours");
while (tmp_hh == 0xFF){
tmp_hh = usart_scanf(23);
}
printf(": %d", tmp_hh);
printf("\r\n Please Set Minutes");
while (tmp_mm == 0xFF){
tmp_mm = usart_scanf(59);
}
printf(": %d", tmp_mm);
printf("\r\n Please Set Seconds");
while (tmp_ss == 0xFF){
tmp_ss = usart_scanf(59);
}
printf(": %d", tmp_ss);
/* return the value store in RTC counter register */
return((tmp_hh*3600 + tmp_mm*60 + tmp_ss));
}
/*!
\brief adjust time
\param[in] none
\param[out] none
\retval none
*/
void time_adjust(void)
{
/* wait until last write operation on RTC registers has finished */
rtc_lwoff_wait();
/* change the current time */
rtc_counter_set(time_regulate());
/* wait until last write operation on RTC registers has finished */
rtc_lwoff_wait();
}
/*!
\brief display the current time
\param[in] timeVar: RTC counter value
\param[out] none
\retval none
*/
void time_display(uint32_t timevar)
{
uint32_t thh = 0, tmm = 0, tss = 0;
/* compute hours */
thh = timevar / 3600;
/* compute minutes */
tmm = (timevar % 3600) / 60;
/* compute seconds */
tss = (timevar % 3600) % 60;
printf(" Time: %0.2d:%0.2d:%0.2d\r\n", thh, tmm, tss);
}
/*!
\brief show the current time (HH:MM:SS) on the Hyperterminal
\param[in] none
\param[out] none
\retval none
*/
void time_show(void)
{
printf("\n\r");
/* infinite loop */
while (1){
/* if 1s has paased */
if (timedisplay == 1){
/* display current time */
time_display(rtc_counter_get());
timedisplay = 0;
}
}
}
/*!
\brief get numeric values from the hyperterminal
\param[in] value: input value from the hyperterminal
\param[out] none
\retval input value in BCD mode
*/
uint8_t usart_scanf(uint32_t value)
{
uint32_t index = 0;
uint32_t tmp[2] = {0, 0};
while (index < 2){
/* loop until RBNE = 1 */
while (usart_flag_get(USART0, USART_FLAG_RBNE) == RESET);
tmp[index++] = (usart_data_receive(USART0));
if ((tmp[index - 1] < 0x30) || (tmp[index - 1] > 0x39)){
printf("\n\rPlease enter valid number between 0 and 9\n");
index--;
}
}
/* calculate the Corresponding value */
index = (tmp[1] - 0x30) + ((tmp[0] - 0x30) * 10);
/* check */
if (index > value){
printf("\n\rPlease enter valid number between 0 and %d\n", value);
return 0xFF;
}
return index;
}

View File

@@ -1,21 +0,0 @@
#ifdef __cplusplus
extern "C" {
#endif
/* See LICENSE of license details. */
#ifndef _NUCLEI_SYS_STUB_H
#define _NUCLEI_SYS_STUB_H
#include <stdint.h>
#include <unistd.h>
void write_hex(int fd, unsigned long int hex);
static inline int _stub(int err) {
return -1;
}
#endif /* _NUCLEI_SYS_STUB_H */
#ifdef __cplusplus
}
#endif

View File

@@ -1,999 +0,0 @@
/*!
\file system_gd32vf103.c
\brief RISC-V Device Peripheral Access Layer Source File for
GD32VF103 Device Series
\version 2019-06-05, 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.
*/
/* This file refers the RISC-V standard, some adjustments are made according to
* GigaDevice chips */
#include "gd32vf103.h"
/* 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 */
/* select a system clock by uncommenting the following line */
/* use IRC8M */
//#define __SYSTEM_CLOCK_48M_PLL_IRC8M (uint32_t)(48000000)
//#define __SYSTEM_CLOCK_72M_PLL_IRC8M (uint32_t)(72000000)
#define __SYSTEM_CLOCK_108M_PLL_IRC8M (uint32_t)(108000000)
/********************************************************************/
//#define __SYSTEM_CLOCK_HXTAL (HXTAL_VALUE)
//#define __SYSTEM_CLOCK_24M_PLL_HXTAL (uint32_t)(24000000)
/********************************************************************/
//#define __SYSTEM_CLOCK_36M_PLL_HXTAL (uint32_t)(36000000)
//#define __SYSTEM_CLOCK_48M_PLL_HXTAL (uint32_t)(48000000)
//#define __SYSTEM_CLOCK_56M_PLL_HXTAL (uint32_t)(56000000)
//#define __SYSTEM_CLOCK_72M_PLL_HXTAL (uint32_t)(72000000)
//#define __SYSTEM_CLOCK_96M_PLL_HXTAL (uint32_t)(96000000)
// #define __SYSTEM_CLOCK_108M_PLL_HXTAL (uint32_t)(108000000)
#define SEL_IRC8M 0x00U
#define SEL_HXTAL 0x01U
#define SEL_PLL 0x02U
/* set the system clock frequency and declare the system clock configuration
* function */
#ifdef __SYSTEM_CLOCK_48M_PLL_IRC8M
uint32_t SystemCoreClock = __SYSTEM_CLOCK_48M_PLL_IRC8M;
static void system_clock_48m_irc8m(void);
#elif defined(__SYSTEM_CLOCK_72M_PLL_IRC8M)
uint32_t SystemCoreClock = __SYSTEM_CLOCK_72M_PLL_IRC8M;
static void system_clock_72m_irc8m(void);
#elif defined(__SYSTEM_CLOCK_108M_PLL_IRC8M)
uint32_t SystemCoreClock = __SYSTEM_CLOCK_108M_PLL_IRC8M;
static void system_clock_108m_irc8m(void);
#elif defined(__SYSTEM_CLOCK_HXTAL)
uint32_t SystemCoreClock = __SYSTEM_CLOCK_HXTAL;
static void system_clock_hxtal(void);
#elif defined(__SYSTEM_CLOCK_24M_PLL_HXTAL)
uint32_t SystemCoreClock = __SYSTEM_CLOCK_24M_PLL_HXTAL;
static void system_clock_24m_hxtal(void);
#elif defined(__SYSTEM_CLOCK_36M_PLL_HXTAL)
uint32_t SystemCoreClock = __SYSTEM_CLOCK_36M_PLL_HXTAL;
static void system_clock_36m_hxtal(void);
#elif defined(__SYSTEM_CLOCK_48M_PLL_HXTAL)
uint32_t SystemCoreClock = __SYSTEM_CLOCK_48M_PLL_HXTAL;
static void system_clock_48m_hxtal(void);
#elif defined(__SYSTEM_CLOCK_56M_PLL_HXTAL)
uint32_t SystemCoreClock = __SYSTEM_CLOCK_56M_PLL_HXTAL;
static void system_clock_56m_hxtal(void);
#elif defined(__SYSTEM_CLOCK_72M_PLL_HXTAL)
uint32_t SystemCoreClock = __SYSTEM_CLOCK_72M_PLL_HXTAL;
static void system_clock_72m_hxtal(void);
#elif defined(__SYSTEM_CLOCK_96M_PLL_HXTAL)
uint32_t SystemCoreClock = __SYSTEM_CLOCK_96M_PLL_HXTAL;
static void system_clock_96m_hxtal(void);
#elif defined(__SYSTEM_CLOCK_108M_PLL_HXTAL)
uint32_t SystemCoreClock = __SYSTEM_CLOCK_108M_PLL_HXTAL;
static void system_clock_108m_hxtal(void);
#else
uint32_t SystemCoreClock = IRC8M_VALUE;
#endif /* __SYSTEM_CLOCK_48M_PLL_IRC8M */
/* configure the system clock */
static void system_clock_config(void);
/*!
\brief configure the system clock
\param[in] none
\param[out] none
\retval none
*/
static void system_clock_config(void) {
#ifdef __SYSTEM_CLOCK_HXTAL
system_clock_hxtal();
#elif defined(__SYSTEM_CLOCK_24M_PLL_HXTAL)
system_clock_24m_hxtal();
#elif defined(__SYSTEM_CLOCK_36M_PLL_HXTAL)
system_clock_36m_hxtal();
#elif defined(__SYSTEM_CLOCK_48M_PLL_HXTAL)
system_clock_48m_hxtal();
#elif defined(__SYSTEM_CLOCK_56M_PLL_HXTAL)
system_clock_56m_hxtal();
#elif defined(__SYSTEM_CLOCK_72M_PLL_HXTAL)
system_clock_72m_hxtal();
#elif defined(__SYSTEM_CLOCK_96M_PLL_HXTAL)
system_clock_96m_hxtal();
#elif defined(__SYSTEM_CLOCK_108M_PLL_HXTAL)
system_clock_108m_hxtal();
#elif defined(__SYSTEM_CLOCK_48M_PLL_IRC8M)
system_clock_48m_irc8m();
#elif defined(__SYSTEM_CLOCK_72M_PLL_IRC8M)
system_clock_72m_irc8m();
#elif defined(__SYSTEM_CLOCK_108M_PLL_IRC8M)
system_clock_108m_irc8m();
#endif /* __SYSTEM_CLOCK_HXTAL */
}
/*!
\brief setup the microcontroller system, initialize the system
\param[in] none
\param[out] none
\retval none
*/
void SystemInit(void) {
/* 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();
}
/*!
\brief update the SystemCoreClock with current core clock retrieved
from cpu registers \param[in] none \param[out] none \retval none
*/
void SystemCoreClockUpdate(void) {
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;
}
}
#ifdef __SYSTEM_CLOCK_HXTAL
/*!
\brief configure the system clock to HXTAL
\param[in] none
\param[out] none
\retval none
*/
static void system_clock_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) {
}
}
/* 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;
/* select HXTAL as system clock */
RCU_CFG0 &= ~RCU_CFG0_SCS;
RCU_CFG0 |= RCU_CKSYSSRC_HXTAL;
/* wait until HXTAL is selected as system clock */
while (0 == (RCU_CFG0 & RCU_SCSS_HXTAL)) {
}
}
#elif defined(__SYSTEM_CLOCK_24M_PLL_HXTAL)
/*!
\brief configure the system clock to 24M 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_24m_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) * 6 = 24 MHz */
RCU_CFG0 &= ~(RCU_CFG0_PLLMF | RCU_CFG0_PLLMF_4);
RCU_CFG0 |= (RCU_PLLSRC_HXTAL | RCU_PLL_MUL6);
if (HXTAL_VALUE == 25000000) {
/* CK_PREDIV0 = (CK_HXTAL)/5 *8 /10 = 4 MHz */
RCU_CFG1 &= ~(RCU_CFG1_PREDV0SEL | RCU_CFG1_PLL1MF | RCU_CFG1_PREDV1 |
RCU_CFG1_PREDV0);
RCU_CFG1 |= (RCU_PREDV0SRC_CKPLL1 | RCU_PLL1_MUL8 | RCU_PREDV1_DIV5 |
RCU_PREDV0_DIV10);
/* enable PLL1 */
RCU_CTL |= RCU_CTL_PLL1EN;
/* wait till PLL1 is ready */
while ((RCU_CTL & RCU_CTL_PLL1STB) == 0) {
}
} 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);
}
/* 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)) {
}
}
#elif defined(__SYSTEM_CLOCK_36M_PLL_HXTAL)
/*!
\brief configure the system clock to 36M 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_36m_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) * 9 = 36 MHz */
RCU_CFG0 &= ~(RCU_CFG0_PLLMF | RCU_CFG0_PLLMF_4);
RCU_CFG0 |= (RCU_PLLSRC_HXTAL | RCU_PLL_MUL9);
if (HXTAL_VALUE == 25000000) {
/* CK_PREDIV0 = (CK_HXTAL)/5 *8 /10 = 4 MHz */
RCU_CFG1 &= ~(RCU_CFG1_PREDV0SEL | RCU_CFG1_PLL1MF | RCU_CFG1_PREDV1 |
RCU_CFG1_PREDV0);
RCU_CFG1 |= (RCU_PREDV0SRC_CKPLL1 | RCU_PLL1_MUL8 | RCU_PREDV1_DIV5 |
RCU_PREDV0_DIV10);
/* enable PLL1 */
RCU_CTL |= RCU_CTL_PLL1EN;
/* wait till PLL1 is ready */
while ((RCU_CTL & RCU_CTL_PLL1STB) == 0) {
}
} 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);
}
/* 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)) {
}
}
#elif defined(__SYSTEM_CLOCK_48M_PLL_HXTAL)
/*!
\brief configure the system clock to 48M 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_48m_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) * 12 = 48 MHz */
RCU_CFG0 &= ~(RCU_CFG0_PLLMF | RCU_CFG0_PLLMF_4);
RCU_CFG0 |= (RCU_PLLSRC_HXTAL | RCU_PLL_MUL12);
if (HXTAL_VALUE == 25000000) {
/* CK_PREDIV0 = (CK_HXTAL)/5 *8 /10 = 4 MHz */
RCU_CFG1 &= ~(RCU_CFG1_PREDV0SEL | RCU_CFG1_PLL1MF | RCU_CFG1_PREDV1 |
RCU_CFG1_PREDV0);
RCU_CFG1 |= (RCU_PREDV0SRC_CKPLL1 | RCU_PLL1_MUL8 | RCU_PREDV1_DIV5 |
RCU_PREDV0_DIV10);
/* enable PLL1 */
RCU_CTL |= RCU_CTL_PLL1EN;
/* wait till PLL1 is ready */
while ((RCU_CTL & RCU_CTL_PLL1STB) == 0) {
}
} 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);
}
/* 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)) {
}
}
#elif defined(__SYSTEM_CLOCK_56M_PLL_HXTAL)
/*!
\brief configure the system clock to 56M 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_56m_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) * 14 = 56 MHz */
RCU_CFG0 &= ~(RCU_CFG0_PLLMF | RCU_CFG0_PLLMF_4);
RCU_CFG0 |= (RCU_PLLSRC_HXTAL | RCU_PLL_MUL14);
if (HXTAL_VALUE == 25000000) {
/* CK_PREDIV0 = (CK_HXTAL)/5 *8 /10 = 4 MHz */
RCU_CFG1 &= ~(RCU_CFG1_PREDV0SEL | RCU_CFG1_PLL1MF | RCU_CFG1_PREDV1 |
RCU_CFG1_PREDV0);
RCU_CFG1 |= (RCU_PREDV0SRC_CKPLL1 | RCU_PLL1_MUL8 | RCU_PREDV1_DIV5 |
RCU_PREDV0_DIV10);
/* enable PLL1 */
RCU_CTL |= RCU_CTL_PLL1EN;
/* wait till PLL1 is ready */
while ((RCU_CTL & RCU_CTL_PLL1STB) == 0) {
}
} 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);
}
/* 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)) {
}
}
#elif defined(__SYSTEM_CLOCK_72M_PLL_HXTAL)
/*!
\brief configure the system clock to 72M 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_72m_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) * 18 = 72 MHz */
RCU_CFG0 &= ~(RCU_CFG0_PLLMF | RCU_CFG0_PLLMF_4);
RCU_CFG0 |= (RCU_PLLSRC_HXTAL | RCU_PLL_MUL18);
if (HXTAL_VALUE == 25000000) {
/* CK_PREDIV0 = (CK_HXTAL)/5 *8 /10 = 4 MHz */
RCU_CFG1 &= ~(RCU_CFG1_PREDV0SEL | RCU_CFG1_PLL1MF | RCU_CFG1_PREDV1 |
RCU_CFG1_PREDV0);
RCU_CFG1 |= (RCU_PREDV0SRC_CKPLL1 | RCU_PLL1_MUL8 | RCU_PREDV1_DIV5 |
RCU_PREDV0_DIV10);
/* enable PLL1 */
RCU_CTL |= RCU_CTL_PLL1EN;
/* wait till PLL1 is ready */
while ((RCU_CTL & RCU_CTL_PLL1STB) == 0) {
}
} 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);
}
/* 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)) {
}
}
#elif defined(__SYSTEM_CLOCK_96M_PLL_HXTAL)
/*!
\brief configure the system clock to 96M 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_96m_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;
if (HXTAL_VALUE == 25000000) {
/* CK_PLL = (CK_PREDIV0) * 24 = 96 MHz */
RCU_CFG0 &= ~(RCU_CFG0_PLLMF | RCU_CFG0_PLLMF_4);
RCU_CFG0 |= (RCU_PLLSRC_HXTAL | RCU_PLL_MUL24);
/* CK_PREDIV0 = (CK_HXTAL)/5 *8 /10 = 4 MHz */
RCU_CFG1 &= ~(RCU_CFG1_PREDV0SEL | RCU_CFG1_PLL1MF | RCU_CFG1_PREDV1 |
RCU_CFG1_PREDV0);
RCU_CFG1 |= (RCU_PREDV0SRC_CKPLL1 | RCU_PLL1_MUL8 | RCU_PREDV1_DIV5 |
RCU_PREDV0_DIV10);
/* enable PLL1 */
RCU_CTL |= RCU_CTL_PLL1EN;
/* wait till PLL1 is ready */
while ((RCU_CTL & RCU_CTL_PLL1STB) == 0) {
}
} else if (HXTAL_VALUE == 8000000) {
/* CK_PLL = (CK_PREDIV0) * 24 = 96 MHz */
RCU_CFG0 &= ~(RCU_CFG0_PLLMF | RCU_CFG0_PLLMF_4);
RCU_CFG0 |= (RCU_PLLSRC_HXTAL | RCU_PLL_MUL24);
RCU_CFG1 &= ~(RCU_CFG1_PREDV0SEL | RCU_CFG1_PREDV1 | RCU_CFG1_PLL1MF |
RCU_CFG1_PREDV0);
RCU_CFG1 |= (RCU_PREDV0SRC_HXTAL | RCU_PREDV0_DIV2);
}
/* 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)) {
}
}
#elif defined(__SYSTEM_CLOCK_108M_PLL_HXTAL)
/*!
\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)) {
}
}
#elif defined(__SYSTEM_CLOCK_48M_PLL_IRC8M)
/*!
\brief configure the system clock to 48M by PLL which selects IRC8M as
its clock source \param[in] none \param[out] none \retval none
*/
static void system_clock_48m_irc8m(void) {
uint32_t timeout = 0U;
uint32_t stab_flag = 0U;
/* enable IRC8M */
RCU_CTL |= RCU_CTL_IRC8MEN;
/* wait until IRC8M is stable or the startup time is longer than
* IRC8M_STARTUP_TIMEOUT */
do {
timeout++;
stab_flag = (RCU_CTL & RCU_CTL_IRC8MSTB);
} while ((0U == stab_flag) && (IRC8M_STARTUP_TIMEOUT != timeout));
/* if fail */
if (0U == (RCU_CTL & RCU_CTL_IRC8MSTB)) {
while (1) {
}
}
/* IRC8M 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_IRC8M/2) * 12 = 48 MHz */
RCU_CFG0 &= ~(RCU_CFG0_PLLMF | RCU_CFG0_PLLMF_4);
RCU_CFG0 |= RCU_PLL_MUL12;
/* 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)) {
}
}
#elif defined(__SYSTEM_CLOCK_72M_PLL_IRC8M)
/*!
\brief configure the system clock to 72M by PLL which selects IRC8M as
its clock source \param[in] none \param[out] none \retval none
*/
static void system_clock_72m_irc8m(void) {
uint32_t timeout = 0U;
uint32_t stab_flag = 0U;
/* enable IRC8M */
RCU_CTL |= RCU_CTL_IRC8MEN;
/* wait until IRC8M is stable or the startup time is longer than
* IRC8M_STARTUP_TIMEOUT */
do {
timeout++;
stab_flag = (RCU_CTL & RCU_CTL_IRC8MSTB);
} while ((0U == stab_flag) && (IRC8M_STARTUP_TIMEOUT != timeout));
/* if fail */
if (0U == (RCU_CTL & RCU_CTL_IRC8MSTB)) {
while (1) {
}
}
/* IRC8M 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_IRC8M/2) * 18 = 72 MHz */
RCU_CFG0 &= ~(RCU_CFG0_PLLMF | RCU_CFG0_PLLMF_4);
RCU_CFG0 |= RCU_PLL_MUL18;
/* 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)) {
}
}
#elif defined(__SYSTEM_CLOCK_108M_PLL_IRC8M)
/*!
\brief configure the system clock to 108M by PLL which selects IRC8M as
its clock source \param[in] none \param[out] none \retval none
*/
static void system_clock_108m_irc8m(void) {
uint32_t timeout = 0U;
uint32_t stab_flag = 0U;
/* enable IRC8M */
RCU_CTL |= RCU_CTL_IRC8MEN;
/* wait until IRC8M is stable or the startup time is longer than
* IRC8M_STARTUP_TIMEOUT */
do {
timeout++;
stab_flag = (RCU_CTL & RCU_CTL_IRC8MSTB);
} while ((0U == stab_flag) && (IRC8M_STARTUP_TIMEOUT != timeout));
/* if fail */
if (0U == (RCU_CTL & RCU_CTL_IRC8MSTB)) {
while (1) {
}
}
/* IRC8M 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_IRC8M/2) * 27 = 108 MHz */
RCU_CFG0 &= ~(RCU_CFG0_PLLMF | RCU_CFG0_PLLMF_4);
RCU_CFG0 |= RCU_PLL_MUL27;
/* 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)) {
}
}
#endif

View File

@@ -1,18 +0,0 @@
/* See LICENSE of license details. */
#include <stdint.h>
#include <unistd.h>
void write_hex(int fd, unsigned long int hex)
{
uint8_t ii;
uint8_t jj;
char towrite;
write(fd , "0x", 2);
for (ii = sizeof(unsigned long int) * 2 ; ii > 0; ii--) {
jj = ii - 1;
uint8_t digit = ((hex & (0xF << (jj*4))) >> (jj*4));
towrite = digit < 0xA ? ('0' + digit) : ('A' + (digit - 0xA));
write(fd, &towrite, 1);
}
}

View File

@@ -1,4 +0,0 @@
int __wrap_printf(const char *fmt, ...) {
//:D
}

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.
*/
#ifndef __CORE_COMPATIABLE_H__
#define __CORE_COMPATIABLE_H__
/*!
* @file core_compatiable.h
* @brief ARM compatiable function definitions header file
*/
#ifdef __cplusplus
extern "C" {
#endif
/* ===== ARM Compatiable Functions ===== */
/**
* \defgroup NMSIS_Core_ARMCompatiable_Functions ARM Compatiable Functions
* \ingroup NMSIS_Core
* \brief A few functions that compatiable with ARM CMSIS-Core.
* \details
*
* Here we provided a few functions that compatiable with ARM CMSIS-Core,
* mostly used in the DSP and NN library.
* @{
*/
/** \brief Instruction Synchronization Barrier, compatiable with ARM */
#define __ISB() __RWMB()
/** \brief Data Synchronization Barrier, compatiable with ARM */
#define __DSB() __RWMB()
/** \brief Data Memory Barrier, compatiable with ARM */
#define __DMB() __RWMB()
/** \brief LDRT Unprivileged (8 bit), ARM Compatiable */
#define __LDRBT(ptr) __LB((ptr))
/** \brief LDRT Unprivileged (16 bit), ARM Compatiable */
#define __LDRHT(ptr) __LH((ptr))
/** \brief LDRT Unprivileged (32 bit), ARM Compatiable */
#define __LDRT(ptr) __LW((ptr))
/** \brief STRT Unprivileged (8 bit), ARM Compatiable */
#define __STRBT(ptr) __SB((ptr))
/** \brief STRT Unprivileged (16 bit), ARM Compatiable */
#define __STRHT(ptr) __SH((ptr))
/** \brief STRT Unprivileged (32 bit), ARM Compatiable */
#define __STRT(ptr) __SW((ptr))
/* ===== Saturation Operations ===== */
/**
* \brief Signed Saturate
* \details Saturates a signed value.
* \param [in] value Value to be saturated
* \param [in] sat Bit position to saturate to (1..32)
* \return Saturated value
*/
#if defined(__DSP_PRESENT) && (__DSP_PRESENT == 1)
#define __SSAT(val, sat) __RV_SCLIP32((val), (sat-1))
#else
__STATIC_FORCEINLINE int32_t __SSAT(int32_t val, uint32_t sat)
{
if ((sat >= 1U) && (sat <= 32U)) {
const int32_t max = (int32_t)((1U << (sat - 1U)) - 1U);
const int32_t min = -1 - max ;
if (val > max) {
return max;
} else if (val < min) {
return min;
}
}
return val;
}
#endif
/**
* \brief Unsigned Saturate
* \details Saturates an unsigned value.
* \param [in] value Value to be saturated
* \param [in] sat Bit position to saturate to (0..31)
* \return Saturated value
*/
#if defined(__DSP_PRESENT) && (__DSP_PRESENT == 1)
#define __USAT(val, sat) __RV_UCLIP32((val), (sat-1))
#else
__STATIC_FORCEINLINE uint32_t __USAT(int32_t val, uint32_t sat)
{
if (sat <= 31U) {
const uint32_t max = ((1U << sat) - 1U);
if (val > (int32_t)max) {
return max;
} else if (val < 0) {
return 0U;
}
}
return (uint32_t)val;
}
#endif
/* ===== Data Processing Operations ===== */
/**
* \brief Reverse byte order (32 bit)
* \details Reverses the byte order in unsigned integer value.
* For example, 0x12345678 becomes 0x78563412.
* \param [in] value Value to reverse
* \return Reversed value
*/
__STATIC_FORCEINLINE uint32_t __REV(uint32_t value)
{
uint32_t result;
result = ((value & 0xff000000) >> 24)
| ((value & 0x00ff0000) >> 8 )
| ((value & 0x0000ff00) << 8 )
| ((value & 0x000000ff) << 24);
return result;
}
/**
* \brief Reverse byte order (16 bit)
* \details Reverses the byte order within each halfword of a word.
* For example, 0x12345678 becomes 0x34127856.
* \param [in] value Value to reverse
* \return Reversed value
*/
__STATIC_FORCEINLINE uint32_t __REV16(uint32_t value)
{
uint32_t result;
result = ((value & 0xff000000) >> 8)
| ((value & 0x00ff00000) << 8 )
| ((value & 0x0000ff00) >> 8 )
| ((value & 0x000000ff) << 8) ;
return result;
}
/**
* \brief Reverse byte order (16 bit)
* \details Reverses the byte order in a 16-bit value
* and returns the signed 16-bit result.
* For example, 0x0080 becomes 0x8000.
* \param [in] value Value to reverse
* \return Reversed value
*/
__STATIC_FORCEINLINE int16_t __REVSH(int16_t value)
{
int16_t result;
result = ((value & 0xff00) >> 8) | ((value & 0x00ff) << 8);
return result;
}
/**
* \brief Rotate Right in unsigned value (32 bit)
* \details Rotate Right (immediate) provides the value of
* the contents of a register rotated by a variable number of bits.
* \param [in] op1 Value to rotate
* \param [in] op2 Number of Bits to rotate(0-31)
* \return Rotated value
*/
__STATIC_FORCEINLINE uint32_t __ROR(uint32_t op1, uint32_t op2)
{
op2 = op2 & 0x1F;
if (op2 == 0U) {
return op1;
}
return (op1 >> op2) | (op1 << (32U - op2));
}
/**
* \brief Reverse bit order of value
* \details Reverses the bit order of the given value.
* \param [in] value Value to reverse
* \return Reversed value
*/
#if defined(__DSP_PRESENT) && (__DSP_PRESENT == 1)
#define __RBIT(value) __RV_BITREVI((value), 31)
#else
__STATIC_FORCEINLINE uint32_t __RBIT(uint32_t value)
{
uint32_t result;
uint32_t s = (4U /*sizeof(v)*/ * 8U) - 1U; /* extra shift needed at end */
result = value; /* r will be reversed bits of v; first get LSB of v */
for (value >>= 1U; value != 0U; value >>= 1U) {
result <<= 1U;
result |= value & 1U;
s--;
}
result <<= s; /* shift when v's highest bits are zero */
return result;
}
#endif /* defined(__DSP_PRESENT) && (__DSP_PRESENT == 1) */
/**
* \brief Count leading zeros
* \details Counts the number of leading zeros of a data value.
* \param [in] data Value to count the leading zeros
* \return number of leading zeros in value
*/
#if defined(__DSP_PRESENT) && (__DSP_PRESENT == 1)
#define __CLZ(data) __RV_CLZ32(data)
#else
__STATIC_FORCEINLINE uint8_t __CLZ(uint32_t data)
{
uint8_t ret = 0;
uint32_t temp = ~data;
while (temp & 0x80000000) {
temp <<= 1;
ret++;
}
return ret;
}
#endif /* defined(__DSP_PRESENT) && (__DSP_PRESENT == 1) */
/** @} */ /* End of Doxygen Group NMSIS_Core_ARMCompatiable_Functions */
#ifdef __cplusplus
}
#endif
#endif /* __CORE_COMPATIABLE_H__ */

File diff suppressed because it is too large Load Diff

View File

@@ -0,0 +1,124 @@
/*
* 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_CACHE_H__
#define __CORE_FEATURE_CACHE_H__
/*!
* @file core_feature_cache.h
* @brief Cache feature API header file for Nuclei N/NX Core
*/
/*
* Cache Feature Configuration Macro:
* 1. __ICACHE_PRESENT: Define whether I-Cache Unit is present or not.
* * 0: Not present
* * 1: Present
* 1. __DCACHE_PRESENT: Define whether D-Cache Unit is present or not.
* * 0: Not present
* * 1: Present
*/
#ifdef __cplusplus
extern "C" {
#endif
#if defined(__ICACHE_PRESENT) && (__ICACHE_PRESENT == 1)
/* ########################## Cache functions #################################### */
/**
* \defgroup NMSIS_Core_Cache Cache Functions
* \brief Functions that configure Instruction and Data Cache.
* @{
*/
/** @} */ /* End of Doxygen Group NMSIS_Core_Cache */
/**
* \defgroup NMSIS_Core_ICache I-Cache Functions
* \ingroup NMSIS_Core_Cache
* \brief Functions that configure Instruction Cache.
* @{
*/
/**
* \brief Enable ICache
* \details
* This function enable I-Cache
* \remarks
* - This \ref CSR_MCACHE_CTL register control I Cache enable.
* \sa
* - \ref DisableICache
*/
__STATIC_FORCEINLINE void EnableICache (void)
{
__RV_CSR_SET(CSR_MCACHE_CTL, CSR_MCACHE_CTL_IE);
}
/**
* \brief Disable ICache
* \details
* This function Disable I-Cache
* \remarks
* - This \ref CSR_MCACHE_CTL register control I Cache enable.
* \sa
* - \ref EnableICache
*/
__STATIC_FORCEINLINE void DisableICache (void)
{
__RV_CSR_CLEAR(CSR_MCACHE_CTL, CSR_MCACHE_CTL_IE);
}
/** @} */ /* End of Doxygen Group NMSIS_Core_ICache */
#endif /* defined(__ICACHE_PRESENT) && (__ICACHE_PRESENT == 1) */
#if defined(__DCACHE_PRESENT) && (__DCACHE_PRESENT == 1)
/**
* \defgroup NMSIS_Core_DCache D-Cache Functions
* \ingroup NMSIS_Core_Cache
* \brief Functions that configure Data Cache.
* @{
*/
/**
* \brief Enable DCache
* \details
* This function enable D-Cache
* \remarks
* - This \ref CSR_MCACHE_CTL register control D Cache enable.
* \sa
* - \ref DisableDCache
*/
__STATIC_FORCEINLINE void EnableDCache (void)
{
__RV_CSR_SET(CSR_MCACHE_CTL, CSR_MCACHE_CTL_DE);
}
/**
* \brief Disable DCache
* \details
* This function Disable D-Cache
* \remarks
* - This \ref CSR_MCACHE_CTL register control D Cache enable.
* \sa
* - \ref EnableDCache
*/
__STATIC_FORCEINLINE void DisableDCache (void)
{
__RV_CSR_CLEAR(CSR_MCACHE_CTL, CSR_MCACHE_CTL_DE);
}
/** @} */ /* End of Doxygen Group NMSIS_Core_DCache */
#endif /* defined(__DCACHE_PRESENT) && (__DCACHE_PRESENT == 1) */
#ifdef __cplusplus
}
#endif
#endif /** __CORE_FEATURE_CACHE_H__ */

File diff suppressed because it is too large Load Diff

View File

@@ -0,0 +1,897 @@
/*
* 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
#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:8; /*!< 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[1] = 1, trig[0] = 0 */
ECLIC_NEGTIVE_EDGE_TRIGGER = 0x3, /*!< Negtive/Falling Edge Triggered, trig[1] = 1, trig[0] = 0 */
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)
{
#if __RISCV_XLEN == 32
volatile uint32_t vec_base;
vec_base = ((uint32_t)__RV_CSR_READ(CSR_MTVT));
(* (unsigned long *) (vec_base + ((int32_t)IRQn) * 4)) = vector;
#elif __RISCV_XLEN == 64
volatile uint64_t vec_base;
vec_base = ((uint64_t)__RV_CSR_READ(CSR_MTVT));
(* (unsigned long *) (vec_base + ((int32_t)IRQn) * 8)) = vector;
#else // TODO Need cover for XLEN=128 case in future
volatile uint64_t vec_base;
vec_base = ((uint64_t)__RV_CSR_READ(CSR_MTVT));
(* (unsigned long *) (vec_base + ((int32_t)IRQn) * 8)) = vector;
#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,304 @@
/*
* 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_FPU_H__
#define __CORE_FEATURE_FPU_H__
/*!
* @file core_feature_fpu.h
* @brief FPU feature API header file for Nuclei N/NX Core
*/
/*
* FPU Feature Configuration Macro:
* 1. __FPU_PRESENT: Define whether Floating Point Unit(FPU) is present or not
* * 0: Not present
* * 1: Single precision FPU present, __RISCV_FLEN == 32
* * 2: Double precision FPU present, __RISCV_FLEN == 64
*/
#ifdef __cplusplus
extern "C" {
#endif
/* ===== FPU Operations ===== */
/**
* \defgroup NMSIS_Core_FPU_Functions FPU Functions
* \ingroup NMSIS_Core
* \brief Functions that related to the RISC-V FPU (F and D extension).
* \details
*
* Nuclei provided floating point unit by RISC-V F and D extension.
* * `F extension` adds single-precision floating-point computational
* instructions compliant with the IEEE 754-2008 arithmetic standard, __RISCV_FLEN = 32.
* The F extension adds 32 floating-point registers, f0-f31, each 32 bits wide,
* and a floating-point control and status register fcsr, which contains the
* operating mode and exception status of the floating-point unit.
* * `D extension` adds double-precision floating-point computational instructions
* compliant with the IEEE 754-2008 arithmetic standard.
* The D extension widens the 32 floating-point registers, f0-f31, to 64 bits, __RISCV_FLEN = 64
* @{
*/
#if defined(__FPU_PRESENT) && (__FPU_PRESENT > 0)
#if __FPU_PRESENT == 1
/** \brief Refer to the width of the floating point register in bits(either 32 or 64) */
#define __RISCV_FLEN 32
#elif __FPU_PRESENT == 2
#define __RISCV_FLEN 64
#else
#define __RISCV_FLEN __riscv_flen
#endif /* __FPU_PRESENT == 1 */
/** \brief Get FCSR CSR Register */
#define __get_FCSR() __RV_CSR_READ(CSR_FCSR)
/** \brief Set FCSR CSR Register with val */
#define __set_FCSR(val) __RV_CSR_WRITE(CSR_FCSR, (val))
/** \brief Get FRM CSR Register */
#define __get_FRM() __RV_CSR_READ(CSR_FRM)
/** \brief Set FRM CSR Register with val */
#define __set_FRM(val) __RV_CSR_WRITE(CSR_FRM, (val))
/** \brief Get FFLAGS CSR Register */
#define __get_FFLAGS() __RV_CSR_READ(CSR_FFLAGS)
/** \brief Set FFLAGS CSR Register with val */
#define __set_FFLAGS(val) __RV_CSR_WRITE(CSR_FFLAGS, (val))
/** \brief Enable FPU Unit */
#define __enable_FPU() __RV_CSR_SET(CSR_MSTATUS, MSTATUS_FS)
/**
* \brief Disable FPU Unit
* \details
* * We can save power by disable FPU Unit.
* * When FPU Unit is disabled, any access to FPU related CSR registers
* and FPU instructions will cause illegal Instuction Exception.
* */
#define __disable_FPU() __RV_CSR_CLEAR(CSR_MSTATUS, MSTATUS_FS)
/**
* \brief Load a single-precision value from memory into float point register freg using flw instruction
* \details The FLW instruction loads a single-precision floating point value from memory
* address (addr + ofs) into floating point register freg(f0-f31)
* \param [in] freg The floating point register, eg. FREG(0), f0
* \param [in] addr The memory base address, 4 byte aligned required
* \param [in] ofs a 12-bit immediate signed byte offset value, should be an const value
* \remarks
* * FLW and FSW operations need to make sure the address is 4 bytes aligned,
* otherwise it will cause exception code 4(Load address misaligned) or 6 (Store/AMO address misaligned)
* * FLW and FSW do not modify the bits being transferred; in particular, the payloads of non-canonical
* NaNs are preserved
*
*/
#define __RV_FLW(freg, addr, ofs) \
({ \
register rv_csr_t __addr = (rv_csr_t)(addr); \
__ASM volatile("flw " STRINGIFY(freg) ", %0(%1) " \
: : "I"(ofs), "r"(__addr) \
: "memory"); \
})
/**
* \brief Store a single-precision value from float point freg into memory using fsw instruction
* \details The FSW instruction stores a single-precision value from floating point register to memory
* \param [in] freg The floating point register(f0-f31), eg. FREG(0), f0
* \param [in] addr The memory base address, 4 byte aligned required
* \param [in] ofs a 12-bit immediate signed byte offset value, should be an const value
* \remarks
* * FLW and FSW operations need to make sure the address is 4 bytes aligned,
* otherwise it will cause exception code 4(Load address misaligned) or 6 (Store/AMO address misaligned)
* * FLW and FSW do not modify the bits being transferred; in particular, the payloads of non-canonical
* NaNs are preserved
*
*/
#define __RV_FSW(freg, addr, ofs) \
({ \
register rv_csr_t __addr = (rv_csr_t)(addr); \
__ASM volatile("fsw " STRINGIFY(freg) ", %0(%1) " \
: : "I"(ofs), "r"(__addr) \
: "memory"); \
})
/**
* \brief Load a double-precision value from memory into float point register freg using fld instruction
* \details The FLD instruction loads a double-precision floating point value from memory
* address (addr + ofs) into floating point register freg(f0-f31)
* \param [in] freg The floating point register, eg. FREG(0), f0
* \param [in] addr The memory base address, 8 byte aligned required
* \param [in] ofs a 12-bit immediate signed byte offset value, should be an const value
* \attention
* * Function only available for double precision floating point unit, FLEN = 64
* \remarks
* * FLD and FSD operations need to make sure the address is 8 bytes aligned,
* otherwise it will cause exception code 4(Load address misaligned) or 6 (Store/AMO address misaligned)
* * FLD and FSD do not modify the bits being transferred; in particular, the payloads of non-canonical
* NaNs are preserved.
*/
#define __RV_FLD(freg, addr, ofs) \
({ \
register rv_csr_t __addr = (rv_csr_t)(addr); \
__ASM volatile("fld " STRINGIFY(freg) ", %0(%1) " \
: : "I"(ofs), "r"(__addr) \
: "memory"); \
})
/**
* \brief Store a double-precision value from float point freg into memory using fsd instruction
* \details The FSD instruction stores double-precision value from floating point register to memory
* \param [in] freg The floating point register(f0-f31), eg. FREG(0), f0
* \param [in] addr The memory base address, 8 byte aligned required
* \param [in] ofs a 12-bit immediate signed byte offset value, should be an const value
* \attention
* * Function only available for double precision floating point unit, FLEN = 64
* \remarks
* * FLD and FSD operations need to make sure the address is 8 bytes aligned,
* otherwise it will cause exception code 4(Load address misaligned) or 6 (Store/AMO address misaligned)
* * FLD and FSD do not modify the bits being transferred; in particular, the payloads of non-canonical
* NaNs are preserved.
*
*/
#define __RV_FSD(freg, addr, ofs) \
({ \
register rv_csr_t __addr = (rv_csr_t)(addr); \
__ASM volatile("fsd " STRINGIFY(freg) ", %0(%1) " \
: : "I"(ofs), "r"(__addr) \
: "memory"); \
})
/**
* \def __RV_FLOAD
* \brief Load a float point value from memory into float point register freg using flw/fld instruction
* \details
* * For Single-Precison Floating-Point Mode(__FPU_PRESENT == 1, __RISCV_FLEN == 32):
* It will call \ref __RV_FLW to load a single-precision floating point value from memory to floating point register
* * For Double-Precison Floating-Point Mode(__FPU_PRESENT == 2, __RISCV_FLEN == 64):
* It will call \ref __RV_FLD to load a double-precision floating point value from memory to floating point register
*
* \attention
* Function behaviour is different for __FPU_PRESENT = 1 or 2, please see the real function this macro represent
*/
/**
* \def __RV_FSTORE
* \brief Store a float value from float point freg into memory using fsw/fsd instruction
* \details
* * For Single-Precison Floating-Point Mode(__FPU_PRESENT == 1, __RISCV_FLEN == 32):
* It will call \ref __RV_FSW to store floating point register into memory
* * For Double-Precison Floating-Point Mode(__FPU_PRESENT == 2, __RISCV_FLEN == 64):
* It will call \ref __RV_FSD to store floating point register into memory
*
* \attention
* Function behaviour is different for __FPU_PRESENT = 1 or 2, please see the real function this macro represent
*/
#if __FPU_PRESENT == 1
#define __RV_FLOAD __RV_FLW
#define __RV_FSTORE __RV_FSW
/** \brief Type of FPU register, depends on the FLEN defined in RISC-V */
typedef uint32_t rv_fpu_t;
#elif __FPU_PRESENT == 2
#define __RV_FLOAD __RV_FLD
#define __RV_FSTORE __RV_FSD
/** \brief Type of FPU register, depends on the FLEN defined in RISC-V */
typedef uint64_t rv_fpu_t;
#endif /* __FPU_PRESENT == 2 */
/**
* \brief Save FPU context into variables for interrupt nesting
* \details
* This macro is used to declare variables which are used for saving
* FPU context, and it will store the nessary fpu registers into
* these variables, it need to be used in a interrupt when in this
* interrupt fpu registers are used.
* \remarks
* - It need to be used together with \ref RESTORE_FPU_CONTEXT
* - Don't use variable names __fpu_context in your ISR code
* - If you isr code will use fpu registers, and this interrupt is nested.
* Then you can do it like this:
* \code
* void eclic_mtip_handler(void)
* {
* // !!!Interrupt is enabled here!!!
* // !!!Higher priority interrupt could nest it!!!
*
* // Necessary only when you need to use fpu registers
* // in this isr handler functions
* SAVE_FPU_CONTEXT();
*
* // put you own interrupt handling code here
*
* // pair of SAVE_FPU_CONTEXT()
* RESTORE_FPU_CONTEXT();
* }
* \endcode
*/
#define SAVE_FPU_CONTEXT() \
rv_fpu_t __fpu_context[20]; \
__RV_FSTORE(FREG(0), __fpu_context, 0 << LOG_FPREGBYTES); \
__RV_FSTORE(FREG(1), __fpu_context, 1 << LOG_FPREGBYTES); \
__RV_FSTORE(FREG(2), __fpu_context, 2 << LOG_FPREGBYTES); \
__RV_FSTORE(FREG(3), __fpu_context, 3 << LOG_FPREGBYTES); \
__RV_FSTORE(FREG(4), __fpu_context, 4 << LOG_FPREGBYTES); \
__RV_FSTORE(FREG(5), __fpu_context, 5 << LOG_FPREGBYTES); \
__RV_FSTORE(FREG(6), __fpu_context, 6 << LOG_FPREGBYTES); \
__RV_FSTORE(FREG(7), __fpu_context, 7 << LOG_FPREGBYTES); \
__RV_FSTORE(FREG(10), __fpu_context, 8 << LOG_FPREGBYTES); \
__RV_FSTORE(FREG(11), __fpu_context, 9 << LOG_FPREGBYTES); \
__RV_FSTORE(FREG(12), __fpu_context, 10 << LOG_FPREGBYTES); \
__RV_FSTORE(FREG(13), __fpu_context, 11 << LOG_FPREGBYTES); \
__RV_FSTORE(FREG(14), __fpu_context, 12 << LOG_FPREGBYTES); \
__RV_FSTORE(FREG(15), __fpu_context, 13 << LOG_FPREGBYTES); \
__RV_FSTORE(FREG(16), __fpu_context, 14 << LOG_FPREGBYTES); \
__RV_FSTORE(FREG(17), __fpu_context, 15 << LOG_FPREGBYTES); \
__RV_FSTORE(FREG(28), __fpu_context, 16 << LOG_FPREGBYTES); \
__RV_FSTORE(FREG(29), __fpu_context, 17 << LOG_FPREGBYTES); \
__RV_FSTORE(FREG(30), __fpu_context, 18 << LOG_FPREGBYTES); \
__RV_FSTORE(FREG(31), __fpu_context, 19 << LOG_FPREGBYTES);
/**
* \brief Restore necessary fpu registers from variables for interrupt nesting
* \details
* This macro is used restore necessary fpu registers from pre-defined variables
* in \ref SAVE_FPU_CONTEXT macro.
* \remarks
* - It need to be used together with \ref SAVE_FPU_CONTEXT
*/
#define RESTORE_FPU_CONTEXT() \
__RV_FLOAD(FREG(0), __fpu_context, 0 << LOG_FPREGBYTES); \
__RV_FLOAD(FREG(1), __fpu_context, 1 << LOG_FPREGBYTES); \
__RV_FLOAD(FREG(2), __fpu_context, 2 << LOG_FPREGBYTES); \
__RV_FLOAD(FREG(3), __fpu_context, 3 << LOG_FPREGBYTES); \
__RV_FLOAD(FREG(4), __fpu_context, 4 << LOG_FPREGBYTES); \
__RV_FLOAD(FREG(5), __fpu_context, 5 << LOG_FPREGBYTES); \
__RV_FLOAD(FREG(6), __fpu_context, 6 << LOG_FPREGBYTES); \
__RV_FLOAD(FREG(7), __fpu_context, 7 << LOG_FPREGBYTES); \
__RV_FLOAD(FREG(10), __fpu_context, 8 << LOG_FPREGBYTES); \
__RV_FLOAD(FREG(11), __fpu_context, 9 << LOG_FPREGBYTES); \
__RV_FLOAD(FREG(12), __fpu_context, 10 << LOG_FPREGBYTES); \
__RV_FLOAD(FREG(13), __fpu_context, 11 << LOG_FPREGBYTES); \
__RV_FLOAD(FREG(14), __fpu_context, 12 << LOG_FPREGBYTES); \
__RV_FLOAD(FREG(15), __fpu_context, 13 << LOG_FPREGBYTES); \
__RV_FLOAD(FREG(16), __fpu_context, 14 << LOG_FPREGBYTES); \
__RV_FLOAD(FREG(17), __fpu_context, 15 << LOG_FPREGBYTES); \
__RV_FLOAD(FREG(28), __fpu_context, 16 << LOG_FPREGBYTES); \
__RV_FLOAD(FREG(29), __fpu_context, 17 << LOG_FPREGBYTES); \
__RV_FLOAD(FREG(30), __fpu_context, 18 << LOG_FPREGBYTES); \
__RV_FLOAD(FREG(31), __fpu_context, 19 << LOG_FPREGBYTES);
#else
#define SAVE_FPU_CONTEXT()
#define RESTORE_FPU_CONTEXT()
#endif /* __FPU_PRESENT > 0 */
/** @} */ /* End of Doxygen Group NMSIS_Core_FPU_Functions */
#ifdef __cplusplus
}
#endif
#endif /** __RISCV_EXT_FPU_H__ */

View File

@@ -0,0 +1,260 @@
/*
* 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_PMP_H__
#define __CORE_FEATURE_PMP_H__
/*!
* @file core_feature_pmp.h
* @brief PMP feature API header file for Nuclei N/NX Core
*/
/*
* PMP Feature Configuration Macro:
* 1. __PMP_PRESENT: Define whether Physical Memory Protection(PMP) is present or not
* * 0: Not present
* * 1: Present
* 2. __PMP_ENTRY_NUM: Define the number of PMP entries, only 8 or 16 is configurable.
*/
#ifdef __cplusplus
extern "C" {
#endif
#if defined(__PMP_PRESENT) && (__PMP_PRESENT == 1)
/* ===== PMP Operations ===== */
/**
* \defgroup NMSIS_Core_PMP_Functions PMP Functions
* \ingroup NMSIS_Core
* \brief Functions that related to the RISCV Phyiscal Memory Protection.
* \details
* Optional physical memory protection (PMP) unit provides per-hart machine-mode
* control registers to allow physical memory access privileges (read, write, execute)
* to be specified for each physical memory region.
*
* The PMP can supports region access control settings as small as four bytes.
*
* @{
*/
#ifndef __PMP_ENTRY_NUM
/* numbers of PMP entries(__PMP_ENTRY_NUM) should be defined in <Device.h> */
#error "__PMP_ENTRY_NUM is not defined, please check!"
#endif
/**
* \brief Get 8bit PMPxCFG Register by PMP entry index
* \details Return the content of the PMPxCFG Register.
* \param [in] idx PMP region index(0-15)
* \return PMPxCFG Register value
*/
__STATIC_INLINE uint8_t __get_PMPxCFG(uint32_t idx)
{
rv_csr_t pmpcfg = 0;
if (idx >= __PMP_ENTRY_NUM) return 0;
#if __RISCV_XLEN == 32
if (idx < 4) {
pmpcfg = __RV_CSR_READ(CSR_PMPCFG0);
} else if ((idx >=4) && (idx < 8)) {
idx -= 4;
pmpcfg = __RV_CSR_READ(CSR_PMPCFG1);
} else if ((idx >=8) && (idx < 12)) {
idx -= 8;
pmpcfg = __RV_CSR_READ(CSR_PMPCFG2);
} else {
idx -= 12;
pmpcfg = __RV_CSR_READ(CSR_PMPCFG3);
}
idx = idx << 3;
return (uint8_t)((pmpcfg>>idx) & 0xFF);
#elif __RISCV_XLEN == 64
if (idx < 8) {
pmpcfg = __RV_CSR_READ(CSR_PMPCFG0);
} else {
idx -= 8;
pmpcfg = __RV_CSR_READ(CSR_PMPCFG2);
}
idx = idx << 3;
return (uint8_t)((pmpcfg>>idx) & 0xFF);
#else
// TODO Add RV128 Handling
return 0;
#endif
}
/**
* \brief Set 8bit PMPxCFG by pmp entry index
* \details Set the given pmpxcfg value to the PMPxCFG Register.
* \param [in] idx PMPx region index(0-15)
* \param [in] pmpxcfg PMPxCFG register value to set
*/
__STATIC_INLINE void __set_PMPxCFG(uint32_t idx, uint8_t pmpxcfg)
{
rv_csr_t pmpcfgx = 0;
if (idx >= __PMP_ENTRY_NUM) return;
#if __RISCV_XLEN == 32
if (idx < 4) {
pmpcfgx = __RV_CSR_READ(CSR_PMPCFG0);
idx = idx << 3;
pmpcfgx = (pmpcfgx & ~(0xFFUL << idx)) | ((rv_csr_t)pmpxcfg << idx);
__RV_CSR_WRITE(CSR_PMPCFG0, pmpcfgx);
} else if ((idx >=4) && (idx < 8)) {
idx -= 4;
pmpcfgx = __RV_CSR_READ(CSR_PMPCFG1);
idx = idx << 3;
pmpcfgx = (pmpcfgx & ~(0xFFUL << idx)) | ((rv_csr_t)pmpxcfg << idx);
__RV_CSR_WRITE(CSR_PMPCFG1, pmpcfgx);
} else if ((idx >=8) && (idx < 12)) {
idx -= 8;
pmpcfgx = __RV_CSR_READ(CSR_PMPCFG2);
idx = idx << 3;
pmpcfgx = (pmpcfgx & ~(0xFFUL << idx)) | ((rv_csr_t)pmpxcfg << idx);
__RV_CSR_WRITE(CSR_PMPCFG2, pmpcfgx);
} else {
idx -= 12;
pmpcfgx = __RV_CSR_READ(CSR_PMPCFG3);
idx = idx << 3;
pmpcfgx = (pmpcfgx & ~(0xFFUL << idx)) | ((rv_csr_t)pmpxcfg << idx);
__RV_CSR_WRITE(CSR_PMPCFG3, pmpcfgx);
}
#elif __RISCV_XLEN == 64
if (idx < 8) {
pmpcfgx = __RV_CSR_READ(CSR_PMPCFG0);
idx = idx << 3;
pmpcfgx = (pmpcfgx & ~(0xFFULL << idx)) | ((rv_csr_t)pmpxcfg << idx);
__RV_CSR_WRITE(CSR_PMPCFG0, pmpcfgx);
} else {
idx -= 8;
pmpcfgx = __RV_CSR_READ(CSR_PMPCFG2);
idx = idx << 3;
pmpcfgx = (pmpcfgx & ~(0xFFULL << idx)) | ((rv_csr_t)pmpxcfg << idx);
__RV_CSR_WRITE(CSR_PMPCFG2, pmpcfgx);
}
#else
// TODO Add RV128 Handling
#endif
}
/**
* \brief Get PMPCFGx Register by index
* \details Return the content of the PMPCFGx Register.
* \param [in] idx PMPCFG CSR index(0-3)
* \return PMPCFGx Register value
* \remark
* - For RV64, only idx = 0 and idx = 2 is allowed.
* pmpcfg0 and pmpcfg2 hold the configurations
* for the 16 PMP entries, pmpcfg1 and pmpcfg3 are illegal
* - For RV32, pmpcfg0pmpcfg3, hold the configurations
* pmp0cfgpmp15cfg for the 16 PMP entries
*/
__STATIC_INLINE rv_csr_t __get_PMPCFGx(uint32_t idx)
{
switch (idx) {
case 0: return __RV_CSR_READ(CSR_PMPCFG0);
case 1: return __RV_CSR_READ(CSR_PMPCFG1);
case 2: return __RV_CSR_READ(CSR_PMPCFG2);
case 3: return __RV_CSR_READ(CSR_PMPCFG3);
default: return 0;
}
}
/**
* \brief Set PMPCFGx by index
* \details Write the given value to the PMPCFGx Register.
* \param [in] idx PMPCFG CSR index(0-3)
* \param [in] pmpcfg PMPCFGx Register value to set
* \remark
* - For RV64, only idx = 0 and idx = 2 is allowed.
* pmpcfg0 and pmpcfg2 hold the configurations
* for the 16 PMP entries, pmpcfg1 and pmpcfg3 are illegal
* - For RV32, pmpcfg0pmpcfg3, hold the configurations
* pmp0cfgpmp15cfg for the 16 PMP entries
*/
__STATIC_INLINE void __set_PMPCFGx(uint32_t idx, rv_csr_t pmpcfg)
{
switch (idx) {
case 0: __RV_CSR_WRITE(CSR_PMPCFG0, pmpcfg); break;
case 1: __RV_CSR_WRITE(CSR_PMPCFG1, pmpcfg); break;
case 2: __RV_CSR_WRITE(CSR_PMPCFG2, pmpcfg); break;
case 3: __RV_CSR_WRITE(CSR_PMPCFG3, pmpcfg); break;
default: return;
}
}
/**
* \brief Get PMPADDRx Register by index
* \details Return the content of the PMPADDRx Register.
* \param [in] idx PMP region index(0-15)
* \return PMPADDRx Register value
*/
__STATIC_INLINE rv_csr_t __get_PMPADDRx(uint32_t idx)
{
switch (idx) {
case 0: return __RV_CSR_READ(CSR_PMPADDR0);
case 1: return __RV_CSR_READ(CSR_PMPADDR1);
case 2: return __RV_CSR_READ(CSR_PMPADDR2);
case 3: return __RV_CSR_READ(CSR_PMPADDR3);
case 4: return __RV_CSR_READ(CSR_PMPADDR4);
case 5: return __RV_CSR_READ(CSR_PMPADDR5);
case 6: return __RV_CSR_READ(CSR_PMPADDR6);
case 7: return __RV_CSR_READ(CSR_PMPADDR7);
case 8: return __RV_CSR_READ(CSR_PMPADDR8);
case 9: return __RV_CSR_READ(CSR_PMPADDR9);
case 10: return __RV_CSR_READ(CSR_PMPADDR10);
case 11: return __RV_CSR_READ(CSR_PMPADDR11);
case 12: return __RV_CSR_READ(CSR_PMPADDR12);
case 13: return __RV_CSR_READ(CSR_PMPADDR13);
case 14: return __RV_CSR_READ(CSR_PMPADDR14);
case 15: return __RV_CSR_READ(CSR_PMPADDR15);
default: return 0;
}
}
/**
* \brief Set PMPADDRx by index
* \details Write the given value to the PMPADDRx Register.
* \param [in] idx PMP region index(0-15)
* \param [in] pmpaddr PMPADDRx Register value to set
*/
__STATIC_INLINE void __set_PMPADDRx(uint32_t idx, rv_csr_t pmpaddr)
{
switch (idx) {
case 0: __RV_CSR_WRITE(CSR_PMPADDR0, pmpaddr); break;
case 1: __RV_CSR_WRITE(CSR_PMPADDR1, pmpaddr); break;
case 2: __RV_CSR_WRITE(CSR_PMPADDR2, pmpaddr); break;
case 3: __RV_CSR_WRITE(CSR_PMPADDR3, pmpaddr); break;
case 4: __RV_CSR_WRITE(CSR_PMPADDR4, pmpaddr); break;
case 5: __RV_CSR_WRITE(CSR_PMPADDR5, pmpaddr); break;
case 6: __RV_CSR_WRITE(CSR_PMPADDR6, pmpaddr); break;
case 7: __RV_CSR_WRITE(CSR_PMPADDR7, pmpaddr); break;
case 8: __RV_CSR_WRITE(CSR_PMPADDR8, pmpaddr); break;
case 9: __RV_CSR_WRITE(CSR_PMPADDR9, pmpaddr); break;
case 10: __RV_CSR_WRITE(CSR_PMPADDR10, pmpaddr); break;
case 11: __RV_CSR_WRITE(CSR_PMPADDR11, pmpaddr); break;
case 12: __RV_CSR_WRITE(CSR_PMPADDR12, pmpaddr); break;
case 13: __RV_CSR_WRITE(CSR_PMPADDR13, pmpaddr); break;
case 14: __RV_CSR_WRITE(CSR_PMPADDR14, pmpaddr); break;
case 15: __RV_CSR_WRITE(CSR_PMPADDR15, pmpaddr); break;
default: return;
}
}
/** @} */ /* End of Doxygen Group NMSIS_Core_PMP_Functions */
#endif /* defined(__PMP_PRESENT) && (__PMP_PRESENT == 1) */
#ifdef __cplusplus
}
#endif
#endif /** __CORE_FEATURE_PMP_H__ */

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,37 @@
/*
* 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_COMPILER_H
#define __NMSIS_COMPILER_H
#include <stdint.h>
/*!
* @file nmsis_compiler.h
* @brief NMSIS compiler generic header file
*/
#if defined ( __GNUC__ )
/** GNU GCC Compiler */
#include "nmsis_gcc.h"
#else
#error Unknown compiler.
#endif
#endif /* __NMSIS_COMPILER_H */

View File

@@ -0,0 +1,87 @@
/*
* Copyright (c) 2009-2019 Arm Limited. All rights reserved.
* -- Adaptable modifications made for Nuclei Processors. --
* 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_CORE_H__
#define __NMSIS_CORE_H__
#include <stdint.h>
#ifdef __cplusplus
extern "C" {
#endif
#include "nmsis_version.h"
/**
* \ingroup NMSIS_Core_VersionControl
* @{
*/
/* The following enum __NUCLEI_N_REV/__NUCLEI_NX_REV 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__)
/**
* \brief Nuclei N class core revision number
* \details
* Reversion number format: [15:8] revision number, [7:0] patch number
* \attention
* This define is exclusive with \ref __NUCLEI_NX_REV
*/
#define __NUCLEI_N_REV (0x0104)
/**
* \brief Nuclei NX class core revision number
* \details
* Reversion number format: [15:8] revision number, [7:0] patch number
* \attention
* This define is exclusive with \ref __NUCLEI_N_REV
*/
#define __NUCLEI_NX_REV (0x0100)
#endif /* __ONLY_FOR_DOXYGEN_DOCUMENT_GENERATION__ */
/** @} */ /* End of Group NMSIS_Core_VersionControl */
#include "nmsis_compiler.h" /* NMSIS compiler specific defines */
/* === Include Nuclei Core Related Headers === */
/* Include core base feature header file */
#include "core_feature_base.h"
#ifndef __NMSIS_GENERIC
/* Include core eclic feature header file */
#include "core_feature_eclic.h"
/* Include core systimer feature header file */
#include "core_feature_timer.h"
#endif
/* Include core fpu feature header file */
#include "core_feature_fpu.h"
/* Include core dsp feature header file */
#include "core_feature_dsp.h"
/* Include core pmp feature header file */
#include "core_feature_pmp.h"
/* Include core cache feature header file */
#include "core_feature_cache.h"
/* Include compatiable functions header file */
#include "core_compatiable.h"
#ifdef __cplusplus
}
#endif
#endif /* __NMSIS_CORE_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,87 @@
/*
* 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_VERSION_H
#define __NMSIS_VERSION_H
/**
* \defgroup NMSIS_Core_VersionControl Version Control
* \ingroup NMSIS_Core
* \brief Version \#define symbols for NMSIS release specific C/C++ source code
* \details
*
* We followed the [semantic versioning 2.0.0](https://semver.org/) to control NMSIS version.
* The version format is **MAJOR.MINOR.PATCH**, increment the:
* 1. MAJOR version when you make incompatible API changes,
* 2. MINOR version when you add functionality in a backwards compatible manner, and
* 3. PATCH version when you make backwards compatible bug fixes.
*
* The header file `nmsis_version.h` is included by each core header so that these definitions are available.
*
* **Example Usage for NMSIS Version Check**:
* \code
* #if defined(__NMSIS_VERSION) && (__NMSIS_VERSION >= 0x00010105)
* #warning "Yes, we have NMSIS 1.1.5 or later"
* #else
* #error "We need NMSIS 1.1.5 or later!"
* #endif
* \endcode
*
* @{
*/
/*!
* \file nmsis_version.h
* \brief NMSIS Version definitions
**/
/**
* \brief Represent the NMSIS major version
* \details
* The NMSIS major version can be used to
* differentiate between NMSIS major releases.
* */
#define __NMSIS_VERSION_MAJOR (1U)
/**
* \brief Represent the NMSIS minor version
* \details
* The NMSIS minor version can be used to
* query a NMSIS release update including new features.
*
**/
#define __NMSIS_VERSION_MINOR (0U)
/**
* \brief Represent the NMSIS patch version
* \details
* The NMSIS patch version can be used to
* show bug fixes in this package.
**/
#define __NMSIS_VERSION_PATCH (0U)
/**
* \brief Represent the NMSIS Version
* \details
* NMSIS Version format: **MAJOR.MINOR.PATCH**
* * MAJOR: \ref __NMSIS_VERSION_MAJOR, stored in `bits [31:16]` of \ref __NMSIS_VERSION
* * MINOR: \ref __NMSIS_VERSION_MINOR, stored in `bits [15:8]` of \ref __NMSIS_VERSION
* * PATCH: \ref __NMSIS_VERSION_PATCH, stored in `bits [7:0]` of \ref __NMSIS_VERSION
**/
#define __NMSIS_VERSION ((__NMSIS_VERSION_MAJOR << 16U) | (__NMSIS_VERSION_MINOR << 8) | __NMSIS_VERSION_PATCH)
/** @} */ /* End of Doxygen Group NMSIS_Core_VersionControl */
#endif

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)
#ifndef __riscv_flen
#define __riscv_flen 32
#endif
#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 */
#define FPREGBYTES (1 << LOG_FPREGBYTES)
#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,617 @@
/*
* 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
* @{
*/
#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
/* === 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_EN (1<<0)
#define MDLM_CTL_DLM_BPA (((1ULL<<((__riscv_xlen)-10))-1)<<10)
#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_DC_EN (1<<16)
#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_ILM_SIZE (0x1F<<16)
#define MICFG_ILM_XONLY (1<<21)
#define MDCFG_DC_SET (0xF<<0)
#define MDCFG_DC_WAY (0x7<<4)
#define MDCFG_DC_LSIZE (0x7<<7)
#define MDCFG_DLM_SIZE (0x1F<<16)
#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 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
#define DEFAULT_RSTVEC 0x00001000
#define DEFAULT_NMIVEC 0x00001004
#define DEFAULT_MTVEC 0x00001010
#define CONFIG_STRING_ADDR 0x0000100C
#define EXT_IO_BASE 0x40000000
#define DRAM_BASE 0x80000000
/* === 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 */
#define DOWNLOAD_MODE_FLASHXIP 0
#define DOWNLOAD_MODE_FLASH 1
#define DOWNLOAD_MODE_ILM 2
#define DOWNLOAD_MODE_DDR 3
/**
* \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
/* === 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
/* === Nuclei custom CSR Registers === */
#define CSR_MCOUNTINHIBIT 0x320
#define CSR_MILM_CTL 0x7C0
#define CSR_MDLM_CTL 0x7C1
#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_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_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
/** @} */ /** 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,685 @@
/*
* FreeRTOS Kernel V10.2.1
* Copyright (C) 2019 Amazon.com, Inc. or its affiliates. All Rights Reserved.
*
* Permission is hereby granted, free of charge, to any person obtaining a copy of
* this software and associated documentation files (the "Software"), to deal in
* the Software without restriction, including without limitation the rights to
* use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of
* the Software, and to permit persons to whom the Software is furnished to do so,
* subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in all
* copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS
* FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR
* COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER
* IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
* CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
*
* http://www.FreeRTOS.org
* http://aws.amazon.com/freertos
*
* 1 tab == 4 spaces!
*/
/*-----------------------------------------------------------
* Implementation of functions defined in portable.h for the Nuclei N/NX Processor port.
*----------------------------------------------------------*/
/* Scheduler includes. */
#include <stdio.h>
#include "FreeRTOS.h"
#include "task.h"
//#define ENABLE_KERNEL_DEBUG
#ifdef ENABLE_KERNEL_DEBUG
#define FREERTOS_PORT_DEBUG(...) printf(__VA_ARGS__)
#else
#define FREERTOS_PORT_DEBUG(...)
#endif
#ifndef configSYSTICK_CLOCK_HZ
#define configSYSTICK_CLOCK_HZ SOC_TIMER_FREQ
#endif
#ifndef configKERNEL_INTERRUPT_PRIORITY
#define configKERNEL_INTERRUPT_PRIORITY 0
#endif
#ifndef configMAX_SYSCALL_INTERRUPT_PRIORITY
// See function prvCheckMaxSysCallPrio and prvCalcMaxSysCallMTH
#define configMAX_SYSCALL_INTERRUPT_PRIORITY 255
#endif
/* Constants required to check the validity of an interrupt priority. */
#define portFIRST_USER_INTERRUPT_NUMBER ( 18 )
#define SYSTICK_TICK_CONST (configSYSTICK_CLOCK_HZ / configTICK_RATE_HZ)
/* Masks off all bits but the ECLIC MTH bits in the MTH register. */
#define portMTH_MASK ( 0xFFUL )
/* Constants required to set up the initial stack. */
#define portINITIAL_MSTATUS ( MSTATUS_MPP | MSTATUS_MPIE | MSTATUS_FS_INITIAL)
#define portINITIAL_EXC_RETURN ( 0xfffffffd )
/* The systick is a 64-bit counter. */
#define portMAX_BIT_NUMBER ( SysTimer_MTIMER_Msk )
/* A fiddle factor to estimate the number of SysTick counts that would have
occurred while the SysTick counter is stopped during tickless idle
calculations. */
#define portMISSED_COUNTS_FACTOR ( 45UL )
/* Let the user override the pre-loading of the initial LR with the address of
prvTaskExitError() in case it messes up unwinding of the stack in the
debugger. */
#ifdef configTASK_RETURN_ADDRESS
#define portTASK_RETURN_ADDRESS configTASK_RETURN_ADDRESS
#else
#define portTASK_RETURN_ADDRESS prvTaskExitError
#endif
/*
* Setup the timer to generate the tick interrupts. The implementation in this
* file is weak to allow application writers to change the timer used to
* generate the tick interrupt.
*/
void vPortSetupTimerInterrupt( void );
/*
* Exception handlers.
*/
void xPortSysTickHandler( void );
/*
* Start first task is a separate function so it can be tested in isolation.
*/
extern void prvPortStartFirstTask( void ) __attribute__ (( naked ));
/*
* Used to catch tasks that attempt to return from their implementing function.
*/
static void prvTaskExitError( void );
#define xPortSysTickHandler eclic_mtip_handler
/*-----------------------------------------------------------*/
/* Each task maintains its own interrupt status in the critical nesting
variable. */
static UBaseType_t uxCriticalNesting = 0xaaaaaaaa;
/*
* Record the real MTH calculated by the configMAX_SYSCALL_INTERRUPT_PRIORITY
* The configMAX_SYSCALL_INTERRUPT_PRIORITY is not the left-aligned level value,
* See equations below:
* Level Bits number: lvlbits = min(nlbits, CLICINTCTLBITS)
* Left align Bits number: lfabits = 8-lvlbits
* 0 < configMAX_SYSCALL_INTERRUPT_PRIORITY <= (2^lvlbits-1)
* uxMaxSysCallMTH = (configMAX_SYSCALL_INTERRUPT_PRIORITY << lfabits) | ((2^lfabits)-1)
* If nlbits = 3, CLICINTCTLBITS=3, then lvlbits = 3, lfabits = 5
* Set configMAX_SYSCALL_INTERRUPT_PRIORITY to 6
* Then uxMaxSysCallMTH = (6<<5) | (2^5 - 1) = 223
*
* See function prvCheckMaxSysCallPrio and prvCalcMaxSysCallMTH
*/
uint8_t uxMaxSysCallMTH = 255;
/*
* The number of SysTick increments that make up one tick period.
*/
#if( configUSE_TICKLESS_IDLE == 1 )
static TickType_t ulTimerCountsForOneTick = 0;
#endif /* configUSE_TICKLESS_IDLE */
/*
* The maximum number of tick periods that can be suppressed is limited by the
* 24 bit resolution of the SysTick timer.
*/
#if( configUSE_TICKLESS_IDLE == 1 )
static TickType_t xMaximumPossibleSuppressedTicks = 0;
#endif /* configUSE_TICKLESS_IDLE */
/*
* Compensate for the CPU cycles that pass while the SysTick is stopped (low
* power functionality only.
*/
#if( configUSE_TICKLESS_IDLE == 1 )
static TickType_t ulStoppedTimerCompensation = 0;
#endif /* configUSE_TICKLESS_IDLE */
/*
* Used by the portASSERT_IF_INTERRUPT_PRIORITY_INVALID() macro to ensure
* FreeRTOS API functions are not called from interrupts that have been assigned
* a priority above configMAX_SYSCALL_INTERRUPT_PRIORITY.
*/
#if( configASSERT_DEFINED == 1 )
static uint8_t ucMaxSysCallPriority = 0;
#endif /* configASSERT_DEFINED */
/*-----------------------------------------------------------*/
/*
* See header file for description.
* As per the standard RISC-V ABI pxTopcOfStack is passed in in a0, pxCode in
* a1, and pvParameters in a2. The new top of stack is passed out in a0.
*
* RISC-V maps registers to ABI names as follows (X1 to X31 integer registers
* for the 'I' profile, X1 to X15 for the 'E' profile, currently I assumed).
*
* Register ABI Name Description Saver
* x0 zero Hard-wired zero -
* x1 ra Return address Caller
* x2 sp Stack pointer Callee
* x3 gp Global pointer -
* x4 tp Thread pointer -
* x5-7 t0-2 Temporaries Caller
* x8 s0/fp Saved register/Frame pointer Callee
* x9 s1 Saved register Callee
* x10-11 a0-1 Function Arguments/return values Caller
* x12-17 a2-7 Function arguments Caller
* x18-27 s2-11 Saved registers Callee
* x28-31 t3-6 Temporaries Caller
*
* The RISC-V context is saved RTOS tasks in the following stack frame,
* where the global and thread pointers are currently assumed to be constant so
* are not saved:
*
* mstatus
* #ifndef __riscv_32e
* x31
* x30
* x29
* x28
* x27
* x26
* x25
* x24
* x23
* x22
* x21
* x20
* x19
* x18
* x17
* x16
* #endif
* x15
* x14
* x13
* x12
* x11
* pvParameters
* x9
* x8
* x7
* x6
* x5
* portTASK_RETURN_ADDRESS
* pxCode
*/
StackType_t *pxPortInitialiseStack( StackType_t *pxTopOfStack, TaskFunction_t pxCode, void *pvParameters )
{
/* Simulate the stack frame as it would be created by a context switch
interrupt. */
/* Offset added to account for the way the MCU uses the stack on entry/exit
of interrupts, and to ensure alignment. */
pxTopOfStack--;
*pxTopOfStack = portINITIAL_MSTATUS; /* MSTATUS */
/* Save code space by skipping register initialisation. */
#ifndef __riscv_32e
pxTopOfStack -= 22; /* X11 - X31. */
#else
pxTopOfStack -= 6; /* X11 - X15. */
#endif
*pxTopOfStack = ( StackType_t ) pvParameters; /* X10/A0 */
pxTopOfStack -= 6; /* X5 - X9 */
*pxTopOfStack = ( StackType_t ) portTASK_RETURN_ADDRESS; /* RA, X1 */
pxTopOfStack --;
*pxTopOfStack = ( ( StackType_t ) pxCode ) ; /* PC */
return pxTopOfStack;
}
/*-----------------------------------------------------------*/
static void prvTaskExitError( void )
{
volatile uint32_t ulDummy = 0;
/* A function that implements a task must not exit or attempt to return to
its caller as there is nothing to return to. If a task wants to exit it
should instead call vTaskDelete( NULL ).
Artificially force an assert() to be triggered if configASSERT() is
defined, then stop here so application writers can catch the error. */
configASSERT( uxCriticalNesting == ~0UL );
portDISABLE_INTERRUPTS();
while( ulDummy == 0 )
{
/* This file calls prvTaskExitError() after the scheduler has been
started to remove a compiler warning about the function being defined
but never called. ulDummy is used purely to quieten other warnings
about code appearing after this function is called - making ulDummy
volatile makes the compiler think the function could return and
therefore not output an 'unreachable code' warning for code that appears
after it. */
/* Sleep and wait for interrupt */
__WFI();
}
}
/*-----------------------------------------------------------*/
static uint8_t prvCheckMaxSysCallPrio( uint8_t max_syscall_prio )
{
uint8_t nlbits = __ECLIC_GetCfgNlbits();
uint8_t intctlbits = __ECLIC_INTCTLBITS;
uint8_t lvlbits, temp;
if (nlbits <= intctlbits) {
lvlbits = nlbits;
} else {
lvlbits = intctlbits;
}
temp = ((1<<lvlbits) - 1);
if (max_syscall_prio > temp) {
max_syscall_prio = temp;
}
return max_syscall_prio;
}
static uint8_t prvCalcMaxSysCallMTH( uint8_t max_syscall_prio )
{
uint8_t nlbits = __ECLIC_GetCfgNlbits();
uint8_t intctlbits = __ECLIC_INTCTLBITS;
uint8_t lvlbits, lfabits;
uint8_t maxsyscallmth = 0;
uint8_t temp;
if (nlbits <= intctlbits) {
lvlbits = nlbits;
} else {
lvlbits = intctlbits;
}
lfabits = 8 - lvlbits;
temp = ((1<<lvlbits) - 1);
if (max_syscall_prio > temp) {
max_syscall_prio = temp;
}
maxsyscallmth = (max_syscall_prio << lfabits) | ((1<<lfabits) - 1);
return maxsyscallmth;
}
/*
* See header file for description.
*/
BaseType_t xPortStartScheduler( void )
{
/* configMAX_SYSCALL_INTERRUPT_PRIORITY must not be set to 0. */
configASSERT( configMAX_SYSCALL_INTERRUPT_PRIORITY );
/* Get the real MTH should be set to ECLIC MTH register */
uxMaxSysCallMTH = prvCalcMaxSysCallMTH(configMAX_SYSCALL_INTERRUPT_PRIORITY);
FREERTOS_PORT_DEBUG("Max SysCall MTH is set to 0x%x\n", uxMaxSysCallMTH);
#if( configASSERT_DEFINED == 1 )
{
/* Use the same mask on the maximum system call priority. */
ucMaxSysCallPriority = prvCheckMaxSysCallPrio(configMAX_SYSCALL_INTERRUPT_PRIORITY);
FREERTOS_PORT_DEBUG("Max SysCall Priority is set to %d\n", ucMaxSysCallPriority);
}
#endif /* conifgASSERT_DEFINED */
__disable_irq();
/* Start the timer that generates the tick ISR. Interrupts are disabled
here already. */
vPortSetupTimerInterrupt();
/* Initialise the critical nesting count ready for the first task. */
uxCriticalNesting = 0;
/* Start the first task. */
prvPortStartFirstTask();
/* Should never get here as the tasks will now be executing! Call the task
exit error function to prevent compiler warnings about a static function
not being called in the case that the application writer overrides this
functionality by defining configTASK_RETURN_ADDRESS. Call
vTaskSwitchContext() so link time optimisation does not remove the
symbol. */
vTaskSwitchContext();
prvTaskExitError();
/* Should not get here! */
return 0;
}
/*-----------------------------------------------------------*/
void vPortEndScheduler( void )
{
/* Not implemented in ports where there is nothing to return to.
Artificially force an assert. */
configASSERT( uxCriticalNesting == 1000UL );
}
/*-----------------------------------------------------------*/
void vPortEnterCritical( void )
{
portDISABLE_INTERRUPTS();
uxCriticalNesting++;
/* This is not the interrupt safe version of the enter critical function so
assert() if it is being called from an interrupt context. Only API
functions that end in "FromISR" can be used in an interrupt. Only assert if
the critical nesting count is 1 to protect against recursive calls if the
assert function also uses a critical section. */
if( uxCriticalNesting == 1 )
{
configASSERT( ( __ECLIC_GetMth() & portMTH_MASK ) == uxMaxSysCallMTH );
}
}
/*-----------------------------------------------------------*/
void vPortExitCritical( void )
{
configASSERT( uxCriticalNesting );
uxCriticalNesting--;
if( uxCriticalNesting == 0 )
{
portENABLE_INTERRUPTS();
}
}
/*-----------------------------------------------------------*/
void vPortAssert( int32_t x )
{
TaskHandle_t th;
if ((x) == 0) {
taskDISABLE_INTERRUPTS();
#if (INCLUDE_xTaskGetCurrentTaskHandle == 1)
th = xTaskGetCurrentTaskHandle();
if (th) {
printf("Assert in task %s\n", pcTaskGetName(th));
}
#endif
while(1) {
/* Sleep and wait for interrupt */
__WFI();
};
}
}
/*-----------------------------------------------------------*/
void xPortTaskSwitch( void )
{
portDISABLE_INTERRUPTS();
/* Clear Software IRQ, A MUST */
SysTimer_ClearSWIRQ();
vTaskSwitchContext();
portENABLE_INTERRUPTS();
}
/*-----------------------------------------------------------*/
void xPortSysTickHandler( void )
{
/* The SysTick runs at the lowest interrupt priority, so when this interrupt
executes all interrupts must be unmasked. There is therefore no need to
save and then restore the interrupt mask value as its value is already
known. */
portDISABLE_INTERRUPTS();
{
SysTick_Reload(SYSTICK_TICK_CONST);
/* Increment the RTOS tick. */
if( xTaskIncrementTick() != pdFALSE )
{
/* A context switch is required. Context switching is performed in
the SWI interrupt. Pend the SWI interrupt. */
portYIELD();
}
}
portENABLE_INTERRUPTS();
}
/*-----------------------------------------------------------*/
#if( configUSE_TICKLESS_IDLE == 1 )
__attribute__((weak)) void vPortSuppressTicksAndSleep( TickType_t xExpectedIdleTime )
{
uint32_t ulReloadValue, ulCompleteTickPeriods, ulCompletedSysTickDecrements;
volatile TickType_t xModifiableIdleTime, xTickCountBeforeSleep, XLastLoadValue;
FREERTOS_PORT_DEBUG("Enter TickLess %d\n", (uint32_t)xExpectedIdleTime);
/* Make sure the SysTick reload value does not overflow the counter. */
if( xExpectedIdleTime > xMaximumPossibleSuppressedTicks )
{
xExpectedIdleTime = xMaximumPossibleSuppressedTicks;
}
/* Stop the SysTick momentarily. The time the SysTick is stopped for
is accounted for as best it can be, but using the tickless mode will
inevitably result in some tiny drift of the time maintained by the
kernel with respect to calendar time. */
SysTimer_Stop();
/* Calculate the reload value required to wait xExpectedIdleTime
tick periods. -1 is used because this code will execute part way
through one of the tick periods. */
ulReloadValue = ( ulTimerCountsForOneTick * ( xExpectedIdleTime - 1UL ) );
if( ulReloadValue > ulStoppedTimerCompensation )
{
ulReloadValue -= ulStoppedTimerCompensation;
}
/* Enter a critical section but don't use the taskENTER_CRITICAL()
method as that will mask interrupts that should exit sleep mode. */
__disable_irq();
/* If a context switch is pending or a task is waiting for the scheduler
to be unsuspended then abandon the low power entry. */
if( eTaskConfirmSleepModeStatus() == eAbortSleep )
{
/* Restart from whatever is left in the count register to complete
this tick period. */
/* Restart SysTick. */
SysTimer_Start();
/* Reset the reload register to the value required for normal tick
periods. */
SysTick_Reload(ulTimerCountsForOneTick);
/* Re-enable interrupts - see comments above the cpsid instruction()
above. */
__enable_irq();
}
else
{
xTickCountBeforeSleep = xTaskGetTickCount();
/* Set the new reload value. */
SysTick_Reload(ulReloadValue);
/* Get System timer load value before sleep */
XLastLoadValue = SysTimer_GetLoadValue();
/* Restart SysTick. */
SysTimer_Start();
ECLIC_EnableIRQ(SysTimer_IRQn);
__RWMB();
/* Sleep until something happens. configPRE_SLEEP_PROCESSING() can
set its parameter to 0 to indicate that its implementation contains
its own wait for interrupt or wait for event instruction, and so wfi
should not be executed again. However, the original expected idle
time variable must remain unmodified, so a copy is taken. */
xModifiableIdleTime = xExpectedIdleTime;
configPRE_SLEEP_PROCESSING( xModifiableIdleTime );
if( xModifiableIdleTime > 0 )
{
__WFI();
}
configPOST_SLEEP_PROCESSING( xExpectedIdleTime );
/* Re-enable interrupts to allow the interrupt that brought the MCU
out of sleep mode to execute immediately. */
__enable_irq();
/* Make sure interrupt enable is executed */
__RWMB();
__FENCE_I();
__NOP();
/* Disable interrupts again because the clock is about to be stopped
and interrupts that execute while the clock is stopped will increase
any slippage between the time maintained by the RTOS and calendar
time. */
__disable_irq();
/* Disable the SysTick clock. Again,
the time the SysTick is stopped for is accounted for as best it can
be, but using the tickless mode will inevitably result in some tiny
drift of the time maintained by the kernel with respect to calendar
time*/
ECLIC_DisableIRQ(SysTimer_IRQn);
/* Determine if SysTimer Interrupt is not yet happened,
(in which case an interrupt other than the SysTick
must have brought the system out of sleep mode). */
if (SysTimer_GetLoadValue() >= (XLastLoadValue + ulReloadValue))
{
/* As the pending tick will be processed as soon as this
function exits, the tick value maintained by the tick is stepped
forward by one less than the time spent waiting. */
ulCompleteTickPeriods = xExpectedIdleTime - 1UL;
FREERTOS_PORT_DEBUG("TickLess - SysTimer Interrupt Entered!\n");
}
else
{
/* Something other than the tick interrupt ended the sleep.
Work out how long the sleep lasted rounded to complete tick
periods (not the ulReload value which accounted for part
ticks). */
xModifiableIdleTime = SysTimer_GetLoadValue();
if ( xModifiableIdleTime > XLastLoadValue ) {
ulCompletedSysTickDecrements = (xModifiableIdleTime - XLastLoadValue);
} else {
ulCompletedSysTickDecrements = (xModifiableIdleTime + portMAX_BIT_NUMBER - XLastLoadValue);
}
/* How many complete tick periods passed while the processor
was waiting? */
ulCompleteTickPeriods = ulCompletedSysTickDecrements / ulTimerCountsForOneTick;
/* The reload value is set to whatever fraction of a single tick
period remains. */
SysTick_Reload(ulTimerCountsForOneTick);
FREERTOS_PORT_DEBUG("TickLess - External Interrupt Happened!\n");
}
FREERTOS_PORT_DEBUG("End TickLess %d\n", (uint32_t)ulCompleteTickPeriods);
/* Restart SysTick */
vTaskStepTick( ulCompleteTickPeriods );
/* Exit with interrupts enabled. */
ECLIC_EnableIRQ(SysTimer_IRQn);
__enable_irq();
}
}
#endif /* #if configUSE_TICKLESS_IDLE */
/*-----------------------------------------------------------*/
/*
* Setup the systick timer to generate the tick interrupts at the required
* frequency.
*/
__attribute__(( weak )) void vPortSetupTimerInterrupt( void )
{
/* Calculate the constants required to configure the tick interrupt. */
#if( configUSE_TICKLESS_IDLE == 1 )
{
ulTimerCountsForOneTick = ( SYSTICK_TICK_CONST );
xMaximumPossibleSuppressedTicks = portMAX_BIT_NUMBER / ulTimerCountsForOneTick;
ulStoppedTimerCompensation = portMISSED_COUNTS_FACTOR / ( configCPU_CLOCK_HZ / configSYSTICK_CLOCK_HZ );
FREERTOS_PORT_DEBUG("CountsForOneTick, SuppressedTicks and TimerCompensation: %u, %u, %u\n", \
(uint32_t)ulTimerCountsForOneTick, (uint32_t)xMaximumPossibleSuppressedTicks, (uint32_t)ulStoppedTimerCompensation);
}
#endif /* configUSE_TICKLESS_IDLE */
TickType_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);
}
/*-----------------------------------------------------------*/
/*-----------------------------------------------------------*/
#if( configASSERT_DEFINED == 1 )
void vPortValidateInterruptPriority( void )
{
uint32_t ulCurrentInterrupt;
uint8_t ucCurrentPriority;
/* Obtain the number of the currently executing interrupt. */
CSR_MCAUSE_Type mcause = (CSR_MCAUSE_Type)__RV_CSR_READ(CSR_MCAUSE);
/* Make sure current trap type is interrupt */
configASSERT(mcause.b.interrupt == 1);
if (mcause.b.interrupt) {
ulCurrentInterrupt = mcause.b.exccode;
/* Is the interrupt number a user defined interrupt? */
if ( ulCurrentInterrupt >= portFIRST_USER_INTERRUPT_NUMBER ) {
/* Look up the interrupt's priority. */
ucCurrentPriority = __ECLIC_GetLevelIRQ(ulCurrentInterrupt);
/* The following assertion will fail if a service routine (ISR) for
an interrupt that has been assigned a priority above
ucMaxSysCallPriority calls an ISR safe FreeRTOS API
function. ISR safe FreeRTOS API functions must *only* be called
from interrupts that have been assigned a priority at or below
ucMaxSysCallPriority.
Numerically low interrupt priority numbers represent logically high
interrupt priorities, therefore the priority of the interrupt must
be set to a value equal to or numerically *higher* than
ucMaxSysCallPriority.
Interrupts that use the FreeRTOS API must not be left at their
default priority of zero as that is the highest possible priority,
which is guaranteed to be above ucMaxSysCallPriority,
and therefore also guaranteed to be invalid.
FreeRTOS maintains separate thread and ISR API functions to ensure
interrupt entry is as fast and simple as possible.
The following links provide detailed information:
http://www.freertos.org/FAQHelp.html */
configASSERT( ucCurrentPriority <= ucMaxSysCallPriority );
}
}
}
#endif /* configASSERT_DEFINED */

View File

@@ -0,0 +1,402 @@
/*
* FreeRTOS Kernel V10.2.1
* Copyright (C) 2019 Amazon.com, Inc. or its affiliates. All Rights Reserved.
*
* Permission is hereby granted, free of charge, to any person obtaining a copy of
* this software and associated documentation files (the "Software"), to deal in
* the Software without restriction, including without limitation the rights to
* use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of
* the Software, and to permit persons to whom the Software is furnished to do so,
* subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in all
* copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS
* FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR
* COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER
* IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
* CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
*
* http://www.FreeRTOS.org
* http://aws.amazon.com/freertos
*
* 1 tab == 4 spaces!
*/
#include "riscv_encoding.h"
#ifndef __riscv_32e
#define portRegNum 30
#else
#define portRegNum 14
#endif
#define portCONTEXT_SIZE ( portRegNum * REGBYTES )
.section .text.entry
.align 8
.extern xPortTaskSwitch
.extern pxCurrentTCB
.global prvPortStartFirstTask
/**
* \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
csrrw sp, CSR_MSCRATCHCSWL, sp
/* 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 */
csrrw sp, CSR_MSCRATCHCSWL, sp
.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
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
/* 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
Undef_Handler:
default_intexc_handler:
1:
j 1b
/* Start the first task. This also clears the bit that indicates the FPU is
in use in case the FPU was used before the scheduler was started - which
would otherwise result in the unnecessary leaving of space in the stack
for lazy saving of FPU registers. */
.align 3
prvPortStartFirstTask:
/* Setup Interrupt Stack using
The stack that was used by main()
before the scheduler is started is
no longer required after the scheduler is started.
Interrupt stack pointer is stored in CSR_MSCRATCH */
la t0, _sp
csrw CSR_MSCRATCH, t0
LOAD sp, pxCurrentTCB /* Load pxCurrentTCB. */
LOAD sp, 0x0(sp) /* Read sp from first TCB member */
/* Pop PC from stack and set MEPC */
LOAD t0, 0 * REGBYTES(sp)
csrw CSR_MEPC, t0
/* 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
.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, pxCurrentTCB
STORE sp, 0(t0)
csrr t0, CSR_MEPC
STORE t0, 0(sp)
jal xPortTaskSwitch
/* Switch task context */
LOAD t0, pxCurrentTCB /* Load pxCurrentTCB. */
LOAD sp, 0x0(t0) /* Read sp from first TCB member */
/* 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

View File

@@ -0,0 +1,174 @@
/*
* FreeRTOS Kernel V10.2.1
* Copyright (C) 2019 Amazon.com, Inc. or its affiliates. All Rights Reserved.
*
* Permission is hereby granted, free of charge, to any person obtaining a copy of
* this software and associated documentation files (the "Software"), to deal in
* the Software without restriction, including without limitation the rights to
* use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of
* the Software, and to permit persons to whom the Software is furnished to do so,
* subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in all
* copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS
* FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR
* COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER
* IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
* CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
*
* http://www.FreeRTOS.org
* http://aws.amazon.com/freertos
*
* 1 tab == 4 spaces!
*/
#ifndef PORTMACRO_H
#define PORTMACRO_H
#ifdef __cplusplus
extern "C" {
#endif
#include "nuclei_sdk_soc.h"
/*-----------------------------------------------------------
* Port specific definitions.
*
* The settings in this file configure FreeRTOS correctly for the
* given hardware and compiler.
*
* These settings should not be altered.
*-----------------------------------------------------------
*/
/* Type definitions. */
#define portCHAR char
#define portFLOAT float
#define portDOUBLE double
#define portLONG long
#define portSHORT short
#define portSTACK_TYPE unsigned long
#define portBASE_TYPE long
#define portPOINTER_SIZE_TYPE unsigned long
typedef portSTACK_TYPE StackType_t;
typedef long BaseType_t;
typedef unsigned long UBaseType_t;
#if (configUSE_16_BIT_TICKS == 1)
typedef uint16_t TickType_t;
#define portMAX_DELAY (TickType_t)0xffff
#else
/* RISC-V TIMER is 64-bit long */
typedef uint64_t TickType_t;
#define portMAX_DELAY (TickType_t)0xFFFFFFFFFFFFFFFFULL
#endif
/*-----------------------------------------------------------*/
/* Architecture specifics. */
#define portSTACK_GROWTH (-1)
#define portTICK_PERIOD_MS ((TickType_t)1000 / configTICK_RATE_HZ)
#define portBYTE_ALIGNMENT 8
/*-----------------------------------------------------------*/
/* Scheduler utilities. */
#define portYIELD() \
{ \
/* Set a software interrupt(SWI) request to request a context switch. */ \
SysTimer_SetSWIRQ(); \
/* Barriers are normally not required but do ensure the code is completely \
within the specified behaviour for the architecture. */ \
__RWMB(); \
}
#define portEND_SWITCHING_ISR(xSwitchRequired) \
if (xSwitchRequired != pdFALSE) \
portYIELD()
#define portYIELD_FROM_ISR(x) portEND_SWITCHING_ISR(x)
/*-----------------------------------------------------------*/
/* Critical section management. */
extern void vPortEnterCritical(void);
extern void vPortExitCritical(void);
#define portSET_INTERRUPT_MASK_FROM_ISR() ulPortRaiseBASEPRI()
#define portCLEAR_INTERRUPT_MASK_FROM_ISR(x) vPortSetBASEPRI(x)
#define portDISABLE_INTERRUPTS() vPortRaiseBASEPRI()
#define portENABLE_INTERRUPTS() vPortSetBASEPRI(0)
#define portENTER_CRITICAL() vPortEnterCritical()
#define portEXIT_CRITICAL() vPortExitCritical()
/*-----------------------------------------------------------*/
/* Task function macros as described on the FreeRTOS.org WEB site. These are
not necessary for to use this port. They are defined so the common demo files
(which build with all the ports) will build. */
#define portTASK_FUNCTION_PROTO(vFunction, pvParameters) void vFunction(void *pvParameters)
#define portTASK_FUNCTION(vFunction, pvParameters) void vFunction(void *pvParameters)
/*-----------------------------------------------------------*/
/* Tickless idle/low power functionality. */
#ifndef portSUPPRESS_TICKS_AND_SLEEP
extern void vPortSuppressTicksAndSleep(TickType_t xExpectedIdleTime);
#define portSUPPRESS_TICKS_AND_SLEEP(xExpectedIdleTime) vPortSuppressTicksAndSleep(xExpectedIdleTime)
#endif
/*-----------------------------------------------------------*/
/*-----------------------------------------------------------*/
#ifdef configASSERT
extern void vPortValidateInterruptPriority(void);
#define portASSERT_IF_INTERRUPT_PRIORITY_INVALID() vPortValidateInterruptPriority()
#endif
/* portNOP() is not required by this port. */
#define portNOP() __NOP()
#define portINLINE __inline
#ifndef portFORCE_INLINE
#define portFORCE_INLINE inline __attribute__((always_inline))
#endif
/* This variable should not be set in any of the FreeRTOS application
only used internal of FreeRTOS Port code */
extern uint8_t uxMaxSysCallMTH;
/*-----------------------------------------------------------*/
portFORCE_INLINE static void vPortRaiseBASEPRI(void) {
ECLIC_SetMth(uxMaxSysCallMTH);
__RWMB();
}
/*-----------------------------------------------------------*/
portFORCE_INLINE static uint8_t ulPortRaiseBASEPRI(void) {
uint8_t ulOriginalBASEPRI;
ulOriginalBASEPRI = ECLIC_GetMth();
ECLIC_SetMth(uxMaxSysCallMTH);
__RWMB();
/* This return might not be reached but is necessary to prevent compiler
warnings. */
return ulOriginalBASEPRI;
}
/*-----------------------------------------------------------*/
portFORCE_INLINE static void vPortSetBASEPRI(uint8_t ulNewMaskValue) {
ECLIC_SetMth(ulNewMaskValue);
__RWMB();
}
/*-----------------------------------------------------------*/
#define portMEMORY_BARRIER() __asm volatile("" :: \
: "memory")
#ifdef __cplusplus
}
#endif
#endif /* PORTMACRO_H */

View File

@@ -1,48 +0,0 @@
// See LICENSE file for licence details
#ifndef N200_ECLIC_H
#define N200_ECLIC_H
#include <riscv_const.h>
#define ECLICINTCTLBITS 4
//ECLIC memory map
// Offset
// 0x0000 1B RW ecliccfg
#define ECLIC_CFG_OFFSET 0x0
// 0x0004 4B R eclicinfo
#define ECLIC_INFO_OFFSET 0x4
// 0x000B 1B RW mintthresh
#define ECLIC_MTH_OFFSET 0xB
//
// 0x1000+4*i 1B/input RW eclicintip[i]
#define ECLIC_INT_IP_OFFSET _AC(0x1000,UL)
// 0x1001+4*i 1B/input RW eclicintie[i]
#define ECLIC_INT_IE_OFFSET _AC(0x1001,UL)
// 0x1002+4*i 1B/input RW eclicintattr[i]
#define ECLIC_INT_ATTR_OFFSET _AC(0x1002,UL)
#define ECLIC_INT_ATTR_SHV 0x01
#define ECLIC_INT_ATTR_TRIG_LEVEL 0x00
#define ECLIC_INT_ATTR_TRIG_EDGE 0x02
#define ECLIC_INT_ATTR_TRIG_POS 0x00
#define ECLIC_INT_ATTR_TRIG_NEG 0x04
// 0x1003+4*i 1B/input RW eclicintctl[i]
#define ECLIC_INT_CTRL_OFFSET _AC(0x1003,UL)
//
// ...
//
#define ECLIC_ADDR_BASE 0xd2000000
#define ECLIC_CFG_NLBITS_MASK _AC(0x1E,UL)
#define ECLIC_CFG_NLBITS_LSB (1u)
#define MSIP_HANDLER eclic_msip_handler
#define MTIME_HANDLER eclic_mtip_handler
#define BWEI_HANDLER eclic_bwei_handler
#define PMOVI_HANDLER eclic_pmovi_handler
#endif

View File

@@ -1,398 +0,0 @@
// See LICENSE for license details.
#include <gd32vf103.h>
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <unistd.h>
#include "riscv_encoding.h"
#include "n200_func.h"
// Configure PMP to make all the address space accesable and executable
void pmp_open_all_space(){
// Config entry0 addr to all 1s to make the range cover all space
asm volatile ("li x6, 0xffffffff":::"x6");
asm volatile ("csrw pmpaddr0, x6":::);
// Config entry0 cfg to make it NAPOT address mode, and R/W/X okay
asm volatile ("li x6, 0x7f":::"x6");
asm volatile ("csrw pmpcfg0, x6":::);
}
void switch_m2u_mode(){
clear_csr (mstatus,MSTATUS_MPP);
//printf("\nIn the m2u function, the mstatus is 0x%x\n", read_csr(mstatus));
//printf("\nIn the m2u function, the mepc is 0x%x\n", read_csr(mepc));
asm volatile ("la x6, 1f ":::"x6");
asm volatile ("csrw mepc, x6":::);
asm volatile ("mret":::);
asm volatile ("1:":::);
}
uint32_t mtime_lo(void)
{
return *(volatile uint32_t *)(TIMER_CTRL_ADDR + TIMER_MTIME);
}
uint32_t mtime_hi(void)
{
return *(volatile uint32_t *)(TIMER_CTRL_ADDR + TIMER_MTIME + 4);
}
uint64_t get_timer_value()
{
while (1) {
uint32_t hi = mtime_hi();
uint32_t lo = mtime_lo();
if (hi == mtime_hi())
return ((uint64_t)hi << 32) | lo;
}
}
uint32_t get_timer_freq()
{
return TIMER_FREQ;
}
uint64_t get_instret_value()
{
while (1) {
uint32_t hi = read_csr(minstreth);
uint32_t lo = read_csr(minstret);
if (hi == read_csr(minstreth))
return ((uint64_t)hi << 32) | lo;
}
}
uint64_t get_cycle_value()
{
while (1) {
uint32_t hi = read_csr(mcycleh);
uint32_t lo = read_csr(mcycle);
if (hi == read_csr(mcycleh))
return ((uint64_t)hi << 32) | lo;
}
}
uint32_t __attribute__((noinline)) measure_cpu_freq(size_t n)
{
uint32_t start_mtime, delta_mtime;
uint32_t mtime_freq = get_timer_freq();
// Don't start measuruing until we see an mtime tick
uint32_t tmp = mtime_lo();
do {
start_mtime = mtime_lo();
} while (start_mtime == tmp);
uint32_t start_mcycle = read_csr(mcycle);
do {
delta_mtime = mtime_lo() - start_mtime;
} while (delta_mtime < n);
uint32_t delta_mcycle = read_csr(mcycle) - start_mcycle;
return (delta_mcycle / delta_mtime) * mtime_freq
+ ((delta_mcycle % delta_mtime) * mtime_freq) / delta_mtime;
}
uint32_t get_cpu_freq()
{
uint32_t cpu_freq;
// warm up
measure_cpu_freq(1);
// measure for real
cpu_freq = measure_cpu_freq(100);
return cpu_freq;
}
// Note that there are no assertions or bounds checking on these
// parameter values.
void eclic_init ( uint32_t num_irq )
{
typedef volatile uint32_t vuint32_t;
//clear cfg register
*(volatile uint8_t*)(ECLIC_ADDR_BASE+ECLIC_CFG_OFFSET)=0;
//clear minthresh register
*(volatile uint8_t*)(ECLIC_ADDR_BASE+ECLIC_MTH_OFFSET)=0;
//clear all IP/IE/ATTR/CTRL bits for all interrupt sources
vuint32_t * ptr;
vuint32_t * base = (vuint32_t*)(ECLIC_ADDR_BASE + ECLIC_INT_IP_OFFSET);
vuint32_t * upper = (vuint32_t*)(base + num_irq*4);
for (ptr = base; ptr < upper; ptr=ptr+4){
*ptr = 0;
}
}
void eclic_enable_interrupt (uint32_t source) {
*(volatile uint8_t*)(ECLIC_ADDR_BASE+ECLIC_INT_IE_OFFSET+source*4) = 1;
}
void eclic_disable_interrupt (uint32_t source){
*(volatile uint8_t*)(ECLIC_ADDR_BASE+ECLIC_INT_IE_OFFSET+source*4) = 0;
}
void eclic_set_pending(uint32_t source){
*(volatile uint8_t*)(ECLIC_ADDR_BASE+ECLIC_INT_IP_OFFSET+source*4) = 1;
}
void eclic_clear_pending(uint32_t source){
*(volatile uint8_t*)(ECLIC_ADDR_BASE+ECLIC_INT_IP_OFFSET+source*4) = 0;
}
void eclic_set_intctrl (uint32_t source, uint8_t intctrl){
*(volatile uint8_t*)(ECLIC_ADDR_BASE+ECLIC_INT_CTRL_OFFSET+source*4) = intctrl;
}
uint8_t eclic_get_intctrl (uint32_t source){
return *(volatile uint8_t*)(ECLIC_ADDR_BASE+ECLIC_INT_CTRL_OFFSET+source*4);
}
void eclic_set_intattr (uint32_t source, uint8_t intattr){
*(volatile uint8_t*)(ECLIC_ADDR_BASE+ECLIC_INT_ATTR_OFFSET+source*4) = intattr;
}
uint8_t eclic_get_intattr (uint32_t source){
return *(volatile uint8_t*)(ECLIC_ADDR_BASE+ECLIC_INT_ATTR_OFFSET+source*4);
}
void eclic_set_cliccfg (uint8_t cliccfg){
*(volatile uint8_t*)(ECLIC_ADDR_BASE+ECLIC_CFG_OFFSET) = cliccfg;
}
uint8_t eclic_get_cliccfg (){
return *(volatile uint8_t*)(ECLIC_ADDR_BASE+ECLIC_CFG_OFFSET);
}
void eclic_set_mth (uint8_t mth){
*(volatile uint8_t*)(ECLIC_ADDR_BASE+ECLIC_MTH_OFFSET) = mth;
}
uint8_t eclic_get_mth (){
return *(volatile uint8_t*)(ECLIC_ADDR_BASE+ECLIC_MTH_OFFSET);
}
//sets nlbits
void eclic_set_nlbits(uint8_t nlbits) {
//shift nlbits to correct position
uint8_t nlbits_shifted = nlbits << ECLIC_CFG_NLBITS_LSB;
//read the current cliccfg
uint8_t old_cliccfg = eclic_get_cliccfg();
uint8_t new_cliccfg = (old_cliccfg & (~ECLIC_CFG_NLBITS_MASK)) | (ECLIC_CFG_NLBITS_MASK & nlbits_shifted);
eclic_set_cliccfg(new_cliccfg);
}
//get nlbits
uint8_t eclic_get_nlbits(void) {
//extract nlbits
uint8_t nlbits = eclic_get_cliccfg();
nlbits = (nlbits & ECLIC_CFG_NLBITS_MASK) >> ECLIC_CFG_NLBITS_LSB;
return nlbits;
}
//sets an interrupt level based encoding of nlbits and ECLICINTCTLBITS
void eclic_set_irq_lvl(uint32_t source, uint8_t lvl) {
//extract nlbits
uint8_t nlbits = eclic_get_nlbits();
if (nlbits > ECLICINTCTLBITS) {
nlbits = ECLICINTCTLBITS;
}
//shift lvl right to mask off unused bits
lvl = lvl >> (8-nlbits);
//shift lvl into correct bit position
lvl = lvl << (8-nlbits);
//write to clicintctrl
uint8_t current_intctrl = eclic_get_intctrl(source);
//shift intctrl left to mask off unused bits
current_intctrl = current_intctrl << nlbits;
//shift intctrl into correct bit position
current_intctrl = current_intctrl >> nlbits;
eclic_set_intctrl(source, (current_intctrl | lvl));
}
//gets an interrupt level based encoding of nlbits
uint8_t eclic_get_irq_lvl(uint32_t source) {
//extract nlbits
uint8_t nlbits = eclic_get_nlbits();
if (nlbits > ECLICINTCTLBITS) {
nlbits = ECLICINTCTLBITS;
}
uint8_t intctrl = eclic_get_intctrl(source);
//shift intctrl
intctrl = intctrl >> (8-nlbits);
//shift intctrl
uint8_t lvl = intctrl << (8-nlbits);
return lvl;
}
void eclic_set_irq_lvl_abs(uint32_t source, uint8_t lvl_abs) {
//extract nlbits
uint8_t nlbits = eclic_get_nlbits();
if (nlbits > ECLICINTCTLBITS) {
nlbits = ECLICINTCTLBITS;
}
//shift lvl_abs into correct bit position
uint8_t lvl = lvl_abs << (8-nlbits);
//write to clicintctrl
uint8_t current_intctrl = eclic_get_intctrl(source);
//shift intctrl left to mask off unused bits
current_intctrl = current_intctrl << nlbits;
//shift intctrl into correct bit position
current_intctrl = current_intctrl >> nlbits;
eclic_set_intctrl(source, (current_intctrl | lvl));
}
uint8_t eclic_get_irq_lvl_abs(uint32_t source) {
//extract nlbits
uint8_t nlbits = eclic_get_nlbits();
if (nlbits > ECLICINTCTLBITS) {
nlbits = ECLICINTCTLBITS;
}
uint8_t intctrl = eclic_get_intctrl(source);
//shift intctrl
intctrl = intctrl >> (8-nlbits);
//shift intctrl
uint8_t lvl_abs = intctrl;
return lvl_abs;
}
//sets an interrupt priority based encoding of nlbits and ECLICINTCTLBITS
uint8_t eclic_set_irq_priority(uint32_t source, uint8_t priority) {
//extract nlbits
uint8_t nlbits = eclic_get_nlbits();
if (nlbits >= ECLICINTCTLBITS) {
nlbits = ECLICINTCTLBITS;
return 0;
}
//shift priority into correct bit position
priority = priority << (8 - ECLICINTCTLBITS);
//write to eclicintctrl
uint8_t current_intctrl = eclic_get_intctrl(source);
//shift intctrl right to mask off unused bits
current_intctrl = current_intctrl >> (8-nlbits);
//shift intctrl into correct bit position
current_intctrl = current_intctrl << (8-nlbits);
eclic_set_intctrl(source, (current_intctrl | priority));
return priority;
}
//gets an interrupt priority based encoding of nlbits
uint8_t eclic_get_irq_priority(uint32_t source) {
//extract nlbits
uint8_t nlbits = eclic_get_nlbits();
if (nlbits > ECLICINTCTLBITS) {
nlbits = ECLICINTCTLBITS;
}
uint8_t intctrl = eclic_get_intctrl(source);
//shift intctrl
intctrl = intctrl << nlbits;
//shift intctrl
uint8_t priority = intctrl >> (nlbits+(8 - ECLICINTCTLBITS));
return priority;
}
void eclic_mode_enable() {
uint32_t mtvec_value = read_csr(mtvec);
mtvec_value = mtvec_value & 0xFFFFFFC0;
mtvec_value = mtvec_value | 0x00000003;
write_csr(mtvec,mtvec_value);
}
//sets vector-mode or non-vector mode
void eclic_set_vmode(uint32_t source) {
//read the current attr
uint8_t old_intattr = eclic_get_intattr(source);
// Keep other bits unchanged and only set the LSB bit
uint8_t new_intattr = (old_intattr | 0x1);
eclic_set_intattr(source,new_intattr);
}
void eclic_set_nonvmode(uint32_t source) {
//read the current attr
uint8_t old_intattr = eclic_get_intattr(source);
// Keep other bits unchanged and only clear the LSB bit
uint8_t new_intattr = (old_intattr & (~0x1));
eclic_set_intattr(source,new_intattr);
}
//sets interrupt as level sensitive
//Bit 1, trig[0], is defined as "edge-triggered" (0: level-triggered, 1: edge-triggered);
//Bit 2, trig[1], is defined as "negative-edge" (0: positive-edge, 1: negative-edge).
void eclic_set_level_trig(uint32_t source) {
//read the current attr
uint8_t old_intattr = eclic_get_intattr(source);
// Keep other bits unchanged and only clear the bit 1
uint8_t new_intattr = (old_intattr & (~0x2));
eclic_set_intattr(source,new_intattr);
}
void eclic_set_posedge_trig(uint32_t source) {
//read the current attr
uint8_t old_intattr = eclic_get_intattr(source);
// Keep other bits unchanged and only set the bit 1
uint8_t new_intattr = (old_intattr | 0x2);
// Keep other bits unchanged and only clear the bit 2
new_intattr = (old_intattr & (~0x4));
eclic_set_intattr(source,new_intattr);
}
void eclic_set_negedge_trig(uint32_t source) {
//read the current attr
uint8_t old_intattr = eclic_get_intattr(source);
// Keep other bits unchanged and only set the bit 1
uint8_t new_intattr = (old_intattr | 0x2);
// Keep other bits unchanged and only set the bit 2
new_intattr = (old_intattr | 0x4);
eclic_set_intattr(source,new_intattr);
}
//void wfe() {
// core_wfe();
//}

View File

@@ -1,109 +0,0 @@
// See LICENSE file for licence details
#ifndef N200_FUNC_H
#define N200_FUNC_H
#include <stdio.h>
#include <stddef.h>
#include "n200_timer.h"
#include "n200_eclic.h"
#define ECLIC_GROUP_LEVEL0_PRIO4 0
#define ECLIC_GROUP_LEVEL1_PRIO3 1
#define ECLIC_GROUP_LEVEL2_PRIO2 2
#define ECLIC_GROUP_LEVEL3_PRIO1 3
#define ECLIC_GROUP_LEVEL4_PRIO0 4
void pmp_open_all_space();
void switch_m2u_mode();
uint32_t get_mtime_freq();
uint32_t mtime_lo(void);
uint32_t mtime_hi(void);
uint64_t get_mtime_value();
uint64_t get_instret_value();
uint64_t get_cycle_value();
uint32_t get_cpu_freq();
uint32_t __attribute__((noinline)) measure_cpu_freq(size_t n);
///////////////////////////////////////////////////////////////////
/////// ECLIC relevant functions
///////
void eclic_init ( uint32_t num_irq );
uint64_t get_timer_value();
void eclic_enable_interrupt (uint32_t source);
void eclic_disable_interrupt (uint32_t source);
void eclic_set_pending(uint32_t source);
void eclic_clear_pending(uint32_t source);
void eclic_set_intctrl (uint32_t source, uint8_t intctrl);
uint8_t eclic_get_intctrl (uint32_t source);
void eclic_set_intattr (uint32_t source, uint8_t intattr);
uint8_t eclic_get_intattr (uint32_t source);
void eclic_set_cliccfg (uint8_t cliccfg);
uint8_t eclic_get_cliccfg ();
void eclic_set_mth (uint8_t mth);
uint8_t eclic_get_mth();
//sets nlbits
void eclic_set_nlbits(uint8_t nlbits);
//get nlbits
uint8_t eclic_get_nlbits();
void eclic_set_irq_lvl(uint32_t source, uint8_t lvl);
uint8_t eclic_get_irq_lvl(uint32_t source);
void eclic_set_irq_lvl_abs(uint32_t source, uint8_t lvl_abs);
uint8_t eclic_get_irq_lvl_abs(uint32_t source);
uint8_t eclic_set_irq_priority(uint32_t source, uint8_t priority);
uint8_t eclic_get_irq_priority(uint32_t source);
void eclic_mode_enable();
void eclic_set_vmode(uint32_t source);
void eclic_set_nonvmode(uint32_t source);
void eclic_set_level_trig(uint32_t source);
void eclic_set_posedge_trig(uint32_t source);
void eclic_set_negedge_trig(uint32_t source);
///** \brief Wait For Interrupt
//
// Wait For Interrupt is a hint instruction that suspends execution
// until one of a number of events occurs.
// */
__attribute__( ( always_inline ) ) static inline void __WFI(void) {
__asm volatile ("wfi");
}
//
//
/** \brief Wait For Event
Wait For Event is a hint instruction that permits the processor to enter
a low-power state until one of a number of events occurs.
*/
__attribute__( ( always_inline ) ) static inline void __WFE(void) {
__asm volatile ("csrs 0x810, 0x1");
__asm volatile ("wfi");
__asm volatile ("csrc 0x810, 0x1");
}
#endif

View File

@@ -1,18 +0,0 @@
// See LICENSE file for licence details
#ifndef N200_TIMER_H
#define N200_TIMER_H
#define TIMER_MSIP 0xFFC
#define TIMER_MSIP_size 0x4
#define TIMER_MTIMECMP 0x8
#define TIMER_MTIMECMP_size 0x8
#define TIMER_MTIME 0x0
#define TIMER_MTIME_size 0x8
#define TIMER_CTRL_ADDR 0xd1000000
#define TIMER_REG(offset) _REG32(TIMER_CTRL_ADDR, offset)
#define TIMER_FREQ ((uint32_t)SystemCoreClock/4) //units HZ
#endif

View File

@@ -1,36 +0,0 @@
// See LICENSE for license details.
#ifndef _RISCV_BITS_H
#define _RISCV_BITS_H
#define likely(x) __builtin_expect((x), 1)
#define unlikely(x) __builtin_expect((x), 0)
#define ROUNDUP(a, b) ((((a)-1)/(b)+1)*(b))
#define ROUNDDOWN(a, b) ((a)/(b)*(b))
#define MAX(a, b) ((a) > (b) ? (a) : (b))
#define MIN(a, b) ((a) < (b) ? (a) : (b))
#define CLAMP(a, lo, hi) MIN(MAX(a, lo), hi)
#define EXTRACT_FIELD(val, which) (((val) & (which)) / ((which) & ~((which)-1)))
#define INSERT_FIELD(val, which, fieldval) (((val) & ~(which)) | ((fieldval) * ((which) & ~((which)-1))))
#define STR(x) XSTR(x)
#define XSTR(x) #x
#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
#define REGBYTES (1 << LOG_REGBYTES)
#endif

View File

@@ -1,18 +0,0 @@
// See LICENSE for license details.
/* Derived from <linux/const.h> */
#ifndef _RISCV_CONST_H
#define _RISCV_CONST_H
#ifdef __ASSEMBLER__
#define _AC(X,Y) X
#define _AT(T,X) X
#else
#define _AC(X,Y) (X##Y)
#define _AT(T,X) ((T)(X))
#endif /* !__ASSEMBLER__*/
#define _BITUL(x) (_AC(1,UL) << (x))
#define _BITULL(x) (_AC(1,ULL) << (x))
#endif /* _NUCLEI_CONST_H */

File diff suppressed because it is too large Load Diff

View File

@@ -1,60 +1,48 @@
/*!
\file system_gd32vf103.h
\brief RISC-V Device Peripheral Access Layer Header File for
GD32VF103 Device Series
\version 2019-06-05, 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.
*/
/* This file refers the RISC-V standard, some adjustments are made according to GigaDevice chips */
#ifndef SYSTEM_GD32VF103_H
#define SYSTEM_GD32VF103_H
#ifdef __cplusplus
extern "C" {
#endif
#include <stdint.h>
/* system clock frequency (core clock) */
extern uint32_t SystemCoreClock;
/* function declarations */
/* initialize the system and update the SystemCoreClock variable */
extern void SystemInit(void);
/* update the SystemCoreClock with current core clock retrieved from cpu registers */
extern void SystemCoreClockUpdate(void);
#ifdef __cplusplus
}
#endif
#endif /* SYSTEM_GD32VF103_H */
/*!
\file gd32vf103v_eval.h
\brief definitions for GD32VF103V_EVAL's leds, keys and COM ports hardware resources
\version 2019-6-5, 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 GD32VF103V_EVAL_H
#define GD32VF103V_EVAL_H
#ifdef cplusplus
extern "C" {
#endif
#include "nuclei_sdk_soc.h"
#ifdef cplusplus
}
#endif
#endif /* GD32VF103V_EVAL_H */

View File

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

View File

@@ -0,0 +1,284 @@
/*
* 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.*)
*(.gnu.linkonce.t.*)
} >flash AT>flash
.rodata : ALIGN(4)
{
. = ALIGN(4);
*(.rdata)
*(.rodata .rodata.*)
/* section information for initial. */
. = ALIGN(4);
__rt_init_start = .;
KEEP(*(SORT(.rti_fn*)))
__rt_init_end = .;
/* section information for finsh shell */
. = ALIGN(4);
__fsymtab_start = .;
KEEP(*(FSymTab))
__fsymtab_end = .;
. = ALIGN(4);
__vsymtab_start = .;
KEEP(*(VSymTab))
__vsymtab_end = .;
*(.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);
PROVIDE( _end = . );
PROVIDE( end = . );
/* Define stack and head location at ram */
.stack ORIGIN(ram) + LENGTH(ram) - __STACK_SIZE :
{
PROVIDE( _heap_end = . );
. = __STACK_SIZE;
PROVIDE( _sp = . );
} >ram AT>ram
}

View File

@@ -1,8 +1,8 @@
/*!
\file systick.h
\brief the header file of systick
\file gd32vf103v_eval.c
\brief firmware functions to manage leds, keys, COM ports
\version 2019-06-05, V1.0.0, firmware for GD32VF103
\version 2019-6-5, V1.0.0, demo for GD32VF103
*/
/*
@@ -31,17 +31,9 @@ WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWIS
ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY
OF SUCH DAMAGE.
*/
#ifdef __cplusplus
extern "C" {
#endif
#ifndef SYS_TICK_H
#define SYS_TICK_H
#include <stdint.h>
#include "nuclei_sdk_hal.h"
#include "gd32vf103_usart.h"
#include "gd32vf103_gpio.h"
#include "gd32vf103_exti.h"
void delay_1ms(uint32_t count);
#endif /* SYS_TICK_H */
#ifdef __cplusplus
}
#endif

View File

@@ -0,0 +1,47 @@
adapter_khz 1000
reset_config srst_only
adapter_nsrst_assert_width 100
interface cmsis-dap
transport select jtag
autoexit true
set _CHIPNAME riscv
jtag newtap $_CHIPNAME cpu -irlen 5 -expected-id 0x1e200a6d
set _TARGETNAME $_CHIPNAME.cpu
target create $_TARGETNAME riscv -chain-position $_TARGETNAME
$_TARGETNAME configure -work-area-phys 0x20000000 -work-area-size 20480 -work-area-backup 0
# Work-area is a space in RAM used for flash programming
if { [info exists WORKAREASIZE] } {
set _WORKAREASIZE $WORKAREASIZE
} else {
set _WORKAREASIZE 0x5000
}
# Allow overriding the Flash bank size
if { [info exists FLASH_SIZE] } {
set _FLASH_SIZE $FLASH_SIZE
} else {
# autodetect size
set _FLASH_SIZE 0
}
# flash size will be probed
set _FLASHNAME $_CHIPNAME.flash
flash bank $_FLASHNAME gd32vf103 0x08000000 0 0 0 $_TARGETNAME
# Expose Nuclei self-defined CSRS range 770-800,835-850,1984-2032,2064-2070
# See https://github.com/riscv/riscv-gnu-toolchain/issues/319#issuecomment-358397306
# Then user can view the csr register value in gdb using: info reg csr775 for CSR MTVT(0x307)
riscv expose_csrs 770-800,835-850,1984-2032,2064-2070
riscv set_reset_timeout_sec 1
init
halt

View File

@@ -0,0 +1,117 @@
/*!
\file drv_usb_core.h
\brief USB core low level driver header file
\version 2019-6-5, V1.0.0, firmware for GD32 USBFS&USBHS
*/
/*
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 __DRV_USB_CORE_H
#define __DRV_USB_CORE_H
#include "drv_usb_regs.h"
#include "usb_ch9_std.h"
#define USB_FS_EP0_MAX_LEN 64U /* maximum packet size of EndPoint0 */
#define HC_MAX_PACKET_COUNT 140U /* maximum packet count */
#define EP_ID(x) ((uint8_t)((x) & 0x7FU)) /* endpoint number */
#define EP_DIR(x) ((uint8_t)((x) >> 7)) /* endpoint direction */
enum _usb_eptype {
USB_EPTYPE_CTRL = 0U, /*!< control endpoint type */
USB_EPTYPE_ISOC = 1U, /*!< isochronous endpoint type */
USB_EPTYPE_BULK = 2U, /*!< bulk endpoint type */
USB_EPTYPE_INTR = 3U, /*!< interrupt endpoint type */
USB_EPTYPE_MASK = 3U, /*!< endpoint type mask */
};
typedef enum
{
USB_OTG_OK = 0, /*!< USB OTG status OK*/
USB_OTG_FAIL /*!< USB OTG status fail*/
} usb_otg_status;
typedef enum
{
USB_OK = 0, /*!< USB status OK*/
USB_FAIL /*!< USB status fail*/
} usb_status;
typedef enum
{
USB_USE_FIFO, /*!< USB use FIFO transfer mode */
USB_USE_DMA /*!< USB use DMA transfer mode */
} usb_transfer_mode;
typedef struct
{
uint8_t core_enum; /*!< USB core type */
uint8_t core_speed; /*!< USB core speed */
uint8_t num_pipe; /*!< USB host channel numbers */
uint8_t num_ep; /*!< USB device endpoint numbers */
uint8_t transfer_mode; /*!< USB transfer mode */
uint8_t phy_itf; /*!< USB core PHY interface */
uint8_t sof_enable; /*!< USB SOF output */
uint8_t low_power; /*!< USB low power */
} usb_core_basic;
/* function declarations */
/* config core capabilities */
usb_status usb_basic_init (usb_core_basic *usb_basic,
usb_core_regs *usb_regs,
usb_core_enum usb_core);
/*initializes the USB controller registers and prepares the core device mode or host mode operation*/
usb_status usb_core_init (usb_core_basic usb_basic, usb_core_regs *usb_regs);
/* read a packet from the Rx FIFO associated with the endpoint */
void *usb_rxfifo_read (usb_core_regs *core_regs, uint8_t *dest_buf, uint16_t byte_count);
/* write a packet into the Tx FIFO associated with the endpoint */
usb_status usb_txfifo_write (usb_core_regs *usb_regs,
uint8_t *src_buf,
uint8_t fifo_num,
uint16_t byte_count);
/* flush a Tx FIFO or all Tx FIFOs */
usb_status usb_txfifo_flush (usb_core_regs *usb_regs, uint8_t fifo_num);
/* flush the entire Rx FIFO */
usb_status usb_rxfifo_flush (usb_core_regs *usb_regs);
/* get the global interrupts */
static inline uint32_t usb_coreintr_get(usb_core_regs *usb_regs)
{
return usb_regs->gr->GINTEN & usb_regs->gr->GINTF;
}
#endif /* __DRV_USB_CORE_H */

View File

@@ -0,0 +1,217 @@
/*!
\file drv_usb_dev.h
\brief USB device low level driver header file
\version 2019-6-5, V1.0.0, firmware for GD32 USBFS&USBHS
*/
/*
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 __DRV_USB_DEV_H
#define __DRV_USB_DEV_H
#include "drv_usb_core.h"
enum usb_ctl_status {
USB_CTL_IDLE = 0U, /*!< USB control transfer idle state */
USB_CTL_DATA_IN, /*!< USB control transfer data in state */
USB_CTL_LAST_DATA_IN, /*!< USB control transfer last data in state */
USB_CTL_DATA_OUT, /*!< USB control transfer data out state */
USB_CTL_LAST_DATA_OUT, /*!< USB control transfer last data out state */
USB_CTL_STATUS_IN, /*!< USB control transfer status in state*/
USB_CTL_STATUS_OUT /*!< USB control transfer status out state */
};
#define EP_IN(x) ((uint8_t)(0x80U | (x))) /*!< device IN endpoint */
#define EP_OUT(x) ((uint8_t)(x)) /*!< device OUT endpoint */
/* USB descriptor */
typedef struct _usb_desc {
uint8_t *dev_desc; /*!< device descriptor */
uint8_t *config_desc; /*!< config descriptor */
uint8_t *bos_desc; /*!< BOS descriptor */
void* const *strings; /*!< string descriptor */
} usb_desc;
/* USB power management */
typedef struct _usb_pm {
uint8_t power_mode; /*!< power mode */
uint8_t power_low; /*!< power low */
uint8_t dev_remote_wakeup; /*!< remote wakeup */
uint8_t remote_wakeup_on; /*!< remote wakeup on */
} usb_pm;
/* USB control information */
typedef struct _usb_control {
usb_req req; /*!< USB standard device request */
uint8_t ctl_state; /*!< USB control transfer state */
uint8_t ctl_zlp; /*!< zero lenth package */
} usb_control;
typedef struct
{
struct {
uint8_t num: 4; /*!< the endpoint number.it can be from 0 to 6 */
uint8_t pad: 3; /*!< padding between number and direction */
uint8_t dir: 1; /*!< the endpoint direction */
} ep_addr;
uint8_t ep_type; /*!< USB endpoint type */
uint8_t ep_stall; /*!< USB endpoint stall status */
uint8_t frame_num; /*!< number of frame */
uint16_t max_len; /*!< Maximum packet lenth */
/* transaction level variables */
uint8_t *xfer_buf; /*!< transmit buffer */
uint32_t xfer_len; /*!< transmit buffer length */
uint32_t xfer_count; /*!< transmit buffer count */
uint32_t remain_len; /*!< remain packet lenth */
uint32_t dma_addr; /*!< DMA address */
} usb_transc;
typedef struct _usb_core_driver usb_dev;
typedef struct _usb_class_core
{
uint8_t command; /*!< device class request command */
uint8_t alter_set; /*!< alternative set */
uint8_t (*init) (usb_dev *udev, uint8_t config_index); /*!< initialize handler */
uint8_t (*deinit) (usb_dev *udev, uint8_t config_index); /*!< de-initialize handler */
uint8_t (*req_proc) (usb_dev *udev, usb_req *req); /*!< device request handler */
uint8_t (*data_in) (usb_dev *udev, uint8_t ep_num); /*!< device data in handler */
uint8_t (*data_out) (usb_dev *udev, uint8_t ep_num); /*!< device data out handler */
uint8_t (*SOF) (usb_dev *udev); /*!< Start of frame handler */
uint8_t (*incomplete_isoc_in) (usb_dev *udev); /*!< Incomplete synchronization IN transfer handler */
uint8_t (*incomplete_isoc_out) (usb_dev *udev); /*!< Incomplete synchronization OUT transfer handler */
} usb_class_core;
typedef struct _usb_perp_dev
{
uint8_t config; /*!< configuration */
uint8_t dev_addr; /*!< device address */
__IO uint8_t cur_status; /*!< current status */
__IO uint8_t backup_status; /*!< backup status */
usb_transc transc_in[USBFS_MAX_TX_FIFOS]; /*!< endpoint IN transaction */
usb_transc transc_out[USBFS_MAX_TX_FIFOS]; /*!< endpoint OUT transaction */
usb_pm pm; /*!< power management */
usb_desc desc; /*!< USB descriptors */
usb_control control; /*!< USB control information */
usb_class_core *class_core; /*!< class driver */
} usb_perp_dev;
typedef struct _usb_core_driver
{
usb_core_basic bp; /*!< USB basic parameters */
usb_core_regs regs; /*!< USB registers */
usb_perp_dev dev; /*!< USB peripheral device */
} usb_core_driver;
/* function declarations */
/* initialize USB core registers for device mode */
usb_status usb_devcore_init (usb_core_driver *udev);
/* enable the USB device mode interrupts */
usb_status usb_devint_enable (usb_core_driver *udev);
/* active the usb transaction */
usb_status usb_transc_active (usb_core_driver *udev, usb_transc *transc);
/* deactive the usb transaction */
usb_status usb_transc_deactivate (usb_core_driver *udev, usb_transc *transc);
/* configure usb transaction to start IN transfer */
usb_status usb_transc_inxfer (usb_core_driver *udev, usb_transc *transc);
/* configure usb transaction to start OUT transfer */
usb_status usb_transc_outxfer (usb_core_driver *udev, usb_transc *transc);
/* set the usb transaction STALL status */
usb_status usb_transc_stall (usb_core_driver *udev, usb_transc *transc);
/* clear the usb transaction STALL status */
usb_status usb_transc_clrstall (usb_core_driver *udev, usb_transc *transc);
/* read device all OUT endpoint interrupt register */
uint32_t usb_oepintnum_read (usb_core_driver *udev);
/* read device OUT endpoint interrupt flag register */
uint32_t usb_oepintr_read (usb_core_driver *udev, uint8_t ep_num);
/* read device all IN endpoint interrupt register */
uint32_t usb_iepintnum_read (usb_core_driver *udev);
/* read device IN endpoint interrupt flag register */
uint32_t usb_iepintr_read (usb_core_driver *udev, uint8_t ep_num);
/* config the USB device to be disconnected */
void usb_dev_disconnect (usb_core_driver *udev);
/* config the USB device to be connected */
void usb_dev_connect (usb_core_driver *udev);
/* set the USB device address */
void usb_devaddr_set (usb_core_driver *pudev, uint8_t dev_addr);
/* configures OUT endpoint 0 to receive SETUP packets */
void usb_ctlep_startout (usb_core_driver *udev);
/* active remote wakeup signalling */
void usb_rwkup_active (usb_core_driver *udev);
/* reset remote wakeup signalling */
void usb_rwkup_reset (usb_core_driver *udev);
/* set remote wakeup signalling */
void usb_rwkup_set (usb_core_driver *udev);
/* active USB core clock */
void usb_clock_active (usb_core_driver *udev);
/* usb device suspend */
void usb_dev_suspend (usb_core_driver *udev);
/* stop the device and clean up fifos */
void usb_dev_stop (usb_core_driver *udev);
#endif /* __DRV_USB_DEV_H */

View File

@@ -0,0 +1,175 @@
/*!
\file drv_usb_host.h
\brief USB host mode low level driver header file
\version 2019-6-5, V1.0.0, firmware for GD32 USBFS&USBHS
*/
/*
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 __DRV_USB_HOST_H
#define __DRV_USB_HOST_H
#include "drv_usb_regs.h"
#include "usb_ch9_std.h"
#include "drv_usb_core.h"
typedef enum _usb_pipe_status
{
PIPE_IDLE = 0U,
PIPE_XF,
PIPE_HALTED,
PIPE_NAK,
PIPE_NYET,
PIPE_STALL,
PIPE_TRACERR,
PIPE_BBERR,
PIPE_REQOVR,
PIPE_DTGERR,
} usb_pipe_staus;
typedef enum _usb_pipe_mode
{
PIPE_PERIOD = 0U,
PIPE_NON_PERIOD = 1U
} usb_pipe_mode;
typedef enum _usb_urb_state
{
URB_IDLE = 0U,
URB_DONE,
URB_NOTREADY,
URB_ERROR,
URB_STALL
} usb_urb_state;
typedef struct _usb_pipe
{
uint8_t in_used;
uint8_t dev_addr;
uint32_t dev_speed;
struct {
uint8_t num;
uint8_t dir;
uint8_t type;
uint16_t mps;
} ep;
uint8_t ping;
uint32_t DPID;
uint8_t *xfer_buf;
uint32_t xfer_len;
uint32_t xfer_count;
uint8_t data_toggle_in;
uint8_t data_toggle_out;
__IO uint32_t err_count;
__IO usb_pipe_staus pp_status;
__IO usb_urb_state urb_state;
} usb_pipe;
typedef struct _usb_host_drv
{
uint8_t rx_buf[512U];
__IO uint32_t connect_status;
__IO uint32_t port_enabled;
__IO uint32_t backup_xfercount[USBFS_MAX_TX_FIFOS];
usb_pipe pipe[USBFS_MAX_TX_FIFOS];
} usb_host_drv;
typedef struct _usb_core_driver
{
usb_core_basic bp;
usb_core_regs regs;
usb_host_drv host;
} usb_core_driver;
/* initializes USB core for host mode */
usb_status usb_host_init (usb_core_driver *pudev);
/* initialize host pipe */
usb_status usb_pipe_init (usb_core_driver *pudev, uint8_t pipe_num);
/* prepare host pipe for transferring packets */
usb_status usb_pipe_xfer (usb_core_driver *pudev, uint8_t pipe_num);
/* halt host pipe */
usb_status usb_pipe_halt (usb_core_driver *pudev, uint8_t pipe_num);
/* configure host pipe to do ping operation */
usb_status usb_pipe_ping (usb_core_driver *pudev, uint8_t pipe_num);
/* reset host port */
uint32_t usb_port_reset (usb_core_driver *pudev);
/* control the VBUS to power */
void usb_portvbus_switch (usb_core_driver *pudev, uint8_t state);
/* stop the USB host and clean up FIFO */
void usb_host_stop (usb_core_driver *pudev);
//__STATIC_INLINE uint8_t usb_frame_even (usb_core_driver *pudev)
uint32_t usb_frame_even (usb_core_driver *pudev);
//{
// return !(pudev->regs.hr->HFINFR & 0x01U);
//}
//__STATIC_INLINE void usb_phyclock_config (usb_core_driver *pudev, uint8_t clock)
void usb_phyclock_config (usb_core_driver *pudev, uint8_t clock) ;
//{
//pudev->regs.hr->HCTL &= ~HCTL_CLKSEL;
// pudev->regs.hr->HCTL |= clock;
//}
uint32_t usb_port_read (usb_core_driver *pudev);
//inline uint32_t usb_port_read (usb_core_driver *pudev)
//{
// return *pudev->regs.HPCS & ~(HPCS_PE | HPCS_PCD | HPCS_PEDC);
//}
uint32_t usb_curspeed_get (usb_core_driver *pudev);
//inline uint32_t usb_curspeed_get (usb_core_driver *pudev)
//{
// return *pudev->regs.HPCS & HPCS_PS;
//}
//__STATIC_INLINE uint32_t usb_curframe_get (usb_core_driver *pudev)
uint32_t usb_curframe_get (usb_core_driver *pudev);
//{
// return (pudev->regs.hr->HFINFR & 0xFFFFU);
//}
#endif /* __DRV_USB_HOST_H */

View File

@@ -0,0 +1,61 @@
/*!
\file drv_usb_hw.h
\brief usb hardware configuration header file
\version 2019-6-5, V1.0.0, firmware for GD32 USBFS&USBHS
*/
/*
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 __DRV_USB_HW_H
#define __DRV_USB_HW_H
#include "usb_conf.h"
/* configure USB clock */
void usb_rcu_config (void);
/* configure USB interrupt */
void usb_intr_config (void);
/* initializes delay unit using Timer2 */
void usb_timer_init (void);
/* delay in micro seconds */
void usb_udelay (const uint32_t usec);
/* delay in milli seconds */
void usb_mdelay (const uint32_t msec);
// Functions for USE_HOST_MODE
/* configure USB VBus */
void usb_vbus_config (void);
/* drive usb VBus */
void usb_vbus_drive (uint8_t State);
#endif /* __DRV_USB_HW_H */

View File

@@ -0,0 +1,666 @@
/*!
\file drv_usb_regs.h
\brief USB cell registers definition and handle macros
\version 2019-6-5, V1.0.0, firmware for GD32 USBFS&USBHS
*/
/*
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 __DRV_USB_REGS_H
#define __DRV_USB_REGS_H
#include "usb_conf.h"
#define USBHS_REG_BASE 0x40040000L /*!< base address of USBHS registers */
#define USBFS_REG_BASE 0x50000000L /*!< base address of USBFS registers */
#define USBFS_MAX_TX_FIFOS 15 /*!< FIFO number */
#define USBFS_MAX_PACKET_SIZE 64U /*!< USBFS max packet size */
#define USBFS_MAX_CHANNEL_COUNT 8U /*!< USBFS host channel count */
#define USBFS_MAX_EP_COUNT 4U /*!< USBFS device endpoint count */
#define USBFS_MAX_FIFO_WORDLEN 320U /*!< USBFS max fifo size in words */
#define USBHS_MAX_PACKET_SIZE 512U /*!< USBHS max packet size */
#define USBHS_MAX_CHANNEL_COUNT 12U /*!< USBHS host channel count */
#define USBHS_MAX_EP_COUNT 6U /*!< USBHS device endpoint count */
#define USBHS_MAX_FIFO_WORDLEN 1280U /*!< USBHS max fifo size in words */
#define USB_DATA_FIFO_OFFSET 0x1000U /*!< USB data fifo offset */
#define USB_DATA_FIFO_SIZE 0x1000U /*!< USB data fifo size */
typedef enum
{
USB_CORE_ENUM_HS = 0, /*!< USB core type is HS */
USB_CORE_ENUM_FS = 1 /*!< USB core type is FS */
} usb_core_enum;
enum usb_reg_offset {
USB_REG_OFFSET_CORE = 0x0000U, /*!< global OTG control and status register */
USB_REG_OFFSET_DEV = 0x0800U, /*!< device mode control and status registers */
USB_REG_OFFSET_EP = 0x0020U,
USB_REG_OFFSET_EP_IN = 0x0900U, /*!< device IN endpoint 0 control register */
USB_REG_OFFSET_EP_OUT = 0x0B00U, /*!< device OUT endpoint 0 control register */
USB_REG_OFFSET_HOST = 0x0400U, /*!< host control register */
USB_REG_OFFSET_CH = 0x0020U,
USB_REG_OFFSET_PORT = 0x0440U, /*!< host port control and status register */
USB_REG_OFFSET_CH_INOUT = 0x0500U, /*!< Host channel-x control registers */
USB_REG_OFFSET_PWRCLKCTL = 0x0E00U, /*!< power and clock register */
};
typedef struct
{
__IO uint32_t GOTGCS; /*!< USB global OTG control and status register 000h */
__IO uint32_t GOTGINTF; /*!< USB global OTG interrupt flag register 004h */
__IO uint32_t GAHBCS; /*!< USB global AHB control and status register 008h */
__IO uint32_t GUSBCS; /*!< USB global USB control and status register 00Ch */
__IO uint32_t GRSTCTL; /*!< USB global reset control register 010h */
__IO uint32_t GINTF; /*!< USB global interrupt flag register 014h */
__IO uint32_t GINTEN; /*!< USB global interrupt enable register 018h */
__IO uint32_t GRSTATR; /*!< USB receive status debug read register 01Ch */
__IO uint32_t GRSTATP; /*!< USB receive status and pop register 020h */
__IO uint32_t GRFLEN; /*!< USB global receive FIFO length register 024h */
__IO uint32_t DIEP0TFLEN_HNPTFLEN; /*!< USB device IN endpoint 0/host non-periodic transmit FIFO length register 028h */
__IO uint32_t HNPTFQSTAT; /*!< USB host non-periodic FIFO/queue status register 02Ch */
uint32_t Reserved30[2]; /*!< Reserved 030h */
__IO uint32_t GCCFG; /*!< USB global core configuration register 038h */
__IO uint32_t CID; /*!< USB core ID register 03Ch */
uint32_t Reserved40[48]; /*!< Reserved 040h-0FFh */
__IO uint32_t HPTFLEN; /*!< USB host periodic transmit FIFO length register 100h */
__IO uint32_t DIEPTFLEN[15]; /*!< USB device IN endpoint transmit FIFO length register 104h */
} usb_gr;
typedef struct
{
__IO uint32_t HCTL; /*!< USB host control register 400h */
__IO uint32_t HFT; /*!< USB host frame interval register 404h */
__IO uint32_t HFINFR; /*!< USB host frame information remaining register 408h */
uint32_t Reserved40C; /*!< Reserved 40Ch */
__IO uint32_t HPTFQSTAT; /*!< USB host periodic transmit FIFO/queue status register 410h */
__IO uint32_t HACHINT; /*!< USB host all channels interrupt register 414h */
__IO uint32_t HACHINTEN; /*!< USB host all channels interrupt enable register 418h */
} usb_hr;
typedef struct
{
__IO uint32_t HCHCTL; /*!< USB host channel control register 500h */
__IO uint32_t HCHSTCTL; /*!< Reserved 504h */
__IO uint32_t HCHINTF; /*!< USB host channel interrupt flag register 508h */
__IO uint32_t HCHINTEN; /*!< USB host channel interrupt enable register 50Ch */
__IO uint32_t HCHLEN; /*!< USB host channel transfer length register 510h */
__IO uint32_t HCHDMAADDR; /*!< USB host channel-x DMA address register 514h*/
uint32_t Reserved[2];
} usb_pr;
typedef struct
{
__IO uint32_t DCFG; /*!< USB device configuration register 800h */
__IO uint32_t DCTL; /*!< USB device control register 804h */
__IO uint32_t DSTAT; /*!< USB device status register 808h */
uint32_t Reserved0C; /*!< Reserved 80Ch */
__IO uint32_t DIEPINTEN; /*!< USB device IN endpoint common interrupt enable register 810h */
__IO uint32_t DOEPINTEN; /*!< USB device OUT endpoint common interrupt enable register 814h */
__IO uint32_t DAEPINT; /*!< USB device all endpoints interrupt register 818h */
__IO uint32_t DAEPINTEN; /*!< USB device all endpoints interrupt enable register 81Ch */
uint32_t Reserved20; /*!< Reserved 820h */
uint32_t Reserved24; /*!< Reserved 824h */
__IO uint32_t DVBUSDT; /*!< USB device VBUS discharge time register 828h */
__IO uint32_t DVBUSPT; /*!< USB device VBUS pulsing time register 82Ch */
__IO uint32_t DTHRCTL; /*!< dev thr 830h */
__IO uint32_t DIEPFEINTEN; /*!< USB Device IN endpoint FIFO empty interrupt enable register 834h */
__IO uint32_t DEP1INT; /*!< USB device endpoint 1 interrupt register 838h */
__IO uint32_t DEP1INTEN; /*!< USB device endpoint 1 interrupt enable register 83Ch */
uint32_t Reserved40; /*!< Reserved 840h */
__IO uint32_t DIEP1INTEN; /*!< USB device IN endpoint-1 interrupt enable register 844h */
uint32_t Reserved48[15]; /*!< Reserved 848-880h */
__IO uint32_t DOEP1INTEN; /*!< USB device OUT endpoint-1 interrupt enable register 884h */
} usb_dr;
typedef struct
{
__IO uint32_t DIEPCTL; /*!< USB device IN endpoint control register 900h + (EpNum * 20h) + 00h */
uint32_t Reserved04; /*!< Reserved 900h + (EpNum * 20h) + 04h */
__IO uint32_t DIEPINTF; /*!< USB device IN endpoint interrupt flag register 900h + (EpNum * 20h) + 08h */
uint32_t Reserved0C; /*!< Reserved 900h + (EpNum * 20h) + 0Ch */
__IO uint32_t DIEPLEN; /*!< USB device IN endpoint transfer length register 900h + (EpNum * 20h) + 10h */
__IO uint32_t DIEPDMAADDR; /*!< Device IN endpoint-x DMA address register 900h + (EpNum * 20h) + 14h */
__IO uint32_t DIEPTFSTAT; /*!< USB device IN endpoint transmit FIFO status register 900h + (EpNum * 20h) + 18h */
} usb_erin;
typedef struct
{
__IO uint32_t DOEPCTL; /*!< USB device IN endpoint control register B00h + (EpNum * 20h) + 00h */
uint32_t Reserved04; /*!< Reserved B00h + (EpNum * 20h) + 04h */
__IO uint32_t DOEPINTF; /*!< USB device IN endpoint interrupt flag register B00h + (EpNum * 20h) + 08h */
uint32_t Reserved0C; /*!< Reserved B00h + (EpNum * 20h) + 0Ch */
__IO uint32_t DOEPLEN; /*!< USB device IN endpoint transfer length register B00h + (EpNum * 20h) + 10h */
__IO uint32_t DOEPDMAADDR; /*!< Device OUT endpoint-x DMA address register B00h + (EpNum * 20h) + 0Ch */
} usb_erout;
typedef struct _usb_regs
{
usb_gr *gr; /*!< USBFS global registers */
usb_dr *dr; /*!< Device control and status registers */
usb_hr *hr; /*!< Host control and status registers */
usb_erin *er_in[6]; /*!< USB device IN endpoint register */
usb_erout *er_out[6]; /*!< USB device OUT endpoint register */
usb_pr *pr[15]; /*!< USB Host channel-x control register */
__IO uint32_t *HPCS; /*!< USB host port control and status register */
__IO uint32_t *DFIFO[USBFS_MAX_TX_FIFOS];
__IO uint32_t *PWRCLKCTL; /*!< USB power and clock control register */
} usb_core_regs;
/* global OTG control and status register bits definitions */
#define GOTGCS_BSV BIT(19) /*!< B-Session Valid */
#define GOTGCS_ASV BIT(18) /*!< A-session valid */
#define GOTGCS_DI BIT(17) /*!< debounce interval */
#define GOTGCS_CIDPS BIT(16) /*!< id pin status */
#define GOTGCS_DHNPEN BIT(11) /*!< device HNP enable */
#define GOTGCS_HHNPEN BIT(10) /*!< host HNP enable */
#define GOTGCS_HNPREQ BIT(9) /*!< HNP request */
#define GOTGCS_HNPS BIT(8) /*!< HNP successes */
#define GOTGCS_SRPREQ BIT(1) /*!< SRP request */
#define GOTGCS_SRPS BIT(0) /*!< SRP successes */
/* global OTG interrupt flag register bits definitions */
#define GOTGINTF_DF BIT(19) /*!< debounce finish */
#define GOTGINTF_ADTO BIT(18) /*!< A-device timeout */
#define GOTGINTF_HNPDET BIT(17) /*!< host negotiation request detected */
#define GOTGINTF_HNPEND BIT(9) /*!< HNP end */
#define GOTGINTF_SRPEND BIT(8) /*!< SRP end */
#define GOTGINTF_SESEND BIT(2) /*!< session end */
/* global AHB control and status register bits definitions */
#define GAHBCS_PTXFTH BIT(8) /*!< periodic Tx FIFO threshold */
#define GAHBCS_TXFTH BIT(7) /*!< tx FIFO threshold */
#define GAHBCS_DMAEN BIT(5) /*!< DMA function Enable */
#define GAHBCS_BURST BITS(1, 4) /*!< the AHB burst type used by DMA */
#define GAHBCS_GINTEN BIT(0) /*!< global interrupt enable */
/* global USB control and status register bits definitions */
#define GUSBCS_FDM BIT(30) /*!< force device mode */
#define GUSBCS_FHM BIT(29) /*!< force host mode */
#define GUSBCS_ULPIEOI BIT(21) /*!< ULPI external over-current indicator */
#define GUSBCS_ULPIEVD BIT(20) /*!< ULPI external VBUS driver */
#define GUSBCS_UTT BITS(10, 13) /*!< USB turnaround time */
#define GUSBCS_HNPCEN BIT(9) /*!< HNP capability enable */
#define GUSBCS_SRPCEN BIT(8) /*!< SRP capability enable */
#define GUSBCS_EMBPHY BIT(6) /*!< embedded PHY selected */
#define GUSBCS_TOC BITS(0, 2) /*!< timeout calibration */
/* global reset control register bits definitions */
#define GRSTCTL_DMAIDL BIT(31) /*!< DMA idle state */
#define GRSTCTL_DMABSY BIT(30) /*!< DMA busy */
#define GRSTCTL_TXFNUM BITS(6, 10) /*!< tx FIFO number */
#define GRSTCTL_TXFF BIT(5) /*!< tx FIFO flush */
#define GRSTCTL_RXFF BIT(4) /*!< rx FIFO flush */
#define GRSTCTL_HFCRST BIT(2) /*!< host frame counter reset */
#define GRSTCTL_HCSRST BIT(1) /*!< HCLK soft reset */
#define GRSTCTL_CSRST BIT(0) /*!< core soft reset */
/* global interrupt flag register bits definitions */
#define GINTF_WKUPIF BIT(31) /*!< wakeup interrupt flag */
#define GINTF_SESIF BIT(30) /*!< session interrupt flag */
#define GINTF_DISCIF BIT(29) /*!< disconnect interrupt flag */
#define GINTF_IDPSC BIT(28) /*!< id pin status change */
#define GINTF_PTXFEIF BIT(26) /*!< periodic tx FIFO empty interrupt flag */
#define GINTF_HCIF BIT(25) /*!< host channels interrupt flag */
#define GINTF_HPIF BIT(24) /*!< host port interrupt flag */
#define GINTF_PXNCIF BIT(21) /*!< periodic transfer not complete interrupt flag */
#define GINTF_ISOONCIF BIT(21) /*!< isochronous OUT transfer not complete interrupt flag */
#define GINTF_ISOINCIF BIT(20) /*!< isochronous IN transfer not complete interrupt flag */
#define GINTF_OEPIF BIT(19) /*!< OUT endpoint interrupt flag */
#define GINTF_IEPIF BIT(18) /*!< IN endpoint interrupt flag */
#define GINTF_EOPFIF BIT(15) /*!< end of periodic frame interrupt flag */
#define GINTF_ISOOPDIF BIT(14) /*!< isochronous OUT packet dropped interrupt flag */
#define GINTF_ENUMFIF BIT(13) /*!< enumeration finished */
#define GINTF_RST BIT(12) /*!< USB reset */
#define GINTF_SP BIT(11) /*!< USB suspend */
#define GINTF_ESP BIT(10) /*!< early suspend */
#define GINTF_GONAK BIT(7) /*!< global OUT NAK effective */
#define GINTF_GNPINAK BIT(6) /*!< global IN non-periodic NAK effective */
#define GINTF_NPTXFEIF BIT(5) /*!< non-periodic tx FIFO empty interrupt flag */
#define GINTF_RXFNEIF BIT(4) /*!< rx FIFO non-empty interrupt flag */
#define GINTF_SOF BIT(3) /*!< start of frame */
#define GINTF_OTGIF BIT(2) /*!< OTG interrupt flag */
#define GINTF_MFIF BIT(1) /*!< mode fault interrupt flag */
#define GINTF_COPM BIT(0) /*!< current operation mode */
/* global interrupt enable register bits definitions */
#define GINTEN_WKUPIE BIT(31) /*!< wakeup interrupt enable */
#define GINTEN_SESIE BIT(30) /*!< session interrupt enable */
#define GINTEN_DISCIE BIT(29) /*!< disconnect interrupt enable */
#define GINTEN_IDPSCIE BIT(28) /*!< id pin status change interrupt enable */
#define GINTEN_PTXFEIE BIT(26) /*!< periodic tx FIFO empty interrupt enable */
#define GINTEN_HCIE BIT(25) /*!< host channels interrupt enable */
#define GINTEN_HPIE BIT(24) /*!< host port interrupt enable */
#define GINTEN_IPXIE BIT(21) /*!< periodic transfer not complete interrupt enable */
#define GINTEN_ISOONCIE BIT(21) /*!< isochronous OUT transfer not complete interrupt enable */
#define GINTEN_ISOINCIE BIT(20) /*!< isochronous IN transfer not complete interrupt enable */
#define GINTEN_OEPIE BIT(19) /*!< OUT endpoints interrupt enable */
#define GINTEN_IEPIE BIT(18) /*!< IN endpoints interrupt enable */
#define GINTEN_EOPFIE BIT(15) /*!< end of periodic frame interrupt enable */
#define GINTEN_ISOOPDIE BIT(14) /*!< isochronous OUT packet dropped interrupt enable */
#define GINTEN_ENUMFIE BIT(13) /*!< enumeration finish enable */
#define GINTEN_RSTIE BIT(12) /*!< USB reset interrupt enable */
#define GINTEN_SPIE BIT(11) /*!< USB suspend interrupt enable */
#define GINTEN_ESPIE BIT(10) /*!< early suspend interrupt enable */
#define GINTEN_GONAKIE BIT(7) /*!< global OUT NAK effective interrupt enable */
#define GINTEN_GNPINAKIE BIT(6) /*!< global non-periodic IN NAK effective interrupt enable */
#define GINTEN_NPTXFEIE BIT(5) /*!< non-periodic Tx FIFO empty interrupt enable */
#define GINTEN_RXFNEIE BIT(4) /*!< receive FIFO non-empty interrupt enable */
#define GINTEN_SOFIE BIT(3) /*!< start of frame interrupt enable */
#define GINTEN_OTGIE BIT(2) /*!< OTG interrupt enable */
#define GINTEN_MFIE BIT(1) /*!< mode fault interrupt enable */
/* global receive status read and pop register bits definitions */
#define GRSTATRP_RPCKST BITS(17, 20) /*!< received packet status */
#define GRSTATRP_DPID BITS(15, 16) /*!< data PID */
#define GRSTATRP_BCOUNT BITS(4, 14) /*!< byte count */
#define GRSTATRP_CNUM BITS(0, 3) /*!< channel number */
#define GRSTATRP_EPNUM BITS(0, 3) /*!< endpoint number */
/* global receive FIFO length register bits definitions */
#define GRFLEN_RXFD BITS(0, 15) /*!< rx FIFO depth */
/* host non-periodic transmit FIFO length register bits definitions */
#define HNPTFLEN_HNPTXFD BITS(16, 31) /*!< non-periodic Tx FIFO depth */
#define HNPTFLEN_HNPTXRSAR BITS(0, 15) /*!< non-periodic Tx RAM start address */
/**
* @brief USB IN endpoint 0 transmit FIFO length register bits definitions
*/
#define DIEP0TFLEN_IEP0TXFD BITS(16, 31) /*!< IN Endpoint 0 Tx FIFO depth */
#define DIEP0TFLEN_IEP0TXRSAR BITS(0, 15) /*!< IN Endpoint 0 TX RAM start address */
/* host non-periodic transmit FIFO/queue status register bits definitions */
#define HNPTFQSTAT_NPTXRQTOP BITS(24, 30) /*!< top entry of the non-periodic Tx request queue */
#define HNPTFQSTAT_NPTXRQS BITS(16, 23) /*!< non-periodic Tx request queue space */
#define HNPTFQSTAT_NPTXFS BITS(0, 15) /*!< non-periodic Tx FIFO space */
#define HNPTFQSTAT_CNUM BITS(27, 30) /*!< channel number*/
#define HNPTFQSTAT_EPNUM BITS(27, 30) /*!< endpoint number */
#define HNPTFQSTAT_TYPE BITS(25, 26) /*!< token type */
#define HNPTFQSTAT_TMF BIT(24) /*!< terminate flag */
/* global core configuration register bits definitions */
#define GCCFG_VBUSIG BIT(21) /*!< vbus ignored */
#define GCCFG_SOFOEN BIT(20) /*!< SOF output enable */
#define GCCFG_VBUSBCEN BIT(19) /*!< the VBUS B-device comparer enable */
#define GCCFG_VBUSACEN BIT(18) /*!< the VBUS A-device comparer enable */
#define GCCFG_PWRON BIT(16) /*!< power on */
/* core ID register bits definitions */
#define CID_CID BITS(0, 31) /*!< core ID */
/* host periodic transmit FIFO length register bits definitions */
#define HPTFLEN_HPTXFD BITS(16, 31) /*!< host periodic Tx FIFO depth */
#define HPTFLEN_HPTXFSAR BITS(0, 15) /*!< host periodic Tx RAM start address */
/* device IN endpoint transmit FIFO length register bits definitions */
#define DIEPTFLEN_IEPTXFD BITS(16, 31) /*!< IN endpoint Tx FIFO x depth */
#define DIEPTFLEN_IEPTXRSAR BITS(0, 15) /*!< IN endpoint FIFOx Tx x RAM start address */
/* host control register bits definitions */
#define HCTL_SPDFSLS BIT(2) /*!< speed limited to FS and LS */
#define HCTL_CLKSEL BITS(0, 1) /*!< clock select for USB clock */
/* host frame interval register bits definitions */
#define HFT_FRI BITS(0, 15) /*!< frame interval */
/* host frame information remaining register bits definitions */
#define HFINFR_FRT BITS(16, 31) /*!< frame remaining time */
#define HFINFR_FRNUM BITS(0, 15) /*!< frame number */
/* host periodic transmit FIFO/queue status register bits definitions */
#define HPTFQSTAT_PTXREQT BITS(24, 31) /*!< top entry of the periodic Tx request queue */
#define HPTFQSTAT_PTXREQS BITS(16, 23) /*!< periodic Tx request queue space */
#define HPTFQSTAT_PTXFS BITS(0, 15) /*!< periodic Tx FIFO space */
#define HPTFQSTAT_OEFRM BIT(31) /*!< odd/eveb frame */
#define HPTFQSTAT_CNUM BITS(27, 30) /*!< channel number */
#define HPTFQSTAT_EPNUM BITS(27, 30) /*!< endpoint number */
#define HPTFQSTAT_TYPE BITS(25, 26) /*!< token type */
#define HPTFQSTAT_TMF BIT(24) /*!< terminate flag */
#define TFQSTAT_TXFS BITS(0, 15)
#define TFQSTAT_CNUM BITS(27, 30)
/* host all channels interrupt register bits definitions */
#define HACHINT_HACHINT BITS(0, 11) /*!< host all channel interrupts */
/* host all channels interrupt enable register bits definitions */
#define HACHINTEN_CINTEN BITS(0, 11) /*!< channel interrupt enable */
/* host port control and status register bits definitions */
#define HPCS_PS BITS(17, 18) /*!< port speed */
#define HPCS_PP BIT(12) /*!< port power */
#define HPCS_PLST BITS(10, 11) /*!< port line status */
#define HPCS_PRST BIT(8) /*!< port reset */
#define HPCS_PSP BIT(7) /*!< port suspend */
#define HPCS_PREM BIT(6) /*!< port resume */
#define HPCS_PEDC BIT(3) /*!< port enable/disable change */
#define HPCS_PE BIT(2) /*!< port enable */
#define HPCS_PCD BIT(1) /*!< port connect detected */
#define HPCS_PCST BIT(0) /*!< port connect status */
/* host channel-x control register bits definitions */
#define HCHCTL_CEN BIT(31) /*!< channel enable */
#define HCHCTL_CDIS BIT(30) /*!< channel disable */
#define HCHCTL_ODDFRM BIT(29) /*!< odd frame */
#define HCHCTL_DAR BITS(22, 28) /*!< device address */
#define HCHCTL_MPC BITS(20, 21) /*!< multiple packet count */
#define HCHCTL_EPTYPE BITS(18, 19) /*!< endpoint type */
#define HCHCTL_LSD BIT(17) /*!< low-speed device */
#define HCHCTL_EPDIR BIT(15) /*!< endpoint direction */
#define HCHCTL_EPNUM BITS(11, 14) /*!< endpoint number */
#define HCHCTL_MPL BITS(0, 10) /*!< maximum packet length */
/* host channel-x split transaction register bits definitions */
#define HCHSTCTL_SPLEN BIT(31) /*!< enable high-speed split transaction */
#define HCHSTCTL_CSPLT BIT(16) /*!< complete-split enable */
#define HCHSTCTL_ISOPCE BITS(14, 15) /*!< isochronous OUT payload continuation encoding */
#define HCHSTCTL_HADDR BITS(7, 13) /*!< HUB address */
#define HCHSTCTL_PADDR BITS(0, 6) /*!< port address */
/* host channel-x interrupt flag register bits definitions */
#define HCHINTF_DTER BIT(10) /*!< data toggle error */
#define HCHINTF_REQOVR BIT(9) /*!< request queue overrun */
#define HCHINTF_BBER BIT(8) /*!< babble error */
#define HCHINTF_USBER BIT(7) /*!< USB bus Error */
#define HCHINTF_NYET BIT(6) /*!< NYET */
#define HCHINTF_ACK BIT(5) /*!< ACK */
#define HCHINTF_NAK BIT(4) /*!< NAK */
#define HCHINTF_STALL BIT(3) /*!< STALL */
#define HCHINTF_DMAER BIT(2) /*!< DMA error */
#define HCHINTF_CH BIT(1) /*!< channel halted */
#define HCHINTF_TF BIT(0) /*!< transfer finished */
/* host channel-x interrupt enable register bits definitions */
#define HCHINTEN_DTERIE BIT(10) /*!< data toggle error interrupt enable */
#define HCHINTEN_REQOVRIE BIT(9) /*!< request queue overrun interrupt enable */
#define HCHINTEN_BBERIE BIT(8) /*!< babble error interrupt enable */
#define HCHINTEN_USBERIE BIT(7) /*!< USB bus error interrupt enable */
#define HCHINTEN_NYETIE BIT(6) /*!< NYET interrupt enable */
#define HCHINTEN_ACKIE BIT(5) /*!< ACK interrupt enable */
#define HCHINTEN_NAKIE BIT(4) /*!< NAK interrupt enable */
#define HCHINTEN_STALLIE BIT(3) /*!< STALL interrupt enable */
#define HCHINTEN_DMAERIE BIT(2) /*!< DMA error interrupt enable */
#define HCHINTEN_CHIE BIT(1) /*!< channel halted interrupt enable */
#define HCHINTEN_TFIE BIT(0) /*!< transfer finished interrupt enable */
/* host channel-x transfer length register bits definitions */
#define HCHLEN_PING BIT(31) /*!< PING token request */
#define HCHLEN_DPID BITS(29, 30) /*!< data PID */
#define HCHLEN_PCNT BITS(19, 28) /*!< packet count */
#define HCHLEN_TLEN BITS(0, 18) /*!< transfer length */
/* host channel-x DMA address register bits definitions */
#define HCHDMAADDR_DMAADDR BITS(0, 31) /*!< DMA address */
#define PORT_SPEED(x) (((uint32_t)(x) << 17) & HPCS_PS) /*!< Port speed */
#define PORT_SPEED_HIGH PORT_SPEED(0) /*!< high speed */
#define PORT_SPEED_FULL PORT_SPEED(1) /*!< full speed */
#define PORT_SPEED_LOW PORT_SPEED(2) /*!< low speed */
#define PIPE_CTL_DAR(x) (((uint32_t)(x) << 22) & HCHCTL_DAR) /*!< device address */
#define PIPE_CTL_EPTYPE(x) (((uint32_t)(x) << 18) & HCHCTL_EPTYPE) /*!< endpoint type */
#define PIPE_CTL_EPNUM(x) (((uint32_t)(x) << 11) & HCHCTL_EPNUM) /*!< endpoint number */
#define PIPE_CTL_EPDIR(x) (((uint32_t)(x) << 15) & HCHCTL_EPDIR) /*!< endpoint direction */
#define PIPE_CTL_EPMPL(x) (((uint32_t)(x) << 0) & HCHCTL_MPL) /*!< maximum packet length */
#define PIPE_CTL_LSD(x) (((uint32_t)(x) << 17) & HCHCTL_LSD) /*!< low-Speed device */
#define PIPE_XFER_PCNT(x) (((uint32_t)(x) << 19) & HCHLEN_PCNT) /*!< packet count */
#define PIPE_XFER_DPID(x) (((uint32_t)(x) << 29) & HCHLEN_DPID) /*!< data PID */
#define PIPE_DPID_DATA0 PIPE_XFER_DPID(0) /*!< DATA0 */
#define PIPE_DPID_DATA1 PIPE_XFER_DPID(2) /*!< DATA1 */
#define PIPE_DPID_DATA2 PIPE_XFER_DPID(1) /*!< DATA2 */
#define PIPE_DPID_SETUP PIPE_XFER_DPID(3) /*!< MDATA (non-control)/SETUP (control) */
extern const uint32_t PIPE_DPID[];
/* device configuration registers bits definitions */
#define DCFG_EOPFT BITS(11, 12) /*!< end of periodic frame time */
#define DCFG_DAR BITS(4, 10) /*!< device address */
#define DCFG_NZLSOH BIT(2) /*!< non-zero-length status OUT handshake */
#define DCFG_DS BITS(0, 1) /*!< device speed */
/* device control registers bits definitions */
#define DCTL_POIF BIT(11) /*!< power-on initialization finished */
#define DCTL_CGONAK BIT(10) /*!< clear global OUT NAK */
#define DCTL_SGONAK BIT(9) /*!< set global OUT NAK */
#define DCTL_CGINAK BIT(8) /*!< clear global IN NAK */
#define DCTL_SGINAK BIT(7) /*!< set global IN NAK */
#define DCTL_GONS BIT(3) /*!< global OUT NAK status */
#define DCTL_GINS BIT(2) /*!< global IN NAK status */
#define DCTL_SD BIT(1) /*!< soft disconnect */
#define DCTL_RWKUP BIT(0) /*!< remote wakeup */
/* device status registers bits definitions */
#define DSTAT_FNRSOF BITS(8, 21) /*!< the frame number of the received SOF. */
#define DSTAT_ES BITS(1, 2) /*!< enumerated speed */
#define DSTAT_SPST BIT(0) /*!< suspend status */
/* device IN endpoint common interrupt enable registers bits definitions */
#define DIEPINTEN_NAKEN BIT(13) /*!< NAK handshake sent by USBHS interrupt enable bit */
#define DIEPINTEN_TXFEEN BIT(7) /*!< transmit FIFO empty interrupt enable bit */
#define DIEPINTEN_IEPNEEN BIT(6) /*!< IN endpoint NAK effective interrupt enable bit */
#define DIEPINTEN_EPTXFUDEN BIT(4) /*!< endpoint Tx FIFO underrun interrupt enable bit */
#define DIEPINTEN_CITOEN BIT(3) /*!< control In Timeout interrupt enable bit */
#define DIEPINTEN_EPDISEN BIT(1) /*!< endpoint disabled interrupt enable bit */
#define DIEPINTEN_TFEN BIT(0) /*!< transfer finished interrupt enable bit */
/* device OUT endpoint common interrupt enable registers bits definitions */
#define DOEPINTEN_NYETEN BIT(14) /*!< NYET handshake is sent interrupt enable bit */
#define DOEPINTEN_BTBSTPEN BIT(6) /*!< back-to-back SETUP packets interrupt enable bit */
#define DOEPINTEN_EPRXFOVREN BIT(4) /*!< endpoint Rx FIFO overrun interrupt enable bit */
#define DOEPINTEN_STPFEN BIT(3) /*!< SETUP phase finished interrupt enable bit */
#define DOEPINTEN_EPDISEN BIT(1) /*!< endpoint disabled interrupt enable bit */
#define DOEPINTEN_TFEN BIT(0) /*!< transfer finished interrupt enable bit */
/* device all endpoints interrupt registers bits definitions */
#define DAEPINT_OEPITB BITS(16, 21) /*!< device all OUT endpoint interrupt bits */
#define DAEPINT_IEPITB BITS(0, 5) /*!< device all IN endpoint interrupt bits */
/* device all endpoints interrupt enable registers bits definitions */
#define DAEPINTEN_OEPIE BITS(16, 21) /*!< OUT endpoint interrupt enable */
#define DAEPINTEN_IEPIE BITS(0, 3) /*!< IN endpoint interrupt enable */
/* device Vbus discharge time registers bits definitions */
#define DVBUSDT_DVBUSDT BITS(0, 15) /*!< device VBUS discharge time */
/* device Vbus pulsing time registers bits definitions */
#define DVBUSPT_DVBUSPT BITS(0, 11) /*!< device VBUS pulsing time */
/* device IN endpoint FIFO empty interrupt enable register bits definitions */
#define DIEPFEINTEN_IEPTXFEIE BITS(0, 5) /*!< IN endpoint Tx FIFO empty interrupt enable bits */
/* device endpoint 0 control register bits definitions */
#define DEP0CTL_EPEN BIT(31) /*!< endpoint enable */
#define DEP0CTL_EPD BIT(30) /*!< endpoint disable */
#define DEP0CTL_SNAK BIT(27) /*!< set NAK */
#define DEP0CTL_CNAK BIT(26) /*!< clear NAK */
#define DIEP0CTL_TXFNUM BITS(22, 25) /*!< tx FIFO number */
#define DEP0CTL_STALL BIT(21) /*!< STALL handshake */
#define DOEP0CTL_SNOOP BIT(20) /*!< snoop mode */
#define DEP0CTL_EPTYPE BITS(18, 19) /*!< endpoint type */
#define DEP0CTL_NAKS BIT(17) /*!< NAK status */
#define DEP0CTL_EPACT BIT(15) /*!< endpoint active */
#define DEP0CTL_MPL BITS(0, 1) /*!< maximum packet length */
/* device endpoint x control register bits definitions */
#define DEPCTL_EPEN BIT(31) /*!< endpoint enable */
#define DEPCTL_EPD BIT(30) /*!< endpoint disable */
#define DEPCTL_SODDFRM BIT(29) /*!< set odd frame */
#define DEPCTL_SD1PID BIT(29) /*!< set DATA1 PID */
#define DEPCTL_SEVNFRM BIT(28) /*!< set even frame */
#define DEPCTL_SD0PID BIT(28) /*!< set DATA0 PID */
#define DEPCTL_SNAK BIT(27) /*!< set NAK */
#define DEPCTL_CNAK BIT(26) /*!< clear NAK */
#define DIEPCTL_TXFNUM BITS(22, 25) /*!< tx FIFO number */
#define DEPCTL_STALL BIT(21) /*!< STALL handshake */
#define DOEPCTL_SNOOP BIT(20) /*!< snoop mode */
#define DEPCTL_EPTYPE BITS(18, 19) /*!< endpoint type */
#define DEPCTL_NAKS BIT(17) /*!< NAK status */
#define DEPCTL_EOFRM BIT(16) /*!< even/odd frame */
#define DEPCTL_DPID BIT(16) /*!< endpoint data PID */
#define DEPCTL_EPACT BIT(15) /*!< endpoint active */
#define DEPCTL_MPL BITS(0, 10) /*!< maximum packet length */
/* device IN endpoint-x interrupt flag register bits definitions */
#define DIEPINTF_NAK BIT(13) /*!< NAK handshake sent by USBHS */
#define DIEPINTF_TXFE BIT(7) /*!< transmit FIFO empty */
#define DIEPINTF_IEPNE BIT(6) /*!< IN endpoint NAK effective */
#define DIEPINTF_EPTXFUD BIT(4) /*!< endpoint Tx FIFO underrun */
#define DIEPINTF_CITO BIT(3) /*!< control In Timeout interrupt */
#define DIEPINTF_EPDIS BIT(1) /*!< endpoint disabled */
#define DIEPINTF_TF BIT(0) /*!< transfer finished */
/* device OUT endpoint-x interrupt flag register bits definitions */
#define DOEPINTF_NYET BIT(14) /*!< NYET handshake is sent */
#define DOEPINTF_BTBSTP BIT(6) /*!< back-to-back SETUP packets */
#define DOEPINTF_EPRXFOVR BIT(4) /*!< endpoint Rx FIFO overrun */
#define DOEPINTF_STPF BIT(3) /*!< SETUP phase finished */
#define DOEPINTF_EPDIS BIT(1) /*!< endpoint disabled */
#define DOEPINTF_TF BIT(0) /*!< transfer finished */
/* device IN endpoint 0 transfer length register bits definitions */
#define DIEP0LEN_PCNT BITS(19, 20) /*!< packet count */
#define DIEP0LEN_TLEN BITS(0, 6) /*!< transfer length */
/* device OUT endpoint 0 transfer length register bits definitions */
#define DOEP0LEN_STPCNT BITS(29, 30) /*!< SETUP packet count */
#define DOEP0LEN_PCNT BIT(19) /*!< packet count */
#define DOEP0LEN_TLEN BITS(0, 6) /*!< transfer length */
/* device OUT endpoint-x transfer length register bits definitions */
#define DOEPLEN_RXDPID BITS(29, 30) /*!< received data PID */
#define DOEPLEN_STPCNT BITS(29, 30) /*!< SETUP packet count */
#define DIEPLEN_MCNT BITS(29, 30) /*!< multi count */
#define DEPLEN_PCNT BITS(19, 28) /*!< packet count */
#define DEPLEN_TLEN BITS(0, 18) /*!< transfer length */
/* device IN endpoint-x DMA address register bits definitions */
#define DIEPDMAADDR_DMAADDR BITS(0, 31) /*!< DMA address */
/* device OUT endpoint-x DMA address register bits definitions */
#define DOEPDMAADDR_DMAADDR BITS(0, 31) /*!< DMA address */
/* device IN endpoint-x transmit FIFO status register bits definitions */
#define DIEPTFSTAT_IEPTFS BITS(0, 15) /*!< IN endpoint Tx FIFO space remaining */
/* USB power and clock registers bits definition */
#define PWRCLKCTL_SHCLK BIT(1) /*!< stop HCLK */
#define PWRCLKCTL_SUCLK BIT(0) /*!< stop the USB clock */
#define RSTAT_GOUT_NAK 1U /* global OUT NAK (triggers an interrupt) */
#define RSTAT_DATA_UPDT 2U /* OUT data packet received */
#define RSTAT_XFER_COMP 3U /* OUT transfer completed (triggers an interrupt) */
#define RSTAT_SETUP_COMP 4U /* SETUP transaction completed (triggers an interrupt) */
#define RSTAT_SETUP_UPDT 6U /* SETUP data packet received */
#define DSTAT_EM_HS_PHY_30MHZ_60MHZ 0U /* USB enumerate speed use high-speed PHY clock in 30MHz or 60MHz */
#define DSTAT_EM_FS_PHY_30MHZ_60MHZ 1U /* USB enumerate speed use full-speed PHY clock in 30MHz or 60MHz */
#define DSTAT_EM_LS_PHY_6MHZ 2U /* USB enumerate speed use low-speed PHY clock in 6MHz */
#define DSTAT_EM_FS_PHY_48MHZ 3U /* USB enumerate speed use full-speed PHY clock in 48MHz */
#define DPID_DATA0 0U /* device endpoint data PID is DATA0 */
#define DPID_DATA1 2U /* device endpoint data PID is DATA1 */
#define DPID_DATA2 1U /* device endpoint data PID is DATA2 */
#define DPID_MDATA 3U /* device endpoint data PID is MDATA */
#define GAHBCS_DMAINCR(regval) (GAHBCS_BURST & ((regval) << 1U)) /*!< AHB burst type used by DMA*/
#define DMA_INCR0 GAHBCS_DMAINCR(0U) /*!< single burst type used by DMA*/
#define DMA_INCR1 GAHBCS_DMAINCR(1U) /*!< 4-beat incrementing burst type used by DMA*/
#define DMA_INCR4 GAHBCS_DMAINCR(3U) /*!< 8-beat incrementing burst type used by DMA*/
#define DMA_INCR8 GAHBCS_DMAINCR(5U) /*!< 16-beat incrementing burst type used by DMA*/
#define DMA_INCR16 GAHBCS_DMAINCR(7U) /*!< 32-beat incrementing burst type used by DMA*/
#define DCFG_PFRI(regval) (DCFG_EOPFT & ((regval) << 11U)) /*!< end of periodic frame time configuration */
#define FRAME_INTERVAL_80 DCFG_PFRI(0U) /*!< 80% of the frame time */
#define FRAME_INTERVAL_85 DCFG_PFRI(1U) /*!< 85% of the frame time */
#define FRAME_INTERVAL_90 DCFG_PFRI(2U) /*!< 90% of the frame time */
#define FRAME_INTERVAL_95 DCFG_PFRI(3U) /*!< 95% of the frame time */
#define DCFG_DEVSPEED(regval) (DCFG_DS & ((regval) << 0U)) /*!< device speed configuration */
#define USB_SPEED_EXP_HIGH DCFG_DEVSPEED(0U) /*!< device external PHY high speed */
#define USB_SPEED_EXP_FULL DCFG_DEVSPEED(1U) /*!< device external PHY full speed */
#define USB_SPEED_INP_FULL DCFG_DEVSPEED(3U) /*!< device internal PHY full speed */
#define DEP0_MPL(regval) (DEP0CTL_MPL & ((regval) << 0U)) /*!< maximum packet length configuration */
#define EP0MPL_64 DEP0_MPL(0U) /*!< maximum packet length 64 bytes */
#define EP0MPL_32 DEP0_MPL(1U) /*!< maximum packet length 32 bytes */
#define EP0MPL_16 DEP0_MPL(2U) /*!< maximum packet length 16 bytes */
#define EP0MPL_8 DEP0_MPL(3U) /*!< maximum packet length 8 bytes */
#define DOEP0_TLEN(regval) (DOEP0LEN_TLEN & ((regval) << 0)) /*!< Transfer length */
#define DOEP0_PCNT(regval) (DOEP0LEN_PCNT & ((regval) << 19)) /*!< Packet count */
#define DOEP0_STPCNT(regval) (DOEP0LEN_STPCNT & ((regval) << 29)) /*!< SETUP packet count */
#define USB_ULPI_PHY 1 /*!< ULPI interface external PHY */
#define USB_EMBEDDED_PHY 2 /*!< Embedded PHY */
#define GRXSTS_PKTSTS_IN 2
#define GRXSTS_PKTSTS_IN_XFER_COMP 3
#define GRXSTS_PKTSTS_DATA_TOGGLE_ERR 5
#define GRXSTS_PKTSTS_CH_HALTED 7
#define DEVICE_MODE 0 /*!< device mode */
#define HOST_MODE 1 /*!< host mode */
#define OTG_MODE 2 /*!< OTG mode */
#define HCTL_30_60MHZ 0 /*!< USB clock 30-60MHZ */
#define HCTL_48MHZ 1 /*!< USB clock 48MHZ */
#define HCTL_6MHZ 2 /*!< USB clock 6MHZ */
enum USB_SPEED {
USB_SPEED_UNKNOWN = 0, /*!< USB speed unknown */
USB_SPEED_LOW, /*!< USB speed low */
USB_SPEED_FULL, /*!< USB speed full */
USB_SPEED_HIGH /*!< USB speed high */
};
#define EP0_OUT ((uint8_t)0x00) /*!< endpoint out 0 */
#define EP0_IN ((uint8_t)0x80) /*!< endpoint in 0 */
#define EP1_OUT ((uint8_t)0x01) /*!< endpoint out 1 */
#define EP1_IN ((uint8_t)0x81) /*!< endpoint in 1 */
#define EP2_OUT ((uint8_t)0x02) /*!< endpoint out 2 */
#define EP2_IN ((uint8_t)0x82) /*!< endpoint in 2 */
#define EP3_OUT ((uint8_t)0x03) /*!< endpoint out 3 */
#define EP3_IN ((uint8_t)0x83) /*!< endpoint in 3 */
#endif /* __DRV_USB_REGS_H */

View File

@@ -1,8 +1,8 @@
/*!
\file rtc.h
\brief headfile of RTC check and config,time_show and time_adjust function
\file drv_usbd_int.h
\brief USB device mode interrupt header file
\version 2019-06-05, V1.0.0, firmware for GD32VF103
\version 2019-6-5, V1.0.0, firmware for GD32 USBFS&USBHS
*/
/*
@@ -31,24 +31,22 @@ WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWIS
ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY
OF SUCH DAMAGE.
*/
#ifdef __cplusplus
extern "C" {
#ifndef __DRV_USBD_INT_H
#define __DRV_USBD_INT_H
#include "drv_usb_core.h"
#include "drv_usb_dev.h"
/* USB device-mode interrupts global service routine handler */
void usbd_isr (usb_core_driver *udev);
#ifdef USB_HS_DEDICATED_EP1_ENABLED
uint32_t USBD_OTG_EP1IN_ISR_Handler (usb_core_driver *udev);
uint32_t USBD_OTG_EP1OUT_ISR_Handler (usb_core_driver *udev);
#endif
#ifndef __RTC_H
#define __RTC_H
#include "gd32vf103.h"
#include <stdio.h>
#endif /* __DRV_USBD_INT_H */
void rtc_configuration(void);
uint32_t time_regulate(void);
void time_adjust(void);
void time_display(uint32_t timevar);
void time_show(void);
uint8_t usart_scanf(uint32_t value);
#endif /* __RTC_H */
#ifdef __cplusplus
}
#endif

View File

@@ -1,8 +1,8 @@
/*!
\file gd32vf103_it.h
\brief the header file of the ISR
\file drv_usbh_int.h.h
\brief USB host mode interrupt management header file
\version 2019-06-05, V1.0.0, firmware for GD32VF103
\version 2019-6-5, V1.0.0, firmware for GD32 USBFS&USBHS
*/
/*
@@ -31,21 +31,19 @@ WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWIS
ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY
OF SUCH DAMAGE.
*/
#ifdef __cplusplus
extern "C" {
#endif
#ifndef GD32VF103_IT_H
#define GD32VF103_IT_H
#include "gd32vf103.h"
#ifndef __DRV_USBH_INT_H
#define __DRV_USBH_INT_H
/* function declarations */
/* this function handles USB wakeup interrupt handler */
void USBFS_WKUP_IRQHandler(void);
/* this function handles USBFS IRQ Handler */
void USBFS_IRQHandler(void);
#include "drv_usb_host.h"
#endif /* GD32VF103_IT_H */
#ifdef __cplusplus
}
#endif
typedef struct _usbh_int_cb
{
uint8_t (*SOF) (usb_core_driver *pudev);
} usbh_int_cb;
extern usbh_int_cb *usbh_int_fop;
uint32_t usbh_isr (usb_core_driver *pudev);
#endif /* __DRV_USBH_INT_H */

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