[bsp][gd32103c-eval] Add gd32103c-eval bsp

This commit is contained in:
iysheng 2021-01-04 14:12:40 +08:00
parent b8bd21f6bc
commit 01adbab9b7
77 changed files with 41061 additions and 0 deletions

70
bsp/gd32103c-eval/Kconfig Normal file
View File

@ -0,0 +1,70 @@
mainmenu "RT-Thread Configuration"
config BSP_DIR
string
option env="BSP_ROOT"
default "."
config RTT_DIR
string
option env="RTT_ROOT"
default "../.."
# you can change the RTT_ROOT default: "rt-thread"
# example : default "F:/git_repositories/rt-thread"
config PKGS_DIR
string
option env="PKGS_ROOT"
default "packages"
source "$RTT_DIR/Kconfig"
source "$PKGS_DIR/Kconfig"
config SOC_SERIES_GD32F1
bool
default y
config SOC_GD32103C
bool
select RT_USING_COMPONENTS_INIT
select RT_USING_USER_MAIN
select SOC_SERIES_GD32F1
default y
menu "On-chip Peripheral Drivers"
menuconfig BSP_USING_UART
bool "Enable UART"
default y
select RT_USING_SERIAL
if BSP_USING_UART
config BSP_USING_UART0
bool "using uart0"
default n
config BSP_USING_UART1
bool "using uart1"
default n
config BSP_USING_UART2
bool "using uart2"
default y
config BSP_USING_UART3
bool "using uart3"
default n
config BSP_USING_UART4
bool "using uart4"
default n
endif
menuconfig BSP_USING_ADC
bool "Enable ADC"
default n
select RT_USING_ADC
if BSP_USING_ADC
config BSP_USING_ADC0
bool "using adc0"
default n
config BSP_USING_ADC1
bool "using adc1"
default n
endif
endmenu

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,39 @@
/**
******************************************************************************
* @brief Configuration file.
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __GD32F10X_CONF_H
#define __GD32F10X_CONF_H
/* Includes ------------------------------------------------------------------*/
/* Comment the line below to disable peripheral header file inclusion */
#include "gd32f10x_adc.h"
#include "gd32f10x_bkp.h"
#include "gd32f10x_can.h"
#include "gd32f10x_crc.h"
#include "gd32f10x_dac.h"
#include "gd32f10x_dma.h"
#include "gd32f10x_eth.h"
#include "gd32f10x_exmc.h"
#include "gd32f10x_exti.h"
#include "gd32f10x_fmc.h"
#include "gd32f10x_gpio.h"
#include "gd32f10x_i2c.h"
#include "gd32f10x_iwdg.h"
#include "gd32f10x_mcudbg.h"
#include "gd32f10x_misc.h"
#include "gd32f10x_pwr.h"
#include "gd32f10x_rcc.h"
#include "gd32f10x_rcu.h"
#include "gd32f10x_rtc.h"
#include "gd32f10x_sdio.h"
#include "gd32f10x_spi.h"
#include "gd32f10x_timer.h"
#include "gd32f10x_usart.h"
#include "gd32f10x_wwdg.h"
#endif /* __GD32F10X_CONF_H */

View File

@ -0,0 +1,64 @@
/**
******************************************************************************
* @brief CMSIS Cortex-M3 Device Peripheral Access Layer System Header File.
******************************************************************************
*/
/** @addtogroup CMSIS
* @{
*/
/** @addtogroup GD32F10x_system
* @{
*/
/**
* @brief Define to prevent recursive inclusion
*/
#ifndef __SYSTEM_GD32F10X_H
#define __SYSTEM_GD32F10X_H
#ifdef __cplusplus
extern "C" {
#endif
/** @addtogroup GD32F10x_System_Includes
* @{
*/
/**
* @}
*/
/** @addtogroup GD32F10x_System_Exported_types
* @{
*/
extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */
/**
* @}
*/
/** @addtogroup GD32F10x_System_Exported_Functions
* @{
*/
extern void SystemInit(void);
extern void SystemCoreClockUpdate(void);
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif /*__SYSTEM_GD32F10X_H */
/**
* @}
*/
/**
* @}
*/

View File

@ -0,0 +1,213 @@
/*
* File : isr_tab.s
* This file is part of RT-Thread RTOS
* COPYRIGHT (C) 2021, RT-Thread Development Team
*
* Change Logs:
* Date Author Notes
* 2021-01-02 iysheng first implementation
*/
.syntax unified
.cpu cortex-m3
.fpu softvfp
.thumb
.global g_isr_vectors
.section .isr_vector,"a",%progbits
.type g_isr_vectors, STT_OBJECT
.weak Reset_Handler
g_isr_vectors:
.word _estack /* Top of Stack */
.word Reset_Handler /* Reset Handler */
.word NMI_Handler /* NMI Handler */
.word HardFault_Handler /* Hard Fault Handler */
.word MemManage_Handler /* MPU Fault Handler */
.word BusFault_Handler /* Bus Fault Handler */
.word UsageFault_Handler /* Usage Fault Handler */
.word 0 /* Reserved */
.word 0 /* Reserved */
.word 0 /* Reserved */
.word 0 /* Reserved */
.word SVC_Handler /* SVCall Handler */
.word DebugMon_Handler /* Debug Monitor Handler */
.word 0 /* Reserved */
.word PendSV_Handler /* PendSV Handler */
.word SysTick_Handler /* SysTick Handler */
/* external interrupts handler */
.word WWDGT_IRQHandler /* 16:Window Watchdog Timer */
.word LVD_IRQHandler /* 17:LVD through EXTI Line detect */
.word TAMPER_IRQHandler /* 18:Tamper through EXTI Line detect */
.word RTC_IRQHandler /* 19:RTC through EXTI Line */
.word FMC_IRQHandler /* 20:FMC */
.word RCU_CTC_IRQHandler /* 21:RCU and CTC */
.word EXTI0_IRQHandler /* 22:EXTI Line 0 */
.word EXTI1_IRQHandler /* 23:EXTI Line 1 */
.word EXTI2_IRQHandler /* 24:EXTI Line 2 */
.word EXTI3_IRQHandler /* 25:EXTI Line 3 */
.word EXTI4_IRQHandler /* 26:EXTI Line 4 */
.word DMA0_Channel0_IRQHandler /* 27:DMA0 Channel0 */
.word DMA0_Channel1_IRQHandler /* 28:DMA0 Channel1 */
.word DMA0_Channel2_IRQHandler /* 29:DMA0 Channel2 */
.word DMA0_Channel3_IRQHandler /* 30:DMA0 Channel3 */
.word DMA0_Channel4_IRQHandler /* 31:DMA0 Channel4 */
.word DMA0_Channel5_IRQHandler /* 32:DMA0 Channel5 */
.word DMA0_Channel6_IRQHandler /* 33:DMA0 Channel6 */
.word ADC0_1_IRQHandler /* 34:ADC0 and ADC1 */
.word USBD_HP_CAN0_TX_IRQHandler /* 35:USBD HP and CAN0 TX */
.word USBD_LP_CAN0_RX0_IRQHandler /* 36:USBD LP and CAN0 RX0 */
.word CAN0_RX1_IRQHandler /* 37:CAN0 RX1 */
.word CAN0_EWMC_IRQHandler /* 38:CAN0 EWMC */
.word EXTI5_9_IRQHandler /* 39:EXTI5 to EXTI9 */
.word TIMER0_BRK_IRQHandler /* 40:TIMER0 Break */
.word TIMER0_UP_IRQHandler /* 41:TIMER0 Update */
.word TIMER0_TRG_CMT_IRQHandler /* 42:TIMER0 Trigger and Commutation */
.word TIMER0_Channel_IRQHandler /* 43:TIMER0 Channel Capture Compare */
.word TIMER1_IRQHandler /* 44:TIMER1 */
.word TIMER2_IRQHandler /* 45:TIMER2 */
.word TIMER3_IRQHandler /* 46:TIMER3 */
.word I2C0_EV_IRQHandler /* 47:I2C0 Event */
.word I2C0_ER_IRQHandler /* 48:I2C0 Error */
.word I2C1_EV_IRQHandler /* 49:I2C1 Event */
.word I2C1_ER_IRQHandler /* 50:I2C1 Error */
.word SPI0_IRQHandler /* 51:SPI0 */
.word SPI1_IRQHandler /* 52:SPI1 */
.word USART0_IRQHandler /* 53:USART0 */
.word USART1_IRQHandler /* 54:USART1 */
.word USART2_IRQHandler /* 55:USART2 */
.word EXTI10_15_IRQHandler /* 56:EXTI10 to EXTI15 */
.word RTC_Alarm_IRQHandler /* 57:RTC Alarm */
.word USBD_WKUP_IRQHandler /* 58:USBD Wakeup */
.word TIMER7_BRK_IRQHandler /* 59:TIMER7 Break */
.word TIMER7_UP_IRQHandler /* 60:TIMER7 Update */
.word TIMER7_TRG_CMT_IRQHandler /* 61:TIMER7 Trigger and Commutation */
.word TIMER7_Channel_IRQHandler /* 62:TIMER7 Channel Capture Compare */
.word ADC2_IRQHandler /* 63:ADC2 */
.word EXMC_IRQHandler /* 64:EXMC */
.word SDIO_IRQHandler /* 65:SDIO */
.word TIMER4_IRQHandler /* 66:TIMER4 */
.word SPI2_IRQHandler /* 67:SPI2 */
.word UART3_IRQHandler /* 68:UART3 */
.word UART4_IRQHandler /* 69:UART4 */
.word TIMER5_IRQHandler /* 70:TIMER5 */
.word TIMER6_IRQHandler /* 71:TIMER6 */
.word DMA1_Channel0_IRQHandler /* 72:DMA1 Channel0 */
.word DMA1_Channel1_IRQHandler /* 73:DMA1 Channel1 */
.word DMA1_Channel2_IRQHandler /* 74:DMA1 Channel2 */
.word DMA1_Channel3_4_IRQHandler /* 75:DMA1 Channel3 and Channel4 */
/* Exception Handlers */
.weak NMI_Handler
.type NMI_Handler, STT_FUNC
NMI_Handler:
b .
.weak MemManage_Handler
.type MemManage_Handler, STT_FUNC
MemManage_Handler:
b .
.weak BusFault_Handler
.type BusFault_Handler, STT_FUNC
BusFault_Handler:
b .
.weak UsageFault_Handler
.type UsageFault_Handler, STT_FUNC
UsageFault_Handler:
b .
.weak SVC_Handler
.type SVC_Handler, STT_FUNC
SVC_Handler:
b .
.weak DebugMon_Handler
.type DebugMon_Handler, STT_FUNC
DebugMon_Handler:
b .
.weak PendSV_Handler
.type PendSV_Handler, STT_FUNC
PendSV_Handler:
b .
.weak SysTick_Handler
.type SysTick_Handler, STT_FUNC
SysTick_Handler:
b .
.global default_irq_handler
.section .text.default_irq_handler,"ax",%progbits
.type default_irq_handler, STT_FUNC
default_irq_handler:
b .
.macro IRQ handler
.weak \handler
.set \handler, default_irq_handler
.endm
/* IQR Handler */
IRQ WWDGT_IRQHandler
IRQ LVD_IRQHandler
IRQ TAMPER_IRQHandler
IRQ RTC_IRQHandler
IRQ FMC_IRQHandler
IRQ RCU_CTC_IRQHandler
IRQ EXTI0_IRQHandler
IRQ EXTI1_IRQHandler
IRQ EXTI2_IRQHandler
IRQ EXTI3_IRQHandler
IRQ EXTI4_IRQHandler
IRQ DMA0_Channel0_IRQHandler
IRQ DMA0_Channel1_IRQHandler
IRQ DMA0_Channel2_IRQHandler
IRQ DMA0_Channel3_IRQHandler
IRQ DMA0_Channel4_IRQHandler
IRQ DMA0_Channel5_IRQHandler
IRQ DMA0_Channel6_IRQHandler
IRQ ADC0_1_IRQHandler
IRQ USBD_HP_CAN0_TX_IRQHandler
IRQ USBD_LP_CAN0_RX0_IRQHandler
IRQ CAN0_RX1_IRQHandler
IRQ CAN0_EWMC_IRQHandler
IRQ EXTI5_9_IRQHandler
IRQ TIMER0_BRK_IRQHandler
IRQ TIMER0_UP_IRQHandler
IRQ TIMER0_TRG_CMT_IRQHandler
IRQ TIMER0_Channel_IRQHandler
IRQ TIMER1_IRQHandler
IRQ TIMER2_IRQHandler
IRQ TIMER3_IRQHandler
IRQ I2C0_EV_IRQHandler
IRQ I2C0_ER_IRQHandler
IRQ I2C1_EV_IRQHandler
IRQ I2C1_ER_IRQHandler
IRQ SPI0_IRQHandler
IRQ SPI1_IRQHandler
IRQ USART0_IRQHandler
IRQ USART1_IRQHandler
IRQ USART2_IRQHandler
IRQ EXTI10_15_IRQHandler
IRQ RTC_Alarm_IRQHandler
IRQ USBD_WKUP_IRQHandler
IRQ TIMER7_BRK_IRQHandler
IRQ TIMER7_UP_IRQHandler
IRQ TIMER7_TRG_CMT_IRQHandler
IRQ TIMER7_Channel_IRQHandler
IRQ ADC2_IRQHandler
IRQ EXMC_IRQHandler
IRQ SDIO_IRQHandler
IRQ TIMER4_IRQHandler
IRQ SPI2_IRQHandler
IRQ UART3_IRQHandler
IRQ UART4_IRQHandler
IRQ TIMER5_IRQHandler
IRQ TIMER6_IRQHandler
IRQ DMA1_Channel0_IRQHandler
IRQ DMA1_Channel1_IRQHandler
IRQ DMA1_Channel2_IRQHandler
IRQ DMA1_Channel3_4_IRQHandler

View File

@ -0,0 +1,48 @@
/*
* File : startup_gd32f10x_hd.s
* This file is part of RT-Thread RTOS
* COPYRIGHT (C) 2006 - 2021, RT-Thread Development Team
*
* Change Logs:
* Date Author Notes
* 2021-01-02 iysheng first implementation
*/
.syntax unified
.cpu cortex-m3
.fpu softvfp
.thumb
.global Reset_Handler
.section .text.Reset_Handler
.type Reset_Handler, STT_FUNC
Reset_Handler:
ldr r1, =_sidata
ldr r2, =_sdata
ldr r3, =_edata
subs r3, r2
ble fill_bss_start
loop_copy_data:
subs r3, #4
ldr r0, [r1,r3]
str r0, [r2,r3]
bgt loop_copy_data
fill_bss_start:
ldr r1, =__bss_start
ldr r2, =__bss_end
movs r0, 0
subs r2, r1
ble startup_enter
loop_fill_bss:
subs r2, #4
str r0, [r1, r2]
bgt loop_fill_bss
startup_enter:
bl SystemInit
bl entry

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,784 @@
/**************************************************************************//**
* @file core_cm3.c
* @brief CMSIS Cortex-M3 Core Peripheral Access Layer Source File
* @version V1.30
* @date 30. October 2009
*
* @note
* Copyright (C) 2009 ARM Limited. All rights reserved.
*
* @par
* ARM Limited (ARM) is supplying this software for use with Cortex-M
* processor based microcontrollers. This file can be freely distributed
* within development tools that are supporting such ARM based processors.
*
* @par
* THIS SOFTWARE IS PROVIDED "AS IS". NO WARRANTIES, WHETHER EXPRESS, IMPLIED
* OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF
* MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE.
* ARM SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, OR
* CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER.
*
******************************************************************************/
#include <stdint.h>
/* define compiler specific symbols */
#if defined ( __CC_ARM )
#define __ASM __asm /*!< asm keyword for ARM Compiler */
#define __INLINE __inline /*!< inline keyword for ARM Compiler */
#elif defined ( __ICCARM__ )
#define __ASM __asm /*!< asm keyword for IAR Compiler */
#define __INLINE inline /*!< inline keyword for IAR Compiler. Only avaiable in High optimization mode! */
#elif defined ( __GNUC__ )
#define __ASM __asm /*!< asm keyword for GNU Compiler */
#define __INLINE inline /*!< inline keyword for GNU Compiler */
#elif defined ( __TASKING__ )
#define __ASM __asm /*!< asm keyword for TASKING Compiler */
#define __INLINE inline /*!< inline keyword for TASKING Compiler */
#endif
/* ################### Compiler specific Intrinsics ########################### */
#if defined ( __CC_ARM ) /*------------------RealView Compiler -----------------*/
/* ARM armcc specific functions */
/**
* @brief Return the Process Stack Pointer
*
* @return ProcessStackPointer
*
* Return the actual process stack pointer
*/
__ASM uint32_t __get_PSP(void)
{
mrs r0, psp
bx lr
}
/**
* @brief Set the Process Stack Pointer
*
* @param topOfProcStack Process Stack Pointer
*
* Assign the value ProcessStackPointer to the MSP
* (process stack pointer) Cortex processor register
*/
__ASM void __set_PSP(uint32_t topOfProcStack)
{
msr psp, r0
bx lr
}
/**
* @brief Return the Main Stack Pointer
*
* @return Main Stack Pointer
*
* Return the current value of the MSP (main stack pointer)
* Cortex processor register
*/
__ASM uint32_t __get_MSP(void)
{
mrs r0, msp
bx lr
}
/**
* @brief Set the Main Stack Pointer
*
* @param topOfMainStack Main Stack Pointer
*
* Assign the value mainStackPointer to the MSP
* (main stack pointer) Cortex processor register
*/
__ASM void __set_MSP(uint32_t mainStackPointer)
{
msr msp, r0
bx lr
}
/**
* @brief Reverse byte order in unsigned short value
*
* @param value value to reverse
* @return reversed value
*
* Reverse byte order in unsigned short value
*/
__ASM uint32_t __REV16(uint16_t value)
{
rev16 r0, r0
bx lr
}
/**
* @brief Reverse byte order in signed short value with sign extension to integer
*
* @param value value to reverse
* @return reversed value
*
* Reverse byte order in signed short value with sign extension to integer
*/
__ASM int32_t __REVSH(int16_t value)
{
revsh r0, r0
bx lr
}
#if (__ARMCC_VERSION < 400000)
/**
* @brief Remove the exclusive lock created by ldrex
*
* Removes the exclusive lock which is created by ldrex.
*/
__ASM void __CLREX(void)
{
clrex
}
/**
* @brief Return the Base Priority value
*
* @return BasePriority
*
* Return the content of the base priority register
*/
__ASM uint32_t __get_BASEPRI(void)
{
mrs r0, basepri
bx lr
}
/**
* @brief Set the Base Priority value
*
* @param basePri BasePriority
*
* Set the base priority register
*/
__ASM void __set_BASEPRI(uint32_t basePri)
{
msr basepri, r0
bx lr
}
/**
* @brief Return the Priority Mask value
*
* @return PriMask
*
* Return state of the priority mask bit from the priority mask register
*/
__ASM uint32_t __get_PRIMASK(void)
{
mrs r0, primask
bx lr
}
/**
* @brief Set the Priority Mask value
*
* @param priMask PriMask
*
* Set the priority mask bit in the priority mask register
*/
__ASM void __set_PRIMASK(uint32_t priMask)
{
msr primask, r0
bx lr
}
/**
* @brief Return the Fault Mask value
*
* @return FaultMask
*
* Return the content of the fault mask register
*/
__ASM uint32_t __get_FAULTMASK(void)
{
mrs r0, faultmask
bx lr
}
/**
* @brief Set the Fault Mask value
*
* @param faultMask faultMask value
*
* Set the fault mask register
*/
__ASM void __set_FAULTMASK(uint32_t faultMask)
{
msr faultmask, r0
bx lr
}
/**
* @brief Return the Control Register value
*
* @return Control value
*
* Return the content of the control register
*/
__ASM uint32_t __get_CONTROL(void)
{
mrs r0, control
bx lr
}
/**
* @brief Set the Control Register value
*
* @param control Control value
*
* Set the control register
*/
__ASM void __set_CONTROL(uint32_t control)
{
msr control, r0
bx lr
}
#endif /* __ARMCC_VERSION */
#elif (defined (__ICCARM__)) /*------------------ ICC Compiler -------------------*/
/* IAR iccarm specific functions */
#pragma diag_suppress=Pe940
/**
* @brief Return the Process Stack Pointer
*
* @return ProcessStackPointer
*
* Return the actual process stack pointer
*/
uint32_t __get_PSP(void)
{
__ASM("mrs r0, psp");
__ASM("bx lr");
}
/**
* @brief Set the Process Stack Pointer
*
* @param topOfProcStack Process Stack Pointer
*
* Assign the value ProcessStackPointer to the MSP
* (process stack pointer) Cortex processor register
*/
void __set_PSP(uint32_t topOfProcStack)
{
__ASM("msr psp, r0");
__ASM("bx lr");
}
/**
* @brief Return the Main Stack Pointer
*
* @return Main Stack Pointer
*
* Return the current value of the MSP (main stack pointer)
* Cortex processor register
*/
uint32_t __get_MSP(void)
{
__ASM("mrs r0, msp");
__ASM("bx lr");
}
/**
* @brief Set the Main Stack Pointer
*
* @param topOfMainStack Main Stack Pointer
*
* Assign the value mainStackPointer to the MSP
* (main stack pointer) Cortex processor register
*/
void __set_MSP(uint32_t topOfMainStack)
{
__ASM("msr msp, r0");
__ASM("bx lr");
}
/**
* @brief Reverse byte order in unsigned short value
*
* @param value value to reverse
* @return reversed value
*
* Reverse byte order in unsigned short value
*/
uint32_t __REV16(uint16_t value)
{
__ASM("rev16 r0, r0");
__ASM("bx lr");
}
/**
* @brief Reverse bit order of value
*
* @param value value to reverse
* @return reversed value
*
* Reverse bit order of value
*/
uint32_t __RBIT(uint32_t value)
{
__ASM("rbit r0, r0");
__ASM("bx lr");
}
/**
* @brief LDR Exclusive (8 bit)
*
* @param *addr address pointer
* @return value of (*address)
*
* Exclusive LDR command for 8 bit values)
*/
uint8_t __LDREXB(uint8_t *addr)
{
__ASM("ldrexb r0, [r0]");
__ASM("bx lr");
}
/**
* @brief LDR Exclusive (16 bit)
*
* @param *addr address pointer
* @return value of (*address)
*
* Exclusive LDR command for 16 bit values
*/
uint16_t __LDREXH(uint16_t *addr)
{
__ASM("ldrexh r0, [r0]");
__ASM("bx lr");
}
/**
* @brief LDR Exclusive (32 bit)
*
* @param *addr address pointer
* @return value of (*address)
*
* Exclusive LDR command for 32 bit values
*/
uint32_t __LDREXW(uint32_t *addr)
{
__ASM("ldrex r0, [r0]");
__ASM("bx lr");
}
/**
* @brief STR Exclusive (8 bit)
*
* @param value value to store
* @param *addr address pointer
* @return successful / failed
*
* Exclusive STR command for 8 bit values
*/
uint32_t __STREXB(uint8_t value, uint8_t *addr)
{
__ASM("strexb r0, r0, [r1]");
__ASM("bx lr");
}
/**
* @brief STR Exclusive (16 bit)
*
* @param value value to store
* @param *addr address pointer
* @return successful / failed
*
* Exclusive STR command for 16 bit values
*/
uint32_t __STREXH(uint16_t value, uint16_t *addr)
{
__ASM("strexh r0, r0, [r1]");
__ASM("bx lr");
}
/**
* @brief STR Exclusive (32 bit)
*
* @param value value to store
* @param *addr address pointer
* @return successful / failed
*
* Exclusive STR command for 32 bit values
*/
uint32_t __STREXW(uint32_t value, uint32_t *addr)
{
__ASM("strex r0, r0, [r1]");
__ASM("bx lr");
}
#pragma diag_default=Pe940
#elif (defined (__GNUC__)) /*------------------ GNU Compiler ---------------------*/
/* GNU gcc specific functions */
/**
* @brief Return the Process Stack Pointer
*
* @return ProcessStackPointer
*
* Return the actual process stack pointer
*/
uint32_t __get_PSP(void) __attribute__((naked));
uint32_t __get_PSP(void)
{
uint32_t result = 0;
__ASM volatile("MRS %0, psp\n\t"
"MOV r0, %0 \n\t"
"BX lr \n\t" : "=r"(result));
return (result);
}
/**
* @brief Set the Process Stack Pointer
*
* @param topOfProcStack Process Stack Pointer
*
* Assign the value ProcessStackPointer to the MSP
* (process stack pointer) Cortex processor register
*/
void __set_PSP(uint32_t topOfProcStack) __attribute__((naked));
void __set_PSP(uint32_t topOfProcStack)
{
__ASM volatile("MSR psp, %0\n\t"
"BX lr \n\t" : : "r"(topOfProcStack));
}
/**
* @brief Return the Main Stack Pointer
*
* @return Main Stack Pointer
*
* Return the current value of the MSP (main stack pointer)
* Cortex processor register
*/
uint32_t __get_MSP(void) __attribute__((naked));
uint32_t __get_MSP(void)
{
uint32_t result = 0;
__ASM volatile("MRS %0, msp\n\t"
"MOV r0, %0 \n\t"
"BX lr \n\t" : "=r"(result));
return (result);
}
/**
* @brief Set the Main Stack Pointer
*
* @param topOfMainStack Main Stack Pointer
*
* Assign the value mainStackPointer to the MSP
* (main stack pointer) Cortex processor register
*/
void __set_MSP(uint32_t topOfMainStack) __attribute__((naked));
void __set_MSP(uint32_t topOfMainStack)
{
__ASM volatile("MSR msp, %0\n\t"
"BX lr \n\t" : : "r"(topOfMainStack));
}
/**
* @brief Return the Base Priority value
*
* @return BasePriority
*
* Return the content of the base priority register
*/
uint32_t __get_BASEPRI(void)
{
uint32_t result = 0;
__ASM volatile("MRS %0, basepri_max" : "=r"(result));
return (result);
}
/**
* @brief Set the Base Priority value
*
* @param basePri BasePriority
*
* Set the base priority register
*/
void __set_BASEPRI(uint32_t value)
{
__ASM volatile("MSR basepri, %0" : : "r"(value));
}
/**
* @brief Return the Priority Mask value
*
* @return PriMask
*
* Return state of the priority mask bit from the priority mask register
*/
uint32_t __get_PRIMASK(void)
{
uint32_t result = 0;
__ASM volatile("MRS %0, primask" : "=r"(result));
return (result);
}
/**
* @brief Set the Priority Mask value
*
* @param priMask PriMask
*
* Set the priority mask bit in the priority mask register
*/
void __set_PRIMASK(uint32_t priMask)
{
__ASM volatile("MSR primask, %0" : : "r"(priMask));
}
/**
* @brief Return the Fault Mask value
*
* @return FaultMask
*
* Return the content of the fault mask register
*/
uint32_t __get_FAULTMASK(void)
{
uint32_t result = 0;
__ASM volatile("MRS %0, faultmask" : "=r"(result));
return (result);
}
/**
* @brief Set the Fault Mask value
*
* @param faultMask faultMask value
*
* Set the fault mask register
*/
void __set_FAULTMASK(uint32_t faultMask)
{
__ASM volatile("MSR faultmask, %0" : : "r"(faultMask));
}
/**
* @brief Return the Control Register value
*
* @return Control value
*
* Return the content of the control register
*/
uint32_t __get_CONTROL(void)
{
uint32_t result = 0;
__ASM volatile("MRS %0, control" : "=r"(result));
return (result);
}
/**
* @brief Set the Control Register value
*
* @param control Control value
*
* Set the control register
*/
void __set_CONTROL(uint32_t control)
{
__ASM volatile("MSR control, %0" : : "r"(control));
}
/**
* @brief Reverse byte order in integer value
*
* @param value value to reverse
* @return reversed value
*
* Reverse byte order in integer value
*/
uint32_t __REV(uint32_t value)
{
uint32_t result = 0;
__ASM volatile("rev %0, %1" : "=r"(result) : "r"(value));
return (result);
}
/**
* @brief Reverse byte order in unsigned short value
*
* @param value value to reverse
* @return reversed value
*
* Reverse byte order in unsigned short value
*/
uint32_t __REV16(uint16_t value)
{
uint32_t result = 0;
__ASM volatile("rev16 %0, %1" : "=r"(result) : "r"(value));
return (result);
}
/**
* @brief Reverse byte order in signed short value with sign extension to integer
*
* @param value value to reverse
* @return reversed value
*
* Reverse byte order in signed short value with sign extension to integer
*/
int32_t __REVSH(int16_t value)
{
uint32_t result = 0;
__ASM volatile("revsh %0, %1" : "=r"(result) : "r"(value));
return (result);
}
/**
* @brief Reverse bit order of value
*
* @param value value to reverse
* @return reversed value
*
* Reverse bit order of value
*/
uint32_t __RBIT(uint32_t value)
{
uint32_t result = 0;
__ASM volatile("rbit %0, %1" : "=r"(result) : "r"(value));
return (result);
}
/**
* @brief LDR Exclusive (8 bit)
*
* @param *addr address pointer
* @return value of (*address)
*
* Exclusive LDR command for 8 bit value
*/
uint8_t __LDREXB(uint8_t *addr)
{
uint8_t result = 0;
__ASM volatile("ldrexb %0, [%1]" : "=r"(result) : "r"(addr));
return (result);
}
/**
* @brief LDR Exclusive (16 bit)
*
* @param *addr address pointer
* @return value of (*address)
*
* Exclusive LDR command for 16 bit values
*/
uint16_t __LDREXH(uint16_t *addr)
{
uint16_t result = 0;
__ASM volatile("ldrexh %0, [%1]" : "=r"(result) : "r"(addr));
return (result);
}
/**
* @brief LDR Exclusive (32 bit)
*
* @param *addr address pointer
* @return value of (*address)
*
* Exclusive LDR command for 32 bit values
*/
uint32_t __LDREXW(uint32_t *addr)
{
uint32_t result = 0;
__ASM volatile("ldrex %0, [%1]" : "=r"(result) : "r"(addr));
return (result);
}
/**
* @brief STR Exclusive (8 bit)
*
* @param value value to store
* @param *addr address pointer
* @return successful / failed
*
* Exclusive STR command for 8 bit values
*/
uint32_t __STREXB(uint8_t value, uint8_t *addr)
{
uint32_t result = 0;
__ASM volatile("strexb %0, %2, [%1]" : "=r"(result) : "r"(addr), "r"(value));
return (result);
}
/**
* @brief STR Exclusive (16 bit)
*
* @param value value to store
* @param *addr address pointer
* @return successful / failed
*
* Exclusive STR command for 16 bit values
*/
uint32_t __STREXH(uint16_t value, uint16_t *addr)
{
uint32_t result = 0;
__ASM volatile("strexh %0, %2, [%1]" : "=r"(result) : "r"(addr), "r"(value));
return (result);
}
/**
* @brief STR Exclusive (32 bit)
*
* @param value value to store
* @param *addr address pointer
* @return successful / failed
*
* Exclusive STR command for 32 bit values
*/
uint32_t __STREXW(uint32_t value, uint32_t *addr)
{
uint32_t result = 0;
__ASM volatile("strex %0, %2, [%1]" : "=r"(result) : "r"(addr), "r"(value));
return (result);
}
#elif (defined (__TASKING__)) /*------------------ TASKING Compiler ---------------------*/
/* TASKING carm specific functions */
/*
* The CMSIS functions have been implemented as intrinsics in the compiler.
* Please use "carm -?i" to get an up to date list of all instrinsics,
* Including the CMSIS ones.
*/
#endif

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,616 @@
/**************************************************************************//**
* @file core_cmFunc.h
* @brief CMSIS Cortex-M Core Function Access Header File
* @version V3.01
* @date 06. March 2012
*
* @note
* Copyright (C) 2009-2012 ARM Limited. All rights reserved.
*
* @par
* ARM Limited (ARM) is supplying this software for use with Cortex-M
* processor based microcontrollers. This file can be freely distributed
* within development tools that are supporting such ARM based processors.
*
* @par
* THIS SOFTWARE IS PROVIDED "AS IS". NO WARRANTIES, WHETHER EXPRESS, IMPLIED
* OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF
* MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE.
* ARM SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, OR
* CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER.
*
******************************************************************************/
#ifndef __CORE_CMFUNC_H
#define __CORE_CMFUNC_H
/* ########################### Core Function Access ########################### */
/** \ingroup CMSIS_Core_FunctionInterface
\defgroup CMSIS_Core_RegAccFunctions CMSIS Core Register Access Functions
@{
*/
#if defined ( __CC_ARM ) /*------------------RealView Compiler -----------------*/
/* ARM armcc specific functions */
#if (__ARMCC_VERSION < 400677)
#error "Please use ARM Compiler Toolchain V4.0.677 or later!"
#endif
/* intrinsic void __enable_irq(); */
/* intrinsic void __disable_irq(); */
/** \brief Get Control Register
This function returns the content of the Control Register.
\return Control Register value
*/
__STATIC_INLINE uint32_t __get_CONTROL(void)
{
register uint32_t __regControl __ASM("control");
return (__regControl);
}
/** \brief Set Control Register
This function writes the given value to the Control Register.
\param [in] control Control Register value to set
*/
__STATIC_INLINE void __set_CONTROL(uint32_t control)
{
register uint32_t __regControl __ASM("control");
__regControl = control;
}
/** \brief Get IPSR Register
This function returns the content of the IPSR Register.
\return IPSR Register value
*/
__STATIC_INLINE uint32_t __get_IPSR(void)
{
register uint32_t __regIPSR __ASM("ipsr");
return (__regIPSR);
}
/** \brief Get APSR Register
This function returns the content of the APSR Register.
\return APSR Register value
*/
__STATIC_INLINE uint32_t __get_APSR(void)
{
register uint32_t __regAPSR __ASM("apsr");
return (__regAPSR);
}
/** \brief Get xPSR Register
This function returns the content of the xPSR Register.
\return xPSR Register value
*/
__STATIC_INLINE uint32_t __get_xPSR(void)
{
register uint32_t __regXPSR __ASM("xpsr");
return (__regXPSR);
}
/** \brief Get Process Stack Pointer
This function returns the current value of the Process Stack Pointer (PSP).
\return PSP Register value
*/
__STATIC_INLINE uint32_t __get_PSP(void)
{
register uint32_t __regProcessStackPointer __ASM("psp");
return (__regProcessStackPointer);
}
/** \brief Set Process Stack Pointer
This function assigns the given value to the Process Stack Pointer (PSP).
\param [in] topOfProcStack Process Stack Pointer value to set
*/
__STATIC_INLINE void __set_PSP(uint32_t topOfProcStack)
{
register uint32_t __regProcessStackPointer __ASM("psp");
__regProcessStackPointer = topOfProcStack;
}
/** \brief Get Main Stack Pointer
This function returns the current value of the Main Stack Pointer (MSP).
\return MSP Register value
*/
__STATIC_INLINE uint32_t __get_MSP(void)
{
register uint32_t __regMainStackPointer __ASM("msp");
return (__regMainStackPointer);
}
/** \brief Set Main Stack Pointer
This function assigns the given value to the Main Stack Pointer (MSP).
\param [in] topOfMainStack Main Stack Pointer value to set
*/
__STATIC_INLINE void __set_MSP(uint32_t topOfMainStack)
{
register uint32_t __regMainStackPointer __ASM("msp");
__regMainStackPointer = topOfMainStack;
}
/** \brief Get Priority Mask
This function returns the current state of the priority mask bit from the Priority Mask Register.
\return Priority Mask value
*/
__STATIC_INLINE uint32_t __get_PRIMASK(void)
{
register uint32_t __regPriMask __ASM("primask");
return (__regPriMask);
}
/** \brief Set Priority Mask
This function assigns the given value to the Priority Mask Register.
\param [in] priMask Priority Mask
*/
__STATIC_INLINE void __set_PRIMASK(uint32_t priMask)
{
register uint32_t __regPriMask __ASM("primask");
__regPriMask = (priMask);
}
#if (__CORTEX_M >= 0x03)
/** \brief Enable FIQ
This function enables FIQ interrupts by clearing the F-bit in the CPSR.
Can only be executed in Privileged modes.
*/
#define __enable_fault_irq __enable_fiq
/** \brief Disable FIQ
This function disables FIQ interrupts by setting the F-bit in the CPSR.
Can only be executed in Privileged modes.
*/
#define __disable_fault_irq __disable_fiq
/** \brief Get Base Priority
This function returns the current value of the Base Priority register.
\return Base Priority register value
*/
__STATIC_INLINE uint32_t __get_BASEPRI(void)
{
register uint32_t __regBasePri __ASM("basepri");
return (__regBasePri);
}
/** \brief Set Base Priority
This function assigns the given value to the Base Priority register.
\param [in] basePri Base Priority value to set
*/
__STATIC_INLINE void __set_BASEPRI(uint32_t basePri)
{
register uint32_t __regBasePri __ASM("basepri");
__regBasePri = (basePri & 0xff);
}
/** \brief Get Fault Mask
This function returns the current value of the Fault Mask register.
\return Fault Mask register value
*/
__STATIC_INLINE uint32_t __get_FAULTMASK(void)
{
register uint32_t __regFaultMask __ASM("faultmask");
return (__regFaultMask);
}
/** \brief Set Fault Mask
This function assigns the given value to the Fault Mask register.
\param [in] faultMask Fault Mask value to set
*/
__STATIC_INLINE void __set_FAULTMASK(uint32_t faultMask)
{
register uint32_t __regFaultMask __ASM("faultmask");
__regFaultMask = (faultMask & (uint32_t)1);
}
#endif /* (__CORTEX_M >= 0x03) */
#if (__CORTEX_M == 0x04)
/** \brief Get FPSCR
This function returns the current value of the Floating Point Status/Control register.
\return Floating Point Status/Control register value
*/
__STATIC_INLINE uint32_t __get_FPSCR(void)
{
#if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
register uint32_t __regfpscr __ASM("fpscr");
return (__regfpscr);
#else
return (0);
#endif
}
/** \brief Set FPSCR
This function assigns the given value to the Floating Point Status/Control register.
\param [in] fpscr Floating Point Status/Control value to set
*/
__STATIC_INLINE void __set_FPSCR(uint32_t fpscr)
{
#if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
register uint32_t __regfpscr __ASM("fpscr");
__regfpscr = (fpscr);
#endif
}
#endif /* (__CORTEX_M == 0x04) */
#elif defined ( __ICCARM__ ) /*------------------ ICC Compiler -------------------*/
/* IAR iccarm specific functions */
#include <cmsis_iar.h>
#elif defined ( __TMS470__ ) /*---------------- TI CCS Compiler ------------------*/
/* TI CCS specific functions */
#include <cmsis_ccs.h>
#elif defined ( __GNUC__ ) /*------------------ GNU Compiler ---------------------*/
/* GNU gcc specific functions */
/** \brief Enable IRQ Interrupts
This function enables IRQ interrupts by clearing the I-bit in the CPSR.
Can only be executed in Privileged modes.
*/
__attribute__((always_inline)) __STATIC_INLINE void __enable_irq(void)
{
__ASM volatile("cpsie i");
}
/** \brief Disable IRQ Interrupts
This function disables IRQ interrupts by setting the I-bit in the CPSR.
Can only be executed in Privileged modes.
*/
__attribute__((always_inline)) __STATIC_INLINE void __disable_irq(void)
{
__ASM volatile("cpsid i");
}
/** \brief Get Control Register
This function returns the content of the Control Register.
\return Control Register value
*/
__attribute__((always_inline)) __STATIC_INLINE uint32_t __get_CONTROL(void)
{
uint32_t result;
__ASM volatile("MRS %0, control" : "=r"(result));
return (result);
}
/** \brief Set Control Register
This function writes the given value to the Control Register.
\param [in] control Control Register value to set
*/
__attribute__((always_inline)) __STATIC_INLINE void __set_CONTROL(uint32_t control)
{
__ASM volatile("MSR control, %0" : : "r"(control));
}
/** \brief Get IPSR Register
This function returns the content of the IPSR Register.
\return IPSR Register value
*/
__attribute__((always_inline)) __STATIC_INLINE uint32_t __get_IPSR(void)
{
uint32_t result;
__ASM volatile("MRS %0, ipsr" : "=r"(result));
return (result);
}
/** \brief Get APSR Register
This function returns the content of the APSR Register.
\return APSR Register value
*/
__attribute__((always_inline)) __STATIC_INLINE uint32_t __get_APSR(void)
{
uint32_t result;
__ASM volatile("MRS %0, apsr" : "=r"(result));
return (result);
}
/** \brief Get xPSR Register
This function returns the content of the xPSR Register.
\return xPSR Register value
*/
__attribute__((always_inline)) __STATIC_INLINE uint32_t __get_xPSR(void)
{
uint32_t result;
__ASM volatile("MRS %0, xpsr" : "=r"(result));
return (result);
}
/** \brief Get Process Stack Pointer
This function returns the current value of the Process Stack Pointer (PSP).
\return PSP Register value
*/
__attribute__((always_inline)) __STATIC_INLINE uint32_t __get_PSP(void)
{
register uint32_t result;
__ASM volatile("MRS %0, psp\n" : "=r"(result));
return (result);
}
/** \brief Set Process Stack Pointer
This function assigns the given value to the Process Stack Pointer (PSP).
\param [in] topOfProcStack Process Stack Pointer value to set
*/
__attribute__((always_inline)) __STATIC_INLINE void __set_PSP(uint32_t topOfProcStack)
{
__ASM volatile("MSR psp, %0\n" : : "r"(topOfProcStack));
}
/** \brief Get Main Stack Pointer
This function returns the current value of the Main Stack Pointer (MSP).
\return MSP Register value
*/
__attribute__((always_inline)) __STATIC_INLINE uint32_t __get_MSP(void)
{
register uint32_t result;
__ASM volatile("MRS %0, msp\n" : "=r"(result));
return (result);
}
/** \brief Set Main Stack Pointer
This function assigns the given value to the Main Stack Pointer (MSP).
\param [in] topOfMainStack Main Stack Pointer value to set
*/
__attribute__((always_inline)) __STATIC_INLINE void __set_MSP(uint32_t topOfMainStack)
{
__ASM volatile("MSR msp, %0\n" : : "r"(topOfMainStack));
}
/** \brief Get Priority Mask
This function returns the current state of the priority mask bit from the Priority Mask Register.
\return Priority Mask value
*/
__attribute__((always_inline)) __STATIC_INLINE uint32_t __get_PRIMASK(void)
{
uint32_t result;
__ASM volatile("MRS %0, primask" : "=r"(result));
return (result);
}
/** \brief Set Priority Mask
This function assigns the given value to the Priority Mask Register.
\param [in] priMask Priority Mask
*/
__attribute__((always_inline)) __STATIC_INLINE void __set_PRIMASK(uint32_t priMask)
{
__ASM volatile("MSR primask, %0" : : "r"(priMask));
}
#if (__CORTEX_M >= 0x03)
/** \brief Enable FIQ
This function enables FIQ interrupts by clearing the F-bit in the CPSR.
Can only be executed in Privileged modes.
*/
__attribute__((always_inline)) __STATIC_INLINE void __enable_fault_irq(void)
{
__ASM volatile("cpsie f");
}
/** \brief Disable FIQ
This function disables FIQ interrupts by setting the F-bit in the CPSR.
Can only be executed in Privileged modes.
*/
__attribute__((always_inline)) __STATIC_INLINE void __disable_fault_irq(void)
{
__ASM volatile("cpsid f");
}
/** \brief Get Base Priority
This function returns the current value of the Base Priority register.
\return Base Priority register value
*/
__attribute__((always_inline)) __STATIC_INLINE uint32_t __get_BASEPRI(void)
{
uint32_t result;
__ASM volatile("MRS %0, basepri_max" : "=r"(result));
return (result);
}
/** \brief Set Base Priority
This function assigns the given value to the Base Priority register.
\param [in] basePri Base Priority value to set
*/
__attribute__((always_inline)) __STATIC_INLINE void __set_BASEPRI(uint32_t value)
{
__ASM volatile("MSR basepri, %0" : : "r"(value));
}
/** \brief Get Fault Mask
This function returns the current value of the Fault Mask register.
\return Fault Mask register value
*/
__attribute__((always_inline)) __STATIC_INLINE uint32_t __get_FAULTMASK(void)
{
uint32_t result;
__ASM volatile("MRS %0, faultmask" : "=r"(result));
return (result);
}
/** \brief Set Fault Mask
This function assigns the given value to the Fault Mask register.
\param [in] faultMask Fault Mask value to set
*/
__attribute__((always_inline)) __STATIC_INLINE void __set_FAULTMASK(uint32_t faultMask)
{
__ASM volatile("MSR faultmask, %0" : : "r"(faultMask));
}
#endif /* (__CORTEX_M >= 0x03) */
#if (__CORTEX_M == 0x04)
/** \brief Get FPSCR
This function returns the current value of the Floating Point Status/Control register.
\return Floating Point Status/Control register value
*/
__attribute__((always_inline)) __STATIC_INLINE uint32_t __get_FPSCR(void)
{
#if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
uint32_t result;
__ASM volatile("VMRS %0, fpscr" : "=r"(result));
return (result);
#else
return (0);
#endif
}
/** \brief Set FPSCR
This function assigns the given value to the Floating Point Status/Control register.
\param [in] fpscr Floating Point Status/Control value to set
*/
__attribute__((always_inline)) __STATIC_INLINE void __set_FPSCR(uint32_t fpscr)
{
#if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
__ASM volatile("VMSR fpscr, %0" : : "r"(fpscr));
#endif
}
#endif /* (__CORTEX_M == 0x04) */
#elif defined ( __TASKING__ ) /*------------------ TASKING Compiler --------------*/
/* TASKING carm specific functions */
/*
* The CMSIS functions have been implemented as intrinsics in the compiler.
* Please use "carm -?i" to get an up to date list of all instrinsics,
* Including the CMSIS ones.
*/
#endif
/*@} end of CMSIS_Core_RegAccFunctions */
#endif /* __CORE_CMFUNC_H */

View File

@ -0,0 +1,618 @@
/**************************************************************************//**
* @file core_cmInstr.h
* @brief CMSIS Cortex-M Core Instruction Access Header File
* @version V3.01
* @date 06. March 2012
*
* @note
* Copyright (C) 2009-2012 ARM Limited. All rights reserved.
*
* @par
* ARM Limited (ARM) is supplying this software for use with Cortex-M
* processor based microcontrollers. This file can be freely distributed
* within development tools that are supporting such ARM based processors.
*
* @par
* THIS SOFTWARE IS PROVIDED "AS IS". NO WARRANTIES, WHETHER EXPRESS, IMPLIED
* OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF
* MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE.
* ARM SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, OR
* CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER.
*
******************************************************************************/
#ifndef __CORE_CMINSTR_H
#define __CORE_CMINSTR_H
/* ########################## Core Instruction Access ######################### */
/** \defgroup CMSIS_Core_InstructionInterface CMSIS Core Instruction Interface
Access to dedicated instructions
@{
*/
#if defined ( __CC_ARM ) /*------------------RealView Compiler -----------------*/
/* ARM armcc specific functions */
#if (__ARMCC_VERSION < 400677)
#error "Please use ARM Compiler Toolchain V4.0.677 or later!"
#endif
/** \brief No Operation
No Operation does nothing. This instruction can be used for code alignment purposes.
*/
#define __NOP __nop
/** \brief Wait For Interrupt
Wait For Interrupt is a hint instruction that suspends execution
until one of a number of events occurs.
*/
#define __WFI __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.
*/
#define __WFE __wfe
/** \brief Send Event
Send Event is a hint instruction. It causes an event to be signaled to the CPU.
*/
#define __SEV __sev
/** \brief Instruction Synchronization Barrier
Instruction Synchronization Barrier flushes the pipeline in the processor,
so that all instructions following the ISB are fetched from cache or
memory, after the instruction has been completed.
*/
#define __ISB() __isb(0xF)
/** \brief Data Synchronization Barrier
This function acts as a special kind of Data Memory Barrier.
It completes when all explicit memory accesses before this instruction complete.
*/
#define __DSB() __dsb(0xF)
/** \brief Data Memory Barrier
This function ensures the apparent order of the explicit memory operations before
and after the instruction, without ensuring their completion.
*/
#define __DMB() __dmb(0xF)
/** \brief Reverse byte order (32 bit)
This function reverses the byte order in integer value.
\param [in] value Value to reverse
\return Reversed value
*/
#define __REV __rev
/** \brief Reverse byte order (16 bit)
This function reverses the byte order in two unsigned short values.
\param [in] value Value to reverse
\return Reversed value
*/
__attribute__((section(".rev16_text"))) __STATIC_INLINE __ASM uint32_t __REV16(uint32_t value)
{
rev16 r0, r0
bx lr
}
/** \brief Reverse byte order in signed short value
This function reverses the byte order in a signed short value with sign extension to integer.
\param [in] value Value to reverse
\return Reversed value
*/
__attribute__((section(".revsh_text"))) __STATIC_INLINE __ASM int32_t __REVSH(int32_t value)
{
revsh r0, r0
bx lr
}
/** \brief Rotate Right in unsigned value (32 bit)
This function Rotate Right (immediate) provides the value of the contents of a register rotated by a variable number of bits.
\param [in] value Value to rotate
\param [in] value Number of Bits to rotate
\return Rotated value
*/
#define __ROR __ror
#if (__CORTEX_M >= 0x03)
/** \brief Reverse bit order of value
This function reverses the bit order of the given value.
\param [in] value Value to reverse
\return Reversed value
*/
#define __RBIT __rbit
/** \brief LDR Exclusive (8 bit)
This function performs a exclusive LDR command for 8 bit value.
\param [in] ptr Pointer to data
\return value of type uint8_t at (*ptr)
*/
#define __LDREXB(ptr) ((uint8_t ) __ldrex(ptr))
/** \brief LDR Exclusive (16 bit)
This function performs a exclusive LDR command for 16 bit values.
\param [in] ptr Pointer to data
\return value of type uint16_t at (*ptr)
*/
#define __LDREXH(ptr) ((uint16_t) __ldrex(ptr))
/** \brief LDR Exclusive (32 bit)
This function performs a exclusive LDR command for 32 bit values.
\param [in] ptr Pointer to data
\return value of type uint32_t at (*ptr)
*/
#define __LDREXW(ptr) ((uint32_t ) __ldrex(ptr))
/** \brief STR Exclusive (8 bit)
This function performs a exclusive STR command for 8 bit values.
\param [in] value Value to store
\param [in] ptr Pointer to location
\return 0 Function succeeded
\return 1 Function failed
*/
#define __STREXB(value, ptr) __strex(value, ptr)
/** \brief STR Exclusive (16 bit)
This function performs a exclusive STR command for 16 bit values.
\param [in] value Value to store
\param [in] ptr Pointer to location
\return 0 Function succeeded
\return 1 Function failed
*/
#define __STREXH(value, ptr) __strex(value, ptr)
/** \brief STR Exclusive (32 bit)
This function performs a exclusive STR command for 32 bit values.
\param [in] value Value to store
\param [in] ptr Pointer to location
\return 0 Function succeeded
\return 1 Function failed
*/
#define __STREXW(value, ptr) __strex(value, ptr)
/** \brief Remove the exclusive lock
This function removes the exclusive lock which is created by LDREX.
*/
#define __CLREX __clrex
/** \brief Signed Saturate
This function saturates a signed value.
\param [in] value Value to be saturated
\param [in] sat Bit position to saturate to (1..32)
\return Saturated value
*/
#define __SSAT __ssat
/** \brief Unsigned Saturate
This function saturates an unsigned value.
\param [in] value Value to be saturated
\param [in] sat Bit position to saturate to (0..31)
\return Saturated value
*/
#define __USAT __usat
/** \brief Count leading zeros
This function counts the number of leading zeros of a data value.
\param [in] value Value to count the leading zeros
\return number of leading zeros in value
*/
#define __CLZ __clz
#endif /* (__CORTEX_M >= 0x03) */
#elif defined ( __ICCARM__ ) /*------------------ ICC Compiler -------------------*/
/* IAR iccarm specific functions */
#include <cmsis_iar.h>
#elif defined ( __TMS470__ ) /*---------------- TI CCS Compiler ------------------*/
/* TI CCS specific functions */
#include <cmsis_ccs.h>
#elif defined ( __GNUC__ ) /*------------------ GNU Compiler ---------------------*/
/* GNU gcc specific functions */
/** \brief No Operation
No Operation does nothing. This instruction can be used for code alignment purposes.
*/
__attribute__((always_inline)) __STATIC_INLINE void __NOP(void)
{
__ASM volatile("nop");
}
/** \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("wfe");
}
/** \brief Send Event
Send Event is a hint instruction. It causes an event to be signaled to the CPU.
*/
__attribute__((always_inline)) __STATIC_INLINE void __SEV(void)
{
__ASM volatile("sev");
}
/** \brief Instruction Synchronization Barrier
Instruction Synchronization Barrier flushes the pipeline in the processor,
so that all instructions following the ISB are fetched from cache or
memory, after the instruction has been completed.
*/
__attribute__((always_inline)) __STATIC_INLINE void __ISB(void)
{
__ASM volatile("isb");
}
/** \brief Data Synchronization Barrier
This function acts as a special kind of Data Memory Barrier.
It completes when all explicit memory accesses before this instruction complete.
*/
__attribute__((always_inline)) __STATIC_INLINE void __DSB(void)
{
__ASM volatile("dsb");
}
/** \brief Data Memory Barrier
This function ensures the apparent order of the explicit memory operations before
and after the instruction, without ensuring their completion.
*/
__attribute__((always_inline)) __STATIC_INLINE void __DMB(void)
{
__ASM volatile("dmb");
}
/** \brief Reverse byte order (32 bit)
This function reverses the byte order in integer value.
\param [in] value Value to reverse
\return Reversed value
*/
__attribute__((always_inline)) __STATIC_INLINE uint32_t __REV(uint32_t value)
{
uint32_t result;
__ASM volatile("rev %0, %1" : "=r"(result) : "r"(value));
return (result);
}
/** \brief Reverse byte order (16 bit)
This function reverses the byte order in two unsigned short values.
\param [in] value Value to reverse
\return Reversed value
*/
__attribute__((always_inline)) __STATIC_INLINE uint32_t __REV16(uint32_t value)
{
uint32_t result;
__ASM volatile("rev16 %0, %1" : "=r"(result) : "r"(value));
return (result);
}
/** \brief Reverse byte order in signed short value
This function reverses the byte order in a signed short value with sign extension to integer.
\param [in] value Value to reverse
\return Reversed value
*/
__attribute__((always_inline)) __STATIC_INLINE int32_t __REVSH(int32_t value)
{
uint32_t result;
__ASM volatile("revsh %0, %1" : "=r"(result) : "r"(value));
return (result);
}
/** \brief Rotate Right in unsigned value (32 bit)
This function Rotate Right (immediate) provides the value of the contents of a register rotated by a variable number of bits.
\param [in] value Value to rotate
\param [in] value Number of Bits to rotate
\return Rotated value
*/
__attribute__((always_inline)) __STATIC_INLINE uint32_t __ROR(uint32_t op1, uint32_t op2)
{
__ASM volatile("ror %0, %0, %1" : "+r"(op1) : "r"(op2));
return (op1);
}
#if (__CORTEX_M >= 0x03)
/** \brief Reverse bit order of value
This function reverses the bit order of the given value.
\param [in] value Value to reverse
\return Reversed value
*/
__attribute__((always_inline)) __STATIC_INLINE uint32_t __RBIT(uint32_t value)
{
uint32_t result;
__ASM volatile("rbit %0, %1" : "=r"(result) : "r"(value));
return (result);
}
/** \brief LDR Exclusive (8 bit)
This function performs a exclusive LDR command for 8 bit value.
\param [in] ptr Pointer to data
\return value of type uint8_t at (*ptr)
*/
__attribute__((always_inline)) __STATIC_INLINE uint8_t __LDREXB(volatile uint8_t *addr)
{
uint8_t result;
__ASM volatile("ldrexb %0, [%1]" : "=r"(result) : "r"(addr));
return (result);
}
/** \brief LDR Exclusive (16 bit)
This function performs a exclusive LDR command for 16 bit values.
\param [in] ptr Pointer to data
\return value of type uint16_t at (*ptr)
*/
__attribute__((always_inline)) __STATIC_INLINE uint16_t __LDREXH(volatile uint16_t *addr)
{
uint16_t result;
__ASM volatile("ldrexh %0, [%1]" : "=r"(result) : "r"(addr));
return (result);
}
/** \brief LDR Exclusive (32 bit)
This function performs a exclusive LDR command for 32 bit values.
\param [in] ptr Pointer to data
\return value of type uint32_t at (*ptr)
*/
__attribute__((always_inline)) __STATIC_INLINE uint32_t __LDREXW(volatile uint32_t *addr)
{
uint32_t result;
__ASM volatile("ldrex %0, [%1]" : "=r"(result) : "r"(addr));
return (result);
}
/** \brief STR Exclusive (8 bit)
This function performs a exclusive STR command for 8 bit values.
\param [in] value Value to store
\param [in] ptr Pointer to location
\return 0 Function succeeded
\return 1 Function failed
*/
__attribute__((always_inline)) __STATIC_INLINE uint32_t __STREXB(uint8_t value, volatile uint8_t *addr)
{
uint32_t result;
__ASM volatile("strexb %0, %2, [%1]" : "=&r"(result) : "r"(addr), "r"(value));
return (result);
}
/** \brief STR Exclusive (16 bit)
This function performs a exclusive STR command for 16 bit values.
\param [in] value Value to store
\param [in] ptr Pointer to location
\return 0 Function succeeded
\return 1 Function failed
*/
__attribute__((always_inline)) __STATIC_INLINE uint32_t __STREXH(uint16_t value, volatile uint16_t *addr)
{
uint32_t result;
__ASM volatile("strexh %0, %2, [%1]" : "=&r"(result) : "r"(addr), "r"(value));
return (result);
}
/** \brief STR Exclusive (32 bit)
This function performs a exclusive STR command for 32 bit values.
\param [in] value Value to store
\param [in] ptr Pointer to location
\return 0 Function succeeded
\return 1 Function failed
*/
__attribute__((always_inline)) __STATIC_INLINE uint32_t __STREXW(uint32_t value, volatile uint32_t *addr)
{
uint32_t result;
__ASM volatile("strex %0, %2, [%1]" : "=&r"(result) : "r"(addr), "r"(value));
return (result);
}
/** \brief Remove the exclusive lock
This function removes the exclusive lock which is created by LDREX.
*/
__attribute__((always_inline)) __STATIC_INLINE void __CLREX(void)
{
__ASM volatile("clrex");
}
/** \brief Signed Saturate
This function saturates a signed value.
\param [in] value Value to be saturated
\param [in] sat Bit position to saturate to (1..32)
\return Saturated value
*/
#define __SSAT(ARG1,ARG2) \
({ \
uint32_t __RES, __ARG1 = (ARG1); \
__ASM ("ssat %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \
__RES; \
})
/** \brief Unsigned Saturate
This function saturates an unsigned value.
\param [in] value Value to be saturated
\param [in] sat Bit position to saturate to (0..31)
\return Saturated value
*/
#define __USAT(ARG1,ARG2) \
({ \
uint32_t __RES, __ARG1 = (ARG1); \
__ASM ("usat %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \
__RES; \
})
/** \brief Count leading zeros
This function counts the number of leading zeros of a data value.
\param [in] value Value to count the leading zeros
\return number of leading zeros in value
*/
__attribute__((always_inline)) __STATIC_INLINE uint8_t __CLZ(uint32_t value)
{
uint8_t result;
__ASM volatile("clz %0, %1" : "=r"(result) : "r"(value));
return (result);
}
#endif /* (__CORTEX_M >= 0x03) */
#elif defined ( __TASKING__ ) /*------------------ TASKING Compiler --------------*/
/* TASKING carm specific functions */
/*
* The CMSIS functions have been implemented as intrinsics in the compiler.
* Please use "carm -?i" to get an up to date list of all intrinsics,
* Including the CMSIS ones.
*/
#endif
/*@}*/ /* end of group CMSIS_Core_InstructionInterface */
#endif /* __CORE_CMINSTR_H */

View File

@ -0,0 +1,278 @@
/**
******************************************************************************
* @brief ADC header file of the firmware library.
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __GD32F10X_ADC_H
#define __GD32F10X_ADC_H
#ifdef __cplusplus
extern "C" {
#endif
typedef enum { FALSE = 0, TRUE } BOOL;
/* Includes ------------------------------------------------------------------*/
#include "gd32f10x.h"
/** @addtogroup GD32F10x_Firmware
* @{
*/
/** @addtogroup ADC
* @{
*/
/** @defgroup ADC_Exported_Types
* @{
*/
/**
* @brief ADC Init structure definition
*/
typedef struct {
uint32_t ADC_Trig_External; /*!< AD conversion of regular channels trigger. */
uint8_t ADC_Channel_Number; /*!< The number of converted ADC channels .
This parameter must range from 1 to 16. */
uint32_t ADC_Data_Align; /*!< ADC data alignment,left or right. */
TypeState ADC_Mode_Scan; /*!< AD conversion mode,multichannels mode or Single channel mode.
This parameter can be ENABLE or DISABLE */
uint32_t ADC_Mode; /*!< AD operation mode,independent mode or dual mode.
This parameter can be a value of @ref ADC_mode */
TypeState ADC_Mode_Continuous; /*!< AD perform mode,continuous mode or single mode.
This parameter can be ENABLE or DISABLE. */
} ADC_InitPara;
/**
* @}
*/
/** @defgroup ADC_Exported_Constants
* @{
*/
/** @defgroup ADC_external_trigger
* @{
*/
#define ADC_EXTERNAL_TRIGGER_MODE_T1_CC1 ((uint32_t)0x00000000) /*!< Only used in ADC1 and ADC2 */
#define ADC_EXTERNAL_TRIGGER_MODE_T1_CC2 ((uint32_t)0x00020000) /*!< Only used in ADC1 and ADC2 */
#define ADC_EXTERNAL_TRIGGER_MODE_T2_CC2 ((uint32_t)0x00060000) /*!< Only used in ADC1 and ADC2 */
#define ADC_EXTERNAL_TRIGGER_MODE_T3_TRGO ((uint32_t)0x00080000) /*!< Only used in ADC1 and ADC2 */
#define ADC_EXTERNAL_TRIGGER_MODE_T4_CC4 ((uint32_t)0x000A0000) /*!< Only used in ADC1 and ADC2 */
#define ADC_EXTERNAL_TRIGGER_MODE_EXT_IT11_T8_TRGO ((uint32_t)0x000C0000) /*!< Only used in ADC1 and ADC2 */
#define ADC_EXTERNAL_TRIGGER_MODE_T1_CC3 ((uint32_t)0x00040000) /*!< Used in ADC1,ADC2 and ADC3 */
#define ADC_EXTERNAL_TRIGGER_MODE_NONE ((uint32_t)0x000E0000) /*!< Used in ADC1,ADC2 and ADC3 */
#define ADC_EXTERNAL_TRIGGER_MODE_T3_CC1 ((uint32_t)0x00000000) /*!< Only used in ADC3 */
#define ADC_EXTERNAL_TRIGGER_MODE_T2_CC3 ((uint32_t)0x00020000) /*!< Only used in ADC3 */
#define ADC_EXTERNAL_TRIGGER_MODE_T8_CC1 ((uint32_t)0x00060000) /*!< Only used in ADC3 */
#define ADC_EXTERNAL_TRIGGER_MODE_T8_TRGO ((uint32_t)0x00080000) /*!< Only used in ADC3 */
#define ADC_EXTERNAL_TRIGGER_MODE_T5_CC1 ((uint32_t)0x000A0000) /*!< Only used in ADC3 */
#define ADC_EXTERNAL_TRIGGER_MODE_T5_CC3 ((uint32_t)0x000C0000) /*!< Only used in ADC3 */
/**
* @}
*/
/** @defgroup ADC_channels
* @{
*/
#define ADC_CHANNEL_0 ((uint8_t)0x00)
#define ADC_CHANNEL_1 ((uint8_t)0x01)
#define ADC_CHANNEL_2 ((uint8_t)0x02)
#define ADC_CHANNEL_3 ((uint8_t)0x03)
#define ADC_CHANNEL_4 ((uint8_t)0x04)
#define ADC_CHANNEL_5 ((uint8_t)0x05)
#define ADC_CHANNEL_6 ((uint8_t)0x06)
#define ADC_CHANNEL_7 ((uint8_t)0x07)
#define ADC_CHANNEL_8 ((uint8_t)0x08)
#define ADC_CHANNEL_9 ((uint8_t)0x09)
#define ADC_CHANNEL_10 ((uint8_t)0x0A)
#define ADC_CHANNEL_11 ((uint8_t)0x0B)
#define ADC_CHANNEL_12 ((uint8_t)0x0C)
#define ADC_CHANNEL_13 ((uint8_t)0x0D)
#define ADC_CHANNEL_14 ((uint8_t)0x0E)
#define ADC_CHANNEL_15 ((uint8_t)0x0F)
#define ADC_CHANNEL_16 ((uint8_t)0x10)
#define ADC_CHANNEL_17 ((uint8_t)0x11)
#define ADC_CHANNEL_TEMPSENSOR ((uint8_t)ADC_CHANNEL_16)
#define ADC_CHANNEL_VREFINT ((uint8_t)ADC_CHANNEL_17)
/**
* @}
*/
/** @defgroup ADC_data_align
* @{
*/
#define ADC_DATAALIGN_RIGHT ((uint32_t)0x00000000)
#define ADC_DATAALIGN_LEFT ((uint32_t)0x00000800)
/**
* @}
*/
/** @defgroup ADC_mode
* @{
*/
#define ADC_MODE_INDEPENDENT ((uint32_t)0x00000000)
#define ADC_MODE_REGINSERTSIMULT ((uint32_t)0x00010000)
#define ADC_MODE_REGSIMULT_ALTERTRIG ((uint32_t)0x00020000)
#define ADC_MODE_INSERTSIMULT_FASTINTERL ((uint32_t)0x00030000)
#define ADC_MODE_INSERTSIMULT_SLOWINTERL ((uint32_t)0x00040000)
#define ADC_MODE_INSERTSIMULT ((uint32_t)0x00050000)
#define ADC_MODE_REGSIMULT ((uint32_t)0x00060000)
#define ADC_MODE_FASTINTERL ((uint32_t)0x00070000)
#define ADC_MODE_SLOWINTERL ((uint32_t)0x00080000)
#define ADC_MODE_ALTERTRIG ((uint32_t)0x00090000)
/**
* @}
*/
/** @defgroup ADC_sampling_time
* @{
*/
#define ADC_SAMPLETIME_1POINT5 ((uint8_t)0x00)
#define ADC_SAMPLETIME_7POINT5 ((uint8_t)0x01)
#define ADC_SAMPLETIME_13POINT5 ((uint8_t)0x02)
#define ADC_SAMPLETIME_28POINT5 ((uint8_t)0x03)
#define ADC_SAMPLETIME_41POINT5 ((uint8_t)0x04)
#define ADC_SAMPLETIME_55POINT5 ((uint8_t)0x05)
#define ADC_SAMPLETIME_71POINT5 ((uint8_t)0x06)
#define ADC_SAMPLETIME_239POINT5 ((uint8_t)0x07)
/**
* @}
*/
/** @defgroup ADC_external_trigger_sources_for_inserted_channels_conversion
* @{
*/
#define ADC_EXTERNAL_TRIG_INSERTCONV_T2_TRGO ((uint32_t)0x00002000) /*!< Only used in ADC1 and ADC2 */
#define ADC_EXTERNAL_TRIG_INSERTCONV_T2_CC1 ((uint32_t)0x00003000) /*!< Only used in ADC1 and ADC2 */
#define ADC_EXTERNAL_TRIG_INSERTCONV_T3_CC4 ((uint32_t)0x00004000) /*!< Only used in ADC1 and ADC2 */
#define ADC_EXTERNAL_TRIG_INSERTCONV_T4_TRGO ((uint32_t)0x00005000) /*!< Only used in ADC1 and ADC2 */
#define ADC_EXTERNAL_TRIG_INSERTCONV_EXT_IT15_T8_CC4 ((uint32_t)0x00006000) /*!< Only used in ADC1 and ADC2 */
#define ADC_EXTERNAL_TRIG_INSERTCONV_T1_TRIG ((uint32_t)0x00000000) /*!< Used in ADC1,ADC2 and ADC3 */
#define ADC_EXTERNAL_TRIG_INSERTCONV_T1_CC4 ((uint32_t)0x00001000) /*!< Used in ADC1,ADC2 and ADC3 */
#define ADC_EXTERNAL_TRIG_INSERTCONV_NONE ((uint32_t)0x00007000) /*!< Used in ADC1,ADC2 and ADC3 */
#define ADC_EXTERNAL_TRIG_INSERTCONV_T4_CC3 ((uint32_t)0x00002000) /*!< Only used in ADC3 */
#define ADC_EXTERNAL_TRIG_INSERTCONV_T8_CC2 ((uint32_t)0x00003000) /*!< Only used in ADC3 */
#define ADC_EXTERNAL_TRIG_INSERTCONV_T8_CC4 ((uint32_t)0x00004000) /*!< Only used in ADC3 */
#define ADC_EXTERNAL_TRIG_INSERTCONV_T5_TRGO ((uint32_t)0x00005000) /*!< Only used in ADC3 */
#define ADC_EXTERNAL_TRIG_INSERTCONV_T5_CC4 ((uint32_t)0x00006000) /*!< Only used in ADC3 */
/**
* @}
*/
/** @defgroup ADC_inserted_channel_selection
* @{
*/
#define ADC_INSERTEDCHANNEL_1 ((uint8_t)0x14)
#define ADC_INSERTEDCHANNEL_2 ((uint8_t)0x18)
#define ADC_INSERTEDCHANNEL_3 ((uint8_t)0x1C)
#define ADC_INSERTEDCHANNEL_4 ((uint8_t)0x20)
/**
* @}
*/
/** @defgroup ADC_analog_watchdog_selection
* @{
*/
#define ADC_ANALOGWATCHDOG_SINGLEREGENABLE ((uint32_t)0x00800200)
#define ADC_ANALOGWATCHDOG_SINGLEINSERTENABLE ((uint32_t)0x00400200)
#define ADC_ANALOGWATCHDOG_SINGLEREGORINSERTENABLE ((uint32_t)0x00C00200)
#define ADC_ANALOGWATCHDOG_ALLREGENABLE ((uint32_t)0x00800000)
#define ADC_ANALOGWATCHDOG_ALLINSERTENABLE ((uint32_t)0x00400000)
#define ADC_ANALOGWATCHDOG_ALLREGALLINSERTENABLE ((uint32_t)0x00C00000)
#define ADC_ANALOGWATCHDOG_NONE ((uint32_t)0x00000000)
/**
* @}
*/
/** @defgroup ADC_interrupts_definition
* @{
*/
#define ADC_INT_EOC ((uint16_t)0x0220)
#define ADC_INT_AWE ((uint16_t)0x0140)
#define ADC_INT_EOIC ((uint16_t)0x0480)
/**
* @}
*/
/** @defgroup ADC_flags_definition
* @{
*/
#define ADC_FLAG_AWE ((uint8_t)0x01)
#define ADC_FLAG_EOC ((uint8_t)0x02)
#define ADC_FLAG_EOIC ((uint8_t)0x04)
#define ADC_FLAG_STIC ((uint8_t)0x08)
#define ADC_FLAG_STRC ((uint8_t)0x10)
/**
* @}
*/
/**
* @}
*/
/** @defgroup ADC_Exported_Functions
* @{
*/
void ADC_DeInit(ADC_TypeDef *ADCx, ADC_InitPara *ADC_InitParaStruct);
void ADC_Init(ADC_TypeDef *ADCx, ADC_InitPara *ADC_InitParaStruct);
void ADC_Enable(ADC_TypeDef *ADCx, TypeState NewValue);
void ADC_DMA_Enable(ADC_TypeDef *ADCx, TypeState NewValue);
void ADC_INTConfig(ADC_TypeDef *ADCx, uint16_t ADC_INT, TypeState NewValue);
void ADC_Calibration(ADC_TypeDef *ADCx);
void ADC_SoftwareStartConv_Enable(ADC_TypeDef *ADCx, TypeState NewValue);
TypeState ADC_GetSoftwareStartConvBitState(ADC_TypeDef *ADCx);
void ADC_DiscModeChannelCount_Config(ADC_TypeDef *ADCx, uint8_t Number);
void ADC_DiscMode_Enable(ADC_TypeDef *ADCx, TypeState NewValue);
void ADC_RegularChannel_Config(ADC_TypeDef *ADCx, uint8_t ADC_Channel, uint8_t Rank, uint8_t ADC_SampleTime);
void ADC_ExternalTrigConv_Enable(ADC_TypeDef *ADCx, TypeState NewValue);
uint16_t ADC_GetConversionValue(ADC_TypeDef *ADCx);
uint32_t ADC_GetDualModeConversionValue(void);
void ADC_AutoInsertedConv_Enable(ADC_TypeDef *ADCx, TypeState NewValue);
void ADC_InsertedDiscMode_Enable(ADC_TypeDef *ADCx, TypeState NewValue);
void ADC_ExternalTrigInsertedConv_Config(ADC_TypeDef *ADCx, uint32_t ADC_ExternalTrigInsertConv);
void ADC_ExternalTrigInsertedConv_Enable(ADC_TypeDef *ADCx, TypeState NewValue);
void ADC_SoftwareStartInsertedConv_Enable(ADC_TypeDef *ADCx, TypeState NewValue);
TypeState ADC_GetSoftwareStartInsertedConvCmdBitState(ADC_TypeDef *ADCx);
void ADC_InsertedChannel_Config(ADC_TypeDef *ADCx, uint8_t ADC_Channel, uint8_t Rank, uint8_t ADC_SampleTime);
void ADC_InsertedSequencerLength_Config(ADC_TypeDef *ADCx, uint8_t Length);
void ADC_SetInsertedOffset(ADC_TypeDef *ADCx, uint8_t ADC_InsertedChannel, uint16_t Offset);
uint16_t ADC_GetInsertedConversionValue(ADC_TypeDef *ADCx, uint8_t ADC_InsertedChannel);
void ADC_AnalogWatchdog_Enable(ADC_TypeDef *ADCx, uint32_t ADC_AnalogWatchdog);
void ADC_AnalogWatchdogThresholds_Config(ADC_TypeDef *ADCx, uint16_t HighThreshold, uint16_t LowThreshold);
void ADC_AnalogWatchdogSingleChannel_Config(ADC_TypeDef *ADCx, uint8_t ADC_Channel);
void ADC_TempSensorVrefint_Enable(TypeState NewValue);
TypeState ADC_GetBitState(ADC_TypeDef *ADCx, uint8_t ADC_FLAG);
void ADC_ClearBitState(ADC_TypeDef *ADCx, uint8_t ADC_FLAG);
TypeState ADC_GetIntState(ADC_TypeDef *ADCx, uint16_t ADC_INT);
void ADC_ClearIntBitState(ADC_TypeDef *ADCx, uint16_t ADC_INT);
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif /*__GD32F10X_ADC_H */

View File

@ -0,0 +1,139 @@
/**
******************************************************************************
* @brief BKP header file of the firmware library.
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __GD32F10X_BKP_H
#define __GD32F10X_BKP_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "gd32f10x.h"
/** @addtogroup GD32F10x_Firmware
* @{
*/
/** @addtogroup BKP
* @{
*/
/** @defgroup BKP_Exported_Constants
* @{
*/
/** @defgroup TAMPER_pin_active_level
* @{
*/
#define BKP_TPAL_HIGH ((uint16_t)0x0000)
#define BKP_TPAL_LOW ((uint16_t)0x0002)
/**
* @}
*/
/** @defgroup RTC_output_on_the_TAMPER_pin
* @{
*/
#define BKP_RTCOUTPUT_NULL ((uint16_t)0x0000)
#define BKP_RTCOUTPUT_CLKCAL ((uint16_t)0x0080)
#define BKP_RTCOUTPUT_ALARM ((uint16_t)0x0100)
#define BKP_RTCOUTPUT_SECOND ((uint16_t)0x0300)
/**
* @}
*/
/** @defgroup Backup_Data_Register
* @{
*/
#define BKP_DR1 ((uint16_t)0x0004)
#define BKP_DR2 ((uint16_t)0x0008)
#define BKP_DR3 ((uint16_t)0x000C)
#define BKP_DR4 ((uint16_t)0x0010)
#define BKP_DR5 ((uint16_t)0x0014)
#define BKP_DR6 ((uint16_t)0x0018)
#define BKP_DR7 ((uint16_t)0x001C)
#define BKP_DR8 ((uint16_t)0x0020)
#define BKP_DR9 ((uint16_t)0x0024)
#define BKP_DR10 ((uint16_t)0x0028)
#define BKP_DR11 ((uint16_t)0x0040)
#define BKP_DR12 ((uint16_t)0x0044)
#define BKP_DR13 ((uint16_t)0x0048)
#define BKP_DR14 ((uint16_t)0x004C)
#define BKP_DR15 ((uint16_t)0x0050)
#define BKP_DR16 ((uint16_t)0x0054)
#define BKP_DR17 ((uint16_t)0x0058)
#define BKP_DR18 ((uint16_t)0x005C)
#define BKP_DR19 ((uint16_t)0x0060)
#define BKP_DR20 ((uint16_t)0x0064)
#define BKP_DR21 ((uint16_t)0x0068)
#define BKP_DR22 ((uint16_t)0x006C)
#define BKP_DR23 ((uint16_t)0x0070)
#define BKP_DR24 ((uint16_t)0x0074)
#define BKP_DR25 ((uint16_t)0x0078)
#define BKP_DR26 ((uint16_t)0x007C)
#define BKP_DR27 ((uint16_t)0x0080)
#define BKP_DR28 ((uint16_t)0x0084)
#define BKP_DR29 ((uint16_t)0x0088)
#define BKP_DR30 ((uint16_t)0x008C)
#define BKP_DR31 ((uint16_t)0x0090)
#define BKP_DR32 ((uint16_t)0x0094)
#define BKP_DR33 ((uint16_t)0x0098)
#define BKP_DR34 ((uint16_t)0x009C)
#define BKP_DR35 ((uint16_t)0x00A0)
#define BKP_DR36 ((uint16_t)0x00A4)
#define BKP_DR37 ((uint16_t)0x00A8)
#define BKP_DR38 ((uint16_t)0x00AC)
#define BKP_DR39 ((uint16_t)0x00B0)
#define BKP_DR40 ((uint16_t)0x00B4)
#define BKP_DR41 ((uint16_t)0x00B8)
#define BKP_DR42 ((uint16_t)0x00BC)
/**
* @}
*/
/**
* @}
*/
/** @defgroup BKP_Exported_Functions
* @{
*/
void BKP_DeInit(void);
void BKP_WriteBackupRegister(uint16_t BKP_DR, uint16_t Data);
uint16_t BKP_ReadBackupRegister(uint16_t BKP_DR);
void BKP_RTCOutputConfig(uint16_t BKP_RTCOUTPUT);
void BKP_SetRTCCalibrationValue(uint8_t CalibrationValue);
void BKP_TamperPinConfig(uint16_t BKP_TPAL, TypeState NewValue);
void BKP_TamperINT_Enable(TypeState NewValue);
TypeState BKP_GetBitState(void);
void BKP_ClearBitState(void);
TypeState BKP_GetIntBitState(void);
void BKP_ClearIntBitState(void);
#ifdef __cplusplus
}
#endif
#endif /* __GD32F10X_BKP_H */
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/

View File

@ -0,0 +1,512 @@
/**
******************************************************************************
* @brief CAN header file of the firmware library.
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __GD32F10X_CAN_H
#define __GD32F10X_CAN_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "gd32f10x.h"
/** @addtogroup GD32F10x_Firmware
* @{
*/
/** @addtogroup CAN
* @{
*/
/** @defgroup CAN_Exported_Types
* @{
*/
/**
* @brief CAN Initial Parameters
*/
typedef struct {
uint16_t CAN_Prescaler; /*!< Baud rate prescaler.It can be 1 to 1024. */
uint8_t CAN_Mode; /*!< Set the CAN operating mode. */
uint8_t CAN_SJW; /*!< Set Resynchronization jump width */
uint8_t CAN_BS1; /*!< Set time segment 1. */
uint8_t CAN_BS2; /*!< Set time segment 2. */
TypeState CAN_TTC; /*!< Set time triggered communication mode. */
TypeState CAN_ABOR; /*!< Set automatic bus-off recovery. */
TypeState CAN_AWK; /*!< Set the automatic wake-up mode. */
TypeState CAN_ARD; /*!< Set the automatic retransmission mode. */
TypeState CAN_RFOD; /*!< Receive FIFO overwrite mode. */
TypeState CAN_TFO; /*!< Set the Transmit FIFO order. */
} CAN_InitPara;
/**
* @brief CAN filter Initial Parameters
*/
typedef struct {
uint16_t CAN_FilterListHigh; /*!< the filter List number.
If the filter scale is 32-bit,the filter list number is MSBs.
If the filter scale is 16-bit,the filter list number is first one.
This value can take from 0x0000 to 0xFFFF */
uint16_t CAN_FilterListLow; /*!< the filter List number.
If the filter scale is 32-bit,the filter list number is LSBs.
If the filter scale is 16-bit,the filter list number is second one.
This value can take from 0x0000 to 0xFFFF */
uint16_t CAN_FilterMaskListHigh; /*!< the filter mask number or list number,according to the filter mode.
If the filter scale is 32-bit,the filter mask number or list number is MSBs.
If the filter scale is 16-bit,the filter mask number or list number is first one.
This value can take from 0x0000 to 0xFFFF */
uint16_t CAN_FilterMaskListLow; /*!< the filter mask number or list number,according to the filter mode.
If the filter scale is 32-bit,the filter mask number or list number is LSBs.
If the filter scale is 16-bit,the filter mask number or list number is second one.
This value can take from 0x0000 to 0xFFFF */
uint16_t CAN_FilterFIFOAssociation; /*!< Set the FIFO (0 or 1) which will be associated with the filter. */
uint8_t CAN_FilterNumber; /*!< Set the which filter to be initialized. It ranges from 0 to 13 or 0 to 27(in GD32F10X_CL). */
uint8_t CAN_FilterMode; /*!< Set the filter mode to be identifier mask or identifier list. */
uint8_t CAN_FilterScale; /*!< Set the filter scale. */
TypeState CAN_FilterWork; /*!< Set the filter to work or not. */
} CAN_FilterInitPara;
/**
* @brief CAN Tx message structure definition
*/
typedef struct {
uint32_t StdId; /*!< Set the standard format frame identifier.
This value can take from 0 to 0x7FF. */
uint32_t ExtId; /*!< Set the extended format frame identifier.
This value can take from 0 to 0x1FFFFFFF. */
uint8_t FF; /*!< Set the format of Frame , Standard or extended Frame
for the message that will be transmitted. */
uint8_t FT; /*!< Set the type of frame, Data or remote
for the message that will be transmitted. */
uint8_t DLC; /*!< Set the length of the frame that will be transmitted.
This value can take from 0 to 8 */
uint8_t Data[8]; /*!< store the data that will be transmitted.
This value can take from 0 to 0xFF. */
} CanTxMessage;
/**
* @brief CAN Rx message structure definition
*/
typedef struct {
uint32_t StdId; /*!< Set the standard format frame identifier.
This value can take from 0 to 0x7FF. */
uint32_t ExtId; /*!< Set the extended format frame identifier.
This value can take from 0 to 0x1FFFFFFF. */
uint8_t FF; /*!< Set the format of Frame , Standard or extended Frame
for the message that will be received. */
uint8_t FT; /*!< Set the type of frame, Data or remote
for the message that will be received. */
uint8_t DLC; /*!< Set the length of the frame that will be received.
This value can take from 0 to 8 */
uint8_t Data[8]; /*!< store the data that will be received.
This value can take from 0 to 0xFF. */
uint8_t FI; /*!< The index of the filter by which the frame is passed..
This value can take from 0 to 0xFF */
} CanRxMessage;
/**
* @}
*/
/** @defgroup CAN_Exported_Constants
* @{
*/
/** @defgroup CAN_sleep_constants
* @{
*/
#define CAN_INITSTATE_FAILED ((uint8_t)0x00) /*!< CAN initialization failed */
#define CAN_INITSTATE_SUCCESS ((uint8_t)0x01) /*!< CAN initialization OK */
/**
* @}
*/
/** @defgroup CAN_Communication_Mode
* @{
*/
#define CAN_MODE_NORMAL ((uint8_t)0x00) /*!< Normal communication mode */
#define CAN_MODE_LOOPBACK ((uint8_t)0x01) /*!< Loopback communication mode */
#define CAN_MODE_SILENT ((uint8_t)0x02) /*!< Silent communication mode */
#define CAN_MODE_SILENT_LOOPBACK ((uint8_t)0x03) /*!< Loopback and silent communication mode */
/**
* @}
*/
/**
* @defgroup CAN_Working_Mode
* @{
*/
#define CAN_WORKINGMODE_INITIAL ((uint8_t)0x00) /*!< Initial working mode */
#define CAN_WORKINGMODE_NORMAL ((uint8_t)0x01) /*!< Normal working mode */
#define CAN_WORKINGMODE_SLEEP ((uint8_t)0x02) /*!< Sleep working mode */
/**
* @}
*/
/**
* @defgroup CAN_Mode_State
* @{
*/
#define CAN_MODESTATE_FAILED ((uint8_t)0x00) /*!< CAN entering the specified mode failed */
#define CAN_MODESTATE_SUCCESS ((uint8_t)!CAN_MODESTATE_FAILED) /*!< CAN entering the specified mode Succeed */
/**
* @}
*/
/** @defgroup CAN_Synchronisation_Jump_Width
* @{
*/
#define CAN_SJW_1TQ ((uint8_t)0x00) /*!< 1 time quanta */
#define CAN_SJW_2TQ ((uint8_t)0x01) /*!< 2 time quanta */
#define CAN_SJW_3TQ ((uint8_t)0x02) /*!< 3 time quanta */
#define CAN_SJW_4TQ ((uint8_t)0x03) /*!< 4 time quanta */
/**
* @}
*/
/** @defgroup CAN_Time_Quanta_In_Bit_Segment_1
* @{
*/
#define CAN_BS1_1TQ ((uint8_t)0x00) /*!< 1 time quanta */
#define CAN_BS1_2TQ ((uint8_t)0x01) /*!< 2 time quanta */
#define CAN_BS1_3TQ ((uint8_t)0x02) /*!< 3 time quanta */
#define CAN_BS1_4TQ ((uint8_t)0x03) /*!< 4 time quanta */
#define CAN_BS1_5TQ ((uint8_t)0x04) /*!< 5 time quanta */
#define CAN_BS1_6TQ ((uint8_t)0x05) /*!< 6 time quanta */
#define CAN_BS1_7TQ ((uint8_t)0x06) /*!< 7 time quanta */
#define CAN_BS1_8TQ ((uint8_t)0x07) /*!< 8 time quanta */
#define CAN_BS1_9TQ ((uint8_t)0x08) /*!< 9 time quanta */
#define CAN_BS1_10TQ ((uint8_t)0x09) /*!< 10 time quanta */
#define CAN_BS1_11TQ ((uint8_t)0x0A) /*!< 11 time quanta */
#define CAN_BS1_12TQ ((uint8_t)0x0B) /*!< 12 time quanta */
#define CAN_BS1_13TQ ((uint8_t)0x0C) /*!< 13 time quanta */
#define CAN_BS1_14TQ ((uint8_t)0x0D) /*!< 14 time quanta */
#define CAN_BS1_15TQ ((uint8_t)0x0E) /*!< 15 time quanta */
#define CAN_BS1_16TQ ((uint8_t)0x0F) /*!< 16 time quanta */
/**
* @}
*/
/** @defgroup CAN_Time_Quanta_In_Bit_Segment_2
* @{
*/
#define CAN_BS2_1TQ ((uint8_t)0x00) /*!< 1 time quanta */
#define CAN_BS2_2TQ ((uint8_t)0x01) /*!< 2 time quanta */
#define CAN_BS2_3TQ ((uint8_t)0x02) /*!< 3 time quanta */
#define CAN_BS2_4TQ ((uint8_t)0x03) /*!< 4 time quanta */
#define CAN_BS2_5TQ ((uint8_t)0x04) /*!< 5 time quanta */
#define CAN_BS2_6TQ ((uint8_t)0x05) /*!< 6 time quanta */
#define CAN_BS2_7TQ ((uint8_t)0x06) /*!< 7 time quanta */
#define CAN_BS2_8TQ ((uint8_t)0x07) /*!< 8 time quanta */
/**
* @}
*/
/** @defgroup CAN_Filter_Mode
* @{
*/
#define CAN_FILTERMODE_MASK ((uint8_t)0x00) /*!< mask mode */
#define CAN_FILTERMODE_LIST ((uint8_t)0x01) /*!< List mode */
/**
* @}
*/
/** @defgroup CAN_Filter_Scale
* @{
*/
#define CAN_FILTERSCALE_16BIT ((uint8_t)0x00) /*!< Two 16-bit filters */
#define CAN_FILTERSCALE_32BIT ((uint8_t)0x01) /*!< One 32-bit filter */
/**
* @}
*/
/** @defgroup CAN_Filter_FIFO
* @{
*/
#define CAN_FILTER_FIFO0 ((uint8_t)0x00) /*!< Filter associated with FIFO0 */
#define CAN_FILTER_FIFO1 ((uint8_t)0x01) /*!< Filter associated with FIFO1 */
/**
* @}
*/
/** @defgroup CAN_Format_Frame
* @{
*/
#define CAN_FF_STANDARD ((uint32_t)0x00000000) /*!< Standard format frame */
#define CAN_FF_EXTENDED ((uint32_t)0x00000004) /*!< Extended format frame */
/**
* @}
*/
/** @defgroup CAN_Frame_Type
* @{
*/
#define CAN_FT_DATA ((uint32_t)0x00000000) /*!< Data frame */
#define CAN_FT_REMOTE ((uint32_t)0x00000002) /*!< Remote frame */
/**
* @}
*/
/** @defgroup CAN_Transmit_State
* @{
*/
#define CAN_TXSTATE_FAILED ((uint8_t)0x00)/*!< CAN transmitted failure */
#define CAN_TXSTATE_OK ((uint8_t)0x01) /*!< CAN transmitted success */
#define CAN_TXSTATE_PENDING ((uint8_t)0x02) /*!< CAN transmitted pending */
#define CAN_TXSTATE_NOMAILBOX ((uint8_t)0x04) /*!< No empty mailbox to be used for CAN */
/**
* @}
*/
/** @defgroup CAN_Receive_FIFO_Number_Constants
* @{
*/
#define CAN_FIFO0 ((uint8_t)0x00) /*!< Use CAN FIFO 0 to receive */
#define CAN_FIFO1 ((uint8_t)0x01) /*!< Use CAN FIFO 1 to receive */
/**
* @}
*/
/** @defgroup CAN_Sleep_Constants
* @{
*/
#define CAN_SLEEP_FAILED ((uint8_t)0x00) /*!< CAN entered the sleep mode failed */
#define CAN_SLEEP_OK ((uint8_t)0x01) /*!< CAN entered the sleep mode succeeded */
/**
* @}
*/
/** @defgroup CAN_Wake_Wp_Constants
* @{
*/
#define CAN_WAKEUP_FAILED ((uint8_t)0x00) /*!< CAN leaved the sleep mode failed */
#define CAN_WAKEUP_OK ((uint8_t)0x01) /*!< CAN leaved the sleep mode succeeded */
/**
* @}
*/
/**
* @defgroup CAN_Error_Type_Constants
* @{
*/
#define CAN_ERRORTYPE_NOERR ((uint8_t)0x00) /*!< No Error */
#define CAN_ERRORTYPE_STUFFERR ((uint8_t)0x10) /*!< Stuff Error */
#define CAN_ERRORTYPE_FORMERR ((uint8_t)0x20) /*!< Form Error */
#define CAN_ERRORTYPE_ACKERR ((uint8_t)0x30) /*!< Acknowledgment Error */
#define CAN_ERRORTYPE_BITRECESSIVEERR ((uint8_t)0x40) /*!< Bit Recessive Error */
#define CAN_ERRORTYPE_BITDOMINANTERR ((uint8_t)0x50) /*!< Bit Dominant Error */
#define CAN_ERRORTYPE_CRCERR ((uint8_t)0x60) /*!< CRC Error */
#define CAN_ERRORTYPE_SOFTWARESETERR ((uint8_t)0x70) /*!< Set by software */
/**
* @}
*/
/** @defgroup CAN_flags
* @{
*/
/* The flag value of 0x3XXXXXXX is used with CAN_GetBitState()and CAN_ClearBitState() functions. */
/* The flag value of 0x1XXXXXXX is only used with CAN_GetBitState() function. */
/* Transmit Flags */
#define CAN_FLAG_MTF0 ((uint32_t)0x38000001) /*!< Mailbox 0 transmit finished Flag */
#define CAN_FLAG_MTF1 ((uint32_t)0x38000100) /*!< Mailbox 1 transmit finished Flag */
#define CAN_FLAG_MTF2 ((uint32_t)0x38010000) /*!< Mailbox 2 transmit finished Flag */
/* Receive Flags */
#define CAN_FLAG_RFL0 ((uint32_t)0x12000003) /*!< the length of the receive FIFO0 Flag */
#define CAN_FLAG_RFF0 ((uint32_t)0x32000008) /*!< Receive FIFO 0 full Flag */
#define CAN_FLAG_RFO0 ((uint32_t)0x32000010) /*!< Receive FIFO 0 overfull Flag */
#define CAN_FLAG_RFL1 ((uint32_t)0x14000003) /*!< the length of the receive FIFO1 Flag */
#define CAN_FLAG_RFF1 ((uint32_t)0x34000008) /*!< Receive FIFO 1 full Flag */
#define CAN_FLAG_RFO1 ((uint32_t)0x34000010) /*!< Receive FIFO 1 overfull Flag */
/* Working Mode Flags, in CAN status register */
#define CAN_FLAG_WU ((uint32_t)0x31000008) /*!< Wake up Flag */
#define CAN_FLAG_SLP ((uint32_t)0x31000012) /*!< Sleep working state Flag */
/* Error Flags, in CAN error register */
#define CAN_FLAG_WE ((uint32_t)0x10F00001) /*!< Warning error Flag */
#define CAN_FLAG_PE ((uint32_t)0x10F00002) /*!< Passive error Flag */
#define CAN_FLAG_BOE ((uint32_t)0x10F00004) /*!< Bus-off error Flag */
#define CAN_FLAG_ET ((uint32_t)0x30F00070) /*!< Error type Flag */
/**
* @}
*/
/** @defgroup CAN_interrupts
* @{
*/
#define CAN_INT_TME ((uint32_t)0x00000001) /*!< Transmit mailbox empty Interrupt*/
/* Receive Interrupts */
#define CAN_INT_RFNE0 ((uint32_t)0x00000002) /*!< FIFO 0 not empty interrupt */
#define CAN_INT_RFF0 ((uint32_t)0x00000004) /*!< FIFO 0 full Interrupt*/
#define CAN_INT_RFO0 ((uint32_t)0x00000008) /*!< FIFO 0 overrun Interrupt*/
#define CAN_INT_RFNE1 ((uint32_t)0x00000010) /*!< FIFO 1 not empty interrupt*/
#define CAN_INT_RFF1 ((uint32_t)0x00000020) /*!< FIFO 1 full Interrupt*/
#define CAN_INT_RFO1 ((uint32_t)0x00000040) /*!< FIFO 1 overfull Interrupt*/
/* Working Mode Interrupts */
#define CAN_INT_WU ((uint32_t)0x00010000) /*!< Wake-up Interrupt*/
#define CAN_INT_SLP ((uint32_t)0x00020000) /*!< Sleep Interrupt*/
/* Error Interrupts */
#define CAN_INT_WE ((uint32_t)0x00000100) /*!< Warning error Interrupt*/
#define CAN_INT_PE ((uint32_t)0x00000200) /*!< Passive error Interrupt*/
#define CAN_INT_BOE ((uint32_t)0x00000400) /*!< Bus-off error Interrupt*/
#define CAN_INT_ET ((uint32_t)0x00000800) /*!< error type Interrupt*/
#define CAN_INT_ERR ((uint32_t)0x00008000) /*!< Error Interrupt*/
#define CAN_INT_MTF0 CAN_INT_TME
#define CAN_INT_MTF1 CAN_INT_TME
#define CAN_INT_MTF2 CAN_INT_TME
/**
* @}
*/
/** @defgroup CAN_Legacy
* @{
*/
#define CANINITFAILED CAN_INITSTATE_FAILED
#define CANINITOK CAN_INITSTATE_SUCCESS
#define CAN_FILTERFIFO0 CAN_FILTER_FIFO0
#define CAN_FILTERFIFO1 CAN_FILTER_FIFO1
#define CAN_FF_STD CAN_FF_STANDARD
#define CAN_FF_EXT CAN_FF_EXTENDED
//#define CAN_FT_DATA CAN_FT_DATA
//#define CAN_FT_REMOTE CAN_FT_REMOTE
#define CANTXFAILE CAN_TXSTATE_FAILED
#define CANTXOK CAN_TXSTATE_OK
#define CANTXPENDING CAN_TXSTATE_PENDING
#define CAN_NO_MB CAN_TXSTATE_NOMAILBOX
#define CANSLEEPFAILED CAN_SLEEP_FAILED
#define CANSLEEPOK CAN_SLEEP_OK
#define CANWAKEUPFAILED CAN_WAKEUP_FAILED
#define CANWAKEUPOK CAN_WAKEUP_OK
/**
* @}
*/
/**
* @}
*/
/** @defgroup CAN_Exported_Functions
* @{
*/
void CAN_DeInit(CAN_TypeDef *CANx);
uint8_t CAN_Init(CAN_TypeDef *CANx, CAN_InitPara *CAN_InitParaStruct);
void CAN_FilterInit(CAN_FilterInitPara *CAN_FilterInitParaStruct);
void CAN_StructInit(CAN_InitPara *CAN_InitParaStruct);
void CAN_HeaderBank(uint8_t CAN_HeaderBankNumber);
void CAN_DebugFreeze(CAN_TypeDef *CANx, TypeState NewValue);
void CAN_TimeTrigComMode_Enable(CAN_TypeDef *CANx, TypeState NewValue);
/* Transmit functions */
uint8_t CAN_Transmit(CAN_TypeDef *CANx, CanTxMessage *TxMessage);
uint8_t CAN_TransmitState(CAN_TypeDef *CANx, uint8_t TransmitMailbox);
void CAN_StopTransmit(CAN_TypeDef *CANx, uint8_t Mailbox);
/* Receive functions */
void CAN_Receive(CAN_TypeDef *CANx, uint8_t FIFONumber, CanRxMessage *RxMessage);
void CAN_FIFODequeue(CAN_TypeDef *CANx, uint8_t FIFONumber);
uint8_t CAN_MessageLength(CAN_TypeDef *CANx, uint8_t FIFONumber);
/* Working modes functions */
uint8_t CAN_WorkingMode(CAN_TypeDef *CANx, uint8_t CAN_WorkingMode);
uint8_t CAN_EnterSleep(CAN_TypeDef *CANx);
uint8_t CAN_WakeUp(CAN_TypeDef *CANx);
/* Error management functions */
uint8_t CAN_GetErrorType(CAN_TypeDef *CANx);
uint8_t CAN_GetReceiveErrorCounter(CAN_TypeDef *CANx);
uint8_t CAN_GetTransmitErrorCounter(CAN_TypeDef *CANx);
/* Interrupts and flags management functions */
void CAN_INTConfig(CAN_TypeDef *CANx, uint32_t CAN_INT, TypeState NewValue);
TypeState CAN_GetBitState(CAN_TypeDef *CANx, uint32_t CAN_FLAG);
void CAN_ClearBitState(CAN_TypeDef *CANx, uint32_t CAN_FLAG);
TypeState CAN_GetIntBitState(CAN_TypeDef *CANx, uint32_t CAN_INT);
void CAN_ClearIntBitState(CAN_TypeDef *CANx, uint32_t CAN_INT);
static TypeState CheckINTState(uint32_t CAN_Reg, uint32_t Int_Bit);
#ifdef __cplusplus
}
#endif
#endif /* __GD32F10x_CAN_H */
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/

View File

@ -0,0 +1,52 @@
/**
******************************************************************************
* @brief CRC header file of the firmware library.
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __GD32F10X_CRC_H
#define __GD32F10X_CRC_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "gd32f10x.h"
/** @addtogroup GD32F10x_Firmware
* @{
*/
/** @addtogroup CRC
* @{
*/
/** @defgroup CRC_Exported_Functions
* @{
*/
void CRC_ResetDTR(void);
uint32_t CRC_CalcSingleData(uint32_t CRC_data);
uint32_t CRC_CalcDataFlow(uint32_t pbuffer[], uint32_t buffer_length);
uint32_t CRC_ReadDTR(void);
void CRC_WriteFDTR(uint8_t CRC_fdtr);
uint8_t CRC_ReadFDTR(void);
#ifdef __cplusplus
}
#endif
#endif /*__GD32F10X_CRC_H */
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/

View File

@ -0,0 +1,208 @@
/**
******************************************************************************
* @brief DAC header file of the firmware library.
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __GD32F10X_DAC_H
#define __GD32F10X_DAC_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "gd32f10x.h"
/** @addtogroup GD32F10x_Firmware
* @{
*/
/** @addtogroup DAC
* @{
*/
/** @defgroup DAC_Exported_Types
* @{
*/
/**
* @brief DAC Init structure definition
*/
typedef struct {
uint32_t DAC_Trigger; /*!< External trigger of the selected DAC channel.
This parameter can be a value of @ref DAC_Trigger */
uint32_t DAC_WaveType; /*!< Wave type of the DAC channel, noise waves or triangle waves.
This parameter can be a value of @ref DAC_wave_type */
uint32_t DAC_LFSRNoise_AmplitudeTriangle; /*!< The LFSR mask for noise wave generation or
the maximum amplitude triangle generation for the DAC channel.
This parameter can be a value of @ref DAC_lfsrnoise_amplitudetriangle */
uint32_t DAC_OutputBuffer; /*!< whether the DAC channel output buffer is enabled or disabled.
This parameter can be a value of @ref DAC_OutputBuffer */
} DAC_InitPara;
/**
* @}
*/
/** @defgroup DAC_Exported_Constants
* @{
*/
/** @defgroup DAC_Trigger
* @{
*/
#define DAC_TRIGGER_NONE ((uint32_t)0x00000000) /*!< no trigger */
#define DAC_TRIGGER_T2_TRIG ((uint32_t)0x00000024) /*!< TIMER2 TRIG */
#define DAC_TRIGGER_T3_TRIG ((uint32_t)0x0000000C) /*!< TIMER3 TRIG */
#define DAC_TRIGGER_T4_TRIG ((uint32_t)0x0000002C) /*!< TIMER4 TRIG */
#define DAC_TRIGGER_T5_TRIG ((uint32_t)0x0000001C) /*!< TIMER5 TRIG */
#define DAC_TRIGGER_T6_TRIG ((uint32_t)0x00000004) /*!< TIMER6 TRIG */
#define DAC_TRIGGER_T7_TRIG ((uint32_t)0x00000014) /*!< TIMER7 TRIG */
#define DAC_TRIGGER_T8_TRIG ((uint32_t)0x0000000C) /*!< TIMER8 TRIG */
#define DAC_TRIGGER_T15_TRIG ((uint32_t)0x0000001C) /*!< TIMER15 TRIG */
#define DAC_TRIGGER_EXTI_LINE9 ((uint32_t)0x00000034) /*!< EXTI Line9 event */
#define DAC_TRIGGER_SOFTWARE ((uint32_t)0x0000003C) /*!< software trigger */
/**
* @}
*/
/** @defgroup DAC_wave_type
* @{
*/
#define DAC_WAVEGENE_NONE ((uint32_t)0x00000000)
#define DAC_WAVEGENE_NOISE ((uint32_t)0x00000040)
#define DAC_WAVEGENE_TRIANGLE ((uint32_t)0x00000080)
/**
* @}
*/
/** @defgroup DAC_lfsrnoise_amplitudetriangle
* @{
*/
#define DAC_LFSR_BIT0 ((uint32_t)0x00000000) /*!< LFSR bit0 for noise wave generation */
#define DAC_LFSR_BITS1_0 ((uint32_t)0x00000100) /*!< LFSR bit[1:0] for noise wave generation */
#define DAC_LFSR_BITS2_0 ((uint32_t)0x00000200) /*!< LFSR bit[2:0] for noise wave generation */
#define DAC_LFSR_BITS3_0 ((uint32_t)0x00000300) /*!< LFSR bit[3:0] for noise wave generation */
#define DAC_LFSR_BITS4_0 ((uint32_t)0x00000400) /*!< LFSR bit[4:0] for noise wave generation */
#define DAC_LFSR_BITS5_0 ((uint32_t)0x00000500) /*!< LFSR bit[5:0] for noise wave generation */
#define DAC_LFSR_BITS6_0 ((uint32_t)0x00000600) /*!< LFSR bit[6:0] for noise wave generation */
#define DAC_LFSR_BITS7_0 ((uint32_t)0x00000700) /*!< LFSR bit[7:0] for noise wave generation */
#define DAC_LFSR_BITS8_0 ((uint32_t)0x00000800) /*!< LFSR bit[8:0] for noise wave generation */
#define DAC_LFSR_BITS9_0 ((uint32_t)0x00000900) /*!< LFSR bit[9:0] for noise wave generation */
#define DAC_LFSR_BITS10_0 ((uint32_t)0x00000A00) /*!< LFSR bit[10:0] for noise wave generation */
#define DAC_LFSR_BITS11_0 ((uint32_t)0x00000B00) /*!< LFSR bit[11:0] for noise wave generation */
#define DAC_AMPLITUDETRIANGLE_1 ((uint32_t)0x00000000) /*!< max triangle amplitude: 1 */
#define DAC_AMPLITUDETRIANGLE_3 ((uint32_t)0x00000100) /*!< max triangle amplitude: 3 */
#define DAC_AMPLITUDETRIANGLE_7 ((uint32_t)0x00000200) /*!< max triangle amplitude: 7 */
#define DAC_AMPLITUDETRIANGLE_15 ((uint32_t)0x00000300) /*!< max triangle amplitude: 15 */
#define DAC_AMPLITUDETRIANGLE_31 ((uint32_t)0x00000400) /*!< max triangle amplitude: 31 */
#define DAC_AMPLITUDETRIANGLE_63 ((uint32_t)0x00000500) /*!< max triangle amplitude: 63 */
#define DAC_AMPLITUDETRIANGLE_127 ((uint32_t)0x00000600) /*!< max triangle amplitude: 127 */
#define DAC_AMPLITUDETRIANGLE_255 ((uint32_t)0x00000700) /*!< max triangle amplitude: 255 */
#define DAC_AMPLITUDETRIANGLE_511 ((uint32_t)0x00000800) /*!< max triangle amplitude: 511 */
#define DAC_AMPLITUDETRIANGLE_1023 ((uint32_t)0x00000900) /*!< max triangle amplitude: 1023 */
#define DAC_AMPLITUDETRIANGLE_2047 ((uint32_t)0x00000A00) /*!< max triangle amplitude: 2047 */
#define DAC_AMPLITUDETRIANGLE_4095 ((uint32_t)0x00000B00) /*!< max triangle amplitude: 4095 */
/**
* @}
*/
/** @defgroup DAC_OutputBuffer
* @{
*/
#define DAC_OUTPUTBUFFER_ENABLE ((uint32_t)0x00000000)
#define DAC_OUTPUTBUFFER_DISABLE ((uint32_t)0x00000002)
/**
* @}
*/
/** @defgroup DAC_Channel_selection
* @{
*/
#define DAC_CHANNEL_1 ((uint32_t)0x00000000)
#define DAC_CHANNEL_2 ((uint32_t)0x00000010)
/**
* @}
*/
/** @defgroup DAC_data_alignment
* @{
*/
#define DAC_ALIGN_12B_R ((uint32_t)0x00000000)
#define DAC_ALIGN_12B_L ((uint32_t)0x00000004)
#define DAC_ALIGN_8B_R ((uint32_t)0x00000008)
/**
* @}
*/
/** @defgroup DAC_wave_generation
* @{
*/
#define DAC_WAVE_NOISE ((uint32_t)0x00000040)
#define DAC_WAVE_TRIANGLE ((uint32_t)0x00000080)
/**
* @}
*/
/** @defgroup DAC_interrupts_definition
* @{
*/
#define DAC_INT_DMAUDR ((uint32_t)0x00002000)
/**
* @}
*/
/** @defgroup DAC_flags_definition
* @{
*/
#define DAC_FLAG_DMAUDR ((uint32_t)0x00002000)
/**
* @}
*/
/**
* @}
*/
/** @defgroup DAC_Exported_Functions
* @{
*/
void DAC_DeInit(DAC_InitPara *DAC_InitParaStruct);
void DAC_Init(uint32_t DAC_Channel, DAC_InitPara *DAC_InitParaStruct);
void DAC_Enable(uint32_t DAC_Channel, TypeState NewValue);
void DAC_IntConfig(uint32_t DAC_Channel, TypeState NewValue);
void DAC_SoftwareTrigger_Enable(uint32_t DAC_Channel, TypeState NewValue);
void DAC_DualSoftwareTrigger_Enable(TypeState NewValue);
void DAC_WaveGeneration_Enable(uint32_t DAC_Channel, uint32_t DAC_Wave, TypeState NewValue);
void DAC_SetChannel1Data(uint32_t DAC_Align, uint16_t Data);
void DAC_SetChannel2Data(uint32_t DAC_Align, uint16_t Data);
void DAC_SetDualChannelData(uint32_t DAC_Align, uint16_t Data2, uint16_t Data1);
uint16_t DAC_GetDataOutputValue(uint32_t DAC_Channel);
void DAC_DMA_Enable(uint32_t DAC_Channel, TypeState NewValue);
#ifdef __cplusplus
}
#endif
#endif /*__GD32F10X_DAC_H */
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/

View File

@ -0,0 +1,321 @@
/**
******************************************************************************
* @brief DMA header file of the firmware library.
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __GD32F10X_DMA_H
#define __GD32F10X_DMA_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "gd32f10x.h"
/** @addtogroup GD32F10x_Firmware
* @{
*/
/** @addtogroup DMA
* @{
*/
/** @defgroup DMA_Exported_Types
* @{
*/
/**
* @brief DMA Initial Parameters
*/
typedef struct {
uint32_t DMA_PeripheralBaseAddr; /*!< The base address of the peripheral. */
uint32_t DMA_MemoryBaseAddr; /*!< The base address of the memory. */
uint32_t DMA_DIR; /*!< The direction of data transmission.
detailed in @ref DMA_data_transfer_direction */
uint32_t DMA_BufferSize; /*!< The buffer size of data transmission. */
uint32_t DMA_PeripheralInc; /*!< The incremented_mode of the Peripheral address register.
detailed in @ref DMA_peripheral_Address_incremented_mode */
uint32_t DMA_MemoryInc; /*!< The incremented_mode of the memory address register.
detailed in @ref DMA_memory_Address_incremented_mode */
uint32_t DMA_PeripheralDataSize; /*!< The data transmission width of Peripheral.
detailed in @ref DMA_peripheral_data_size */
uint32_t DMA_MemoryDataSize; /*!< The data transmission width of Memory.
detailed in @ref DMA_memory_data_size */
uint32_t DMA_Mode; /*!< The mode of circular transmission.
detailed in @ref DMA_circular_normal_mode */
uint32_t DMA_Priority; /*!< The software priority for the DMAy Channelx.
detailed in @ref DMA_priority_level */
uint32_t DMA_MTOM; /*!< The mode of memory-to-memory transfer.
detailed in @ref DMA_memory_to_memory */
} DMA_InitPara;
/**
* @}
*/
/** @defgroup DMA_Exported_Constants
* @{
*/
/** @defgroup DMA_data_transfer_direction
* @{
*/
#define DMA_DIR_PERIPHERALDST DMA_CTLR_DIR
#define DMA_DIR_PERIPHERALSRC ((uint32_t)0x00000000)
/**
* @}
*/
/** @defgroup DMA_peripheral_Address_Increasing_mode
* @{
*/
#define DMA_PERIPHERALINC_ENABLE DMA_CTLR_PNAGA
#define DMA_PERIPHERALINC_DISABLE ((uint32_t)0x00000000)
/**
* @}
*/
/** @defgroup DMA_memory_Address_Increasing_mode
* @{
*/
#define DMA_MEMORYINC_ENABLE DMA_CTLR_MNAGA
#define DMA_MEMORYINC_DISABLE ((uint32_t)0x00000000)
/**
* @}
*/
/** @defgroup DMA_peripheral_data_size
* @{
*/
#define DMA_PERIPHERALDATASIZE_BYTE ((uint32_t)0x00000000)
#define DMA_PERIPHERALDATASIZE_HALFWORD DMA_CTLR_PSIZE_0
#define DMA_PERIPHERALDATASIZE_WORD DMA_CTLR_PSIZE_1
/**
* @}
*/
/** @defgroup DMA_memory_data_size
* @{
*/
#define DMA_MEMORYDATASIZE_BYTE ((uint32_t)0x00000000)
#define DMA_MEMORYDATASIZE_HALFWORD DMA_CTLR_MSIZE_0
#define DMA_MEMORYDATASIZE_WORD DMA_CTLR_MSIZE_1
/**
* @}
*/
/** @defgroup DMA_circular_normal_mode
* @{
*/
#define DMA_MODE_CIRCULAR DMA_CTLR_CIRC
#define DMA_MODE_NORMAL ((uint32_t)0x00000000)
/**
* @}
*/
/** @defgroup DMA_priority_level
* @{
*/
#define DMA_PRIORITY_VERYHIGH DMA_CTLR_PRIO
#define DMA_PRIORITY_HIGH DMA_CTLR_PRIO_1
#define DMA_PRIORITY_MEDIUM DMA_CTLR_PRIO_0
#define DMA_PRIORITY_LOW ((uint32_t)0x00000000)
/**
* @}
*/
/** @defgroup DMA_memory_to_memory
* @{
*/
#define DMA_MEMTOMEM_ENABLE DMA_CTLR_MEMTOMEM
#define DMA_MEMTOMEM_DISABLE ((uint32_t)0x00000000)
/**
* @}
*/
/** @defgroup DMA_interrupts_definition
* @{
*/
#define DMA_INT_TC DMA_CTLR_TCIE
#define DMA_INT_HT DMA_CTLR_HTIE
#define DMA_INT_ERR DMA_CTLR_ERRIE
#define DMA1_INT_GL1 DMA_IFR_GIF1
#define DMA1_INT_TC1 DMA_IFR_TCIF1
#define DMA1_INT_HT1 DMA_IFR_HTIF1
#define DMA1_INT_ERR1 DMA_IFR_ERRIF1
#define DMA1_INT_GL2 DMA_IFR_GIF2
#define DMA1_INT_TC2 DMA_IFR_TCIF2
#define DMA1_INT_HT2 DMA_IFR_HTIF2
#define DMA1_INT_ERR2 DMA_IFR_ERRIF2
#define DMA1_INT_GL3 DMA_IFR_GIF3
#define DMA1_INT_TC3 DMA_IFR_TCIF3
#define DMA1_INT_HT3 DMA_IFR_HTIF3
#define DMA1_INT_ERR3 DMA_IFR_ERRIF3
#define DMA1_INT_GL4 DMA_IFR_GIF4
#define DMA1_INT_TC4 DMA_IFR_TCIF4
#define DMA1_INT_HT4 DMA_IFR_HTIF4
#define DMA1_INT_ERR4 DMA_IFR_ERRIF4
#define DMA1_INT_GL5 DMA_IFR_GIF5
#define DMA1_INT_TC5 DMA_IFR_TCIF5
#define DMA1_INT_HT5 DMA_IFR_HTIF5
#define DMA1_INT_ERR5 DMA_IFR_ERRIF5
#define DMA1_INT_GL6 DMA_IFR_GIF6
#define DMA1_INT_TC6 DMA_IFR_TCIF6
#define DMA1_INT_HT6 DMA_IFR_HTIF6
#define DMA1_INT_ERR6 DMA_IFR_ERRIF6
#define DMA1_INT_GL7 DMA_IFR_GIF7
#define DMA1_INT_TC7 DMA_IFR_TCIF7
#define DMA1_INT_HT7 DMA_IFR_HTIF7
#define DMA1_INT_ERR7 DMA_IFR_ERRIF7
#define DMA2_INT_GL1 ((uint32_t)0x10000001)
#define DMA2_INT_TC1 ((uint32_t)0x10000002)
#define DMA2_INT_HT1 ((uint32_t)0x10000004)
#define DMA2_INT_TE1 ((uint32_t)0x10000008)
#define DMA2_INT_GL2 ((uint32_t)0x10000010)
#define DMA2_INT_TC2 ((uint32_t)0x10000020)
#define DMA2_INT_HT2 ((uint32_t)0x10000040)
#define DMA2_INT_TE2 ((uint32_t)0x10000080)
#define DMA2_INT_GL3 ((uint32_t)0x10000100)
#define DMA2_INT_TC3 ((uint32_t)0x10000200)
#define DMA2_INT_HT3 ((uint32_t)0x10000400)
#define DMA2_INT_TE3 ((uint32_t)0x10000800)
#define DMA2_INT_GL4 ((uint32_t)0x10001000)
#define DMA2_INT_TC4 ((uint32_t)0x10002000)
#define DMA2_INT_HT4 ((uint32_t)0x10004000)
#define DMA2_INT_TE4 ((uint32_t)0x10008000)
#define DMA2_INT_GL5 ((uint32_t)0x10010000)
#define DMA2_INT_TC5 ((uint32_t)0x10020000)
#define DMA2_INT_HT5 ((uint32_t)0x10040000)
#define DMA2_INT_TE5 ((uint32_t)0x10080000)
/**
* @}
*/
/** @defgroup DMA_flags_definition
* @{
*/
#define DMA1_FLAG_GL1 DMA_IFR_GIF1
#define DMA1_FLAG_TC1 DMA_IFR_TCIF1
#define DMA1_FLAG_HT1 DMA_IFR_HTIF1
#define DMA1_FLAG_ERR1 DMA_IFR_ERRIF1
#define DMA1_FLAG_GL2 DMA_IFR_GIF2
#define DMA1_FLAG_TC2 DMA_IFR_TCIF2
#define DMA1_FLAG_HT2 DMA_IFR_HTIF2
#define DMA1_FLAG_ERR2 DMA_IFR_ERRIF2
#define DMA1_FLAG_GL3 DMA_IFR_GIF3
#define DMA1_FLAG_TC3 DMA_IFR_TCIF3
#define DMA1_FLAG_HT3 DMA_IFR_HTIF3
#define DMA1_FLAG_ERR3 DMA_IFR_ERRIF3
#define DMA1_FLAG_GL4 DMA_IFR_GIF4
#define DMA1_FLAG_TC4 DMA_IFR_TCIF4
#define DMA1_FLAG_HT4 DMA_IFR_HTIF4
#define DMA1_FLAG_ERR4 DMA_IFR_ERRIF4
#define DMA1_FLAG_GL5 DMA_IFR_GIF5
#define DMA1_FLAG_TC5 DMA_IFR_TCIF5
#define DMA1_FLAG_HT5 DMA_IFR_HTIF5
#define DMA1_FLAG_ERR5 DMA_IFR_ERRIF5
#define DMA1_FLAG_GL6 DMA_IFR_GIF6
#define DMA1_FLAG_TC6 DMA_IFR_TCIF6
#define DMA1_FLAG_HT6 DMA_IFR_HTIF6
#define DMA1_FLAG_ERR6 DMA_IFR_ERRIF6
#define DMA1_FLAG_GL7 DMA_IFR_GIF7
#define DMA1_FLAG_TC7 DMA_IFR_TCIF7
#define DMA1_FLAG_HT7 DMA_IFR_HTIF7
#define DMA1_FLAG_ERR7 DMA_IFR_ERRIF7
#define DMA2_FLAG_GL1 ((uint32_t)0x10000001)
#define DMA2_FLAG_TC1 ((uint32_t)0x10000002)
#define DMA2_FLAG_HT1 ((uint32_t)0x10000004)
#define DMA2_FLAG_TE1 ((uint32_t)0x10000008)
#define DMA2_FLAG_GL2 ((uint32_t)0x10000010)
#define DMA2_FLAG_TC2 ((uint32_t)0x10000020)
#define DMA2_FLAG_HT2 ((uint32_t)0x10000040)
#define DMA2_FLAG_TE2 ((uint32_t)0x10000080)
#define DMA2_FLAG_GL3 ((uint32_t)0x10000100)
#define DMA2_FLAG_TC3 ((uint32_t)0x10000200)
#define DMA2_FLAG_HT3 ((uint32_t)0x10000400)
#define DMA2_FLAG_TE3 ((uint32_t)0x10000800)
#define DMA2_FLAG_GL4 ((uint32_t)0x10001000)
#define DMA2_FLAG_TC4 ((uint32_t)0x10002000)
#define DMA2_FLAG_HT4 ((uint32_t)0x10004000)
#define DMA2_FLAG_TE4 ((uint32_t)0x10008000)
#define DMA2_FLAG_GL5 ((uint32_t)0x10010000)
#define DMA2_FLAG_TC5 ((uint32_t)0x10020000)
#define DMA2_FLAG_HT5 ((uint32_t)0x10040000)
#define DMA2_FLAG_TE5 ((uint32_t)0x10080000)
/**
* @}
*/
/**
* @}
*/
/** @defgroup DMA_Exported_Functions
* @{
*/
/* Function used to reset the DMA configuration */
void DMA_DeInit(DMA_Channel_TypeDef *DMAy_Channelx);
/* The functions of Initialization and Configuration */
void DMA_Init(DMA_Channel_TypeDef *DMAy_Channelx, DMA_InitPara *DMA_InitParaStruct);
void DMA_ParaInit(DMA_InitPara *DMA_InitParaStruct);
void DMA_Enable(DMA_Channel_TypeDef *DMAy_Channelx, TypeState NewValue);
/* The functions of Data Counter */
void DMA_SetCurrDataCounter(DMA_Channel_TypeDef *DMAy_Channelx, uint16_t DataNumber);
uint16_t DMA_GetCurrDataCounter(DMA_Channel_TypeDef *DMAy_Channelx);
/* The functions of Interrupts and flags management */
void DMA_INTConfig(DMA_Channel_TypeDef *DMAy_Channelx, uint32_t DMA_INT, TypeState NewValue);
TypeState DMA_GetBitState(uint32_t DMA_FLAG);
void DMA_ClearBitState(uint32_t DMA_FLAG);
TypeState DMA_GetIntBitState(uint32_t DMA_INT);
void DMA_ClearIntBitState(uint32_t DMA_INT);
#ifdef __cplusplus
}
#endif
#endif /*__GD32F10x_DMA_H */
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,454 @@
/**
******************************************************************************
* @brief EXMC header file of the firmware library.
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __GD32F10X_EXMC_H
#define __GD32F10X_EXMC_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "gd32f10x.h"
/** @addtogroup GD32F10x_Firmware
* @{
*/
/** @addtogroup EXMC
* @{
*/
/** @defgroup EXMC_Exported_Types
* @{
*/
/**
* @brief Initial Timing Parameters For NOR/SRAM Banks
*/
typedef struct {
uint32_t EXMC_AsynAccessMode; /*!< The asynchronous access mode, detailed in @ref EXMC_AsynAccess_Mode*/
uint32_t EXMC_SynDataLatency; /*!< The number of CLK cycles to configure the data latency,
which may assume a value between 0x0 and 0xF. */
uint32_t EXMC_SynCLKDivision; /*!< The number of HCLK cycles to configure the clock divide ratio,
which can be a value between 0x0 and 0xF. */
uint32_t EXMC_BusLatency; /*!< The number of HCLK cycles to configure the bus latency,
which can be a value between 0x0 and 0xF. */
uint32_t EXMC_AsynDataSetupTime; /*!< The number of HCLK cycles to configure the data setup time
while in the asynchronous access mode, which can be a value
between 0x00 and 0xFF. */
uint32_t EXMC_AsynAddressHoldTime; /*!< The number of HCLK cycles to configure the address hold time
while in the asynchronous access mode, which can be a value
between 0x0 and 0xF. */
uint32_t EXMC_AsynAddressSetupTime; /*!< The number of HCLK cycles to configure the data setup time
while in the asynchronous access mode, which can be a value
between 0x0 and 0xF. */
} EXMC_NORSRAMTimingInitPara;
/**
* @brief EXMC NOR/SRAM Init structure definition
*/
typedef struct {
uint32_t EXMC_NORSRAMBank; /*!< The specified region of NORSRAM Bank1,
choose one from @ref EXMC_NORSRAMBank. */
uint32_t EXMC_WriteMode; /*!< The write mode, details in @ref EXMC_WriteMode. */
uint32_t EXMC_ExtendedMode; /*!< Enable or Disable the extended mode, details in
@ref EXMC_ExtendedMode. */
uint32_t EXMC_AsynWait; /*!< Enable or disable the asynchronous wait feature,detial
in @ref EXMC_AsynWait. */
uint32_t EXMC_NWAITSignal; /*!< Enable or Disable the NWAIT signal while in synchronous
bust mode, details in @ref EXMC_NWAITSignal. */
uint32_t EXMC_MemoryWrite; /*!< Enable or Disable the write operation, details in
@ref EXMC_MemoryWrite. */
uint32_t EXMC_NWAITConfig; /*!< NWAIT signal configuration, details in @ref EXMC_NWAITConfig */
uint32_t EXMC_WrapBurstMode; /*!< Enable or Disable the wrap burst mode, details in
@ref EXMC_WrapBurstMode. */
uint32_t EXMC_NWAITPolarity; /*!< Specifies the polarity of NWAIT signal from memory,
details in @ref EXMC_NWAITPolarity. */
uint32_t EXMC_BurstMode; /*!< Enable or Disable the burst mode, details in
@ref EXMC_BurstMode. */
uint32_t EXMC_DatabusWidth; /*!< Specifies the databus width of external memory,
details in @ref EXMC_DatabusWidth. */
uint32_t EXMC_MemoryType; /*!< Specifies the type of external memory, details in
@ref EXMC_MemoryType. */
uint32_t EXMC_AddressDataMux; /*!< Specifies whether the data bus and address bus are multiplexed
or not,details in @ref EXMC_AddressDataMux. */
EXMC_NORSRAMTimingInitPara *EXMC_ReadWriteTimingParaStruct; /*!< The struct EXMC_NORSRAMTimingInitPara pointer,which is
used to define the timing parameters for read and write
if the ExtendedMode is not used or define the timing
parameters for read if the ExtendedMode is used. */
EXMC_NORSRAMTimingInitPara *EXMC_WriteTimingParaStruct; /*!< The struct EXMC_NORSRAMTimingInitPara pointer,which is
only used to define the timing parameters for write when
the ExtendedMode is used. */
} EXMC_NORSRAMInitPara;
/**
* @brief Timing parameters For EXMC NAND and PCCARD Banks
*/
typedef struct {
uint32_t EXMC_DatabusHiZTime; /*!< The number of HCLK cycles to configure the dadtabus HiZ time
for write operation, which can be a value between 0x00 and 0xFF. */
uint32_t EXMC_HoldTime; /*!< The number of HCLK cycles to configure the address hold time
(or the data hold time for write operation),which can be a value
between 0x00 and 0xFF. */
uint32_t EXMC_WaitTime; /*!< The number of HCLK cycles to configure the minimum wait time,
which can be a value between 0x00 and 0xFF. */
uint32_t EXMC_SetupTime; /*!< The number of HCLK cycles to configure the address setup time ,
which can be a value between 0x00 and 0xFF. */
} EXMC_NAND_PCCARDTimingInitPara;
/**
* @brief EXMC NAND Init structure definition
*/
typedef struct {
uint32_t EXMC_NANDBank; /*!< The specified Bank of NAND FLASH, choose one
from @ref EXMC_NANDBank. */
uint32_t EXMC_ECCSize; /*!< The page size for the ECC calculation,details
in @ref EXMC_ECCSize. */
uint32_t EXMC_ATRLatency; /*!< The number of HCLK cycles to configure the
latency of ALE low to RB low, which can be a
value between 0x0 and 0xF. */
uint32_t EXMC_CTRLatency; /*!< The number of HCLK cycles to configure the
latency of CLE low to RB low, which can be a
value between 0x0 and 0xF. */
uint32_t EXMC_ECCLogic; /*!< Enable or Disable the ECC calculation logic,
details in @ref EXMC_ECCLogic. */
uint32_t EXMC_DatabusWidth; /*!< the NAND flash databus width, details in
@ref EXMC_DatabusWidth. */
uint32_t EXMC_WaitFeature; /*!< Enables or Disables the Wait feature,details
in @ref EXMC_WaitFeature. */
EXMC_NAND_PCCARDTimingInitPara *EXMC_CommonSpaceTimingParaStruct; /*!< The struct EXMC_NAND_PCCARDTimingInitPara
pointer, which is used to define the timing
parameters for NAND flash Common Space. */
EXMC_NAND_PCCARDTimingInitPara *EXMC_AttributeSpaceTimingParaStruct; /*!< The struct EXMC_NAND_PCCARDTimingInitPara
pointer, which is used to define the timing
parameters for NAND flash Attribute Space. */
} EXMC_NANDInitPara;
/**
* @brief EXMC PCCARD Init structure definition
*/
typedef struct {
uint32_t EXMC_ATRLatency; /*!< The number of HCLK cycles to configure
the latency of ALE low to RB low, which can
be a value between 0x0 and 0xF. */
uint32_t EXMC_CTRLatency; /*!< The number of HCLK cycles to configure
the latency of CLE low to RB low, which can
be a value between 0x0 and 0xF. */
uint32_t EXMC_WaitFeature; /*!< Enables or Disables the Wait feature,details
in @ref EXMC_WaitFeature. */
EXMC_NAND_PCCARDTimingInitPara *EXMC_CommonSpaceTimingParaStruct; /*!< The struct EXMC_NAND_PCCARDTimingInitPara
pointer, which is used to define the timing
parameters for PC CARD Common Space. */
EXMC_NAND_PCCARDTimingInitPara *EXMC_AttributeSpaceTimingParaStruct; /*!< The struct EXMC_NAND_PCCARDTimingInitPara
pointer, which is used to define the timing
parameters for PC CARD Attribute Space. */
EXMC_NAND_PCCARDTimingInitPara *EXMC_IOSpaceTimingParaStruct; /*!< The struct EXMC_NAND_PCCARDTimingInitPara
pointer, which is used to define the timing
parameters for PC CARD I/O Space. */
} EXMC_PCCARDInitPara;
/**
* @}
*/
/** @defgroup EXMC_Exported_Constants
* @{
*/
/** @defgroup EXMC_NORSRAMBank
* @{
*/
#define EXMC_BANK1_NORSRAM1 ((uint32_t)0x00000001)
#define EXMC_BANK1_NORSRAM2 ((uint32_t)0x00000002)
#define EXMC_BANK1_NORSRAM3 ((uint32_t)0x00000003)
#define EXMC_BANK1_NORSRAM4 ((uint32_t)0x00000004)
/**
* @}
*/
/** @defgroup EXMC_NANDBank
* @{
*/
#define EXMC_BANK2_NAND ((uint32_t)0x00000010)
#define EXMC_BANK3_NAND ((uint32_t)0x00000100)
/**
* @}
*/
/** @defgroup EXMC_PCCARD_Bank
* @{
*/
#define EXMC_BANK4_PCCARD ((uint32_t)0x00001000)
/**
* @}
*/
/** @defgroup NORSRAM_Controller
* @{
*/
/** @defgroup EXMC_AddressDataMux
* @{
*/
#define EXMC_ADDRESS_DATA_MUX_DISABLE ((uint32_t)0x00000000)
#define EXMC_ADDRESS_DATA_MUX_ENABLE ((uint32_t)0x00000002)
/**
* @}
*/
/** @defgroup EXMC_MemoryType
* @{
*/
#define EXMC_MEMORY_TYPE_SRAM ((uint32_t)0x00000000)
#define EXMC_MEMORY_TYPE_PSRAM ((uint32_t)0x00000004)
#define EXMC_MEMORY_TYPE_NOR ((uint32_t)0x00000008)
/**
* @}
*/
/** @defgroup EXMC_DatabusWidth
* @{
*/
#define EXMC_DATABUS_WIDTH_8B ((uint32_t)0x00000000)
#define EXMC_DATABUS_WIDTH_16B ((uint32_t)0x00000010)
/**
* @}
*/
/** @defgroup EXMC_NORFlash_Access
* @{
*/
#define EXMC_NORFLASH_ACCESS_DISABLE ((uint32_t)0x00000000)
#define EXMC_NORFLASH_ACCESS_ENABLE ((uint32_t)0x00000040)
/**
* @}
*/
/** @defgroup EXMC_BurstMode
* @{
*/
#define EXMC_BURST_MODE_DISABLE ((uint32_t)0x00000000)
#define EXMC_BURST_MODE_ENABLE ((uint32_t)0x00000100)
/**
* @}
*/
/** @defgroup EXMC_AsynWait
* @{
*/
#define EXMC_ASYN_WAIT_DISABLE ((uint32_t)0x00000000)
#define EXMC_ASYN_WAIT_ENABLE ((uint32_t)0x00008000)
/**
* @}
*/
/** @defgroup EXMC_NWAITPolarity
* @{
*/
#define EXMC_NWAIT_POLARITY_LOW ((uint32_t)0x00000000)
#define EXMC_NWAIT_POLARITY_HIGH ((uint32_t)0x00000200)
/**
* @}
*/
/** @defgroup EXMC_WrapBurstMode
* @{
*/
#define EXMC_WRAP_BURST_MODE_DISABLE ((uint32_t)0x00000000)
#define EXMC_WRAP_BURST_MODE_ENABLE ((uint32_t)0x00000400)
/**
* @}
*/
/** @defgroup EXMC_NWAITConfig
* @{
*/
#define EXMC_NWAIT_CONFIG_BEFORE ((uint32_t)0x00000000)
#define EXMC_NWAIT_CONFIG_DURING ((uint32_t)0x00000800)
/**
* @}
*/
/** @defgroup EXMC_MemoryWrite
* @{
*/
#define EXMC_MEMORY_WRITE_DISABLE ((uint32_t)0x00000000)
#define EXMC_MEMORY_WRITE_ENABLE ((uint32_t)0x00001000)
/**
* @}
*/
/** @defgroup EXMC_NWAITSignal
* @{
*/
#define EXMC_NWAIT_SIGNAL_DISABLE ((uint32_t)0x00000000)
#define EXMC_NWAIT_SIGNAL_ENABLE ((uint32_t)0x00002000)
/**
* @}
*/
/** @defgroup EXMC_ExtendedMode
* @{
*/
#define EXMC_EXTENDED_MODE_DISABLE ((uint32_t)0x00000000)
#define EXMC_EXTENDED_MODE_ENABLE ((uint32_t)0x00004000)
/**
* @}
*/
/** @defgroup EXMC_WriteMode
* @{
*/
#define EXMC_ASYN_WRITE ((uint32_t)0x00000000)
#define EXMC_SYN_WRITE ((uint32_t)0x00080000)
/**
* @}
*/
/** @defgroup EXMC_AsynAccess_Mode
* @{
*/
#define EXMC_ACCESS_MODE_A ((uint32_t)0x00000000)
#define EXMC_ACCESS_MODE_B ((uint32_t)0x10000000)
#define EXMC_ACCESS_MODE_C ((uint32_t)0x20000000)
#define EXMC_ACCESS_MODE_D ((uint32_t)0x30000000)
/**
* @}
*/
/**
* @}
*/
/** @defgroup NAND_PCCARD_Controller
* @{
*/
/** @defgroup EXMC_WaitFeature
* @{
*/
#define EXMC_WAIT_FEATURE_DISABLE ((uint32_t)0x00000000)
#define EXMC_WAIT_FEATURE_ENABLE ((uint32_t)0x00000002)
/**
* @}
*/
/** @defgroup EXMC_ECCLogic
* @{
*/
#define EXMC_ECC_LOGIC_DISABLE ((uint32_t)0x00000000)
#define EXMC_ECC_LOGIC_ENABLE ((uint32_t)0x00000040)
/**
* @}
*/
/** @defgroup EXMC_ECCSize
* @{
*/
#define EXMC_ECC_SIZE_256BYTES ((uint32_t)0x00000000)
#define EXMC_ECC_SIZE_512BYTES ((uint32_t)0x00020000)
#define EXMC_ECC_SIZE_1024BYTES ((uint32_t)0x00040000)
#define EXMC_ECC_SIZE_2048BYTES ((uint32_t)0x00060000)
#define EXMC_ECC_SIZE_4096BYTES ((uint32_t)0x00080000)
#define EXMC_ECC_SIZE_8192BYTES ((uint32_t)0x000A0000)
/**
* @}
*/
/** @defgroup EXMC_Interrupt_Source
* @{
*/
#define EXMC_INT_RISE ((uint32_t)0x00000008)
#define EXMC_INT_LEVEL ((uint32_t)0x00000010)
#define EXMC_INT_FALL ((uint32_t)0x00000020)
/**
* @}
*/
/** @defgroup EXMC_FLAG
* @{
*/
#define EXMC_FLAG_RISE ((uint32_t)0x00000001)
#define EXMC_FLAG_LEVEL ((uint32_t)0x00000002)
#define EXMC_FLAG_FALL ((uint32_t)0x00000004)
#define EXMC_FLAG_FIFOE ((uint32_t)0x00000040)
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/** @defgroup EXMC_Exported_Functions
* @{
*/
void EXMC_NORSRAM_DeInit(uint32_t EXMC_NORSRAMBank);
void EXMC_NAND_DeInit(uint32_t EXMC_NANDBank);
void EXMC_PCCARD_DeInit(void);
void EXMC_NORSRAM_Init(EXMC_NORSRAMInitPara *EXMC_NORSRAMInitParaStruct);
void EXMC_NAND_Init(EXMC_NANDInitPara *EXMC_NANDInitParaStruct);
void EXMC_PCCARD_Init(EXMC_PCCARDInitPara *EXMC_PCCARDInitParaStruct);
void EXMC_NORSRAMStruct_Init(EXMC_NORSRAMInitPara *EXMC_NORSRAMInitParaStruct);
void EXMC_NANDStruct_Init(EXMC_NANDInitPara *EXMC_NANDInitParaStruct);
void EXMC_PCCARDStruct_Init(EXMC_PCCARDInitPara *EXMC_PCCARDInitParaStruct);
void EXMC_NORSRAM_Enable(uint32_t EXMC_NORSRAMBank, TypeState NewValue);
void EXMC_NAND_Enable(uint32_t EXMC_NANDBank, TypeState NewValue);
void EXMC_PCCARD_Enable(TypeState NewValue);
void EXMC_NANDECC_Enable(uint32_t EXMC_NANDBank, TypeState NewValue);
uint32_t EXMC_GetECC(uint32_t EXMC_NANDBank);
void EXMC_INTConfig(uint32_t EXMC_PCNANDBank, uint32_t EXMC_INT, TypeState NewValue);
TypeState EXMC_GetBitState(uint32_t EXMC_PCNANDBank, uint32_t EXMC_FLAG);
void EXMC_ClearBitState(uint32_t EXMC_PCNANDBank, uint32_t EXMC_FLAG);
TypeState EXMC_GetIntBitState(uint32_t EXMC_PCNANDBank, uint32_t EXMC_INT);
void EXMC_ClearIntBitState(uint32_t EXMC_PCNANDBank, uint32_t EXMC_INT);
#ifdef __cplusplus
}
#endif
#endif /*__GD32F10x_EXMC_H */
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/

View File

@ -0,0 +1,130 @@
/**
******************************************************************************
* @brief EXTI header file of the firmware library.
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __GD32F10X_EXTI_H
#define __GD32F10X_EXTI_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "gd32f10x.h"
/** @addtogroup GD32F10x_Firmware
* @{
*/
/** @addtogroup EXTI
* @{
*/
/** @defgroup EXTI_Exported_Types
* @{
*/
/**
* @brief EXTI Mode enumeration
*/
typedef enum {
EXTI_Mode_Interrupt = 0x00,
EXTI_Mode_Event = 0x04
} EXTI_ModePara;
/**
* @brief EXTI Trigger enumeration
*/
typedef enum {
EXTI_Trigger_Rising = 0x08,
EXTI_Trigger_Falling = 0x0C,
EXTI_Trigger_Rising_Falling = 0x10
} EXTI_TriggerPara;
/**
* @brief EXTI Initial Parameters
*/
typedef struct {
uint32_t EXTI_LINE; /*!< The selection of EXTI lines. */
EXTI_ModePara EXTI_Mode; /*!< The mode for the EXTI lines, detailed in @ref EXTIMode_Para. */
EXTI_TriggerPara EXTI_Trigger; /*!< The trigger edge for the EXTI lines, detailed in EXTI_TriggerPara. */
TypeState EXTI_LINEEnable; /*!< The new value of the selected EXTI lines. */
} EXTI_InitPara;
/**
* @}
*/
/** @defgroup EXTI_Exported_Constants
* @{
*/
/** @defgroup EXTI_lines
* @{
*/
#define EXTI_LINE0 ((uint32_t)0x00000001) /*!< External interrupt line 0 */
#define EXTI_LINE1 ((uint32_t)0x00000002) /*!< External interrupt line 1 */
#define EXTI_LINE2 ((uint32_t)0x00000004) /*!< External interrupt line 2 */
#define EXTI_LINE3 ((uint32_t)0x00000008) /*!< External interrupt line 3 */
#define EXTI_LINE4 ((uint32_t)0x00000010) /*!< External interrupt line 4 */
#define EXTI_LINE5 ((uint32_t)0x00000020) /*!< External interrupt line 5 */
#define EXTI_LINE6 ((uint32_t)0x00000040) /*!< External interrupt line 6 */
#define EXTI_LINE7 ((uint32_t)0x00000080) /*!< External interrupt line 7 */
#define EXTI_LINE8 ((uint32_t)0x00000100) /*!< External interrupt line 8 */
#define EXTI_LINE9 ((uint32_t)0x00000200) /*!< External interrupt line 9 */
#define EXTI_LINE10 ((uint32_t)0x00000400) /*!< External interrupt line 10 */
#define EXTI_LINE11 ((uint32_t)0x00000800) /*!< External interrupt line 11 */
#define EXTI_LINE12 ((uint32_t)0x00001000) /*!< External interrupt line 12 */
#define EXTI_LINE13 ((uint32_t)0x00002000) /*!< External interrupt line 13 */
#define EXTI_LINE14 ((uint32_t)0x00004000) /*!< External interrupt line 14 */
#define EXTI_LINE15 ((uint32_t)0x00008000) /*!< External interrupt line 15 */
#define EXTI_LINE16 ((uint32_t)0x00010000) /*!< External interrupt line 16
Connected to the LVD */
#define EXTI_LINE17 ((uint32_t)0x00020000) /*!< External interrupt line 17
Connected to the RTC Alarm */
#define EXTI_LINE18 ((uint32_t)0x00040000) /*!< External interrupt line 18
Connected to the USB Wakeup */
#define EXTI_LINE19 ((uint32_t)0x00080000) /*!< External interrupt line 19
Connected to the Ethernet Wakeup */
/**
* @}
*/
/**
* @}
*/
/** @defgroup EXTI_Exported_Functions
* @{
*/
void EXTI_DeInit(EXTI_InitPara *EXTI_InitParaStruct);
void EXTI_Init(EXTI_InitPara *EXTI_InitParaStruct);
void EXTI_SWINT_Enable(uint32_t EXTI_LINE);
TypeState EXTI_GetBitState(uint32_t EXTI_LINE);
void EXTI_ClearBitState(uint32_t EXTI_LINE);
TypeState EXTI_GetIntBitState(uint32_t EXTI_LINE);
void EXTI_ClearIntBitState(uint32_t EXTI_LINE);
#ifdef __cplusplus
}
#endif
#endif /* __GD32F10X_EXTI_H */
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/

View File

@ -0,0 +1,263 @@
/**
******************************************************************************
* @brief FMC header file of the firmware library.
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __GD32F10X_FMC_H
#define __GD32F10X_FMC_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "gd32f10x.h"
/** @addtogroup GD32F10x_Firmware
* @{
*/
/** @addtogroup FMC
* @{
*/
/* Exported types ------------------------------------------------------------*/
/** @defgroup FMC_Exported_Types
* @{
*/
/**
* @brief FMC State
*/
typedef enum {
FMC_READY,
FMC_BSY,
FMC_WRPERR,
FMC_PGERR,
FMC_TIMEOUT_ERR
} FMC_State;
/**
* @}
*/
/* Exported constants --------------------------------------------------------*/
/** @defgroup FMC_Exported_Constants
* @{
*/
/** @defgroup FMC_Interrupts
* @{
*/
#define FMC_INT_EOP FMC_CMR_ENDIE /*!< End of programming interrupt source */
#define FMC_INT_ERR FMC_CMR_ERIE /*!< Error interrupt source */
#define FMC_INT_B2_EOP ((uint32_t)0x80000400) /*!< Bank2 End of programming interrupt source */
#define FMC_INT_B2_ERR ((uint32_t)0x80001000) /*!< Bank2 Error interrupt source */
/**
* @}
*/
/** @defgroup FMC_Option_Bytes_Write_Protection
* @{
*/
#define WRP_SECTOR0 ((uint32_t)0x00000001) /*!< Write protection of sector 0 */
#define WRP_SECTOR1 ((uint32_t)0x00000002) /*!< Write protection of sector 1 */
#define WRP_SECTOR2 ((uint32_t)0x00000004) /*!< Write protection of sector 2 */
#define WRP_SECTOR3 ((uint32_t)0x00000008) /*!< Write protection of sector 3 */
#define WRP_SECTOR4 ((uint32_t)0x00000010) /*!< Write protection of sector 4 */
#define WRP_SECTOR5 ((uint32_t)0x00000020) /*!< Write protection of sector 5 */
#define WRP_SECTOR6 ((uint32_t)0x00000040) /*!< Write protection of sector 6 */
#define WRP_SECTOR7 ((uint32_t)0x00000080) /*!< Write protection of sector 7 */
#define WRP_SECTOR8 ((uint32_t)0x00000100) /*!< Write protection of sector 8 */
#define WRP_SECTOR9 ((uint32_t)0x00000200) /*!< Write protection of sector 9 */
#define WRP_SECTOR10 ((uint32_t)0x00000400) /*!< Write protection of sector 10 */
#define WRP_SECTOR11 ((uint32_t)0x00000800) /*!< Write protection of sector 11 */
#define WRP_SECTOR12 ((uint32_t)0x00001000) /*!< Write protection of sector 12 */
#define WRP_SECTOR13 ((uint32_t)0x00002000) /*!< Write protection of sector 13 */
#define WRP_SECTOR14 ((uint32_t)0x00004000) /*!< Write protection of sector 14 */
#define WRP_SECTOR15 ((uint32_t)0x00008000) /*!< Write protection of sector 15 */
#define WRP_SECTOR16 ((uint32_t)0x00010000) /*!< Write protection of sector 16 */
#define WRP_SECTOR17 ((uint32_t)0x00020000) /*!< Write protection of sector 17 */
#define WRP_SECTOR18 ((uint32_t)0x00040000) /*!< Write protection of sector 18 */
#define WRP_SECTOR19 ((uint32_t)0x00080000) /*!< Write protection of sector 19 */
#define WRP_SECTOR20 ((uint32_t)0x00100000) /*!< Write protection of sector 20 */
#define WRP_SECTOR21 ((uint32_t)0x00200000) /*!< Write protection of sector 21 */
#define WRP_SECTOR22 ((uint32_t)0x00400000) /*!< Write protection of sector 22 */
#define WRP_SECTOR23 ((uint32_t)0x00800000) /*!< Write protection of sector 23 */
#define WRP_SECTOR24 ((uint32_t)0x01000000) /*!< Write protection of sector 24 */
#define WRP_SECTOR25 ((uint32_t)0x02000000) /*!< Write protection of sector 25 */
#define WRP_SECTOR26 ((uint32_t)0x04000000) /*!< Write protection of sector 26 */
#define WRP_SECTOR27 ((uint32_t)0x08000000) /*!< Write protection of sector 27 */
#define WRP_SECTOR28 ((uint32_t)0x10000000) /*!< Write protection of sector 28 */
#define WRP_SECTOR29 ((uint32_t)0x20000000) /*!< Write protection of sector 29 */
#define WRP_SECTOR30 ((uint32_t)0x40000000) /*!< Write protection of sector 30 */
#define WRP_SECTOR31 ((uint32_t)0x80000000) /*!< Write protection of sector 31 */
#define WRP_ALLSECTORS ((uint32_t)0xFFFFFFFF) /*!< Write protection of all Sectors */
/**
* @}
*/
/** @defgroup FMC_Option_Bytes_Read_Protection
* @{
*/
/**
* @brief FMC_Read Protection Level
*/
#define RDP_LEVEL_0 ((uint8_t)0xA5)
#define RDP_LEVEL_1 ((uint8_t)0xBB)
/**
* @}
*/
/** @defgroup FMC_Option_Bytes_IWatchdog
* @{
*/
#define OB_IWDG_SW ((uint8_t)0x01) /*!< Software IWDG selected */
#define OB_IWDG_HW ((uint8_t)0x00) /*!< Hardware IWDG selected */
/**
* @}
*/
/** @defgroup FMC_Option_Bytes_nRST_DEEPSLEEP
* @{
*/
#define OB_DEEPSLEEP_NORST ((uint8_t)0x02) /*!< No reset generated when entering in DEEPSLEEP */
#define OB_DEEPSLEEP_RST ((uint8_t)0x00) /*!< Reset generated when entering in DEEPSLEEP */
/**
* @}
*/
/** @defgroup FMC_Option_Bytes_nRST_STDBY
* @{
*/
#define OB_STDBY_NORST ((uint8_t)0x04) /*!< No reset generated when entering in STANDBY */
#define OB_STDBY_RST ((uint8_t)0x00) /*!< Reset generated when entering in STANDBY */
/**
* @}
*/
/** @defgroup FMC_Option_Bytes_BOOT
* @{
*/
#define OB_BOOT_B1 ((uint8_t)0x08) /*!< BOOT from Bank1 */
#define OB_BOOT_B2 ((uint8_t)0x00) /*!< BOOT from Bank2 */
#define OB_USER_BFB2 ((uint16_t)0x0008) /*!< Configure BOOT from Bank1 */
/**
* @}
*/
/** @defgroup FMC_Flags
* @{
*/
#define FMC_FLAG_BSY FMC_CSR_BUSY /*!< FMC Busy flag */
#define FMC_FLAG_PERR FMC_CSR_PGEF /*!< FMC Programming error flag */
#define FMC_FLAG_WERR FMC_CSR_WPEF /*!< FMC Write protected error flag */
#define FMC_FLAG_EOP FMC_CSR_ENDF /*!< FMC End of Programming flag */
#define FMC_FLAG_OPTERR ((uint32_t)0x00000001) /*!< FMC Option Byte error flag */
#define FMC_FLAG_B2_BSY ((uint32_t)0x80000001) /*!< FMC Busy flag */
#define FMC_FLAG_B2_PERR ((uint32_t)0x80000004) /*!< FMC Programming error flag */
#define FMC_FLAG_B2_WERR ((uint32_t)0x80000010) /*!< FMC Write protected error flag */
#define FMC_FLAG_B2_EOP ((uint32_t)0x80000020) /*!< FMC End of Programming flag */
/**
* @}
*/
/** @defgroup FMC_Timeout_definition
* @{
*/
#define FMC_TIMEOUT_COUNT ((uint32_t)0x000F0000)
/**
* @}
*/
/* FMC BANK address */
#define FMC_B1_END_ADDRESS ((uint32_t)0x807FFFF)
#define FMC_BANK1_SIZE 0x0200
#define FMC_SIZE (*(uint16_t *)0x1ffff7e0)
/**
* @}
*/
/** @defgroup FMC_Exported_Functions
* @{
*/
/**
* @brief FMC memory functions.
*/
/* FMC Main Memory Programming functions *****************************************/
void FMC_Unlock(void);
void FMC_UnlockB1(void);
void FMC_UnlockB2(void);
void FMC_Lock(void);
void FMC_LockB1(void);
void FMC_LockB2(void);
FMC_State FMC_ErasePage(uint32_t Page_Address);
FMC_State FMC_MassErase(void);
FMC_State FMC_MassB1Erase(void);
FMC_State FMC_MassB2Erase(void);
FMC_State FMC_ProgramWord(uint32_t Address, uint32_t Data);
/* FMC Option Bytes Programming functions *****************************************/
void FMC_OB_Unlock(void);
void FMC_OB_Lock(void);
void FMC_OB_Reset(void);
FMC_State FMC_OB_Erase(void);
FMC_State FMC_OB_EnableWRP(uint32_t OB_WRP);
FMC_State FMC_ReadOutProtection(TypeState NewValue);
FMC_State FMC_OB_RDPConfig(uint8_t OB_RDP);
FMC_State FMC_OB_UserConfig(uint8_t OB_IWDG, uint8_t OB_DEEPSLEEP, uint8_t OB_STDBY);
FMC_State FMC_OB_BOOTConfig(uint8_t OB_BOOT);
FMC_State FMC_OB_WriteUser(uint8_t OB_USER);
FMC_State FMC_ProgramOptionByteData(uint32_t Address, uint8_t Data);
uint8_t FMC_OB_GetUser(void);
uint32_t FMC_OB_GetWRP(void);
TypeState FMC_OB_GetRDP(void);
/* FMC Interrupts and flags management functions **********************************/
void FMC_INTConfig(uint32_t FMC_INT, TypeState NewValue);
TypeState FMC_GetBitState(uint32_t FMC_FLAG);
void FMC_ClearBitState(uint32_t FMC_FLAG);
FMC_State FMC_GetState(void);
FMC_State FMC_GetB1State(void);
FMC_State FMC_GetB2State(void);
FMC_State FMC_WaitReady(uint32_t uCount);
FMC_State FMC_B1_WaitReady(uint32_t uCount);
FMC_State FMC_B2_WaitReady(uint32_t uCount);
#ifdef __cplusplus
}
#endif
#endif /* __GD32F10X_FMC_H */
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/

View File

@ -0,0 +1,281 @@
/**
******************************************************************************
* @brief GPIO header file of the firmware library.
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __GD32F10x_GPIO_H
#define __GD32F10x_GPIO_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "gd32f10x.h"
/** @addtogroup GD32F10x_Firmware
* @{
*/
/** @addtogroup GPIO
* @{
*/
/** @defgroup GPIO_Exported_Types
* @{
*/
/**
* @brief Output_Maximum_frequency_enumeration
*/
typedef enum {
GPIO_SPEED_10MHZ = 1,
GPIO_SPEED_2MHZ,
GPIO_SPEED_50MHZ
} GPIO_SpeedPara;
/**
* @brief GPIO_Mode_enumeration
*/
typedef enum {
GPIO_MODE_AIN = 0x0,
GPIO_MODE_IN_FLOATING = 0x04,
GPIO_MODE_IPD = 0x28,
GPIO_MODE_IPU = 0x48,
GPIO_MODE_OUT_OD = 0x14,
GPIO_MODE_OUT_PP = 0X10,
GPIO_MODE_AF_OD = 0X1C,
GPIO_MODE_AF_PP = 0X18
} GPIO_ModePara;
/**
* @brief GPIO Initial Parameters
*/
typedef struct {
uint16_t GPIO_Pin; /*!< The GPIO pins to be configured. choose several from @ref GPIO_pins_define */
GPIO_SpeedPara GPIO_Speed; /*!< The speed for This parameter can be a value of @ref GPIOSpeed_TypeDef */
GPIO_ModePara GPIO_Mode; /*!< The operating mode for the selected pins. choose one from @ref GPIO_ModePara */
} GPIO_InitPara;
/**
* @brief Bit_State_enumeration
*/
typedef enum {
Bit_RESET = 0,
Bit_SET
} BitState;
/**
* @}
*/
/** @defgroup GPIO_Exported_Constants
* @{
*/
/** @defgroup GPIO_pins_define
* @{
*/
#define GPIO_PIN_0 ((uint16_t)0x0001)
#define GPIO_PIN_1 ((uint16_t)0x0002)
#define GPIO_PIN_2 ((uint16_t)0x0004)
#define GPIO_PIN_3 ((uint16_t)0x0008)
#define GPIO_PIN_4 ((uint16_t)0x0010)
#define GPIO_PIN_5 ((uint16_t)0x0020)
#define GPIO_PIN_6 ((uint16_t)0x0040)
#define GPIO_PIN_7 ((uint16_t)0x0080)
#define GPIO_PIN_8 ((uint16_t)0x0100)
#define GPIO_PIN_9 ((uint16_t)0x0200)
#define GPIO_PIN_10 ((uint16_t)0x0400)
#define GPIO_PIN_11 ((uint16_t)0x0800)
#define GPIO_PIN_12 ((uint16_t)0x1000)
#define GPIO_PIN_13 ((uint16_t)0x2000)
#define GPIO_PIN_14 ((uint16_t)0x4000)
#define GPIO_PIN_15 ((uint16_t)0x8000)
#define GPIO_PIN_ALL ((uint16_t)0xFFFF)
/**
* @}
*/
/** @defgroup GPIO_Remap_define
* @{
*/
#define GPIO_REMAP_SPI1 ((uint32_t)0x00000001)
#define GPIO_REMAP_I2C1 ((uint32_t)0x00000002)
#define GPIO_REMAP_USART1 ((uint32_t)0x00000004)
#define GPIO_REMAP_USART2 ((uint32_t)0x00000008)
#define GPIO_PARTIAL_REMAP_USART3 ((uint32_t)0x00140010)
#define GPIO_FULL_REMAP_USART3 ((uint32_t)0x00140030)
#define GPIO_PARTIAL_REMAP_TIMER1 ((uint32_t)0x00160040)
#define GPIO_FULL_REMAP_TIMER1 ((uint32_t)0x001600C0)
#define GPIO_PARTIAL_REMAP1_TIMER2 ((uint32_t)0x00180100)
#define GPIO_PARTIAL_REMAP2_TIMER2 ((uint32_t)0x00180200)
#define GPIO_FULL_REMAP_TIMER2 ((uint32_t)0x00180300)
#define GPIO_PARTIAL_REMAP_TIMER3 ((uint32_t)0x001A0800)
#define GPIO_FULL_REMAP_TIMER3 ((uint32_t)0x001A0C00)
#define GPIO_REMAP_TIMER4 ((uint32_t)0x00001000)
#define GPIO_REMAP1_CAN1 ((uint32_t)0x001D4000)
#define GPIO_REMAP2_CAN1 ((uint32_t)0x001D6000)
#define GPIO_REMAP_PD01 ((uint32_t)0x00008000)
#define GPIO_REMAP_TIMER5CH4_LSI ((uint32_t)0x00200001)
#define GPIO_REMAP_ADC1_ETRGINJ ((uint32_t)0x00200002)
#define GPIO_REMAP_ADC1_ETRGREG ((uint32_t)0x00200004)
#define GPIO_REMAP_ADC2_ETRGINJ ((uint32_t)0x00200008)
#define GPIO_REMAP_ADC2_ETRGREG ((uint32_t)0x00200010)
#define GPIO_REMAP_ETH ((uint32_t)0x00200020)
#define GPIO_REMAP_CAN2 ((uint32_t)0x00200040)
#define GPIO_REMAP_SWJ_NOJTRST ((uint32_t)0x00300100)
#define GPIO_REMAP_SWJ_JTAGDISABLE ((uint32_t)0x00300200)
#define GPIO_REMAP_SWJ_DISABLE ((uint32_t)0x00300400)
#define GPIO_REMAP_SPI3 ((uint32_t)0x00201100)
#define GPIO_REMAP_TIMER2ITR1_PTP_SOF ((uint32_t)0x00202000)
#define GPIO_REMAP_PTP_PPS ((uint32_t)0x00204000)
#define GPIO_REMAP_TIMER15 ((uint32_t)0x80000001)
#define GPIO_REMAP_TIMER16 ((uint32_t)0x80000002)
#define GPIO_REMAP_TIMER17 ((uint32_t)0x80000004)
#define GPIO_REMAP_CEC ((uint32_t)0x80000008)
#define GPIO_REMAP_TIMER1_DMA ((uint32_t)0x80000010)
#define GPIO_REMAP_TIMER9 ((uint32_t)0x80000020)
#define GPIO_REMAP_TIMER10 ((uint32_t)0x80000040)
#define GPIO_REMAP_TIMER11 ((uint32_t)0x80000080)
#define GPIO_REMAP_TIMER13 ((uint32_t)0x80000100)
#define GPIO_REMAP_TIMER14 ((uint32_t)0x80000200)
#define GPIO_REMAP_EXMC_NADV ((uint32_t)0x80000400)
#define GPIO_REMAP_TIMER67_DAC_DMA ((uint32_t)0x80000800)
#define GPIO_REMAP_TIMER12 ((uint32_t)0x80001000)
#define GPIO_REMAP_MISC ((uint32_t)0x80002000)
/**
* @}
*/
/** @defgroup GPIO_Port_Sources
* @{
*/
#define GPIO_PORT_SOURCE_GPIOA ((uint8_t)0x00)
#define GPIO_PORT_SOURCE_GPIOB ((uint8_t)0x01)
#define GPIO_PORT_SOURCE_GPIOC ((uint8_t)0x02)
#define GPIO_PORT_SOURCE_GPIOD ((uint8_t)0x03)
#define GPIO_PORT_SOURCE_GPIOE ((uint8_t)0x04)
#define GPIO_PORT_SOURCE_GPIOF ((uint8_t)0x05)
#define GPIO_PORT_SOURCE_GPIOG ((uint8_t)0x06)
/**
* @}
*/
/** @defgroup GPIO_Pin_sources
* @{
*/
#define GPIO_PINSOURCE0 ((uint8_t)0x00)
#define GPIO_PINSOURCE1 ((uint8_t)0x01)
#define GPIO_PINSOURCE2 ((uint8_t)0x02)
#define GPIO_PINSOURCE3 ((uint8_t)0x03)
#define GPIO_PINSOURCE4 ((uint8_t)0x04)
#define GPIO_PINSOURCE5 ((uint8_t)0x05)
#define GPIO_PINSOURCE6 ((uint8_t)0x06)
#define GPIO_PINSOURCE7 ((uint8_t)0x07)
#define GPIO_PINSOURCE8 ((uint8_t)0x08)
#define GPIO_PINSOURCE9 ((uint8_t)0x09)
#define GPIO_PINSOURCE10 ((uint8_t)0x0A)
#define GPIO_PINSOURCE11 ((uint8_t)0x0B)
#define GPIO_PINSOURCE12 ((uint8_t)0x0C)
#define GPIO_PINSOURCE13 ((uint8_t)0x0D)
#define GPIO_PINSOURCE14 ((uint8_t)0x0E)
#define GPIO_PINSOURCE15 ((uint8_t)0x0F)
/**
* @}
*/
/** @defgroup Ethernet_Media_Interface
* @{
*/
#define GPIO_ETH_MEDIAINTERFACE_MII ((uint32_t)0x00000000)
#define GPIO_ETH_MEDIAINTERFACE_RMII ((uint32_t)0x00800000)
/**
* @}
*/
/* output mode definitions */
#define CTL_CLTR(regval) (BITS(0,1) & ((uint32_t)(regval) << 0))
#define GPIO_MODE_INPUT CTL_CLTR(0) /*!< input mode */
#define GPIO_MODE_OUTPUT CTL_CLTR(1) /*!< output mode */
#define GPIO_MODE_AF CTL_CLTR(2) /*!< alternate function mode */
#define GPIO_MODE_ANALOG CTL_CLTR(3) /*!< analog mode */
/** @defgroup AFIO_Event_Output
* @{
*/
#define AFIO_ECR_EVOE_SET ((uint32_t)0x00000080)
#define AFIO_ECR_EVOE_RESET ((uint32_t)0xffffff7f)
/* gpio alternate function */
#define AF(regval) (BITS(0,3) & ((uint32_t)(regval) << 0))
#define GPIO_AF_0 AF(0) /*!< alternate function selected 0 */
#define GPIO_AF_1 AF(1) /*!< alternate function selected 1 */
#define GPIO_AF_2 AF(2) /*!< alternate function selected 2 */
#define GPIO_AF_3 AF(3) /*!< alternate function selected 3 */
#define GPIO_AF_4 AF(4) /*!< alternate function selected 4 */
#define GPIO_AF_5 AF(5) /*!< alternate function selected 5 */
#define GPIO_AF_6 AF(6) /*!< alternate function selected 6 */
#define GPIO_AF_7 AF(7) /*!< alternate function selected 7 */
#define GPIO_AF_8 AF(8) /*!< alternate function selected 8 */
#define GPIO_AF_9 AF(9) /*!< alternate function selected 9 */
#define GPIO_AF_10 AF(10) /*!< alternate function selected 10 */
#define GPIO_AF_11 AF(11) /*!< alternate function selected 11 */
#define GPIO_AF_12 AF(12) /*!< alternate function selected 12 */
#define GPIO_AF_13 AF(13) /*!< alternate function selected 13 */
#define GPIO_AF_14 AF(14) /*!< alternate function selected 14 */
#define GPIO_AF_15 AF(15) /*!< alternate function selected 15 */
/**
* @}
*/
/**
* @}
*/
/** @defgroup GPIO_Exported_Functions
* @{
*/
void GPIO_DeInit(GPIO_TypeDef *GPIOx);
void GPIO_AFDeInit(void);
void GPIO_Init(GPIO_TypeDef *GPIOx, GPIO_InitPara *GPIO_InitStruct);
void GPIO_ParaInit(GPIO_InitPara *GPIO_InitStruct);
uint8_t GPIO_ReadInputBit(GPIO_TypeDef *GPIOx, uint16_t GPIO_Pin);
uint16_t GPIO_ReadInputData(GPIO_TypeDef *GPIOx);
uint8_t GPIO_ReadOutputBit(GPIO_TypeDef *GPIOx, uint16_t GPIO_Pin);
uint16_t GPIO_ReadOutputData(GPIO_TypeDef *GPIOx);
void GPIO_SetBits(GPIO_TypeDef *GPIOx, uint16_t GPIO_Pin);
void GPIO_ResetBits(GPIO_TypeDef *GPIOx, uint16_t GPIO_Pin);
void GPIO_WriteBit(GPIO_TypeDef *GPIOx, uint16_t GPIO_Pin, BitState BitVal);
void GPIO_Write(GPIO_TypeDef *GPIOx, uint16_t PortVal);
void GPIO_PinLockConfig(GPIO_TypeDef *GPIOx, uint16_t GPIO_Pin);
void GPIO_EventOutputConfig(uint8_t GPIO_PortSource, uint8_t GPIO_PinSource);
void GPIO_EventOutputEnable(TypeState NewState);
void GPIO_PinRemapConfig(uint32_t GPIO_Remap, TypeState NewState);
void GPIO_EXTILineConfig(uint8_t GPIO_PortSource, uint8_t GPIO_PinSource);
void GPIO_ETH_MediaInterfaceConfig(uint32_t GPIO_ETH_MediaInterface);
#ifdef __cplusplus
}
#endif
#endif /* __GD32F10X_GPIO_H */
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/

View File

@ -0,0 +1,289 @@
/**
******************************************************************************
* @brief I2C header file of the firmware library.
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __GD32F10X_I2C_H
#define __GD32F10X_I2C_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "gd32f10x.h"
/** @addtogroup GD32F10x_Firmware
* @{
*/
/** @addtogroup I2C
* @{
*/
/** @defgroup I2C_Exported_Types
* @{
*/
/**
* @brief I2C Initial Parameters
*/
typedef struct {
uint16_t I2C_Protocol; /*!< The protocol type, detailed in @ref I2C_Protocol */
uint16_t I2C_DutyCycle; /*!< The fast mode duty cycle, detailed in @ref I2C_Duty_Cycle */
uint32_t I2C_BitRate; /*!< The I2C bit rate which must be lower than 400k bit/s */
uint16_t I2C_AddressingMode; /*!< The I2C addressing mode, detailed in @ref I2C_Addressing_Mode */
uint16_t I2C_DeviceAddress; /*!< The device address */
} I2C_InitPara;
/**
* @}
*/
/** @defgroup I2C_Exported_Constants
* @{
*/
/** @defgroup I2C_Protocol
* @{
*/
#define I2C_PROTOCOL_I2C ((uint16_t)0x0000)
#define I2C_PROTOCOL_SMBUSDEVICE ((uint16_t)0x0002)
#define I2C_PROTOCOL_SMBUSHOST ((uint16_t)0x000A)
/**
* @}
*/
/** @defgroup I2C_Duty_Cycle
* @{
*/
#define I2C_DUTYCYCLE_16_9 ((uint16_t)0x4000) /*!< I2C fast mode Tlow/Thigh = 16/9 */
#define I2C_DUTYCYCLE_2 ((uint16_t)0xBFFF) /*!< I2C fast mode Tlow/Thigh = 2 */
/**
* @}
*/
/** @defgroup I2C_Addressing_Mode
* @{
*/
#define I2C_ADDRESSING_MODE_7BIT ((uint16_t)0x4000)
#define I2C_ADDRESSING_MODE_10BIT ((uint16_t)0xC000)
/**
* @}
*/
/** @defgroup I2C_Direction
* @{
*/
#define I2C_DIRECTION_TRANSMITTER ((uint8_t)0x00)
#define I2C_DIRECTION_RECEIVER ((uint8_t)0x01)
/**
* @}
*/
/** @defgroup I2C_Registers
* @{
*/
#define I2C_REGISTER_CTLR1 ((uint8_t)0x00)
#define I2C_REGISTER_CTLR2 ((uint8_t)0x04)
#define I2C_REGISTER_AR1 ((uint8_t)0x08)
#define I2C_REGISTER_AR2 ((uint8_t)0x0C)
#define I2C_REGISTER_DTR ((uint8_t)0x10)
#define I2C_REGISTER_STR1 ((uint8_t)0x14)
#define I2C_REGISTER_STR2 ((uint8_t)0x18)
#define I2C_REGISTER_CLKR ((uint8_t)0x1C)
#define I2C_REGISTER_RTR ((uint8_t)0x20)
/**
* @}
*/
/** @defgroup I2C_PEC_Position
* @{
*/
#define I2C_PECPOSITION_NEXT I2C_CTLR1_POAP
#define I2C_PECPOSITION_CURRENT ((uint16_t)~I2C_CTLR1_POAP)
/**
* @}
*/
/** @defgroup I2C_NACK_Position
* @{
*/
#define I2C_NACKPOSITION_NEXT I2C_CTLR1_POAP
#define I2C_NACKPOSITION_CURRENT ((uint16_t)~I2C_CTLR1_POAP)
/**
* @}
*/
/** @defgroup I2C_Interrupt_Control
* @{
*/
#define I2C_INT_EIE I2C_CTLR2_EIE
#define I2C_INT_EE I2C_CTLR2_EE
#define I2C_INT_BIE I2C_CTLR2_BIE
/**
* @}
*/
/** @defgroup I2C_Interrupt_Source
* @{
*/
#define I2C_INT_SMBALTS ((uint32_t)0x01008000)
#define I2C_INT_SMBTO ((uint32_t)0x01004000)
#define I2C_INT_PECE ((uint32_t)0x01001000)
#define I2C_INT_RXORE ((uint32_t)0x01000800)
#define I2C_INT_AE ((uint32_t)0x01000400)
#define I2C_INT_LOSTARB ((uint32_t)0x01000200)
#define I2C_INT_BE ((uint32_t)0x01000100)
#define I2C_INT_TBE ((uint32_t)0x06000080)
#define I2C_INT_RBNE ((uint32_t)0x06000040)
#define I2C_INT_STPSEND ((uint32_t)0x02000010)
#define I2C_INT_ADD10SEND ((uint32_t)0x02000008)
#define I2C_INT_BTC ((uint32_t)0x02000004)
#define I2C_INT_ADDSEND ((uint32_t)0x02000002)
#define I2C_INT_SBSEND ((uint32_t)0x02000001)
/**
* @}
*/
/** @defgroup I2C_FLAG
* @{
*/
/**
* @brief STR2 register flags
*/
#define I2C_FLAG_DUMODF ((uint32_t)0x00800000)
#define I2C_FLAG_HSTSMB ((uint32_t)0x00400000)
#define I2C_FLAG_DEFSMB ((uint32_t)0x00200000)
#define I2C_FLAG_RXGC ((uint32_t)0x00100000)
#define I2C_FLAG_TRS ((uint32_t)0x00040000)
#define I2C_FLAG_I2CBSY ((uint32_t)0x00020000)
#define I2C_FLAG_MASTER ((uint32_t)0x00010000)
/**
* @brief STR1 register flags
*/
#define I2C_FLAG_SMBALTS ((uint32_t)0x10008000)
#define I2C_FLAG_SMBTO ((uint32_t)0x10004000)
#define I2C_FLAG_PECE ((uint32_t)0x10001000)
#define I2C_FLAG_RXORE ((uint32_t)0x10000800)
#define I2C_FLAG_AE ((uint32_t)0x10000400)
#define I2C_FLAG_LOSTARB ((uint32_t)0x10000200)
#define I2C_FLAG_BE ((uint32_t)0x10000100)
#define I2C_FLAG_TBE ((uint32_t)0x10000080)
#define I2C_FLAG_RBNE ((uint32_t)0x10000040)
#define I2C_FLAG_STPSEND ((uint32_t)0x10000010)
#define I2C_FLAG_ADD10SEND ((uint32_t)0x10000008)
#define I2C_FLAG_BTC ((uint32_t)0x10000004)
#define I2C_FLAG_ADDSEND ((uint32_t)0x10000002)
#define I2C_FLAG_SBSEND ((uint32_t)0x10000001)
/**
* @}
*/
/** @defgroup I2C_ProgrammingMode
* @{
*/
#define I2C_PROGRAMMINGMODE_MASTER_SBSEND ((uint32_t)0x00030001) /*!< I2CBSY, MASTER and SBSEND flag */
#define I2C_PROGRAMMINGMODE_MASTER_TRANSMITTER_ADDSEND ((uint32_t)0x00070002) /*!< I2CBSY, MASTER, ADDSEND and TRS flags */
#define I2C_PROGRAMMINGMODE_MASTER_RECEIVER_ADDSEND ((uint32_t)0x00030002) /*!< I2CBSY, MASTER and ADDSEND flags */
#define I2C_PROGRAMMINGMODE_MASTER_ADD10SEND ((uint32_t)0x00030008) /*!< I2CBSY, MASTER and ADD10SEND flags */
#define I2C_PROGRAMMINGMODE_MASTER_BYTE_RECEIVED ((uint32_t)0x00030040) /*!< I2CBSY, MASTER and RBNE flags */
#define I2C_PROGRAMMINGMODE_MASTER_BYTE_TRANSMITTING ((uint32_t)0x00070080) /*!< TRS, I2CBSY, MASTER, TBE flags */
#define I2C_PROGRAMMINGMODE_MASTER_BYTE_TRANSMITTED ((uint32_t)0x00070084) /*!< TRS, I2CBSY, MASTER, TBE and BTC flags */
#define I2C_PROGRAMMINGMODE_SLAVE_RECEIVER_ADDSEND ((uint32_t)0x00020002) /*!< I2CBSY and ADDSEND flags */
#define I2C_PROGRAMMINGMODE_SLAVE_TRANSMITTER_ADDSEND ((uint32_t)0x00060002) /*!< TRS, I2CBSY and ADDSEND flags */
#define I2C_PROGRAMMINGMODE_SLAVE_RECEIVER_SECONDADDRESS_SELECTED ((uint32_t)0x00820000) /*!< DUMODF and I2CBSY flags */
#define I2C_PROGRAMMINGMODE_SLAVE_TRANSMITTER_SECONDADDRESS_SELECTED ((uint32_t)0x00860080) /*!< DUMODF, TRS, I2CBSY and TBE flags */
#define I2C_PROGRAMMINGMODE_SLAVE_GENERALCALLADDRESS_SELECTED ((uint32_t)0x00120000) /*!< RXGC and I2CBSY flags */
#define I2C_PROGRAMMINGMODE_SLAVE_BYTE_RECEIVED ((uint32_t)0x00020040) /*!< I2CBSY and RBNE flags */
#define I2C_PROGRAMMINGMODE_SLAVE_STOP_DETECTED ((uint32_t)0x00000010) /*!< STPSEND flag */
#define I2C_PROGRAMMINGMODE_SLAVE_BYTE_TRANSMITTED ((uint32_t)0x00060084) /*!< TRS, I2CBSY, TBE and BTC flags */
#define I2C_PROGRAMMINGMODE_SLAVE_BYTE_TRANSMITTING ((uint32_t)0x00060080) /*!< TRS, I2CBSY and TBE flags */
#define I2C_PROGRAMMINGMODE_SLAVE_ACK_FAILURE ((uint32_t)0x00000400) /*!< AE flag */
/**
* @}
*/
/**
* @}
*/
/** @defgroup I2C_Exported_Functions
* @{
*/
void I2C_DeInit(I2C_TypeDef *I2Cx);
void I2C_Init(I2C_TypeDef *I2Cx, I2C_InitPara *I2C_InitParaStruct);
void I2C_ParaInit(I2C_InitPara *I2C_InitParaStruct);
void I2C_Enable(I2C_TypeDef *I2Cx, TypeState NewValue);
void I2C_DMA_Enable(I2C_TypeDef *I2Cx, TypeState NewValue);
void I2C_DMALastTransfer_Enable(I2C_TypeDef *I2Cx, TypeState NewValue);
void I2C_StartOnBus_Enable(I2C_TypeDef *I2Cx, TypeState NewValue);
void I2C_StopOnBus_Enable(I2C_TypeDef *I2Cx, TypeState NewValue);
void I2C_Acknowledge_Enable(I2C_TypeDef *I2Cx, TypeState NewValue);
void I2C_OwnAddress2(I2C_TypeDef *I2Cx, uint8_t Address);
void I2C_DualAddress_Enable(I2C_TypeDef *I2Cx, TypeState NewValue);
void I2C_GeneralCall_Enable(I2C_TypeDef *I2Cx, TypeState NewValue);
void I2C_INTConfig(I2C_TypeDef *I2Cx, uint16_t I2C_INT, TypeState NewValue);
void I2C_SendData(I2C_TypeDef *I2Cx, uint8_t Data);
uint8_t I2C_ReceiveData(I2C_TypeDef *I2Cx);
void I2C_AddressingDevice_7bit(I2C_TypeDef *I2Cx, uint8_t Address, uint8_t I2C_Direction);
uint16_t I2C_ReadRegister(I2C_TypeDef *I2Cx, uint8_t I2C_Register);
void I2C_SoftwareReset_Enable(I2C_TypeDef *I2Cx, TypeState NewValue);
void I2C_NACKPosition_Enable(I2C_TypeDef *I2Cx, uint16_t I2C_NACKPosition);
void I2C_SMBusAlertSend_Enable(I2C_TypeDef *I2Cx, TypeState NewValue);
void I2C_PECTransmit_Enable(I2C_TypeDef *I2Cx, TypeState NewValue);
void I2C_PECPosition_Enable(I2C_TypeDef *I2Cx, uint16_t I2C_PECPosition);
void I2C_PEC_Enable(I2C_TypeDef *I2Cx, TypeState NewValue);
uint8_t I2C_GetPECValue(I2C_TypeDef *I2Cx);
void I2C_ARP_Enable(I2C_TypeDef *I2Cx, TypeState NewValue);
void I2C_StretchClock_Enable(I2C_TypeDef *I2Cx, TypeState NewValue);
void I2C_FastModeDutyCycle(I2C_TypeDef *I2Cx, uint16_t I2C_DutyCycle);
TypeState I2C_StateDetect(I2C_TypeDef *I2Cx, uint32_t I2C_State);
uint32_t I2C_GetCurrentState(I2C_TypeDef *I2Cx);
TypeState I2C_GetBitState(I2C_TypeDef *I2Cx, uint32_t I2C_FLAG);
void I2C_ClearBitState(I2C_TypeDef *I2Cx, uint32_t I2C_FLAG);
TypeState I2C_GetIntBitState(I2C_TypeDef *I2Cx, uint32_t I2C_INT);
void I2C_ClearIntBitState(I2C_TypeDef *I2Cx, uint32_t I2C_INT);
#ifdef __cplusplus
}
#endif
#endif /*__GD32F10X_I2C_H */
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/

View File

@ -0,0 +1,103 @@
/**
******************************************************************************
* @brief IWDG header file of the firmware library.
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __GD32F10X_IWDG_H
#define __GD32F10X_IWDG_H
/* Exported macro ------------------------------------------------------------*/
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "gd32f10x.h"
/** @addtogroup GD32F10x_Firmware
* @{
*/
/** @defgroup IWDG
* @{
*/
/** @defgroup IWDG_Exported_Constants
* @{
*/
/** @defgroup IWDG_WriteAccess
* @{
*/
#define IWDG_WRITEACCESS_ENABLE ((uint16_t)0x5555)
#define IWDG_WRITEACCESS_DISABLE ((uint16_t)0x0000)
/**
* @}
*/
/** @defgroup IWDG_prescaler
* @{
*/
#define IWDG_PRESCALER_4 ((uint8_t)0x00)
#define IWDG_PRESCALER_8 ((uint8_t)0x01)
#define IWDG_PRESCALER_16 ((uint8_t)0x02)
#define IWDG_PRESCALER_32 ((uint8_t)0x03)
#define IWDG_PRESCALER_64 ((uint8_t)0x04)
#define IWDG_PRESCALER_128 ((uint8_t)0x05)
#define IWDG_PRESCALER_256 ((uint8_t)0x06)
/**
* @}
*/
/** @defgroup IWDG_Flag
* @{
*/
#define IWDG_BIT_PUD IWDG_STR_PUD
#define IWDG_BIT_RUD IWDG_STR_RUD
#define IWDG_BIT_WUD IWDG_STR_WUD
/**
* @}
*/
/**
* @}
*/
/** @defgroup IWDG_Exported_functions
* @{
*/
/* Prescaler and Counter configuration functions ******************************/
void IWDG_Write_Enable(uint16_t IWDG_WriteAccess);
void IWDG_SetPrescaler(uint8_t PrescalerValue);
void IWDG_SetReloadValue(uint16_t ReloadValue);
void IWDG_ReloadCounter(void);
/* IWDG activation function ***************************************************/
void IWDG_Enable(void);
/* Flag management function ***************************************************/
TypeState IWDG_GetBitState(uint16_t IWDG_FLAG);
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif /* __IWDG_GD32F10X_H */
/**
* @}
*/
/**
* @}
*/

View File

@ -0,0 +1,90 @@
/**
******************************************************************************
* @brief MCUDBG header file of the firmware library.
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __GD32F10X_MCUDBG_H
#define __GD32F10X_MCUDBG_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "gd32f10x.h"
/** @addtogroup GD32F10x_Firmware
* @{
*/
/** @addtogroup MCUDBG
* @{
*/
/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
/** @defgroup MCUDBG_Exported_Constants
* @{
*/
#define MCUDBG_SLEEP_HOLD ((uint32_t)0x00000001)
#define MCUDBG_DEEPSLEEP_HOLD ((uint32_t)0x00000002)
#define MCUDBG_STDBY_HOLD ((uint32_t)0x00000004)
#define MCUDBG_IWDG_HOLD ((uint32_t)0x00000100)
#define MCUDBG_WWDG_HOLD ((uint32_t)0x00000200)
#define MCUDBG_TIMER1_HOLD ((uint32_t)0x00000400)
#define MCUDBG_TIMER2_HOLD ((uint32_t)0x00000800)
#define MCUDBG_TIMER3_HOLD ((uint32_t)0x00001000)
#define MCUDBG_TIMER4_HOLD ((uint32_t)0x00002000)
#define MCUDBG_CAN1_HOLD ((uint32_t)0x00004000)
#define MCUDBG_I2C1_HOLD ((uint32_t)0x00008000)
#define MCUDBG_I2C2_HOLD ((uint32_t)0x00010000)
#define MCUDBG_TIMER5_HOLD ((uint32_t)0x00020000)
#define MCUDBG_TIMER6_HOLD ((uint32_t)0x00040000)
#define MCUDBG_TIMER7_HOLD ((uint32_t)0x00080000)
#define MCUDBG_TIMER8_HOLD ((uint32_t)0x00100000)
#define MCUDBG_CAN2_HOLD ((uint32_t)0x00200000)
#define MCUDBG_TIMER12_HOLD ((uint32_t)0x02000000)
#define MCUDBG_TIMER13_HOLD ((uint32_t)0x04000000)
#define MCUDBG_TIMER14_HOLD ((uint32_t)0x08000000)
#define MCUDBG_TIMER9_HOLD ((uint32_t)0x10000000)
#define MCUDBG_TIMER10_HOLD ((uint32_t)0x20000000)
#define MCUDBG_TIMER11_HOLD ((uint32_t)0x40000000)
/**
* @}
*/
/* Exported macro ------------------------------------------------------------*/
/* Exported functions ------------------------------------------------------- */
/** @defgroup MCUDBG_Exported_Functions
* @{
*/
uint32_t MCUDBG_GetREVID(void);
uint32_t MCUDBG_GetDEVID(void);
void MCUDBG_PeriphConfig(uint32_t MCUDBG_Periph, TypeState NewValue);
#ifdef __cplusplus
}
#endif
#endif /* __GD32F10X_MCUDBG_H */
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/

View File

@ -0,0 +1,119 @@
/**
******************************************************************************
* @brief MISC header file of the firmware library.
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __GD32F10X_MISC_H
#define __GD32F10X_MISC_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "gd32f10x.h"
/** @addtogroup GD32F10x_Firmware
* @{
*/
/** @addtogroup MISC
* @{
*/
/** @defgroup MISC_Exported_Types
* @{
*/
/**
* @brief MISC Initial Parameters
*/
typedef struct {
uint8_t NVIC_IRQ; /*!< The IRQ type,detailed in @ref IRQn_Type */
uint8_t NVIC_IRQPreemptPriority; /*!< The pre-emption priority of NVIC_IRQ, detailed in @ref NVIC_Priority_Table */
uint8_t NVIC_IRQSubPriority; /*!< The SubPriority of NVIC_IRQ, detailed in @ref NVIC_Priority_Table */
TypeState NVIC_IRQEnable; /*!< Enable or disable the IRQ,this parameter can be ENABLE or DISABLE */
} NVIC_InitPara;
/**
* @}
*/
/** @defgroup MISC_Exported_Constants
* @{
*/
/** @defgroup MISC_System_Low_Power
* @{
*/
#define NVIC_VECTTAB_RAM ((uint32_t)0x20000000)
#define NVIC_VECTTAB_FLASH ((uint32_t)0x08000000)
#define NVIC_LOWPOWER_SEVONPEND ((uint8_t)0x10)
#define NVIC_LOWPOWER_SLEEPDEEP ((uint8_t)0x04)
#define NVIC_LOWPOWER_SLEEPONEXIT ((uint8_t)0x02)
/**
* @}
*/
/** @defgroup MISC_Preemption_Priority_Group
* @{
*/
/* Preemption Priority Group -------------------------------------------------*/
#define NVIC_PRIGROUP_0 ((uint32_t)0x700) /*!< 0 bits for pre-emption priority 4 bits for subpriority */
#define NVIC_PRIGROUP_1 ((uint32_t)0x600) /*!< 1 bits for pre-emption priority 3 bits for subpriority */
#define NVIC_PRIGROUP_2 ((uint32_t)0x500) /*!< 2 bits for pre-emption priority 2 bits for subpriority */
#define NVIC_PRIGROUP_3 ((uint32_t)0x400) /*!< 3 bits for pre-emption priority 1 bits for subpriority */
#define NVIC_PRIGROUP_4 ((uint32_t)0x300) /*!< 4 bits for pre-emption priority 0 bits for subpriority */
/**
* @}
*/
/** @defgroup MISC_SysTick_clock_source
* @{
*/
#define SYSTICK_CKSOURCE_HCLK_DIV8 ((uint32_t)0xFFFFFFFB)
#define SYSTICK_CKSOURCE_HCLK ((uint32_t)0x00000004)
/**
* @}
*/
/**
* @}
*/
/** @defgroup MISC_Exported_Functions
* @{
*/
void NVIC_Init(NVIC_InitPara *NVIC_InitStruct);
void NVIC_SystemLowPowerConfig(uint8_t LowPowerMode, TypeState NewValue);
void SysTick_CKSource_Enable(uint32_t SysTick_CKSource);
void NVIC_VectTableSet(uint32_t NVIC_VectTab, uint32_t Offset);
void NVIC_PRIGroup_Enable(uint32_t NVIC_PRIGroup);
#ifdef __cplusplus
}
#endif
#endif /*__GD32F10X_MISC_H */
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/

View File

@ -0,0 +1,131 @@
/**
******************************************************************************
* @brief PWR header file of the firmware library.
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __GD32F10X_PWR_H
#define __GD32F10X_PWR_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "gd32f10x.h"
/** @addtogroup GD32F10x_Firmware
* @{
*/
/** @addtogroup PWR
* @{
*/
/** @defgroup PWR_Exported_Constants
* @{
*/
/** @defgroup PWR_Low_Voltage_Detector_Threshold
* @{
*/
#define PWR_LVDT_0 PWR_CTLR_LVDT_2V2
#define PWR_LVDT_1 PWR_CTLR_LVDT_2V3
#define PWR_LVDT_2 PWR_CTLR_LVDT_2V4
#define PWR_LVDT_3 PWR_CTLR_LVDT_2V5
#define PWR_LVDT_4 PWR_CTLR_LVDT_2V6
#define PWR_LVDT_5 PWR_CTLR_LVDT_2V7
#define PWR_LVDT_6 PWR_CTLR_LVDT_2V8
#define PWR_LVDT_7 PWR_CTLR_LVDT_2V9
/**
* @}
*/
/** @defgroup PWR_LDO_state_in_Deep-sleep_mode
* @{
*/
#define PWR_LDO_ON ((uint32_t)0x00000000)
#define PWR_LDO_LOWPOWER PWR_CTLR_LDOLP
/**
* @}
*/
/** @defgroup PWR_Sleep_mode_entry
* @{
*/
#define PWR_SLEEPENTRY_WFI ((uint8_t)0x01)
#define PWR_SLEEPENTRY_WFE ((uint8_t)0x02)
/**
* @}
*/
/** @defgroup PWR_Deep-sleep_mode_entry
* @{
*/
#define PWR_DEEPSLEEPENTRY_WFI ((uint8_t)0x01)
#define PWR_DEEPSLEEPENTRY_WFE ((uint8_t)0x02)
/**
* @}
*/
/** @defgroup PWR_Standby_mode_entry
* @{
*/
#define PWR_STDBYENTRY_WFI ((uint8_t)0x01)
#define PWR_STDBYENTRY_WFE ((uint8_t)0x02)
/**
* @}
*/
/** @defgroup PWR_Flag
* @{
*/
#define PWR_FLAG_WKUP PWR_STR_WUF
#define PWR_FLAG_STB PWR_STR_SBF
#define PWR_FLAG_LVDF PWR_STR_LVDF
/**
* @}
*/
/**
* @}
*/
/** @defgroup PWR_Exported_Functions
* @{
*/
void PWR_DeInit(void);
void PWR_BackupAccess_Enable(TypeState NewValue);
void PWR_LVDConfig(uint32_t PWR_LVDT, TypeState NewValue);
void PWR_WKUP_Pin_Enable(TypeState NewValue);
void PWR_SLEEPMode_Entry(uint8_t PWR_SLEEPENTRY);
void PWR_DEEPSLEEPMode_Entry(uint32_t PWR_LDO, uint8_t PWR_DEEPSLEEPENTRY);
void PWR_STDBYMode_Entry(uint8_t PWR_STDBYENTRY);
TypeState PWR_GetBitState(uint32_t PWR_FLAG);
void PWR_ClearBitState(uint32_t PWR_FLAG);
#ifdef __cplusplus
}
#endif
#endif /* __GD32F10X_PWR_H */
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/

View File

@ -0,0 +1,690 @@
/**
******************************************************************************
* @brief RCC header file of the firmware library.
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __GD32F10X_RCC_H
#define __GD32F10X_RCC_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "gd32f10x.h"
/** @addtogroup GD32F10x_Firmware
* @{
*/
/** @addtogroup RCC
* @{
*/
/** @defgroup RCC_Exported_Types
* @{
*/
/**
* @brief RCC Initial Parameters
*/
typedef struct {
uint32_t CK_SYS_Frequency; /*!< The frequency of the CK_SYS. */
uint32_t AHB_Frequency; /*!< The frequency of the AHB. */
uint32_t APB1_Frequency; /*!< The frequency of the APB1. */
uint32_t APB2_Frequency; /*!< The frequency of the APB2. */
uint32_t ADCCLK_Frequency; /*!< The frequency of the ADCCLK. */
} RCC_ClocksPara;
/**
* @}
*/
/** @defgroup RCC_Exported_Constants
* @{
*/
/** @defgroup RCC_HSE_configuration
* @{
*/
#define RCC_HSE_OFF ((uint32_t)0x00000000)
#define RCC_HSE_ON RCC_GCCR_HSEEN
#define RCC_HSE_BYPASS RCC_GCCR_HSEEN | RCC_GCCR_HSEBPS
/**
* @}
*/
/** @defgroup RCC_PLL_input_clock_source
* @{
*/
#define RCC_PLLSOURCE_HSI_DIV2 RCC_GCFGR_PLLSEL_HSI_DIV2
#ifdef GD32F10X_CL
#define RCC_PLLSOURCE_PREDIV1 RCC_GCFGR_PLLSEL_PREDIV1
#else
#define RCC_PLLSOURCE_HSE_DIV1 ((uint32_t)0x00010000)
#define RCC_PLLSOURCE_HSE_DIV2 ((uint32_t)0x00030000)
#endif /* GD32F10X_CL */
/**
* @}
*/
/** @defgroup RCC_PLL_Multiplication_factor
* @{
*/
#define RCC_PLLMUL_2 RCC_GCFGR_PLLMF2
#define RCC_PLLMUL_3 RCC_GCFGR_PLLMF3
#define RCC_PLLMUL_4 RCC_GCFGR_PLLMF4
#define RCC_PLLMUL_5 RCC_GCFGR_PLLMF5
#define RCC_PLLMUL_6 RCC_GCFGR_PLLMF6
#define RCC_PLLMUL_7 RCC_GCFGR_PLLMF7
#define RCC_PLLMUL_8 RCC_GCFGR_PLLMF8
#define RCC_PLLMUL_9 RCC_GCFGR_PLLMF9
#define RCC_PLLMUL_10 RCC_GCFGR_PLLMF10
#define RCC_PLLMUL_11 RCC_GCFGR_PLLMF11
#define RCC_PLLMUL_12 RCC_GCFGR_PLLMF12
#define RCC_PLLMUL_13 RCC_GCFGR_PLLMF13
#define RCC_PLLMUL_14 RCC_GCFGR_PLLMF14
#define RCC_PLLMUL_16 RCC_GCFGR_PLLMF16
#define RCC_PLLMUL_17 RCC_GCFGR_PLLMF17
#define RCC_PLLMUL_18 RCC_GCFGR_PLLMF18
#define RCC_PLLMUL_19 RCC_GCFGR_PLLMF19
#define RCC_PLLMUL_20 RCC_GCFGR_PLLMF20
#define RCC_PLLMUL_21 RCC_GCFGR_PLLMF21
#define RCC_PLLMUL_22 RCC_GCFGR_PLLMF22
#define RCC_PLLMUL_23 RCC_GCFGR_PLLMF23
#define RCC_PLLMUL_24 RCC_GCFGR_PLLMF24
#define RCC_PLLMUL_25 RCC_GCFGR_PLLMF25
#define RCC_PLLMUL_26 RCC_GCFGR_PLLMF26
#define RCC_PLLMUL_27 RCC_GCFGR_PLLMF27
#define RCC_PLLMUL_28 RCC_GCFGR_PLLMF28
#define RCC_PLLMUL_29 RCC_GCFGR_PLLMF29
#define RCC_PLLMUL_30 RCC_GCFGR_PLLMF30
#define RCC_PLLMUL_31 RCC_GCFGR_PLLMF31
#define RCC_PLLMUL_32 RCC_GCFGR_PLLMF32
#ifdef GD32F10X_CL
#define RCC_PLLMUL_6_5 RCC_GCFGR_PLLMF6_5
#else
#define RCC_PLLMUL_15 RCC_GCFGR_PLLMF15
#endif /* GD32F10X_CL */
/**
* @}
*/
#ifdef GD32F10X_CL
/** @defgroup RCC_PREDIV1_division_factor
* @{
*/
#define RCC_PREDIV1_DIV1 RCC_GCFGR2_PREDV1_DIV1
#define RCC_PREDIV1_DIV2 RCC_GCFGR2_PREDV1_DIV2
#define RCC_PREDIV1_DIV3 RCC_GCFGR2_PREDV1_DIV3
#define RCC_PREDIV1_DIV4 RCC_GCFGR2_PREDV1_DIV4
#define RCC_PREDIV1_DIV5 RCC_GCFGR2_PREDV1_DIV5
#define RCC_PREDIV1_DIV6 RCC_GCFGR2_PREDV1_DIV6
#define RCC_PREDIV1_DIV7 RCC_GCFGR2_PREDV1_DIV7
#define RCC_PREDIV1_DIV8 RCC_GCFGR2_PREDV1_DIV8
#define RCC_PREDIV1_DIV9 RCC_GCFGR2_PREDV1_DIV9
#define RCC_PREDIV1_DIV10 RCC_GCFGR2_PREDV1_DIV10
#define RCC_PREDIV1_DIV11 RCC_GCFGR2_PREDV1_DIV11
#define RCC_PREDIV1_DIV12 RCC_GCFGR2_PREDV1_DIV12
#define RCC_PREDIV1_DIV13 RCC_GCFGR2_PREDV1_DIV13
#define RCC_PREDIV1_DIV14 RCC_GCFGR2_PREDV1_DIV14
#define RCC_PREDIV1_DIV15 RCC_GCFGR2_PREDV1_DIV15
#define RCC_PREDIV1_DIV16 RCC_GCFGR2_PREDV1_DIV16
/**
* @}
*/
/** @defgroup RCC_PREDIV1_clock_source
* @{
*/
#define RCC_PREDIV1_SOURCE_HSE RCC_GCFGR2_PREDV1SEL_HSE
#define RCC_PREDIV1_SOURCE_PLL2 RCC_GCFGR2_PREDV1SEL_PLL2
/**
* @}
*/
/** @defgroup RCC_PREDIV2_division_factor
* @{
*/
#define RCC_PREDIV2_DIV1 RCC_GCFGR2_PREDV2_DIV1
#define RCC_PREDIV2_DIV2 RCC_GCFGR2_PREDV2_DIV2
#define RCC_PREDIV2_DIV3 RCC_GCFGR2_PREDV2_DIV3
#define RCC_PREDIV2_DIV4 RCC_GCFGR2_PREDV2_DIV4
#define RCC_PREDIV2_DIV5 RCC_GCFGR2_PREDV2_DIV5
#define RCC_PREDIV2_DIV6 RCC_GCFGR2_PREDV2_DIV6
#define RCC_PREDIV2_DIV7 RCC_GCFGR2_PREDV2_DIV7
#define RCC_PREDIV2_DIV8 RCC_GCFGR2_PREDV2_DIV8
#define RCC_PREDIV2_DIV9 RCC_GCFGR2_PREDV2_DIV9
#define RCC_PREDIV2_DIV10 RCC_GCFGR2_PREDV2_DIV10
#define RCC_PREDIV2_DIV11 RCC_GCFGR2_PREDV2_DIV11
#define RCC_PREDIV2_DIV12 RCC_GCFGR2_PREDV2_DIV12
#define RCC_PREDIV2_DIV13 RCC_GCFGR2_PREDV2_DIV13
#define RCC_PREDIV2_DIV14 RCC_GCFGR2_PREDV2_DIV14
#define RCC_PREDIV2_DIV15 RCC_GCFGR2_PREDV2_DIV15
#define RCC_PREDIV2_DIV16 RCC_GCFGR2_PREDV2_DIV16
/**
* @}
*/
/** @defgroup RCC_PLL2_multiplication_factor
* @{
*/
#define RCC_PLL2MUL_8 RCC_GCFGR2_PLL2MF8
#define RCC_PLL2MUL_9 RCC_GCFGR2_PLL2MF9
#define RCC_PLL2MUL_10 RCC_GCFGR2_PLL2MF10
#define RCC_PLL2MUL_11 RCC_GCFGR2_PLL2MF11
#define RCC_PLL2MUL_12 RCC_GCFGR2_PLL2MF12
#define RCC_PLL2MUL_13 RCC_GCFGR2_PLL2MF13
#define RCC_PLL2MUL_14 RCC_GCFGR2_PLL2MF14
#define RCC_PLL2MUL_16 RCC_GCFGR2_PLL2MF16
#define RCC_PLL2MUL_20 RCC_GCFGR2_PLL2MF20
/**
* @}
*/
/** @defgroup RCC_PLL3_multiplication_factor
* @{
*/
#define RCC_PLL3MUL_8 RCC_GCFGR2_PLL3MF8
#define RCC_PLL3MUL_9 RCC_GCFGR2_PLL3MF9
#define RCC_PLL3MUL_10 RCC_GCFGR2_PLL3MF10
#define RCC_PLL3MUL_11 RCC_GCFGR2_PLL3MF11
#define RCC_PLL3MUL_12 RCC_GCFGR2_PLL3MF12
#define RCC_PLL3MUL_13 RCC_GCFGR2_PLL3MF13
#define RCC_PLL3MUL_14 RCC_GCFGR2_PLL3MF14
#define RCC_PLL3MUL_16 RCC_GCFGR2_PLL3MF16
#define RCC_PLL3MUL_20 RCC_GCFGR2_PLL3MF20
/**
* @}
*/
#endif /* GD32F10X_CL */
/** @defgroup RCC_System_Clock_Source
* @{
*/
#define RCC_SYSCLKSOURCE_HSI RCC_GCFGR_SCS_HSI
#define RCC_SYSCLKSOURCE_HSE RCC_GCFGR_SCS_HSE
#define RCC_SYSCLKSOURCE_PLLCLK RCC_GCFGR_SCS_PLL
/**
* @}
*/
/** @defgroup RCC_AHB_Clock_Source
* @{
*/
#define RCC_SYSCLK_DIV1 RCC_GCFGR_AHBPS_DIV1
#define RCC_SYSCLK_DIV2 RCC_GCFGR_AHBPS_DIV2
#define RCC_SYSCLK_DIV4 RCC_GCFGR_AHBPS_DIV4
#define RCC_SYSCLK_DIV8 RCC_GCFGR_AHBPS_DIV8
#define RCC_SYSCLK_DIV16 RCC_GCFGR_AHBPS_DIV16
#define RCC_SYSCLK_DIV64 RCC_GCFGR_AHBPS_DIV64
#define RCC_SYSCLK_DIV128 RCC_GCFGR_AHBPS_DIV128
#define RCC_SYSCLK_DIV256 RCC_GCFGR_AHBPS_DIV256
#define RCC_SYSCLK_DIV512 RCC_GCFGR_AHBPS_DIV512
/**
* @}
*/
/** @defgroup RCC_APB_Clock_Source
* @{
*/
#define RCC_APB1AHB_DIV1 RCC_GCFGR_APB1PS_DIV1
#define RCC_APB1AHB_DIV2 RCC_GCFGR_APB1PS_DIV2
#define RCC_APB1AHB_DIV4 RCC_GCFGR_APB1PS_DIV4
#define RCC_APB1AHB_DIV8 RCC_GCFGR_APB1PS_DIV8
#define RCC_APB1AHB_DIV16 RCC_GCFGR_APB1PS_DIV16
#define RCC_APB2AHB_DIV1 RCC_GCFGR_APB2PS_DIV1
#define RCC_APB2AHB_DIV2 RCC_GCFGR_APB2PS_DIV2
#define RCC_APB2AHB_DIV4 RCC_GCFGR_APB2PS_DIV4
#define RCC_APB2AHB_DIV8 RCC_GCFGR_APB2PS_DIV8
#define RCC_APB2AHB_DIV16 RCC_GCFGR_APB2PS_DIV16
/**
* @}
*/
/** @defgroup RCC_ADC_clock_source
* @{
*/
#define RCC_ADCCLK_APB2_DIV2 RCC_GCFGR_ADCPS_DIV2
#define RCC_ADCCLK_APB2_DIV4 RCC_GCFGR_ADCPS_DIV4
#define RCC_ADCCLK_APB2_DIV6 RCC_GCFGR_ADCPS_DIV6
#define RCC_ADCCLK_APB2_DIV8 RCC_GCFGR_ADCPS_DIV8
#define RCC_ADCCLK_APB2_DIV12 RCC_GCFGR_ADCPS_DIV12
#define RCC_ADCCLK_APB2_DIV16 RCC_GCFGR_ADCPS_DIV16
/**
* @}
*/
#ifdef GD32F10X_CL
/** @defgroup RCC_USB_OTG_clock_source
* @{
*/
#define RCC_OTGCLK_PLL_DIV1 RCC_GCFGR_OTGFSPS_Div1
#define RCC_OTGCLK_PLL_DIV1_5 RCC_GCFGR_OTGFSPS_Div1_5
#define RCC_OTGCLK_PLL_DIV2 RCC_GCFGR_OTGFSPS_Div2
#define RCC_OTGCLK_PLL_DIV2_5 RCC_GCFGR_OTGFSPS_Div2_5
/**
* @}
*/
#else
/** @defgroup RCC_USB_clock_source
* @{
*/
#define RCC_USBCLK_PLL_DIV1 RCC_GCFGR_USBPS_Div1
#define RCC_USBCLK_PLL_DIV1_5 RCC_GCFGR_USBPS_Div1_5
#define RCC_USBCLK_PLL_DIV2 RCC_GCFGR_USBPS_Div2
#define RCC_USBCLK_PLL_DIV2_5 RCC_GCFGR_USBPS_Div2_5
/**
* @}
*/
#endif /* GD32F10X_CL */
/** @defgroup RCC_CK_OUT_Clock_Source
* @{
*/
#ifdef GD32F10X_CL
#define RCC_CKOUTSRC_NOCLOCK RCC_GCFGR_CKOUTSEL_NoClock
#define RCC_CKOUTSRC_SYSCLK RCC_GCFGR_CKOUTSEL_SYSCLK
#define RCC_CKOUTSRC_HSI RCC_GCFGR_CKOUTSEL_HSI
#define RCC_CKOUTSRC_HSE RCC_GCFGR_CKOUTSEL_HSE
#define RCC_CKOUTSRC_PLLCLK_DIV2 RCC_GCFGR_CKOUTSEL_PLL_DIV2
#define RCC_CKOUTSRC_PLL2CLK RCC_GCFGR_CKOUTSEL_PLL2
#define RCC_CKOUTSRC_PLL3CLK RCC_GCFGR_CKOUTSEL_PLL3
#define RCC_CKOUTSRC_PLL3CLK_DIV2 RCC_GCFGR_CKOUTSEL_PLL3_DIV2
#define RCC_CKOUTSRC_EXT1 RCC_GCFGR_CKOUTSEL_EXT1
#else
#define RCC_CKOUTSRC_NOCLOCK RCC_GCFGR_CKOUTSEL_NoClock
#define RCC_CKOUTSRC_SYSCLK RCC_GCFGR_CKOUTSEL_SYSCLK
#define RCC_CKOUTSRC_HSI RCC_GCFGR_CKOUTSEL_HSI
#define RCC_CKOUTSRC_HSE RCC_GCFGR_CKOUTSEL_HSE
#define RCC_CKOUTSRC_PLLCLK_DIV2 RCC_GCFGR_CKOUTSEL_PLL_DIV2
#endif /* GD32F10X_CL */
/**
* @}
*/
/** @defgroup RCC_Interrupt_Source
* @{
*/
#define RCC_INT_LSISTB ((uint8_t)0x01)
#define RCC_INT_LSESTB ((uint8_t)0x02)
#define RCC_INT_HSISTB ((uint8_t)0x04)
#define RCC_INT_HSESTB ((uint8_t)0x08)
#define RCC_INT_PLLSTB ((uint8_t)0x10)
#define RCC_INT_CKM ((uint8_t)0x80)
#ifdef GD32F10X_CL
#define RCC_INT_PLL2STB ((uint8_t)0x20)
#define RCC_INT_PLL3STB ((uint8_t)0x40)
#endif /* GD32F10X_CL */
/**
* @}
*/
#ifdef GD32F10X_CL
/** @defgroup RCC_I2S2_clock_source
* @{
*/
#define RCC_I2S2CLK_SYSCLK RCC_GCFGR2_I2S2SEL_CK_SYS
#define RCC_I2S2CLK_PLL3 RCC_GCFGR2_I2S2SEL_PLL3
/**
* @}
*/
/** @defgroup RCC_I2S3_clock_source
* @{
*/
#define RCC_I2S3CLK_SYSCLK RCC_GCFGR2_I2S3SEL_CK_SYS
#define RCC_I2S3CLK_PLL3 RCC_GCFGR2_I2S3SEL_PLL3
/**
* @}
*/
#endif /* GD32F10X_CL */
/** @defgroup RCC_LSE_configuration
* @{
*/
#define RCC_LSE_OFF ((uint32_t)0x00000000)
#define RCC_LSE_EN RCC_BDCR_LSEEN
#define RCC_LSE_BYPASS ((uint32_t)(RCC_BDCR_LSEEN | RCC_BDCR_LSEBPS))
/**
* @}
*/
/** @defgroup RCC_RTC_clock_source
* @{
*/
#define RCC_RTCCLKSOURCE_LSE RCC_BDCR_RTCSEL_LSE
#define RCC_RTCCLKSOURCE_LSI RCC_BDCR_RTCSEL_LSI
#define RCC_RTCCLKSOURCE_HSE_DIV128 RCC_BDCR_RTCSEL_HSE128
/**
* @}
*/
/** @defgroup RCC_AHB_peripheral
* @{
*/
#define RCC_AHBPERIPH_DMA1 RCC_AHBCCR_DMA1EN
#define RCC_AHBPERIPH_DMA2 RCC_AHBCCR_DMA2EN
#define RCC_AHBPERIPH_SRAM RCC_AHBCCR_SRAMEN
#define RCC_AHBPERIPH_FMC RCC_AHBCCR_FMCEN
#define RCC_AHBPERIPH_CRC RCC_AHBCCR_CRCEN
#define RCC_AHBPERIPH_EXMC RCC_AHBCCR_EXMCEN
#ifdef GD32F10X_CL
#define RCC_AHBPERIPH_OTG_FS RCC_AHBCCR_OTGFSEN
#define RCC_AHBPERIPH_ETH_MAC RCC_AHBCCR_ETHMACEN
#define RCC_AHBPERIPH_ETH_MAC_RX RCC_AHBCCR_ETHMACRXEN
#define RCC_AHBPERIPH_ETH_MAC_TX RCC_AHBCCR_ETHMACTXEN
#else
#define RCC_AHBPERIPH_SDIO RCC_AHBCCR_SDIOEN
#endif/* GD32F10X_CL */
/**
* @}
*/
/** @defgroup RCC_AHB_Peripherals_RST
* @{
*/
#ifdef GD32F10X_CL
#define RCC_AHBPERIPH_OTGFSRST RCC_AHBRCR_OTGFSRST
#define RCC_AHBPERIPH_ETHMACRST RCC_AHBRCR_ETHMACRST
#endif/* GD32F10X_CL */
/**
* @}
*/
/** @defgroup RCC_APB2_peripheral
* @{
*/
#define RCC_APB2PERIPH_AF RCC_APB2CCR_AFEN
#define RCC_APB2PERIPH_GPIOA RCC_APB2CCR_PAEN
#define RCC_APB2PERIPH_GPIOB RCC_APB2CCR_PBEN
#define RCC_APB2PERIPH_GPIOC RCC_APB2CCR_PCEN
#define RCC_APB2PERIPH_GPIOD RCC_APB2CCR_PDEN
#define RCC_APB2PERIPH_GPIOE RCC_APB2CCR_PEEN
#define RCC_APB2PERIPH_GPIOF RCC_APB2CCR_PFEN
#define RCC_APB2PERIPH_GPIOG RCC_APB2CCR_PGEN
#define RCC_APB2PERIPH_ADC0 RCC_APB2CCR_ADC0EN
#define RCC_APB2PERIPH_ADC1 RCC_APB2CCR_ADC1EN
#define RCC_APB2PERIPH_TIMER1 RCC_APB2CCR_TIMER1EN
#define RCC_APB2PERIPH_SPI1 RCC_APB2CCR_SPI1EN
#define RCC_APB2PERIPH_TIMER8 RCC_APB2CCR_TIMER8EN
#define RCC_APB2PERIPH_USART1 RCC_APB2CCR_USART1EN
#define RCC_APB2PERIPH_ADC2 RCC_APB2CCR_ADC2EN
#define RCC_APB2PERIPH_TIMER9 RCC_APB2CCR_TIMER9EN
#define RCC_APB2PERIPH_TIMER10 RCC_APB2CCR_TIMER10EN
#define RCC_APB2PERIPH_TIMER11 RCC_APB2CCR_TIMER11EN
/**
* @}
*/
/** @defgroup RCC_APB2_Peripherals_RST
* @{
*/
#define RCC_APB2PERIPH_AFRST RCC_APB2RCR_AFRST
#define RCC_APB2PERIPH_GPIOARST RCC_APB2RCR_PARST
#define RCC_APB2PERIPH_GPIOBRST RCC_APB2RCR_PBRST
#define RCC_APB2PERIPH_GPIOCRST RCC_APB2RCR_PCRST
#define RCC_APB2PERIPH_GPIODRST RCC_APB2RCR_PDRST
#define RCC_APB2PERIPH_GPIOERST RCC_APB2RCR_PERST
#define RCC_APB2PERIPH_GPIOFRST RCC_APB2RCR_PFRST
#define RCC_APB2PERIPH_GPIOGRST RCC_APB2RCR_PGRST
#define RCC_APB2PERIPH_ADC0RST RCC_APB2RCR_ADC0RST
#define RCC_APB2PERIPH_ADC1RST RCC_APB2RCR_ADC1RST
#define RCC_APB2PERIPH_TIMER1RST RCC_APB2RCR_TIMER1RST
#define RCC_APB2PERIPH_SPI1RST RCC_APB2RCR_SPI1RST
#define RCC_APB2PERIPH_TIMER8RST RCC_APB2RCR_TIMER8RST
#define RCC_APB2PERIPH_USART0RST RCC_APB2RCR_USART0RST
#define RCC_APB2PERIPH_ADC2RST RCC_APB2RCR_ADC2RST
#define RCC_APB2PERIPH_TIMER9RST RCC_APB2RCR_TIMER9RST
#define RCC_APB2PERIPH_TIMER10RST RCC_APB2RCR_TIMER10RST
#define RCC_APB2PERIPH_TIMER11RST RCC_APB2RCR_TIMER11RST
/**
* @}
*/
/** @defgroup RCC_APB1_peripheral
* @{
*/
#define RCC_APB1PERIPH_TIMER2 RCC_APB1CCR_TIMER2EN
#define RCC_APB1PERIPH_TIMER3 RCC_APB1CCR_TIMER3EN
#define RCC_APB1PERIPH_TIMER4 RCC_APB1CCR_TIMER4EN
#define RCC_APB1PERIPH_TIMER5 RCC_APB1CCR_TIMER5EN
#define RCC_APB1PERIPH_TIMER6 RCC_APB1CCR_TIMER6EN
#define RCC_APB1PERIPH_TIMER7 RCC_APB1CCR_TIMER7EN
#define RCC_APB1PERIPH_TIMER12 RCC_APB1CCR_TIMER12EN
#define RCC_APB1PERIPH_TIMER13 RCC_APB1CCR_TIMER13EN
#define RCC_APB1PERIPH_TIMER14 RCC_APB1CCR_TIMER14EN
#define RCC_APB1PERIPH_WWDG RCC_APB1CCR_WWDGEN
#define RCC_APB1PERIPH_SPI2 RCC_APB1CCR_SPI2EN
#define RCC_APB1PERIPH_SPI3 RCC_APB1CCR_SPI3EN
#define RCC_APB1PERIPH_USART2 RCC_APB1CCR_USART2EN
#define RCC_APB1PERIPH_USART3 RCC_APB1CCR_USART3EN
#define RCC_APB1PERIPH_UART4 RCC_APB1CCR_UART4EN
#define RCC_APB1PERIPH_UART5 RCC_APB1CCR_UART5EN
#define RCC_APB1PERIPH_I2C1 RCC_APB1CCR_I2C1EN
#define RCC_APB1PERIPH_I2C2 RCC_APB1CCR_I2C2EN
#define RCC_APB1PERIPH_USB RCC_APB1CCR_USBEN
#define RCC_APB1PERIPH_CAN1 RCC_APB1CCR_CAN1EN
#define RCC_APB1PERIPH_CAN2 RCC_APB1CCR_CAN2EN
#define RCC_APB1PERIPH_BKP RCC_APB1CCR_BKPEN
#define RCC_APB1PERIPH_PWR RCC_APB1CCR_PWREN
#define RCC_APB1PERIPH_DAC RCC_APB1CCR_DACEN
/**
* @}
*/
/** @defgroup RCC_APB1_Peripherals_RST
* @{
*/
#define RCC_APB1PERIPH_TIMER2RST RCC_APB1RCR_TIMER2RST
#define RCC_APB1PERIPH_TIMER3RST RCC_APB1RCR_TIMER3RST
#define RCC_APB1PERIPH_TIMER4RST RCC_APB1RCR_TIMER4RST
#define RCC_APB1PERIPH_TIMER5RST RCC_APB1RCR_TIMER5RST
#define RCC_APB1PERIPH_TIMER6RST RCC_APB1RCR_TIMER6RST
#define RCC_APB1PERIPH_TIMER7RST RCC_APB1RCR_TIMER7RST
#define RCC_APB1PERIPH_TIMER12RST RCC_APB1RCR_TIMER12RST
#define RCC_APB1PERIPH_TIMER13RST RCC_APB1RCR_TIMER13RST
#define RCC_APB1PERIPH_TIMER14RST RCC_APB1RCR_TIMER14RST
#define RCC_APB1PERIPH_WWDGRST RCC_APB1RCR_WWDGRST
#define RCC_APB1PERIPH_SPI2RST RCC_APB1RCR_SPI2RST
#define RCC_APB1PERIPH_SPI3RST RCC_APB1RCR_SPI3RST
#define RCC_APB1PERIPH_USART1RST RCC_APB1RCR_USART1RST
#define RCC_APB1PERIPH_USART2RST RCC_APB1RCR_USART2RST
#define RCC_APB1PERIPH_UART3RST RCC_APB1RCR_UART3RST
#define RCC_APB1PERIPH_UART4RST RCC_APB1RCR_UART4RST
#define RCC_APB1PERIPH_I2C1RST RCC_APB1RCR_I2C1RST
#define RCC_APB1PERIPH_I2C2RST RCC_APB1RCR_I2C2RST
#define RCC_APB1PERIPH_USBRST RCC_APB1RCR_USBRST
#define RCC_APB1PERIPH_CAN1RST RCC_APB1RCR_CAN1RST
#define RCC_APB1PERIPH_CAN2RST RCC_APB1RCR_CAN2RST
#define RCC_APB1PERIPH_BKPRST RCC_APB1RCR_BKPRST
#define RCC_APB1PERIPH_PWRRST RCC_APB1RCR_PWRRST
#define RCC_APB1PERIPH_DACRST RCC_APB1RCR_DACRST
/**
* @}
*/
/** @defgroup RCC_Flag
* @{
*/
/* The flag to check is in GCCR register */
#define RCC_FLAG_HSISTB ((uint8_t)0x21)
#define RCC_FLAG_HSESTB ((uint8_t)0x31)
#define RCC_FLAG_PLLSTB ((uint8_t)0x39)
/* The flag to check is in BDCR register */
#define RCC_FLAG_LSESTB ((uint8_t)0x41)
/* The flag to check is in GCSR register */
#define RCC_FLAG_LSISTB ((uint8_t)0x61)
#define RCC_FLAG_EPRST ((uint8_t)0x7A)
#define RCC_FLAG_POPDRST ((uint8_t)0x7B)
#define RCC_FLAG_SWRRST ((uint8_t)0x7C)
#define RCC_FLAG_IWDGRST ((uint8_t)0x7D)
#define RCC_FLAG_WWDGRST ((uint8_t)0x7E)
#define RCC_FLAG_LPRRST ((uint8_t)0x7F)
#ifdef GD32F10X_CL
/* The flag to check is in GCCR register */
#define RCC_FLAG_PLL2STB ((uint8_t)0x3B)
#define RCC_FLAG_PLL3STB ((uint8_t)0x3D)
#endif/* GD32F10X_CL */
/**
* @}
*/
/**
* @}
*/
/** @defgroup RCC_Exported_Functions
* @{
*/
/* Reset the RCC clock configuration to the default reset state */
void RCC_DeInit(void);
/* Internal/external clocks, PLL, CKM and CK_OUT configuration functions */
void RCC_HSEConfig(uint32_t RCC_HSE);
TypeState RCC_WaitForHSEStartUp(void);
void RCC_AdjustHSICalibrationValue(uint8_t HSICalibrationValue);
void RCC_HSI_Enable(TypeState NewValue);
void RCC_PLLConfig(uint32_t RCC_PLLSelect, uint32_t RCC_PLLMF);
void RCC_PLL_Enable(TypeState NewValue);
void RCC_LSEConfig(uint32_t RCC_LSE);
void RCC_LSI_Enable(TypeState NewValue);
void RCC_HSEClockMonitor_Enable(TypeState NewValue);
void RCC_CKOUTSRCConfig(uint32_t RCC_CKOUTSRC);
#ifdef GD32F10X_CL
void RCC_PREDV1Config(uint32_t RCC_PREDV1_Source, uint32_t RCC_PREDV1_Div);
void RCC_PREDV2Config(uint32_t RCC_PREDV2_Div);
void RCC_PLL2Config(uint32_t RCC_PLL2MF);
void RCC_PLL2_Enable(TypeState NewValue);
void RCC_PLL3Config(uint32_t RCC_PLL3MF);
void RCC_PLL3_Enable(TypeState NewValue);
#endif /* GD32F10X_CL */
/* System, AHB, APB1 and APB2 busses clocks configuration functions */
void RCC_CK_SYSConfig(uint32_t RCC_SYSCLKSource);
uint8_t RCC_GetCK_SYSSource(void);
void RCC_AHBConfig(uint32_t RCC_CK_SYSDiv);
void RCC_APB1Config(uint32_t RCC_APB1);
void RCC_APB2Config(uint32_t RCC_APB2);
#ifndef GD32F10X_CL
void RCC_USBCLKConfig(uint32_t RCC_USBCLK);
#else
void RCC_OTGFSCLKConfig(uint32_t RCC_OTGFSCLK);
#endif /* GD32F10X_CL */
void RCC_ADCCLKConfig(uint32_t RCC_ADCCLK);
#ifdef GD32F10X_CL
void RCC_I2S2CLKConfig(uint32_t RCC_I2S2CLK);
void RCC_I2S3CLKConfig(uint32_t RCC_I2S3CLK);
#endif /* GD32F10X_CL */
void RCC_RTCCLKConfig(uint32_t RCC_RTCCLKSource);
void RCC_GetClocksFreq(RCC_ClocksPara *RCC_Clocks);
/* Peripheral clocks configuration functions */
void RCC_AHBPeriphClock_Enable(uint32_t RCC_AHBPeriph, TypeState NewValue);
void RCC_APB2PeriphClock_Enable(uint32_t RCC_APB2Periph, TypeState NewValue);
void RCC_APB1PeriphClock_Enable(uint32_t RCC_APB1Periph, TypeState NewValue);
void RCC_RTCCLK_Enable(TypeState NewValue);
#ifdef GD32F10X_CL
void RCC_AHBPeriphReset_Enable(uint32_t RCC_AHBPeriphRST, TypeState NewValue);
#endif /* GD32F10X_CL */
void RCC_APB2PeriphReset_Enable(uint32_t RCC_APB2PeriphRST, TypeState NewValue);
void RCC_APB1PeriphReset_Enable(uint32_t RCC_APB1PeriphRST, TypeState NewValue);
void RCC_BackupReset_Enable(TypeState NewValue);
/* Interrupts and flags management functions */
void RCC_INTConfig(uint8_t RCC_INT, TypeState NewValue);
TypeState RCC_GetIntBitState(uint8_t RCC_INT);
void RCC_ClearIntBitState(uint8_t RCC_INT);
TypeState RCC_GetBitState(uint8_t RCC_FLAG);
void RCC_ClearBitState(void);
void RCC_KERNELVOLConfig(uint32_t RCC_KERNEL_VOL);
#ifdef __cplusplus
}
#endif
#endif /* __GD32F10x_RCC_H */
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,92 @@
/**
******************************************************************************
* @brief RTC header file of the firmware library.
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __GD32F10X_RTC_H
#define __GD32F10X_RTC_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "gd32f10x.h"
/** @addtogroup GD32F10x_Firmware
* @{
*/
/** @addtogroup RTC
* @{
*/
/** @defgroup RTC_Exported_Defines
* @{
*/
/** @defgroup RTC_Interrupt_Def
* @{
*/
#define RTC_INT_OVF ((uint16_t)0x0004) /*!< Overflow interrupt */
#define RTC_INT_AF ((uint16_t)0x0002) /*!< Alarm interrupt */
#define RTC_INT_SF ((uint16_t)0x0001) /*!< Second interrupt */
/**
* @}
*/
/** @defgroup RTC_Interrupts_Flags
* @{
*/
#define RTC_FLAG_LWOFF ((uint16_t)0x0020) /*!< Last write operation finished flag */
#define RTC_FLAG_RSF ((uint16_t)0x0008) /*!< Registers Synchronized flag */
#define RTC_FLAG_OVF ((uint16_t)0x0004) /*!< Overflow flag */
#define RTC_FLAG_AF ((uint16_t)0x0002) /*!< Alarm flag */
#define RTC_FLAG_SF ((uint16_t)0x0001) /*!< Second flag */
/**
* @}
*/
/**
* @}
*/
/** @defgroup RTC_Exported_Functions
* @{
*/
void RTC_INT_Enable(uint16_t RTC_int, TypeState NewValue);
void RTC_EnterConfigMode(void);
void RTC_ExitConfigMode(void);
uint32_t RTC_GetCounter(void);
void RTC_SetCounter(uint32_t CounterValue);
void RTC_SetPrescaler(uint32_t PrescalerValue);
void RTC_SetAlarm(uint32_t AlarmTime);
uint32_t RTC_GetDividerValue(void);
void RTC_WaitLWOFF(void);
void RTC_WaitRSF(void);
TypeState RTC_GetBitState(uint16_t RTC_flag);
void RTC_ClearBitState(uint16_t RTC_flag);
TypeState RTC_GetIntBitState(uint16_t RTC_INT);
void RTC_ClearIntBitState(uint16_t RTC_INT);
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif /*__GD32F10X_RTC_H */
/**
* @}
*/
/**
* @}
*/

View File

@ -0,0 +1,369 @@
/**
******************************************************************************
* @brief SDIO header file of the firmware library
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __GD32F10X_SDIO_H
#define __GD32F10X_SDIO_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "gd32f10x.h"
/** @addtogroup GD32F10x_Firmware
* @{
*/
/** @addtogroup SDIO
* @{
*/
/** @defgroup SDIO_Exported_Types
* @{
*/
typedef struct {
uint32_t SDIO_ClockEdge; /*!< Configure the SDIO Clock edge on which the bit capture is made.
This parameter can be a value of @ref SDIO_Clock_Edge*/
uint32_t SDIO_ClockBypassState; /*!< Configure the SDIO Clock divider bypass mode
This parameter can be a value of @ref SDIO_Clock_Bypass_State */
uint32_t SDIO_ClockPWRSave; /*!< Configure the SDIO Clock output powersave mode when the bus is idle.
This parameter can be a value of @ref SDIO_Clock_Power_Save */
uint32_t SDIO_BusMode; /*!< Configure the SDIO bus mode.
This parameter can be a value of @ref SDIO_Bus_Mode */
uint32_t SDIO_HWFlowCtrlState; /*!< Configure the SDIO hardware flow control is enabled or disabled.
This parameter can be a value of @ref SDIO_HW_Flow_Control_State */
uint8_t SDIO_ClockDiv; /*!< Configure the clock frequency prescaler of the SDIO controller.
This parameter can be a value between 0x00 and 0xFF. */
} SDIO_InitPara;
typedef struct {
uint32_t SDIO_CMDParameter; /*!< Configure the SDIO command parameter which is sent to
a card as part of a command message. */
uint32_t SDIO_CMDIndex; /*!< Configure the SDIO command index. */
uint32_t SDIO_ResponseType; /*!< Configure the SDIO response type.
This parameter can be a value of @ref SDIO_Response_Type */
uint32_t SDIO_WaitINTState; /*!< Configure whether SDIO wait-for-interrupt request is enabled or disabled.
This parameter can be a value of @ref SDIO_Wait_Interrupt_State */
uint32_t SDIO_CSMState; /*!< Configure SDIO Command state machine (CSM) is enabled or disabled.
This parameter can be a value of @ref SDIO_CSM_State */
} SDIO_CmdInitPara;
typedef struct {
uint32_t SDIO_DataTimeOut; /*!< Configure the data timeout period in card bus clock periods. */
uint32_t SDIO_DataLength; /*!< Configure the number of data bytes to be transferred. */
uint32_t SDIO_DataBlockSize; /*!< Configure the data block size for block transfer.
This parameter can be a value of @ref SDIO_Data_Block_Size */
uint32_t SDIO_TransDirection; /*!< Configure the data transfer direction, read or write.
This parameter can be a value of @ref SDIO_Transfer_Direction */
uint32_t SDIO_TransMode; /*!< Configure whether data transfer is in stream or block mode.
This parameter can be a value of @ref SDIO_Transfer_Mode */
uint32_t SDIO_DSMState; /*!< Configure whether SDIO Data state machine (DSM) is enabled or disabled.
This parameter can be a value of @ref SDIO_DSM_State */
} SDIO_DataInitPara;
/**
* @}
*/
/** @defgroup SDIO_Exported_Constants
* @{
*/
/** @defgroup SDIO_Clock_Edge
* @{
*/
#define SDIO_CLOCKEDGE_RISING ((uint32_t)0x00000000)
#define SDIO_CLOCKEDGE_FALLING ((uint32_t)0x00002000)
/**
* @}
*/
/** @defgroup SDIO_Clock_Bypass_State
* @{
*/
#define SDIO_CLOCKBYPASSSTATE_DISABLE ((uint32_t)0x00000000)
#define SDIO_CLOCKBYPASSSTATE_ENABLE ((uint32_t)0x00000400)
/**
* @}
*/
/** @defgroup SDIO_Clock_PWR_Save
* @{
*/
#define SDIO_CLOCKPWRSAVE_DISABLE ((uint32_t)0x00000000)
#define SDIO_CLOCKPWRSAVE_ENABLE ((uint32_t)0x00000200)
/**
* @}
*/
/** @defgroup SDIO_Bus_Mode
* @{
*/
#define SDIO_BUSMODE_1B ((uint32_t)0x00000000)
#define SDIO_BUSMODE_4B ((uint32_t)0x00000800)
#define SDIO_BUSMODE_8B ((uint32_t)0x00001000)
/**
* @}
*/
/** @defgroup SDIO_HW_Flow_Control_State
* @{
*/
#define SDIO_HWFLOWCTRLSTATE_DISABLE ((uint32_t)0x00000000)
#define SDIO_HWFLOWCTRLSTATE_ENABLE ((uint32_t)0x00004000)
/**
* @}
*/
/** @defgroup SDIO_Power_State
* @{
*/
#define SDIO_PWRSTATE_OFF ((uint32_t)0x00000000)
#define SDIO_PWRSTATE_ON ((uint32_t)0x00000003)
/**
* @}
*/
/** @defgroup SDIO_Interrupt_sources
* @{
*/
#define SDIO_INT_CCRCFAIL ((uint32_t)0x00000001)
#define SDIO_INT_DTCRCFAIL ((uint32_t)0x00000002)
#define SDIO_INT_CMDTMOUT ((uint32_t)0x00000004)
#define SDIO_INT_DTTMOUT ((uint32_t)0x00000008)
#define SDIO_INT_TXURE ((uint32_t)0x00000010)
#define SDIO_INT_RXORE ((uint32_t)0x00000020)
#define SDIO_INT_CMDREND ((uint32_t)0x00000040)
#define SDIO_INT_CMDSENT ((uint32_t)0x00000080)
#define SDIO_INT_DTEND ((uint32_t)0x00000100)
#define SDIO_INT_STBITE ((uint32_t)0x00000200)
#define SDIO_INT_DTBLKEND ((uint32_t)0x00000400)
#define SDIO_INT_CMDRUN ((uint32_t)0x00000800)
#define SDIO_INT_TXRUN ((uint32_t)0x00001000)
#define SDIO_INT_RXRUN ((uint32_t)0x00002000)
#define SDIO_INT_TXFIFOHE ((uint32_t)0x00004000)
#define SDIO_INT_RXFIFOHF ((uint32_t)0x00008000)
#define SDIO_INT_TXFIFOF ((uint32_t)0x00010000)
#define SDIO_INT_RXFIFOF ((uint32_t)0x00020000)
#define SDIO_INT_TXFIFOE ((uint32_t)0x00040000)
#define SDIO_INT_RXFIFOE ((uint32_t)0x00080000)
#define SDIO_INT_TXDTVAL ((uint32_t)0x00100000)
#define SDIO_INT_RXDTVAL ((uint32_t)0x00200000)
#define SDIO_INT_SDIOINT ((uint32_t)0x00400000)
#define SDIO_INT_ATAEND ((uint32_t)0x00800000)
/**
* @}
*/
/** @defgroup SDIO_Response_Type
* @{
*/
#define SDIO_RESPONSETYPE_NO ((uint32_t)0x00000000)
#define SDIO_RESPONSETYPE_SHORT ((uint32_t)0x00000040)
#define SDIO_RESPONSETYPE_LONG ((uint32_t)0x000000C0)
/**
* @}
*/
/** @defgroup SDIO_Wait_Interrupt_State
* @{
*/
#define SDIO_WAITINTSTATE_NO ((uint32_t)0x00000000)
#define SDIO_WAITINTSTATE_INT ((uint32_t)0x00000100)
#define SDIO_WAITINTSTATE_PEND ((uint32_t)0x00000200)
/**
* @}
*/
/** @defgroup SDIO_CSM_State
* @{
*/
#define SDIO_CSMSTATE_DISABLE ((uint32_t)0x00000000)
#define SDIO_CSMSTATE_ENABLE ((uint32_t)0x00000400)
/**
* @}
*/
/** @defgroup SDIO_Response_Registers
* @{
*/
#define SDIO_RESP1 ((uint32_t)0x00000000)
#define SDIO_RESP2 ((uint32_t)0x00000004)
#define SDIO_RESP3 ((uint32_t)0x00000008)
#define SDIO_RESP4 ((uint32_t)0x0000000C)
/**
* @}
*/
/** @defgroup SDIO_Data_Block_Size
* @{
*/
#define SDIO_DATABLOCKSIZE_1B ((uint32_t)0x00000000)
#define SDIO_DATABLOCKSIZE_2B ((uint32_t)0x00000010)
#define SDIO_DATABLOCKSIZE_4B ((uint32_t)0x00000020)
#define SDIO_DATABLOCKSIZE_8B ((uint32_t)0x00000030)
#define SDIO_DATABLOCKSIZE_16B ((uint32_t)0x00000040)
#define SDIO_DATABLOCKSIZE_32B ((uint32_t)0x00000050)
#define SDIO_DATABLOCKSIZE_64B ((uint32_t)0x00000060)
#define SDIO_DATABLOCKSIZE_128B ((uint32_t)0x00000070)
#define SDIO_DATABLOCKSIZE_256B ((uint32_t)0x00000080)
#define SDIO_DATABLOCKSIZE_512B ((uint32_t)0x00000090)
#define SDIO_DATABLOCKSIZE_1024B ((uint32_t)0x000000A0)
#define SDIO_DATABLOCKSIZE_2048B ((uint32_t)0x000000B0)
#define SDIO_DATABLOCKSIZE_4096B ((uint32_t)0x000000C0)
#define SDIO_DATABLOCKSIZE_8192B ((uint32_t)0x000000D0)
#define SDIO_DATABLOCKSIZE_16384B ((uint32_t)0x000000E0)
/**
* @}
*/
/** @defgroup SDIO_Transfer_Direction
* @{
*/
#define SDIO_TRANSDIRECTION_TOCARD ((uint32_t)0x00000000)
#define SDIO_TRANSDIRECTION_TOSDIO ((uint32_t)0x00000002)
/**
* @}
*/
/** @defgroup SDIO_Transfer_Mode
* @{
*/
#define SDIO_TRANSMODE_BLOCK ((uint32_t)0x00000000)
#define SDIO_TRANSMODE_STREAM ((uint32_t)0x00000004)
/**
* @}
*/
/** @defgroup SDIO_DSM_State
* @{
*/
#define SDIO_DSMSTATE_DISABLE ((uint32_t)0x00000000)
#define SDIO_DSMSTATE_ENABLE ((uint32_t)0x00000001)
/**
* @}
*/
/** @defgroup SDIO_Flag
* @{
*/
#define SDIO_FLAG_CCRCFAIL ((uint32_t)0x00000001)
#define SDIO_FLAG_DTCRCFAIL ((uint32_t)0x00000002)
#define SDIO_FLAG_CMDTMOUT ((uint32_t)0x00000004)
#define SDIO_FLAG_DTTMOUT ((uint32_t)0x00000008)
#define SDIO_FLAG_TXURE ((uint32_t)0x00000010)
#define SDIO_FLAG_RXORE ((uint32_t)0x00000020)
#define SDIO_FLAG_CMDREND ((uint32_t)0x00000040)
#define SDIO_FLAG_CMDSENT ((uint32_t)0x00000080)
#define SDIO_FLAG_DTEND ((uint32_t)0x00000100)
#define SDIO_FLAG_STBITE ((uint32_t)0x00000200)
#define SDIO_FLAG_DTBLKEND ((uint32_t)0x00000400)
#define SDIO_FLAG_CMDRUN ((uint32_t)0x00000800)
#define SDIO_FLAG_TXRUN ((uint32_t)0x00001000)
#define SDIO_FLAG_RXRUN ((uint32_t)0x00002000)
#define SDIO_FLAG_TXFIFOHE ((uint32_t)0x00004000)
#define SDIO_FLAG_RXFIFOHF ((uint32_t)0x00008000)
#define SDIO_FLAG_TXFIFOF ((uint32_t)0x00010000)
#define SDIO_FLAG_RXFIFOF ((uint32_t)0x00020000)
#define SDIO_FLAG_TXFIFOE ((uint32_t)0x00040000)
#define SDIO_FLAG_RXFIFOE ((uint32_t)0x00080000)
#define SDIO_FLAG_TXDTVAL ((uint32_t)0x00100000)
#define SDIO_FLAG_RXDTVAL ((uint32_t)0x00200000)
#define SDIO_FLAG_SDIOINT ((uint32_t)0x00400000)
#define SDIO_FLAG_ATAEND ((uint32_t)0x00800000)
/**
* @}
*/
/** @defgroup SDIO_Read_Wait_Mode
* @{
*/
#define SDIO_READWAITMODE_CLK ((uint32_t)0x00000001)
#define SDIO_READWAITMODE_DAT2 ((uint32_t)0x00000000)
/**
* @}
*/
/**
* @}
*/
/** @defgroup SDIO_Exported_Functions
* @{
*/
void SDIO_DeInit(void);
void SDIO_Init(SDIO_InitPara *SDIO_InitParaStruct);
void SDIO_ParaInit(SDIO_InitPara *SDIO_InitParaStruct);
void SDIO_Clock_Enable(TypeState NewState);
void SDIO_SetPWRState(uint32_t SDIO_PWRState);
uint32_t SDIO_GetPWRState(void);
void SDIO_INTConfig(uint32_t SDIO_INT, TypeState NewState);
void SDIO_DMA_Enable(TypeState NewState);
void SDIO_SendCMD(SDIO_CmdInitPara *SDIO_CmdInitParaStruct);
void SDIO_CMDParaInit(SDIO_CmdInitPara *SDIO_CmdInitParaStruct);
uint8_t SDIO_GetCMDResponse(void);
uint32_t SDIO_GetResponse(uint32_t SDIO_RESP);
void SDIO_DataConfig(SDIO_DataInitPara *SDIO_DataInitParaStruct);
void SDIO_DataParaInit(SDIO_DataInitPara *SDIO_DataInitParaStruct);
uint32_t SDIO_GetDataCount(void);
uint32_t SDIO_ReadData(void);
void SDIO_WriteData(uint32_t Data);
uint32_t SDIO_GetFIFOCount(void);
void SDIO_StartSDIOReadWait(TypeState NewState);
void SDIO_StopSDIOReadWait(TypeState NewState);
void SDIO_SetSDIOReadWaitMode(uint32_t SDIO_ReadWaitMode);
void SDIO_SetSDIOOperation(TypeState NewState);
void SDIO_SendSDIOSuspend_Enable(TypeState NewState);
void SDIO_CMDCompletion_Enable(TypeState NewState);
void SDIO_CEATAInt_Enable(TypeState NewState);
void SDIO_SendCEATA_Enable(TypeState NewState);
TypeState SDIO_GetBitState(uint32_t SDIO_FLAG);
void SDIO_ClearBitState(uint32_t SDIO_FLAG);
TypeState SDIO_GetIntBitState(uint32_t SDIO_INT);
void SDIO_ClearIntBitState(uint32_t SDIO_INT);
#ifdef __cplusplus
}
#endif
#endif /* __GD32F10X_SDIO_H */
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/

View File

@ -0,0 +1,353 @@
/**
******************************************************************************
* @brief SPI header file of the firmware library.
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __GD32F10X_SPI_H
#define __GD32F10X_SPI_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "gd32f10x.h"
/** @addtogroup GD32F10x_Firmware
* @{
*/
/** @addtogroup SPI
* @{
*/
/** @defgroup SPI_Exported_Types
* @{
*/
/**
* @brief SPI Initial Parameters
*/
typedef struct {
uint16_t SPI_TransType; /*!< The transfer type, choose one from @ref SPI_transfer_type. */
uint16_t SPI_Mode; /*!< The operating mode, choose one from @ref SPI_mode. */
uint16_t SPI_FrameFormat; /*!< The SPI data frame format, choose one from @ref SPI_data_frame_format. */
uint16_t SPI_SCKPL; /*!< The clock polarity in idel state, choose one from @ref SPI_Clock_Polarity. */
uint16_t SPI_SCKPH; /*!< The clock phase, choose one from @ref SPI_Clock_Phase. */
uint16_t SPI_SWNSSEN; /*!< The NSS signal management, choose one from @ref SPI_Software_NSS_management. */
uint16_t SPI_PSC; /*!< The Baud Rate prescaler value, choose one from @ref SPI_BaudRate_Prescaler. */
uint16_t SPI_FirstBit; /*!< The data transfers start from MSB or LSB bit, choose one from @ref SPI_MSB_LSB_transmission. */
uint16_t SPI_CRCPOL; /*!< The polynomial used for the CRC calculation. */
} SPI_InitPara;
/**
* @brief I2S Initial Parameters
*/
typedef struct {
uint16_t I2S_Mode; /*!< The operating mode and transfer direction, choose one from @ref I2S_Mode. */
uint16_t I2S_STD; /*!< The I2S standard, choose one from @ref I2S_Standard. */
uint16_t I2S_FrameFormat; /*!< The I2S data length and channel length, choose one from @ref I2S_Data_Format. */
uint16_t I2S_MCKOE; /*!< The I2S MCK output is enabled or disable, choose one from @ref I2S_MCLK_Output. */
uint32_t I2S_AudioFreq; /*!< The audio sampling frequency, choose one from @ref I2S_Audio_Frequency. */
uint16_t I2S_CKPL; /*!< The clock polarity in idel state, choose one from @ref I2S_Clock_Polarity. */
} I2S_InitPara;
/**
* @}
*/
/** @defgroup SPI_Exported_Constants
* @{
*/
/** @defgroup SPI_transfer_type
* @{
*/
#define SPI_TRANSTYPE_FULLDUPLEX ((uint16_t)0x0000)
#define SPI_TRANSTYPE_RXONLY SPI_CTLR1_RO
#define SPI_TRANSTYPE_BDMRX SPI_CTLR1_BDM
#define SPI_TRANSTYPE_BDMTX (SPI_CTLR1_BDM | SPI_CTLR1_BDOE)
/**
* @}
*/
/** @defgroup SPI_mode
* @{
*/
#define SPI_MODE_MASTER (SPI_CTLR1_MSTMODE|SPI_CTLR1_SWNSS)
#define SPI_MODE_SLAVE ((uint16_t)0x0000)
/**
* @}
*/
/** @defgroup SPI_data_frame_format
* @{
*/
#define SPI_FRAMEFORMAT_16BIT SPI_CTLR1_FF16
#define SPI_FRAMEFORMAT_8BIT ((uint16_t)0x0000)
/**
* @}
*/
/** @defgroup SPI_Clock_Polarity
* @{
*/
#define SPI_SCKPL_LOW ((uint16_t)0x0000)
#define SPI_SCKPL_HIGH SPI_CTLR1_SCKPL
/**
* @}
*/
/** @defgroup SPI_Clock_Phase
* @{
*/
#define SPI_SCKPH_1EDGE ((uint16_t)0x0000)
#define SPI_SCKPH_2EDGE SPI_CTLR1_SCKPH
/**
* @}
*/
/** @defgroup SPI_Software_NSS_management
* @{
*/
#define SPI_SWNSS_SOFT SPI_CTLR1_SWNSSEN
#define SPI_SWNSS_HARD ((uint16_t)0x0000)
/**
* @}
*/
/** @defgroup SPI_BaudRate_Prescaler
* @{
*/
#define SPI_PSC_2 ((uint16_t)0x0000)
#define SPI_PSC_4 ((uint16_t)0x0008)
#define SPI_PSC_8 ((uint16_t)0x0010)
#define SPI_PSC_16 ((uint16_t)0x0018)
#define SPI_PSC_32 ((uint16_t)0x0020)
#define SPI_PSC_64 ((uint16_t)0x0028)
#define SPI_PSC_128 ((uint16_t)0x0030)
#define SPI_PSC_256 ((uint16_t)0x0038)
/**
* @}
*/
/** @defgroup SPI_MSB_LSB_transmission
* @{
*/
#define SPI_FIRSTBIT_MSB ((uint16_t)0x0000)
#define SPI_FIRSTBIT_LSB SPI_CTLR1_LF
/**
* @}
*/
/** @defgroup I2S_Mode
* @{
*/
#define I2S_MODE_SLAVETX ((uint16_t)0x0000)
#define I2S_MODE_SLAVERX ((uint16_t)0x0100)
#define I2S_MODE_MASTERTX ((uint16_t)0x0200)
#define I2S_MODE_MASTERRX ((uint16_t)0x0300)
/**
* @}
*/
/** @defgroup I2S_Standard
* @{
*/
#define I2S_STD_PHILLIPS ((uint16_t)0x0000)
#define I2S_STD_MSB ((uint16_t)0x0010)
#define I2S_STD_LSB ((uint16_t)0x0020)
#define I2S_STD_PCMSHORT ((uint16_t)0x0030)
#define I2S_STD_PCMLONG ((uint16_t)0x00B0)
/**
* @}
*/
/** @defgroup I2S_Data_Format
* @{
*/
#define I2S_FRAMEFORMAT_DL16b_CL16b ((uint16_t)0x0000)
#define I2S_FRAMEFORMAT_DL16b_CL32b ((uint16_t)0x0001)
#define I2S_FRAMEFORMAT_DL24b_CL32b ((uint16_t)0x0003)
#define I2S_FRAMEFORMAT_DL32b_CL32b ((uint16_t)0x0005)
/**
* @}
*/
/** @defgroup I2S_MCLK_Output
* @{
*/
#define I2S_MCK_ENABLE SPI_I2SCKP_MCKOE
#define I2S_MCK_DISABLE ((uint16_t)0x0000)
/**
* @}
*/
/** @defgroup I2S_Audio_Frequency
* @{
*/
#define I2S_AUDIOFREQ_DEFAULT ((uint32_t)2)
#define I2S_AUDIOFREQ_8K ((uint32_t)8000)
#define I2S_AUDIOFREQ_11K ((uint32_t)11025)
#define I2S_AUDIOFREQ_16K ((uint32_t)16000)
#define I2S_AUDIOFREQ_22K ((uint32_t)22050)
#define I2S_AUDIOFREQ_32K ((uint32_t)32000)
#define I2S_AUDIOFREQ_44K ((uint32_t)44100)
#define I2S_AUDIOFREQ_48K ((uint32_t)48000)
#define I2S_AUDIOFREQ_96K ((uint32_t)96000)
#define I2S_AUDIOFREQ_192K ((uint32_t)192000)
/**
* @}
*/
/** @defgroup I2S_Clock_Polarity
* @{
*/
#define I2S_CKPL_LOW ((uint16_t)0x0000)
#define I2S_CKPL_HIGH SPI_I2SCTLR_CKPL
/**
* @}
*/
/** @defgroup SPI_I2S_DMA_transfer_requests
* @{
*/
#define SPI_I2S_DMA_TX SPI_CTLR2_DMATE
#define SPI_I2S_DMA_RX SPI_CTLR2_DMARE
/**
* @}
*/
/** @defgroup SPI_NSS_internal_software_management
* @{
*/
#define SPI_SWNSS_SET ((uint16_t)0x0001)
#define SPI_SWNSS_RESET ((uint16_t)0x0000)
/**
* @}
*/
/** @defgroup SPI_CRC_Transmit_Receive
* @{
*/
#define SPI_CRC_TX ((uint8_t)0x00)
#define SPI_CRC_RX ((uint8_t)0x01)
/**
* @}
*/
/** @defgroup SPI_direction_transmit_receive
* @{
*/
#define SPI_BDOE_RX (~SPI_CTLR1_BDOE)
#define SPI_BDOE_TX SPI_CTLR1_BDOE
/**
* @}
*/
/** @defgroup SPI_I2S_interrupts_definition
* @{
*/
#define SPI_I2S_INT_TBE ((uint8_t)0x71)
#define SPI_I2S_INT_RBNE ((uint8_t)0x60)
#define SPI_I2S_INT_ERR ((uint8_t)0x50)
#define SPI_I2S_INT_OVR ((uint8_t)0x56)
#define SPI_INT_MODF ((uint8_t)0x55)
#define SPI_INT_CRCERR ((uint8_t)0x54)
#define I2S_INT_UDR ((uint8_t)0x53)
/**
* @}
*/
/** @defgroup SPI_I2S_flags_definition
* @{
*/
#define SPI_FLAG_RBNE SPI_STR_RBNE
#define SPI_FLAG_TBE SPI_STR_TBE
#define SPI_FLAG_CRCERR SPI_STR_CRCE
#define SPI_FLAG_MODF SPI_STR_CONFE
#define SPI_FLAG_OVR SPI_STR_RXORE
#define SPI_FLAG_BSY SPI_STR_TRANS
#define I2S_FLAG_RBNE SPI_STR_RBNE
#define I2S_FLAG_TBE SPI_STR_TBE
#define I2S_FLAG_CHSIDE SPI_STR_I2SCH
#define I2S_FLAG_UDR SPI_STR_TXURE
#define I2S_FLAG_OVR SPI_STR_RXORE
#define I2S_FLAG_BSY SPI_STR_TRANS
/**
* @}
*/
/**
* @}
*/
/** @defgroup SPI_Exported_Functions
* @{
*/
void SPI_I2S_DeInit(SPI_TypeDef *SPIx);
void SPI_Init(SPI_TypeDef *SPIx, SPI_InitPara *SPI_InitParameter);
void I2S_Init(SPI_TypeDef *SPIx, I2S_InitPara *I2S_InitParameter);
void SPI_ParaInit(SPI_InitPara *SPI_InitParameter);
void I2S_ParaInit(I2S_InitPara *I2S_InitParameter);
void SPI_Enable(SPI_TypeDef *SPIx, TypeState NewValue);
void I2S_Enable(SPI_TypeDef *SPIx, TypeState NewValue);
void SPI_I2S_INTConfig(SPI_TypeDef *SPIx, uint8_t SPI_I2S_INT, TypeState NewValue);
void SPI_I2S_DMA_Enable(SPI_TypeDef *SPIx, uint16_t SPI_I2S_DMAReq, TypeState NewValue);
void SPI_I2S_SendData(SPI_TypeDef *SPIx, uint16_t Data);
uint16_t SPI_I2S_ReceiveData(SPI_TypeDef *SPIx);
void SPI_SWNSSConfig(SPI_TypeDef *SPIx, uint16_t SPI_SWNSS);
void SPI_NSSDRV(SPI_TypeDef *SPIx, TypeState NewValue);
void SPI_FrameFormatConfig(SPI_TypeDef *SPIx, uint16_t SPI_DataSize);
void SPI_SendCRCNext(SPI_TypeDef *SPIx);
void SPI_CRC_Enable(SPI_TypeDef *SPIx, TypeState NewValue);
uint16_t SPI_GetCRC(SPI_TypeDef *SPIx, uint8_t SPI_CRC);
uint16_t SPI_GetCRCPolynomial(SPI_TypeDef *SPIx);
void SPI_BDOEConfig(SPI_TypeDef *SPIx, uint16_t SPI_BDOE);
TypeState SPI_I2S_GetBitState(SPI_TypeDef *SPIx, uint16_t SPI_I2S_FLAG);
void SPI_I2S_ClearBitState(SPI_TypeDef *SPIx, uint16_t SPI_I2S_FLAG);
TypeState SPI_I2S_GetIntBitState(SPI_TypeDef *SPIx, uint8_t SPI_I2S_INT);
void SPI_I2S_ClearIntBitState(SPI_TypeDef *SPIx, uint8_t SPI_I2S_INT);
#ifdef __cplusplus
}
#endif
#endif /*__GD32F10X_SPI_H */
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/

View File

@ -0,0 +1,758 @@
/**
******************************************************************************
* @brief TIMER header file of the firmware library
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __GD32F10X_TIMER_H
#define __GD32F10X_TIMER_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "gd32f10x.h"
/** @addtogroup GD32F10x_Firmware
* @{
*/
/** @addtogroup TIMER
* @{
*/
/** @defgroup TIMER_Exported_Types
* @{
*/
/**
* @brief Timer base init structure
*/
typedef struct {
uint16_t TIMER_Prescaler; /*!< Clock prescaler value . */
uint16_t TIMER_CounterMode; /*!< Counter mode ,
a value of @ref TIMER_Counter_Mode. */
uint32_t TIMER_Period; /*!< Value to be loaded into the active CARL at the next update event. */
uint16_t TIMER_ClockDivision; /*!< Clock division ,
a value of @ref TIMER_Clock_Division_CDIV. */
uint8_t TIMER_RepetitionCounter; /*!< Repetition counter value , only valid in TIMER1/8. */
} TIMER_BaseInitPara;
/**
* @brief Timer output compare init structure
*/
typedef struct {
uint16_t TIMER_OCMode; /*!< Out mode,
a value of @ref TIMER_Output_Compare_and_PWM_modes */
uint16_t TIMER_OutputState; /*!< Output Compare state ,
a value of @ref TIMER_Output_Compare_State */
uint16_t TIMER_OutputNState; /*!< Complementary Output Compare state ,
a value of @ref TIMER_Output_Compare_N_State,
valid only for TIMER1. */
uint32_t TIMER_Pulse; /*!< Pulse value to be loaded into the CHCCx. */
uint16_t TIMER_OCPolarity; /*!< Output polarity ,
a value of @ref TIMER_Output_Compare_Polarity */
uint16_t TIMER_OCNPolarity; /*!< Complementary output polarity ,
a value of @ref TIMER_Output_Compare_N_Polarity */
uint16_t TIMER_OCIdleState; /*!< TIM Output Compare pin state during Idle state ,
a value of @ref TIMER_Output_Compare_Idle_State,
valid only for TIMER1. */
uint16_t TIMER_OCNIdleState; /*!< TIM Complementary Output Compare pin state during Idle state.
a value of @ref TIMER_Output_Compare_N_Idle_State ,
valid only for TIMER1. */
} TIMER_OCInitPara;
/**
* @brief Timer input capture init structure
*/
typedef struct {
uint16_t TIMER_CH; /*!< TIMER channel ,
a value of @ref TIMER_Channel */
uint16_t TIMER_ICPolarity; /*!< Active edge of the input signal ,
a value of @ref TIMER_Input_Capture_Polarity */
uint16_t TIMER_ICSelection; /*!< Input Selection ,
a value of @ref TIMER_Input_Capture_Selection */
uint16_t TIMER_ICPrescaler; /*!< Input Capture Prescaler ,
a value of @ref TIMER_Input_Capture_Prescaler */
uint16_t TIMER_ICFilter; /*!< Input capture filter ,
a number between 0x0 and 0xF */
} TIMER_ICInitPara;
/**
* @brief Timer break and dead-time structure , valid only for TIMER1.
*/
typedef struct {
uint16_t TIMER_ROSState; /*!< Off-State selection used in Run mode ,
a value of @ref TIMER_ROS_Off_State_Selection_for_Run_mode_State */
uint16_t TIMER_IOSState; /*!< Off-State used in Idle state ,
a value of @ref TIMER_IOS_Off_State_Selection_for_Idle_mode_State */
uint16_t TIMER_LOCKLevel; /*!< LOCK level ,
a value of @ref TIMER_Lock_level */
uint16_t TIMER_DeadTime; /*!< delay time between the switching off and on of the outputs.
a number between 0x00 and 0xFF */
uint16_t TIMER_Break; /*!< Break input is enabled or disable,
a value of @ref TIMER_Break_Input_State */
uint16_t TIMER_BreakPolarity; /*!< Break Input pin polarity ,
a value of @ref TIMER_Break_Input_Polarity */
uint16_t TIMER_OutAuto; /*!< Automatic Output is enabled or disable.
a value of @ref TIMER_OAE_Bit_State */
} TIMER_BKDTInitPara;
/**
* @}
*/
/** @defgroup TIMER_Exported_Constants
* @{
*/
/** @defgroup TIMER_Output_Compare_and_PWM_modes
* @{
*/
#define TIMER_OC_MODE_TIMING ((uint16_t)0x0000)
#define TIMER_OC_MODE_ACTIVE ((uint16_t)0x0010)
#define TIMER_OC_MODE_INACTIVE ((uint16_t)0x0020)
#define TIMER_OC_MODE_TOGGLE ((uint16_t)0x0030)
#define TIMER_OC_MODE_PWM1 ((uint16_t)0x0060)
#define TIMER_OC_MODE_PWM2 ((uint16_t)0x0070)
/**
* @}
*/
/** @defgroup TIMER_Single_Pulse_Mode
* @{
*/
#define TIMER_SP_MODE_SINGLE ((uint16_t)0x0008)
#define TIMER_SP_MODE_REPETITIVE ((uint16_t)0x0000)
/**
* @}
*/
/** @defgroup TIMER_Channel
* @{
*/
#define TIMER_CH_1 ((uint16_t)0x0000)
#define TIMER_CH_2 ((uint16_t)0x0004)
#define TIMER_CH_3 ((uint16_t)0x0008)
#define TIMER_CH_4 ((uint16_t)0x000C)
/**
* @}
*/
/** @defgroup TIMER_Clock_Division_CDIV
* @{
*/
#define TIMER_CDIV_DIV1 ((uint16_t)0x0000)
#define TIMER_CDIV_DIV2 ((uint16_t)0x0100)
#define TIMER_CDIV_DIV4 ((uint16_t)0x0200)
/**
* @}
*/
/** @defgroup TIMER_Counter_Mode
* @{
*/
#define TIMER_COUNTER_UP ((uint16_t)0x0000)
#define TIMER_COUNTER_DOWN ((uint16_t)0x0010)
#define TIMER_COUNTER_CENTER_ALIGNED1 ((uint16_t)0x0020)
#define TIMER_COUNTER_CENTER_ALIGNED2 ((uint16_t)0x0040)
#define TIMER_COUNTER_CENTER_ALIGNED3 ((uint16_t)0x0060)
/**
* @}
*/
/** @defgroup TIMER_Output_Compare_Polarity
* @{
*/
#define TIMER_OC_POLARITY_HIGH ((uint16_t)0x0000)
#define TIMER_OC_POLARITY_LOW ((uint16_t)0x0002)
/**
* @}
*/
/** @defgroup TIMER_Output_Compare_N_Polarity
* @{
*/
#define TIMER_OCN_POLARITY_HIGH ((uint16_t)0x0000)
#define TIMER_OCN_POLARITY_LOW ((uint16_t)0x0008)
/**
* @}
*/
/** @defgroup TIMER_Output_Compare_State
* @{
*/
#define TIMER_OUTPUT_STATE_DISABLE ((uint16_t)0x0000)
#define TIMER_OUTPUT_STATE_ENABLE ((uint16_t)0x0001)
/**
* @}
*/
/** @defgroup TIMER_Output_Compare_N_State
* @{
*/
#define TIMER_OUTPUTN_STATE_DISABLE ((uint16_t)0x0000)
#define TIMER_OUTPUTN_STATE_ENABLE ((uint16_t)0x0004)
/**
* @}
*/
/** @defgroup TIMER_Capture_Compare_State
* @{
*/
#define TIMER_CCX_ENABLE ((uint16_t)0x0001)
#define TIMER_CCX_DISABLE ((uint16_t)0x0000)
/**
* @}
*/
/** @defgroup TIMER_Capture_Compare_N_State
* @{
*/
#define TIMER_CCXN_ENABLE ((uint16_t)0x0004)
#define TIMER_CCXN_DISABLE ((uint16_t)0x0000)
/**
* @}
*/
/** @defgroup TIMER_Break_Input_State
* @{
*/
#define TIMER_BREAK_ENABLE ((uint16_t)0x1000)
#define TIMER_BREAK_DISABLE ((uint16_t)0x0000)
/**
* @}
*/
/** @defgroup TIMER_Break_Input_Polarity
* @{
*/
#define TIMER_BREAK_POLARITY_LOW ((uint16_t)0x0000)
#define TIMER_BREAK_POLARITY_HIGH ((uint16_t)0x2000)
/**
* @}
*/
/** @defgroup TIMER_OAE_Bit_State
* @{
*/
#define TIMER_OUTAUTO_ENABLE ((uint16_t)0x4000)
#define TIMER_OUTAUTO_DISABLE ((uint16_t)0x0000)
/**
* @}
*/
/** @defgroup TIMER_Lock_level
* @{
*/
#define TIMER_LOCK_LEVEL_OFF ((uint16_t)0x0000)
#define TIMER_LOCK_LEVEL_1 ((uint16_t)0x0100)
#define TIMER_LOCK_LEVEL_2 ((uint16_t)0x0200)
#define TIMER_LOCK_LEVEL_3 ((uint16_t)0x0300)
/**
* @}
*/
/** @defgroup TIMER_IOS_Off_State_Selection_for_Idle_mode_State
* @{
*/
#define TIMER_IOS_STATE_ENABLE ((uint16_t)0x0400)
#define TIMER_IOS_STATE_DISABLE ((uint16_t)0x0000)
/**
* @}
*/
/** @defgroup TIMER_ROS_Off_State_Selection_for_Run_mode_State
* @{
*/
#define TIMER_ROS_STATE_ENABLE ((uint16_t)0x0800)
#define TIMER_ROS_STATE_DISABLE ((uint16_t)0x0000)
/**
* @}
*/
/** @defgroup TIMER_Output_Compare_Idle_State
* @{
*/
#define TIMER_OC_IDLE_STATE_SET ((uint16_t)0x0100)
#define TIMER_OC_IDLE_STATE_RESET ((uint16_t)0x0000)
/**
* @}
*/
/** @defgroup TIMER_Output_Compare_N_Idle_State
* @{
*/
#define TIMER_OCN_IDLE_STATE_SET ((uint16_t)0x0200)
#define TIMER_OCN_IDLE_STATE_RESET ((uint16_t)0x0000)
/**
* @}
*/
/** @defgroup TIMER_Input_Capture_Polarity
* @{
*/
#define TIMER_IC_POLARITY_RISING ((uint16_t)0x0000)
#define TIMER_IC_POLARITY_FALLING ((uint16_t)0x0002)
/**
* @}
*/
/** @defgroup TIMER_Input_Capture_Selection
* @{
*/
#define TIMER_IC_SELECTION_DIRECTTI ((uint16_t)0x0001)
#define TIMER_IC_SELECTION_INDIRECTTI ((uint16_t)0x0002)
#define TIMER_IC_SELECTION_TRC ((uint16_t)0x0003)
/**
* @}
*/
/** @defgroup TIMER_Input_Capture_Prescaler
* @{
*/
#define TIMER_IC_PSC_DIV1 ((uint16_t)0x0000)
#define TIMER_IC_PSC_DIV2 ((uint16_t)0x0004)
#define TIMER_IC_PSC_DIV4 ((uint16_t)0x0008)
#define TIMER_IC_PSC_DIV8 ((uint16_t)0x000C)
/**
* @}
*/
/** @defgroup TIMER_interrupt_sources
* @{
*/
#define TIMER_INT_UPDATE ((uint16_t)0x0001)
#define TIMER_INT_CH1 ((uint16_t)0x0002)
#define TIMER_INT_CH2 ((uint16_t)0x0004)
#define TIMER_INT_CH3 ((uint16_t)0x0008)
#define TIMER_INT_CH4 ((uint16_t)0x0010)
#define TIMER_INT_CCUG ((uint16_t)0x0020)
#define TIMER_INT_TRIGGER ((uint16_t)0x0040)
#define TIMER_INT_BREAK ((uint16_t)0x0080)
/**
* @}
*/
/** @defgroup TIMER_DMA_Base_address
* @{
*/
#define TIMER_DMA_BASE_ADDR_CTLR1 ((uint16_t)0x0000)
#define TIMER_DMA_BASE_ADDR_CTLR2 ((uint16_t)0x0001)
#define TIMER_DMA_BASE_ADDR_SMC ((uint16_t)0x0002)
#define TIMER_DMA_BASE_ADDR_DIE ((uint16_t)0x0003)
#define TIMER_DMA_BASE_ADDR_STR ((uint16_t)0x0004)
#define TIMER_DMA_BASE_ADDR_EVG ((uint16_t)0x0005)
#define TIMER_DMA_BASE_ADDR_CHCTLR1 ((uint16_t)0x0006)
#define TIMER_DMA_BASE_ADDR_CHCTLR2 ((uint16_t)0x0007)
#define TIMER_DMA_BASE_ADDR_CHE ((uint16_t)0x0008)
#define TIMER_DMA_BASE_ADDR_CNT ((uint16_t)0x0009)
#define TIMER_DMA_BASE_ADDR_PSC ((uint16_t)0x000A)
#define TIMER_DMA_BASE_ADDR_CARL ((uint16_t)0x000B)
#define TIMER_DMA_BASE_ADDR_CREP ((uint16_t)0x000C)
#define TIMER_DMA_BASE_ADDR_CHCC1 ((uint16_t)0x000D)
#define TIMER_DMA_BASE_ADDR_CHCC2 ((uint16_t)0x000E)
#define TIMER_DMA_BASE_ADDR_CHCC3 ((uint16_t)0x000F)
#define TIMER_DMA_BASE_ADDR_CHCC4 ((uint16_t)0x0010)
#define TIMER_DMA_BASE_ADDR_BKDT ((uint16_t)0x0011)
#define TIMER_DMA_BASE_ADDR_DCTLR ((uint16_t)0x0012)
/**
* @}
*/
/** @defgroup TIMER_DMA_Burst_Transfer_Length
* @{
*/
#define TIMER_DMA_BURST_1TRANSFER ((uint16_t)0x0000)
#define TIMER_DMA_BURST_2TRANSFERS ((uint16_t)0x0100)
#define TIMER_DMA_BURST_3TRANSFERS ((uint16_t)0x0200)
#define TIMER_DMA_BURST_4TRANSFERS ((uint16_t)0x0300)
#define TIMER_DMA_BURST_5TRANSFERS ((uint16_t)0x0400)
#define TIMER_DMA_BURST_6TRANSFERS ((uint16_t)0x0500)
#define TIMER_DMA_BURST_7TRANSFERS ((uint16_t)0x0600)
#define TIMER_DMA_BURST_8TRANSFERS ((uint16_t)0x0700)
#define TIMER_DMA_BURST_9TRANSFERS ((uint16_t)0x0800)
#define TIMER_DMA_BURST_10TRANSFERS ((uint16_t)0x0900)
#define TIMER_DMA_BURST_11TRANSFERS ((uint16_t)0x0A00)
#define TIMER_DMA_BURST_12TRANSFERS ((uint16_t)0x0B00)
#define TIMER_DMA_BURST_13TRANSFERS ((uint16_t)0x0C00)
#define TIMER_DMA_BURST_14TRANSFERS ((uint16_t)0x0D00)
#define TIMER_DMA_BURST_15TRANSFERS ((uint16_t)0x0E00)
#define TIMER_DMA_BURST_16TRANSFERS ((uint16_t)0x0F00)
#define TIMER_DMA_BURST_17TRANSFERS ((uint16_t)0x1000)
#define TIMER_DMA_BURST_18TRANSFERS ((uint16_t)0x1100)
/**
* @}
*/
/** @defgroup TIMER_DMA_sources
* @{
*/
#define TIMER_DMA_UPDATE ((uint16_t)0x0100)
#define TIMER_DMA_CH1 ((uint16_t)0x0200)
#define TIMER_DMA_CH2 ((uint16_t)0x0400)
#define TIMER_DMA_CH3 ((uint16_t)0x0800)
#define TIMER_DMA_CH4 ((uint16_t)0x1000)
#define TIMER_DMA_COM ((uint16_t)0x2000)
#define TIMER_DMA_TRIGGER ((uint16_t)0x4000)
/**
* @}
*/
/** @defgroup TIMER_External_Trigger_Prescaler
* @{
*/
#define TIMER_EXT_TRI_PSC_OFF ((uint16_t)0x0000)
#define TIMER_EXT_TRI_PSC_DIV2 ((uint16_t)0x1000)
#define TIMER_EXT_TRI_PSC_DIV4 ((uint16_t)0x2000)
#define TIMER_EXT_TRI_PSC_DIV8 ((uint16_t)0x3000)
/**
* @}
*/
/** @defgroup TIMER_Internal_Trigger_Selection
* @{
*/
#define TIMER_TS_ITR0 ((uint16_t)0x0000)
#define TIMER_TS_ITR1 ((uint16_t)0x0010)
#define TIMER_TS_ITR2 ((uint16_t)0x0020)
#define TIMER_TS_ITR3 ((uint16_t)0x0030)
#define TIMER_TS_TI1F_ED ((uint16_t)0x0040)
#define TIMER_TS_TI1FP1 ((uint16_t)0x0050)
#define TIMER_TS_TI2FP2 ((uint16_t)0x0060)
#define TIMER_TS_ETRF ((uint16_t)0x0070)
/**
* @}
*/
/** @defgroup TIMER_TIx_External_Clock_Source
* @{
*/
#define TIMER_TIX_EXCLK1_SRC_TI1 ((uint16_t)0x0050)
#define TIMER_TIX_EXCLK1_SRC_TI2 ((uint16_t)0x0060)
#define TIMER_TIX_EXCLK1_SRC_TI1ED ((uint16_t)0x0040)
/**
* @}
*/
/** @defgroup TIMER_External_Trigger_Polarity
* @{
*/
#define TIMER_EXT_TRI_POLARITY_INVERTED ((uint16_t)0x8000)
#define TIMER_EXT_TRI_POLARITY_NONINVERTED ((uint16_t)0x0000)
/**
* @}
*/
/** @defgroup TIMER_Prescaler_Reload_Mode
* @{
*/
#define TIMER_PSC_RELOAD_UPDATE ((uint16_t)0x0000)
#define TIMER_PSC_RELOAD_NOW ((uint16_t)0x0001)
/**
* @}
*/
/** @defgroup TIMER_Forced_Output
* @{
*/
#define TIMER_FORCED_HIGH ((uint16_t)0x0050)
#define TIMER_FORCED_LOW ((uint16_t)0x0040)
/**
* @}
*/
/** @defgroup TIMER_Encoder_Mode
* @{
*/
#define TIMER_ENCODER_MODE_TI1 ((uint16_t)0x0001)
#define TIMER_ENCODER_MODE_TI2 ((uint16_t)0x0002)
#define TIMER_ENCODER_MODE_TI12 ((uint16_t)0x0003)
/**
* @}
*/
/** @defgroup TIMER_Event_Source
* @{
*/
#define TIMER_EVENT_SRC_UPDATE ((uint16_t)0x0001)
#define TIMER_EVENT_SRC_CH1 ((uint16_t)0x0002)
#define TIMER_EVENT_SRC_CH2 ((uint16_t)0x0004)
#define TIMER_EVENT_SRC_CH3 ((uint16_t)0x0008)
#define TIMER_EVENT_SRC_CH4 ((uint16_t)0x0010)
#define TIMER_EVENT_SRC_COM ((uint16_t)0x0020)
#define TIMER_EVENT_SRC_TRIGGER ((uint16_t)0x0040)
#define TIMER_EVENT_SRC_BREAK ((uint16_t)0x0080)
/**
* @}
*/
/** @defgroup TIMER_Update_Source
* @{
*/
#define TIMER_UPDATE_SRC_GLOBAL ((uint16_t)0x0000)
#define TIMER_UPDATE_SRC_REGULAR ((uint16_t)0x0001)
/**
* @}
*/
/** @defgroup TIMER_Output_Compare_Preload_State
* @{
*/
#define TIMER_OC_PRELOAD_ENABLE ((uint16_t)0x0008)
#define TIMER_OC_PRELOAD_DISABLE ((uint16_t)0x0000)
/**
* @}
*/
/** @defgroup TIMER_Output_Compare_Fast_State
* @{
*/
#define TIMER_OC_FAST_ENABLE ((uint16_t)0x0004)
#define TIMER_OC_FAST_DISABLE ((uint16_t)0x0000)
/**
* @}
*/
/** @defgroup TIMER_Output_Compare_Clear_State
* @{
*/
#define TIMER_OC_CLEAR_ENABLE ((uint16_t)0x0080)
#define TIMER_OC_CLEAR_DISABLE ((uint16_t)0x0000)
/**
* @}
*/
/** @defgroup TIMER_Trigger_Output_Source
* @{
*/
#define TIMER_TRI_OUT_SRC_RESET ((uint16_t)0x0000)
#define TIMER_TRI_OUT_SRC_ENABLE ((uint16_t)0x0010)
#define TIMER_TRI_OUT_SRC_UPDATE ((uint16_t)0x0020)
#define TIMER_TRI_OUT_SRC_OC1 ((uint16_t)0x0030)
#define TIMER_TRI_OUT_SRC_OC1REF ((uint16_t)0x0040)
#define TIMER_TRI_OUT_SRC_OC2REF ((uint16_t)0x0050)
#define TIMER_TRI_OUT_SRC_OC3REF ((uint16_t)0x0060)
#define TIMER_TRI_OUT_SRC_OC4REF ((uint16_t)0x0070)
/**
* @}
*/
/** @defgroup TIMER_Slave_Mode
* @{
*/
#define TIMER_SLAVE_MODE_RESET ((uint16_t)0x0004)
#define TIMER_SLAVE_MODE_GATED ((uint16_t)0x0005)
#define TIMER_SLAVE_MODE_TRIGGER ((uint16_t)0x0006)
#define TIMER_SLAVE_MODE_EXTERNAL1 ((uint16_t)0x0007)
/**
* @}
*/
/** @defgroup TIMER_Master_Slave_Mode
* @{
*/
#define TIMER_MASTER_SLAVE_MODE_ENABLE ((uint16_t)0x0080)
#define TIMER_MASTER_SLAVE_MODE_DISABLE ((uint16_t)0x0000)
/**
* @}
*/
/** @defgroup TIMER_Flags
* @{
*/
#define TIMER_FLAG_UPDATE ((uint16_t)0x0001)
#define TIMER_FLAG_CH1 ((uint16_t)0x0002)
#define TIMER_FLAG_CH2 ((uint16_t)0x0004)
#define TIMER_FLAG_CH3 ((uint16_t)0x0008)
#define TIMER_FLAG_CH4 ((uint16_t)0x0010)
#define TIMER_FLAG_COM ((uint16_t)0x0020)
#define TIMER_FLAG_TRIGGER ((uint16_t)0x0040)
#define TIMER_FLAG_BREAK ((uint16_t)0x0080)
#define TIMER_FLAG_CH1OF ((uint16_t)0x0200)
#define TIMER_FLAG_CH2OF ((uint16_t)0x0400)
#define TIMER_FLAG_CH3OF ((uint16_t)0x0800)
#define TIMER_FLAG_CH4OF ((uint16_t)0x1000)
/**
* @}
*/
/**
* @}
*/
/** @defgroup TIMER_Exported_Functions
* @{
*/
/* TimeBase management ********************************************************/
void TIMER_DeInit(TIMER_TypeDef *TIMERx);
void TIMER_BaseInit(TIMER_TypeDef *TIMERx, TIMER_BaseInitPara *TIMER_Init);
void TIMER_BaseStructInit(TIMER_BaseInitPara *TIMER_Init);
void TIMER_PrescalerConfig(TIMER_TypeDef *TIMERx, uint16_t Prescaler, uint16_t TIMER_PSCReloadMode);
void TIMER_CounterMode(TIMER_TypeDef *TIMERx, uint16_t TIMER_CounterMode);
void TIMER_SetCounter(TIMER_TypeDef *TIMERx, uint32_t Counter);
void TIMER_SetAutoreload(TIMER_TypeDef *TIMERx, uint32_t AutoReloadValue);
uint32_t TIMER_GetCounter(TIMER_TypeDef *TIMERx);
uint16_t TIMER_GetPrescaler(TIMER_TypeDef *TIMERx);
void TIMER_UpdateDisableConfig(TIMER_TypeDef *TIMERx, TypeState NewValue);
void TIMER_UpdateRequestConfig(TIMER_TypeDef *TIMERx, uint16_t TIMER_UpdateSrc);
void TIMER_CARLPreloadConfig(TIMER_TypeDef *TIMERx, TypeState NewValue);
void TIMER_SinglePulseMode(TIMER_TypeDef *TIMERx, uint16_t TIMER_SPMode);
void TIMER_SetClockDivision(TIMER_TypeDef *TIMERx, uint16_t TIMER_CDIV);
void TIMER_Enable(TIMER_TypeDef *TIMERx, TypeState NewValue);
/* Advanced timer features*******************/
void TIMER_BKDTConfig(TIMER_TypeDef *TIMERx, TIMER_BKDTInitPara *TIMER_BKDTInit);
void TIMER_BKDTStructInit(TIMER_BKDTInitPara *TIMER_BKDTInit);
void TIMER_CtrlPWMOutputs(TIMER_TypeDef *TIMERx, TypeState NewValue);
/* Output Compare management **************************************************/
void TIMER_OC1_Init(TIMER_TypeDef *TIMERx, TIMER_OCInitPara *TIMER_OCInit);
void TIMER_OC2_Init(TIMER_TypeDef *TIMERx, TIMER_OCInitPara *TIMER_OCInit);
void TIMER_OC3_Init(TIMER_TypeDef *TIMERx, TIMER_OCInitPara *TIMER_OCInit);
void TIMER_OC4_Init(TIMER_TypeDef *TIMERx, TIMER_OCInitPara *TIMER_OCInit);
void TIMER_OCStructInit(TIMER_OCInitPara *TIMER_OCInit);
void TIMER_OCxModeConfig(TIMER_TypeDef *TIMERx, uint16_t TIMER_Ch, uint16_t TIMER_OCMode);
void TIMER_Compare1Config(TIMER_TypeDef *TIMERx, uint32_t CompValue1);
void TIMER_Compare2Config(TIMER_TypeDef *TIMERx, uint32_t CompValue2);
void TIMER_Compare3Config(TIMER_TypeDef *TIMERx, uint32_t CompValue3);
void TIMER_Compare4Config(TIMER_TypeDef *TIMERx, uint32_t CompValue4);
void TIMER_Forced_OC1(TIMER_TypeDef *TIMERx, uint16_t TIMER_Forced);
void TIMER_Forced_OC2(TIMER_TypeDef *TIMERx, uint16_t TIMER_Forced);
void TIMER_Forced_OC3(TIMER_TypeDef *TIMERx, uint16_t TIMER_Forced);
void TIMER_Forced_OC4(TIMER_TypeDef *TIMERx, uint16_t TIMER_Forced);
void TIMER_CC_PreloadControl(TIMER_TypeDef *TIMERx, TypeState NewValue);
void TIMER_OC1_Preload(TIMER_TypeDef *TIMERx, uint16_t TIMER_OCPreload);
void TIMER_OC2_Preload(TIMER_TypeDef *TIMERx, uint16_t TIMER_OCPreload);
void TIMER_OC3_Preload(TIMER_TypeDef *TIMERx, uint16_t TIMER_OCPreload);
void TIMER_OC4_Preload(TIMER_TypeDef *TIMERx, uint16_t TIMER_OCPreload);
void TIMER_OC1_FastConfig(TIMER_TypeDef *TIMERx, uint16_t TIMER_OCFast);
void TIMER_OC2_FastConfig(TIMER_TypeDef *TIMERx, uint16_t TIMER_OCFast);
void TIMER_OC3_FastConfig(TIMER_TypeDef *TIMERx, uint16_t TIMER_OCFast);
void TIMER_OC4_FastConfig(TIMER_TypeDef *TIMERx, uint16_t TIMER_OCFast);
void TIMER_OC1_RefClear(TIMER_TypeDef *TIMERx, uint16_t TIMER_OCClear);
void TIMER_OC2_RefClear(TIMER_TypeDef *TIMERx, uint16_t TIMER_OCClear);
void TIMER_OC3_RefClear(TIMER_TypeDef *TIMERx, uint16_t TIMER_OCClear);
void TIMER_OC4_RefClear(TIMER_TypeDef *TIMERx, uint16_t TIMER_OCClear);
void TIMER_OC1_Polarity(TIMER_TypeDef *TIMERx, uint16_t TIMER_OCPolarity);
void TIMER_OC1N_Polarity(TIMER_TypeDef *TIMERx, uint16_t TIMER_OCNPolarity);
void TIMER_OC2_Polarity(TIMER_TypeDef *TIMERx, uint16_t TIMER_OCPolarity);
void TIMER_OC2N_Polarity(TIMER_TypeDef *TIMERx, uint16_t TIMER_OCNPolarity);
void TIMER_OC3_Polarity(TIMER_TypeDef *TIMERx, uint16_t TIMER_OCPolarity);
void TIMER_OC3N_Polarity(TIMER_TypeDef *TIMERx, uint16_t TIMER_OCNPolarity);
void TIMER_OC4_Polarity(TIMER_TypeDef *TIMERx, uint16_t TIMER_OCPolarity);
void TIMER_SelectOCRefClear(TIMER_TypeDef *TIMERx, uint16_t TIMER_OCRef_Clear);
void TIMER_CCxCmd(TIMER_TypeDef *TIMERx, uint16_t TIMER_Ch, uint16_t TIMER_CCx);
void TIMER_CCxNCmd(TIMER_TypeDef *TIMERx, uint16_t TIMER_Ch, uint16_t TIMER_CCxN);
void TIMER_SelectCOM(TIMER_TypeDef *TIMERx, TypeState NewValue);
/* Input Capture management ***************************************************/
void TIMER_ICInit(TIMER_TypeDef *TIMERx, TIMER_ICInitPara *TIMER_ICInit);
void TIMER_ICStructInit(TIMER_ICInitPara *TIMER_ICInit);
void TIMER_PWMCaptureConfig(TIMER_TypeDef *TIMERx, TIMER_ICInitPara *TIMER_ICInit);
uint32_t TIMER_GetCapture1(TIMER_TypeDef *TIMERx);
uint32_t TIMER_GetCapture2(TIMER_TypeDef *TIMERx);
uint32_t TIMER_GetCapture3(TIMER_TypeDef *TIMERx);
uint32_t TIMER_GetCapture4(TIMER_TypeDef *TIMERx);
void TIMER_Set_IC1_Prescaler(TIMER_TypeDef *TIMERx, uint16_t TIMER_ICPSC);
void TIMER_Set_IC2_Prescaler(TIMER_TypeDef *TIMERx, uint16_t TIMER_ICPSC);
void TIMER_Set_IC3_Prescaler(TIMER_TypeDef *TIMERx, uint16_t TIMER_ICPSC);
void TIMER_Set_IC4_Prescaler(TIMER_TypeDef *TIMERx, uint16_t TIMER_ICPSC);
/* Interrupts, DMA and flags management ***************************************/
void TIMER_INTConfig(TIMER_TypeDef *TIMERx, uint16_t TIMER_INT, TypeState NewValue);
void TIMER_GenerateEvent(TIMER_TypeDef *TIMERx, uint16_t TIMER_EventSrc);
TypeState TIMER_GetBitState(TIMER_TypeDef *TIMERx, uint16_t TIMER_FLAG);
void TIMER_ClearBitState(TIMER_TypeDef *TIMERx, uint16_t TIMER_FLAG);
TypeState TIMER_GetIntBitState(TIMER_TypeDef *TIMERx, uint16_t TIMER_INT);
void TIMER_ClearIntBitState(TIMER_TypeDef *TIMERx, uint16_t TIMER_INT);
void TIMER_DMAConfig(TIMER_TypeDef *TIMERx, uint16_t TIMER_DMABase, uint16_t TIMER_DMABurstLength);
void TIMER_DMACmd(TIMER_TypeDef *TIMERx, uint16_t TIMER_DMASrc, TypeState NewValue);
void TIMER_CC_DMA(TIMER_TypeDef *TIMERx, TypeState NewValue);
/* Clocks management **********************************************************/
void TIMER_InternalClockConfig(TIMER_TypeDef *TIMERx);
void TIMER_ITRxExtClock(TIMER_TypeDef *TIMERx, uint16_t TIMER_InputTriSrc);
void TIMER_TIxExtCLkConfig(TIMER_TypeDef *TIMERx, uint16_t TIMER_TIxExCLKSrc,
uint16_t TIMER_ICPolarity, uint16_t ICFilter);
void TIMER_ETRClockMode1Config(TIMER_TypeDef *TIMERx, uint16_t TIMER_ExTriPrescaler, uint16_t TIMER_ExTriPolarity,
uint16_t ExtTriFilter);
void TIMER_ETRClockMode2Config(TIMER_TypeDef *TIMERx, uint16_t TIMER_ExTriPrescaler,
uint16_t TIMER_ExTriPolarity, uint16_t ExtTriFilter);
/* Synchronization management *************************************************/
void TIMER_SelectInputTrigger(TIMER_TypeDef *TIMERx, uint16_t TIMER_InputTriSrc);
void TIMER_SelectOutputTrigger(TIMER_TypeDef *TIMERx, uint16_t TIMER_TriOutSrc);
void TIMER_SelectSlaveMode(TIMER_TypeDef *TIMERx, uint16_t TIMER_SlaveMode);
void TIMER_SelectMasterSlaveMode(TIMER_TypeDef *TIMERx, uint16_t TIMER_MasterSlaveMode);
void TIMER_ETRConfig(TIMER_TypeDef *TIMERx, uint16_t TIMER_ExTriPrescaler, uint16_t TIMER_ExTriPolarity,
uint16_t ExtTriFilter);
/* Specific interface management **********************************************/
void TIMER_EncoderInterfaceConfig(TIMER_TypeDef *TIMERx, uint16_t TIMER_EncoderMode,
uint16_t TIMER_IC1Polarity, uint16_t TIMER_IC2Polarity);
void TIMER_SelectHallSensor(TIMER_TypeDef *TIMERx, TypeState NewValue);
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif /*__GD32F10X_TIMER_H */
/**
* @}
*/
/**
* @}
*/

View File

@ -0,0 +1,297 @@
/**
******************************************************************************
* @brief USART header file of the firmware library.
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __GD32F10X_USART_H
#define __GD32F10X_USART_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "gd32f10x.h"
/** @addtogroup GD32F10x_Firmware
* @{
*/
/** @addtogroup USART
* @{
*/
/** @defgroup USART_Exported_Types
* @{
*/
/**
* @brief USART Initial Parameters
*/
typedef struct {
uint32_t USART_BRR; /*!< the USART communication baud rate configuration */
uint16_t USART_WL; /*!< Set by USART_CTLR1_WL Word length 0: 8 Data bits,
1: 9 Data bits */
uint16_t USART_STBits; /*!< Stop bits configuration */
uint16_t USART_Parity; /*!< Set by USART_CTLR1_PCEN */
uint16_t USART_RxorTx; /*!< Specifies wether the Receive or Transmit mode is enabled or disabled. */
uint16_t USART_HardwareFlowControl; /*!< Specifies wether the hardware flow control mode is enabled
or disabled.This parameter can be a value of @ref USART_Hardware_Flow_Control */
} USART_InitPara;
/**
* @brief USART Clock Init Structure definition
*/
typedef struct {
uint16_t USART_CKEN; /*!< USART clock enabled this parameter can be a value of @ref USART_CKEN */
uint16_t USART_CPL; /*!< Clock polarity of Steady state this parameter can be a value of @ref USART_Clock_Polarity */
uint16_t USART_CPH; /*!< Clock phase this parameter can be a value of @ref USART_Clock_Phase */
uint16_t USART_LBCP; /*!< Last bit clock pulse this parameter can be a value of @ref USART_Last_Bit */
} USART_ClockInitPara;
/**
* @}
*/
/** @defgroup USART_Exported_Constants
* @{
*/
/** @defgroup USART_WL
* @{
*/
#define USART_WL_8B ((uint16_t)0x0000)
#define USART_WL_9B USART_CTLR1_WL
/**
* @}
*/
/** @defgroup USART_STBits
* @{
*/
#define USART_STBITS_1 ((uint16_t)0x0000)
#define USART_STBITS_0_5 ((uint16_t)0x1000)
#define USART_STBITS_2 USART_CTLR2_STB_1
#define USART_STBITS_1_5 (USART_CTLR2_STB_0 | USART_CTLR2_STB_1)
/**
* @}
*/
/** @defgroup USART_Parity
* @{
*/
#define USART_PARITY_RESET ((uint16_t)0x0000)
#define USART_PARITY_SETEVEN USART_CTLR1_PCEN
#define USART_PARITY_SETODD (USART_CTLR1_PCEN | USART_CTLR1_PM)
/**
* @}
*/
/** @defgroup USART_RxorTx
* @{
*/
#define USART_RXORTX_RX USART_CTLR1_REN
#define USART_RXORTX_TX USART_CTLR1_TEN
/**
* @}
*/
/** @defgroup USART_Hardware_Flow_Control
* @{
*/
#define USART_HARDWAREFLOWCONTROL_NONE ((uint16_t)0x0000)
#define USART_HARDWAREFLOWCONTROL_RTS USART_CTLR3_RTSEN
#define USART_HARDWAREFLOWCONTROL_CTS USART_CTLR3_CTSEN
#define USART_HARDWAREFLOWCONTROL_RTS_CTS (USART_CTLR3_RTSEN | USART_CTLR3_CTSEN)
/**
* @}
*/
/** @defgroup USART_CKEN
* @{
*/
#define USART_CKEN_RESET ((uint16_t)0x0000)
#define USART_CKEN_SET USART_CTLR2_CKEN
/**
* @}
*/
/** @defgroup USART_Clock_Polarity
* @{
*/
#define USART_CPL_LOW ((uint16_t)0x0000)
#define USART_CPL_HIGH USART_CTLR2_CPL
/**
* @}
*/
/** @defgroup USART_Clock_Phase
* @{
*/
#define USART_CPH_1EDGE ((uint16_t)0x0000)
#define USART_CPH_2EDGE USART_CTLR2_CPH
/**
* @}
*/
/** @defgroup USART_Last_Bit
* @{
*/
#define USART_LBCP_DISABLE ((uint16_t)0x0000)
#define USART_LBCP_ENABLE USART_CTLR2_LBCP
/**
* @}
*/
/** @defgroup USART_DMA_Requests
* @{
*/
#define USART_DMAREQ_TX USART_CTLR3_DENT
#define USART_DMAREQ_RX USART_CTLR3_DENR
/**
* @}
*/
/** @defgroup USART_Interrupt_definition
* @brief USART Interrupt definition
* USART_INT possible values
* @{
*/
#define USART_INT_PE ((uint16_t)0x0028)
#define USART_INT_TBE ((uint16_t)0x0727)
#define USART_INT_TC ((uint16_t)0x0626)
#define USART_INT_RBNE ((uint16_t)0x0525)
#define USART_INT_IDLEF ((uint16_t)0x0424)
#define USART_INT_LBDF ((uint16_t)0x0846)
#define USART_INT_CTSF ((uint16_t)0x096A)
#define USART_INT_ERIE ((uint16_t)0x0060)
#define USART_INT_ORE ((uint16_t)0x0360)
#define USART_INT_NE ((uint16_t)0x0260)
#define USART_INT_FE ((uint16_t)0x0160)
/**
* @}
*/
/** @defgroup USART_MuteMode_WakeUp_methods
* @{
*/
#define USART_WAKEUP_IDLELINE ((uint16_t)0x0000)
#define USART_WAKEUP_ADDRESSMARK USART_CTLR1_WM
/**
* @}
*/
/** @defgroup USART_LIN_Break_Detection_Length
* @{
*/
#define USART_LINBREAKDETECTLENGTH_10B ((uint16_t)0x0000)
#define USART_LINBREAKDETECTLENGTH_11B USART_CTLR2_LBDL
/**
* @}
*/
/** @defgroup USART_IrDA_Low_Power
* @{
*/
#define USART_IRDAMODE_LOWPOWER USART_CTLR3_IRLP
#define USART_IRDAMODE_NORMAL ((uint16_t)0x0000)
/**
* @}
*/
/** @defgroup USART_Flags
* @{
*/
#define USART_FLAG_CTSF ((uint16_t)0x0200)
#define USART_FLAG_LBDF ((uint16_t)0x0100)
#define USART_FLAG_TBE ((uint16_t)0x0080)
#define USART_FLAG_TC ((uint16_t)0x0040)
#define USART_FLAG_RBNE ((uint16_t)0x0020)
#define USART_FLAG_IDLEF ((uint16_t)0x0010)
#define USART_FLAG_ORE ((uint16_t)0x0008)
#define USART_FLAG_NE ((uint16_t)0x0004)
#define USART_FLAG_FE ((uint16_t)0x0002)
#define USART_FLAG_PE ((uint16_t)0x0001)
/**
* @}
*/
/**
* @}
*/
/** @defgroup USART_Exported_Functions
* @{
*/
void USART_DeInit(USART_TypeDef *USARTx);
void USART_Init(USART_TypeDef *USARTx, USART_InitPara *USART_InitParaStruct);
void USART_ParaInit(USART_InitPara *USART_InitParaStruct);
void USART_ClockInit(USART_TypeDef *USARTx, USART_ClockInitPara *USART_ClockInitStruct);
void USART_ClockStructInit(USART_ClockInitPara *USART_ClockInitParaStruct);
void USART_Enable(USART_TypeDef *USARTx, TypeState NewValue);
void USART_HalfDuplex_Enable(USART_TypeDef *USARTx, TypeState NewValue);
void USART_SetPrescaler(USART_TypeDef *USARTx, uint8_t USART_Prescaler);
void USART_DataSend(USART_TypeDef *USARTx, uint16_t Data);
uint16_t USART_DataReceive(USART_TypeDef *USARTx);
void USART_Address(USART_TypeDef *USARTx, uint8_t USART_Address);
void USART_MuteMode_Enable(USART_TypeDef *USARTx, TypeState NewState);
void USART_MuteModeWakeUp_Set(USART_TypeDef *USARTx, uint16_t USART_WakeUp);
void USART_SetLINBDLength(USART_TypeDef *USARTx, uint16_t USART_LINBreakDetectLength);
void USART_LIN_Enable(USART_TypeDef *USARTx, TypeState NewValue);
void USART_GuardTime_Set(USART_TypeDef *USARTx, uint8_t USART_GuardTime);
void USART_SmartCard_Enable(USART_TypeDef *USARTx, TypeState NewValue);
void USART_SmartCardNACK_Enable(USART_TypeDef *USARTx, TypeState NewValue);
void USART_IrDA_Set(USART_TypeDef *USARTx, uint16_t USART_IrDAMode);
void USART_IrDA_Enable(USART_TypeDef *USARTx, TypeState NewValue);
void USART_DMA_Enable(USART_TypeDef *USARTx, uint16_t USART_DMAEnable, TypeState NewValue);
void USART_INT_Set(USART_TypeDef *USARTx, uint16_t USART_INT, TypeState NewValue);
TypeState USART_GetBitState(USART_TypeDef *USARTx, uint16_t USART_FLAG);
void USART_ClearBitState(USART_TypeDef *USARTx, uint16_t USART_FLAG);
TypeState USART_GetIntBitState(USART_TypeDef *USARTx, uint16_t USART_INT);
void USART_ClearIntBitState(USART_TypeDef *USARTx, uint16_t USART_INT);
void USART_SendBreak(USART_TypeDef *USARTx);
#ifdef __cplusplus
}
#endif
#endif /*__GD32F10X_USART_H */
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/

View File

@ -0,0 +1,77 @@
/**
******************************************************************************
* @brief WWDG header file of the firmware library.
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __GD32F10X_WWDG_H
#define __GD32F10X_WWDG_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "gd32f10x.h"
/** @addtogroup GD32F10x_Firmware
* @{
*/
/** @defgroup WWDG
* @{
*/
/** @defgroup WWDG_Exported_Constants
* @{
*/
/** @defgroup WWDG_PRESCALER
* @{
*/
#define WWDG_PRESCALER_1 ((uint32_t)0x00000000)
#define WWDG_PRESCALER_2 ((uint32_t)0x00000080)
#define WWDG_PRESCALER_4 ((uint32_t)0x00000100)
#define WWDG_PRESCALER_8 ((uint32_t)0x00000180)
/**
* @}
*/
/**
* @}
*/
/* Exported functions ------------------------------------------------------- */
/** @defgroup WWDG_Exported_Functions
* @{
*/
void WWDG_DeInit(void);
void WWDG_SetPrescalerValue(uint32_t PrescalerValue);
void WWDG_SetWindowValue(uint8_t WindowValue);
void WWDG_EnableInt(void);
void WWDG_SetCounterValue(uint8_t CounterValue);
void WWDG_Enable(uint8_t CounterValue);
TypeState WWDG_GetBitState(void);
void WWDG_ClearBitState(void);
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif /* __GD32F10X_WWDG_H */
/**
* @}
*/
/**
* @}
*/

View File

@ -0,0 +1,977 @@
/**
******************************************************************************
* @brief ADC functions of the firmware library.
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "gd32f10x_adc.h"
#include "gd32f10x_rcc.h"
/** @addtogroup GD32F10x_Firmware
* @{
*/
/** @defgroup ADC
* @brief ADC driver modules
* @{
*/
/** @defgroup ADC_Private_Defines
* @{
*/
/* ADC CTLR1_DISNUM mask */
#define CTLR1_DISNUM_RESET ((uint32_t)0xFFFF1FFF)
/* ADC CTLR1_DISRC mask */
#define CTLR1_DISRC_SET ((uint32_t)0x00000800)
/* ADC CTLR1_ICA mask */
#define CTLR1_ICA_SET ((uint32_t)0x00000400)
/* ADC CTLR1_DISIC mask */
#define CTLR1_DISIC_SET ((uint32_t)0x00001000)
/* ADC CTLR1_AWCS mask */
#define CTLR1_AWCS_RESET ((uint32_t)0xFFFFFFE0)
/* ADC CTLR1_AWDMode mask */
#define CTLR1_AWDMODE_RESET ((uint32_t)0xFF3FFDFF)
/* CTLR1 register mask */
#define CTLR1_BITS_CLEAR ((uint32_t)0xFFF0FEFF)
/* ADC CTLR2_ADCON mask */
#define CTLR2_ADCON_SET ((uint32_t)0x00000001)
/* ADC CTLR2_DMA mask */
#define CTLR2_DMA_SET ((uint32_t)0x00000100)
/* ADC CTLR2_RSTCLB mask */
#define CTLR2_RSTCLB_SET ((uint32_t)0x00000008)
/* ADC CTLR2_CLB mask */
#define CTLR2_CLB_SET ((uint32_t)0x00000004)
/* ADC CTLR2_SWRCST mask */
#define CTLR2_SWRCST_SET ((uint32_t)0x00400000)
/* ADC CTLR2_ETERC mask */
#define CTLR2_ETERC_SET ((uint32_t)0x00100000)
/* ADC CTLR2_ETERC_SWRCST mask */
#define CTLR2_ETERC_SWRCST_SET ((uint32_t)0x00500000)
/* ADC CTLR2_ETSIC mask */
#define CTLR2_ETSIC_RESET ((uint32_t)0xFFFF8FFF)
/* ADC CTLR2_ETEIC mask */
#define CTLR2_ETEIC_SET ((uint32_t)0x00008000)
/* ADC CTLR2_SWICST mask */
#define CTLR2_SWICST_SET ((uint32_t)0x00200000)
/* ADC CTLR2_ETEIC_SWICST mask */
#define CTLR2_ETEIC_SWICST_SET ((uint32_t)0x00208000)
/* ADC CTLR2_TSVREN mask */
#define CTLR2_TSVREN_SET ((uint32_t)0x00800000)
/* CTLR2 register mask */
#define CTLR2_BITS_CLEAR ((uint32_t)0xFFF1F7FD)
/* ADC RSQx mask */
#define RSQ3_RSQ_SET ((uint32_t)0x0000001F)
#define RSQ2_RSQ_SET ((uint32_t)0x0000001F)
#define RSQ1_RSQ_SET ((uint32_t)0x0000001F)
/* RSQ1 register mask */
#define RSQ1_BITS_CLEAR ((uint32_t)0xFF0FFFFF)
/* ADC ISQx mask */
#define ISQ_ISQ_SET ((uint32_t)0x0000001F)
/* ADC IL mask */
#define ISQ_IL_SET ((uint32_t)0x00300000)
/* ADC SPTx mask */
#define SPT1_SPT_SET ((uint32_t)0x00000007)
#define SPT2_SPT_SET ((uint32_t)0x00000007)
/* ADC IDTRx registers offset */
#define IDTR_OFFSET ((uint8_t)0x28)
/* ADC0 RDTR register base address */
#define RDTR_ADDRESS ((uint32_t)0x4001244C)
/**
* @}
*/
/** @defgroup ADC_Private_Functions
* @{
*/
/**
* @brief Reset the ADC interface and init the sturct ADC_InitPara.
* @param ADCx: the ADC interface where x can be 1..3.
* @param ADC_InitParaStruct : the sturct ADC_InitPara pointer.
* @retval None
*/
void ADC_DeInit(ADC_TypeDef *ADCx, ADC_InitPara *ADC_InitParaStruct)
{
if (ADCx == ADC0) {
/* Enable ADC0 reset state */
RCC_APB2PeriphReset_Enable(RCC_APB2PERIPH_ADC0RST, ENABLE);
/* Release ADC0 from reset state */
RCC_APB2PeriphReset_Enable(RCC_APB2PERIPH_ADC0RST, DISABLE);
} else if (ADCx == ADC1) {
/* Enable ADC1 reset state */
RCC_APB2PeriphReset_Enable(RCC_APB2PERIPH_ADC1RST, ENABLE);
/* Release ADC1 from reset state */
RCC_APB2PeriphReset_Enable(RCC_APB2PERIPH_ADC1RST, DISABLE);
}
/* Initialize the ADC_Mode member,independent mode */
ADC_InitParaStruct->ADC_Mode = ADC_MODE_INDEPENDENT;
/* Initialize the ADC_Mode_Scan member,disable scan mode */
ADC_InitParaStruct->ADC_Mode_Scan = DISABLE;
/* Initialize the ADC_Mode_Continuous member,disable continuous mode */
ADC_InitParaStruct->ADC_Mode_Continuous = DISABLE;
/* Initialize the ADC_Trig_External member,choose T1 CC1 as external trigger */
ADC_InitParaStruct->ADC_Trig_External = ADC_EXTERNAL_TRIGGER_MODE_T1_CC1;
/* Initialize the ADC_Data_Align member,specifies the ADC data alignment right */
ADC_InitParaStruct->ADC_Data_Align = ADC_DATAALIGN_RIGHT;
/* Initialize the ADC_Channel_Number member,only 1 channel */
ADC_InitParaStruct->ADC_Channel_Number = 1;
}
/**
* @brief Initialize the ADCx interface parameters.
* @param ADCx: the ADC interface where x can be 1..3.
* @param ADC_InitParaStruct: the sturct ADC_InitPara pointer.
* @retval None
*/
void ADC_Init(ADC_TypeDef *ADCx, ADC_InitPara *ADC_InitParaStruct)
{
uint32_t temp1 = 0;
uint8_t temp2 = 0;
/* ADCx CTLR1 Configuration */
/* Get the ADCx CTLR1 previous value */
temp1 = ADCx->CTLR1;
/* Clear SM bits */
temp1 &= CTLR1_BITS_CLEAR;
/* Configure ADCx: Dual mode and scan conversion mode */
/* Set DUALMOD bits according to ADC_Mode value */
/* Configure SCAN bit according to ADC_Mode_Scan value */
temp1 |= (uint32_t)(ADC_InitParaStruct->ADC_Mode | ((uint32_t)ADC_InitParaStruct->ADC_Mode_Scan << 8));
/* Write new value to ADCx CTLR1 */
ADCx->CTLR1 = temp1;
/* ADCx CTLR2 Configuration */
/* Get the ADCx CTLR2 previous value */
temp1 = ADCx->CTLR2;
/* Clear CTN, DAL and ETSRC bits */
temp1 &= CTLR2_BITS_CLEAR;
/* Configure ADCx: select external trigger mode and continuous conversion mode */
/* Configure DAL bit according to ADC_Data_Align value */
/* Configure ETSRC bits according to ADC_Trig_External value */
/* Configure CTN bit according to ADC_Mode_Continuous value */
temp1 |= (uint32_t)(ADC_InitParaStruct->ADC_Data_Align | ADC_InitParaStruct->ADC_Trig_External |
((uint32_t)ADC_InitParaStruct->ADC_Mode_Continuous << 1));
/* Write new value to ADCx CTLR2 */
ADCx->CTLR2 = temp1;
/* ADCx RSQ1 Configuration */
/* Get the ADCx RSQ1 previous value */
temp1 = ADCx->RSQ1;
/* Clear RL bits */
temp1 &= RSQ1_BITS_CLEAR;
/* Configure ADCx: regular channel sequence length */
/* Configure RL bits according to ADC_Channel_Number value */
temp2 |= (uint8_t)(ADC_InitParaStruct->ADC_Channel_Number - (uint8_t)1);
temp1 |= (uint32_t)temp2 << 20;
/* Write new value to ADCx RSQ1 */
ADCx->RSQ1 = temp1;
}
/**
* @brief Enable or disable the ADCx interface.
* @param ADCx: the ADC interface where x can be 1..3.
* @param NewValue: New state of the ADCx interface.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void ADC_Enable(ADC_TypeDef *ADCx, TypeState NewValue)
{
if (NewValue != DISABLE) {
/* Enable the ADCx interface */
ADCx->CTLR2 |= CTLR2_ADCON_SET;
} else {
/* Disable the ADCx interface */
ADCx->CTLR2 &= ~CTLR2_ADCON_SET;
}
}
/**
* @brief Enable or disable the ADCx DMA request.
* @param ADCx: the ADC interface where x can be 1..3.
* Note: ADC1 doesn't support DMA function.
* @param NewValue: New state of ADCx DMA transfer.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void ADC_DMA_Enable(ADC_TypeDef *ADCx, TypeState NewValue)
{
if (NewValue != DISABLE) {
/* Enable ADCx DMA request */
ADCx->CTLR2 |= CTLR2_DMA_SET;
} else {
/* Disable ADCx DMA request */
ADCx->CTLR2 &= ~CTLR2_DMA_SET;
}
}
/**
* @brief Enable or disable ADCx interrupts.
* @param ADCx: the ADC interface where x can be 1..3.
* @param ADC_INT: ADCx interrupt sources.
* This parameter can be any combination of the following values:
* @arg ADC_INT_EOC: Regular conversion over interrupt mask
* @arg ADC_INT_AWE: Analog watchdog interrupt mask
* @arg ADC_INT_EOIC: Inserted conversion over interrupt mask
* @param NewValue: ADCx interrupts state.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void ADC_INTConfig(ADC_TypeDef *ADCx, uint16_t ADC_INT, TypeState NewValue)
{
uint8_t temp_it = 0;
/* ADCx INT old state */
temp_it = (uint8_t)ADC_INT;
if (NewValue != DISABLE) {
/* Enable the ADCx interrupt */
ADCx->CTLR1 |= temp_it;
} else {
/* Disable the ADCx interrupt */
ADCx->CTLR1 &= (~(uint32_t)temp_it);
}
}
/**
* @brief ADCx calibration.
* @param ADCx: the ADC interface where x can be 1..3.
* @retval None
*/
void ADC_Calibration(ADC_TypeDef *ADCx)
{
/* Reset the selected ADCx calibration registers */
ADCx->CTLR2 |= CTLR2_RSTCLB_SET;
/* Check the RSTCLB bit state */
while ((ADCx->CTLR2 & CTLR2_RSTCLB_SET));
/* Enable ADCx calibration process */
ADCx->CTLR2 |= CTLR2_CLB_SET;
/* Check the CLB bit state */
while ((ADCx->CTLR2 & CTLR2_CLB_SET) != (uint32_t)RESET);
}
/**
* @brief Enable or disable ADCx software start conversion.
* @param ADCx: the ADC interface where x can be 1..3.
* @param NewValue: ADCx software start conversion state.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void ADC_SoftwareStartConv_Enable(ADC_TypeDef *ADCx, TypeState NewValue)
{
if (NewValue != DISABLE) {
/* ADCx software conversion start */
ADCx->CTLR2 |= CTLR2_ETERC_SWRCST_SET;
} else {
/* ADCx software conversion stop */
ADCx->CTLR2 &= ~CTLR2_ETERC_SWRCST_SET;
}
}
/**
* @brief Get the bit state of ADCx software start conversion.
* @param ADCx: the ADC interface where x can be 1..3.
* @retval ADCx software start conversion state(SET or RESET).
*/
TypeState ADC_GetSoftwareStartConvBitState(ADC_TypeDef *ADCx)
{
/* Check the SWRCST bit state*/
if ((ADCx->CTLR2 & CTLR2_SWRCST_SET) != (uint32_t)RESET) {
return SET;
} else {
return RESET;
}
}
/**
* @brief Configure the ADCx channel discontinuous mode.
* @param ADCx: the ADC interface where x can be 1..3.
* @param Number: the count value of discontinuous mode regular channel.
* This number must be 1~8.
* @retval None
*/
void ADC_DiscModeChannelCount_Config(ADC_TypeDef *ADCx, uint8_t Number)
{
uint32_t temp1 = 0;
uint32_t temp2 = 0;
/* Get the old value of CTLR1 */
temp1 = ADCx->CTLR1;
/* Clear discontinuous mode channel count */
temp1 &= CTLR1_DISNUM_RESET;
/* Set the discontinuous mode channel count */
temp2 = Number - 1;
temp1 |= temp2 << 13;
/* Write new value to CTLR1 */
ADCx->CTLR1 = temp1;
}
/**
* @brief Enable or disable the discontinuous mode.
* @param ADCx: the ADC interface where x can be 1..3.
* @param NewValue: ADCx discontinuous mode state.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void ADC_DiscMode_Enable(ADC_TypeDef *ADCx, TypeState NewValue)
{
if (NewValue != DISABLE) {
/* Enable ADCx regular discontinuous mode */
ADCx->CTLR1 |= CTLR1_DISRC_SET;
} else {
/* Disable ADCx regular discontinuous mode */
ADCx->CTLR1 &= ~CTLR1_DISRC_SET;
}
}
/**
* @brief Configure array and sample time.
* @param ADCx: the ADC interface where x can be 1..3.
* @param ADC_Channel: the selected ADC channel.
* This parameter can be as follows:
* @arg ADC_CHANNEL_0: ADC Channel0
* @arg ADC_CHANNEL_1: ADC Channel1
* @arg ADC_CHANNEL_2: ADC Channel2
* @arg ADC_CHANNEL_3: ADC Channel3
* @arg ADC_CHANNEL_4: ADC Channel4
* @arg ADC_CHANNEL_5: ADC Channel5
* @arg ADC_CHANNEL_6: ADC Channel6
* @arg ADC_CHANNEL_7: ADC Channel7
* @arg ADC_CHANNEL_8: ADC Channel8
* @arg ADC_CHANNEL_9: ADC Channel9
* @arg ADC_CHANNEL_10: ADC Channel10
* @arg ADC_CHANNEL_11: ADC Channel11
* @arg ADC_CHANNEL_12: ADC Channel12
* @arg ADC_CHANNEL_13: ADC Channel13
* @arg ADC_CHANNEL_14: ADC Channel14
* @arg ADC_CHANNEL_15: ADC Channel15
* @arg ADC_CHANNEL_16: ADC Channel16
* @arg ADC_CHANNEL_17: ADC Channel17
* @param Array: The regular group sequencer rank. This parameter must be between 1 to 16.
* @param ADC_SampleTime: The sample time value.
* This parameter can be one of the following values:
* @arg ADC_SAMPLETIME_1POINT5: 1.5 cycles
* @arg ADC_SAMPLETIME_7POINT5: 7.5 cycles
* @arg ADC_SAMPLETIME_13POINT5: 13.5 cycles
* @arg ADC_SAMPLETIME_28POINT5: 28.5 cycles
* @arg ADC_SAMPLETIME_41POINT5: 41.5 cycles
* @arg ADC_SAMPLETIME_55POINT5: 55.5 cycles
* @arg ADC_SAMPLETIME_71POINT5: 71.5 cycles
* @arg ADC_SAMPLETIME_239POINT5: 239.5 cycles
* @retval None
*/
void ADC_RegularChannel_Config(ADC_TypeDef *ADCx, uint8_t ADC_Channel, uint8_t Array, uint8_t ADC_SampleTime)
{
uint32_t temp1 = 0, temp2 = 0;
/* if ADC_Channel is between 10 to 17 */
if (ADC_Channel > ADC_CHANNEL_9) {
/* Get SPT1 value */
temp1 = ADCx->SPT1;
/* Calculate the mask to clear */
temp2 = SPT1_SPT_SET << (3 * (ADC_Channel - 10));
/* Clear sample time */
temp1 &= ~temp2;
/* Calculate the mask to set */
temp2 = (uint32_t)ADC_SampleTime << (3 * (ADC_Channel - 10));
/* Configure sample time */
temp1 |= temp2;
/* Write to SPT1 */
ADCx->SPT1 = temp1;
} else { /* ADC_Channel is between 0 to 9 */
/* Get SPT2 value */
temp1 = ADCx->SPT2;
/* Calculate the mask to clear */
temp2 = SPT2_SPT_SET << (3 * ADC_Channel);
/* Clear sample time */
temp1 &= ~temp2;
/* Calculate the mask to set */
temp2 = (uint32_t)ADC_SampleTime << (3 * ADC_Channel);
/* Set sample time */
temp1 |= temp2;
/* Write to SPT2 */
ADCx->SPT2 = temp1;
}
/* For Array 1 to 6 */
if (Array < 7) {
/* Get RSQ3 value */
temp1 = ADCx->RSQ3;
/* Calculate the mask to clear */
temp2 = RSQ3_RSQ_SET << (5 * (Array - 1));
/* Clear RSQ3 bits */
temp1 &= ~temp2;
/* Calculate the mask to set */
temp2 = (uint32_t)ADC_Channel << (5 * (Array - 1));
/* Configure the RSQ3 bits */
temp1 |= temp2;
/* Write to RSQ3 */
ADCx->RSQ3 = temp1;
}
/* For Array 7 to 12 */
else if (Array < 13) {
/* Get RSQ2 value */
temp1 = ADCx->RSQ2;
/* Calculate the mask to clear */
temp2 = RSQ2_RSQ_SET << (5 * (Array - 7));
/* Clear the old RSQ2 bits */
temp1 &= ~temp2;
/* Calculate the mask to set */
temp2 = (uint32_t)ADC_Channel << (5 * (Array - 7));
/* Set the RSQ2 bits */
temp1 |= temp2;
/* Write to RSQ2 */
ADCx->RSQ2 = temp1;
}
/* For Array 13 to 16 */
else {
/* Get RSQ1 value */
temp1 = ADCx->RSQ1;
/* Calculate the mask to clear */
temp2 = RSQ1_RSQ_SET << (5 * (Array - 13));
/* Clear the old RSQ1 bits */
temp1 &= ~temp2;
/* Calculate the mask to set */
temp2 = (uint32_t)ADC_Channel << (5 * (Array - 13));
/* Set the RSQ1 bits */
temp1 |= temp2;
/* Write to RSQ1 */
ADCx->RSQ1 = temp1;
}
}
/**
* @brief Enable or disable the ADCx external conversion.
* @param ADCx: the ADC interface where x can be 1..3.
* @param NewValue: ADCx external trigger state.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void ADC_ExternalTrigConv_Enable(ADC_TypeDef *ADCx, TypeState NewValue)
{
if (NewValue != DISABLE) {
/* Enable external trigger conversion */
ADCx->CTLR2 |= CTLR2_ETERC_SET;
} else {
/* Disable external trigger conversion */
ADCx->CTLR2 &= ~CTLR2_ETERC_SET;
}
}
/**
* @brief Return the ADCx regular channel conversion data.
* @param ADCx: the ADC interface where x can be 1..3.
* @retval conversion data.
*/
uint16_t ADC_GetConversionValue(ADC_TypeDef *ADCx)
{
/* Return ADCx conversion data */
return (uint16_t) ADCx->RDTR;
}
/**
* @brief Return the last ADC0 and ADC1 conversion result data in dual mode.
* @retval The Data conversion value.
*/
uint32_t ADC_GetDualModeConversionValue(void)
{
/* Return conversion value */
return (*(__IO uint32_t *) RDTR_ADDRESS);
}
/**
* @brief Enable or disable ADCx automatic inserted conversion.
* @param ADCx: the ADC interface where x can be 1..3.
* @param NewValue: ADCx auto inserted conversion state.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void ADC_AutoInsertedConv_Enable(ADC_TypeDef *ADCx, TypeState NewValue)
{
if (NewValue != DISABLE) {
/* Enable ADCx automatic inserted conversion */
ADCx->CTLR1 |= CTLR1_ICA_SET;
} else {
/* Disable ADCx automatic inserted conversion */
ADCx->CTLR1 &= ~CTLR1_ICA_SET;
}
}
/**
* @brief Enable or disable the discontinuous mode for ADCx inserted group channel.
* @param ADCx: the ADC interface where x can be 1..3.
* @param NewValue: ADCx discontinuous mode state.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void ADC_InsertedDiscMode_Enable(ADC_TypeDef *ADCx, TypeState NewValue)
{
if (NewValue != DISABLE) {
/* Enable the inserted discontinuous mode of the selected ADC channel */
ADCx->CTLR1 |= CTLR1_DISIC_SET;
} else {
/* Disable the inserted discontinuous mode of the selected ADC channel */
ADCx->CTLR1 &= ~CTLR1_DISIC_SET;
}
}
/**
* @brief Configure the ADCx inserted channels external trigger conversion.
* @param ADCx: the ADC interface where x can be 1..3.
* @param ADC_ExternalTrigInsertConv: ADC inserted conversion trigger.
* This parameter can be as follows:
* @arg ADC_EXTERNAL_TRIG_INSERTCONV_T1_TRGO: Timer1 TRIG event (used in ADC0, ADC1 and ADC2)
* @arg ADC_EXTERNAL_TRIG_INSERTCONV_T1_CC4: Timer1 capture compare4 (used in ADC0, ADC1 and ADC2)
* @arg ADC_EXTERNAL_TRIG_INSERTCONV_T2_TRGO: Timer2 TRIG event (used in ADC0 and ADC1)
* @arg ADC_EXTERNAL_TRIG_INSERTCONV_T2_CC1: Timer2 capture compare1 (used in ADC0 and ADC1)
* @arg ADC_EXTERNAL_TRIG_INSERTCONV_T3_CC4: Timer3 capture compare4 (used in ADC0 and ADC1)
* @arg ADC_EXTERNAL_TRIG_INSERTCONV_T4_TRGO: Timer4 TRIG event (used in ADC0 and ADC1)
* @arg ADC_EXTERNAL_TRIG_INSERTCONV_EXT_IT15_T8_CC4: External interrupt line 15 or Timer8
* capture compare4 (used in ADC0 and ADC1)
* @arg ADC_EXTERNAL_TRIG_INSERTCONV_T4_CC3: Timer4 capture compare3 (used in ADC2)
* @arg ADC_EXTERNAL_TRIG_INSERTCONV_T8_CC2: Timer8 capture compare2 (used in ADC2)
* @arg ADC_EXTERNAL_TRIG_INSERTCONV_T8_CC4: Timer8 capture compare4 (used in ADC2)
* @arg ADC_EXTERNAL_TRIG_INSERTCONV_T5_TRGO: Timer5 TRIG event (used in ADC2)
* @arg ADC_EXTERNAL_TRIG_INSERTCONV_T5_CC4: Timer5 capture compare4 (used in ADC2)
* @arg ADC_EXTERNAL_TRIG_INSERTCONV_NONE: Inserted conversion started by software (used in ADC0, ADC1 and ADC2)
* @retval None
*/
void ADC_ExternalTrigInsertedConv_Config(ADC_TypeDef *ADCx, uint32_t ADC_ExternalTrigInsertConv)
{
uint32_t temp = 0;
/* Get CRLR2 value */
temp = ADCx->CTLR2;
/* Clear inserted external event */
temp &= CTLR2_ETSIC_RESET;
/* Configure inserted external event */
temp |= ADC_ExternalTrigInsertConv;
/* Write to CTLR2 */
ADCx->CTLR2 = temp;
}
/**
* @brief Enable or disable the ADCx inserted channels conversion through
* external trigger
* @param ADCx: the ADC interface where x can be 1..3.
* @param NewValue: ADCx external trigger start of inserted conversion state.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void ADC_ExternalTrigInsertedConv_Enable(ADC_TypeDef *ADCx, TypeState NewValue)
{
if (NewValue != DISABLE) {
/* Enable external event */
ADCx->CTLR2 |= CTLR2_ETEIC_SET;
} else {
/* Disable external event */
ADCx->CTLR2 &= ~CTLR2_ETEIC_SET;
}
}
/**
* @brief Enable or disable ADCx inserted channels conversion start.
* @param ADCx: the ADC interface where x can be 1..3.
* @param NewValue: ADC software start inserted conversion state.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void ADC_SoftwareStartInsertedConv_Enable(ADC_TypeDef *ADCx, TypeState NewValue)
{
if (NewValue != DISABLE) {
/* Start ADCx inserted conversion */
ADCx->CTLR2 |= CTLR2_ETEIC_SWICST_SET;
} else {
/* Stop ADCx inserted conversion */
ADCx->CTLR2 &= ~CTLR2_ETEIC_SWICST_SET;
}
}
/**
* @brief Get ADC Software start inserted conversion State.
* @param ADCx: the ADC interface where x can be 1..3.
* @retval ADC software start inserted conversion state(SET or RESET).
*/
TypeState ADC_GetSoftwareStartInsertedConvCmdBitState(ADC_TypeDef *ADCx)
{
/* Check SWICST bit */
if ((ADCx->CTLR2 & CTLR2_SWICST_SET) != (uint32_t)RESET) {
/* Set SWICST bit */
return SET;
} else {
/* Reset SWICST bit */
return RESET;
}
}
/**
* @brief Configure Array and sample time for the selected ADC inserted channel.
* @param ADCx: the ADC interface where x can be 1..3.
* @param ADC_Channel: the selected ADC channel.
* This parameter can be as follows:
* @arg ADC_CHANNEL_0: ADC Channel0
* @arg ADC_CHANNEL_1: ADC Channel1
* @arg ADC_CHANNEL_2: ADC Channel2
* @arg ADC_CHANNEL_3: ADC Channel3
* @arg ADC_CHANNEL_4: ADC Channel4
* @arg ADC_CHANNEL_5: ADC Channel5
* @arg ADC_CHANNEL_6: ADC Channel6
* @arg ADC_CHANNEL_7: ADC Channel7
* @arg ADC_CHANNEL_8: ADC Channel8
* @arg ADC_CHANNEL_9: ADC Channel9
* @arg ADC_CHANNEL_10: ADC Channel10
* @arg ADC_CHANNEL_11: ADC Channel11
* @arg ADC_CHANNEL_12: ADC Channel12
* @arg ADC_CHANNEL_13: ADC Channel13
* @arg ADC_CHANNEL_14: ADC Channel14
* @arg ADC_CHANNEL_15: ADC Channel15
* @arg ADC_CHANNEL_16: ADC Channel16
* @arg ADC_CHANNEL_17: ADC Channel17
* @param Array: The inserted group sequencer Array. This parameter must be between 1 and 4.
* @param ADC_SampleTime: The sample time of the selected channel.
* This parameter can be as follows:
* @arg ADC_SAMPLETIME_1POINT5: 1.5 cycles
* @arg ADC_SAMPLETIME_7POINT5: 7.5 cycles
* @arg ADC_SAMPLETIME_13POINT5: 13.5 cycles
* @arg ADC_SAMPLETIME_28POINT5: 28.5 cycles
* @arg ADC_SAMPLETIME_41POINT5: 41.5 cycles
* @arg ADC_SAMPLETIME_55POINT5: 55.5 cycles
* @arg ADC_SAMPLETIME_71POINT5: 71.5 cycles
* @arg ADC_SAMPLETIME_239POINT5: 239.5 cycles
* @retval None
*/
void ADC_InsertedChannel_Config(ADC_TypeDef *ADCx, uint8_t ADC_Channel, uint8_t Array, uint8_t ADC_SampleTime)
{
uint32_t temp1 = 0, temp2 = 0, temp3 = 0;
/* if ADC_Channel is between 10 to 17 */
if (ADC_Channel > ADC_CHANNEL_9) {
/* Get SPT1 value */
temp1 = ADCx->SPT1;
/* Calculate the sample time mask */
temp2 = SPT1_SPT_SET << (3 * (ADC_Channel - 10));
/* Clear sample time */
temp1 &= ~temp2;
/* Calculate the sample time mask */
temp2 = (uint32_t)ADC_SampleTime << (3 * (ADC_Channel - 10));
/* Set sample time */
temp1 |= temp2;
/* Write to SPT1 */
ADCx->SPT1 = temp1;
} else { /* ADC_Channel is between 0 to 9 */
/* Get SPT2 value */
temp1 = ADCx->SPT2;
/* Calculate the sample time mask */
temp2 = SPT2_SPT_SET << (3 * ADC_Channel);
/* Clear sample time */
temp1 &= ~temp2;
/* Calculate the sample time mask */
temp2 = (uint32_t)ADC_SampleTime << (3 * ADC_Channel);
/* Set sample time */
temp1 |= temp2;
/* Write to SPT2 */
ADCx->SPT2 = temp1;
}
/* Array configuration */
/* Get ISQ value */
temp1 = ADCx->ISQ;
/* Get IL value: Number = IL+1 */
temp3 = (temp1 & ISQ_IL_SET) >> 20;
/* Calculate the ISQ mask : ((Array-1)+(4-IL-1)) */
temp2 = ISQ_ISQ_SET << (5 * (uint8_t)((Array + 3) - (temp3 + 1)));
/* Clear ISQx bits */
temp1 &= ~temp2;
/* Calculate the ISQ mask: ((Array-1)+(4-IL-1)) */
temp2 = (uint32_t)ADC_Channel << (5 * (uint8_t)((Array + 3) - (temp3 + 1)));
/* Set ISQx bits */
temp1 |= temp2;
/* Write to ISQ */
ADCx->ISQ = temp1;
}
/**
* @brief Configure the sequencer length of inserted channels
* @param ADCx: the ADC interface where x can be 1..3.
* @param Length: The sequencer length.
* This parameter must be a number between 1 to 4.
* @retval None
*/
void ADC_InsertedSequencerLength_Config(ADC_TypeDef *ADCx, uint8_t Length)
{
uint32_t temp1 = 0;
uint32_t temp2 = 0;
/* Get ISQ value */
temp1 = ADCx->ISQ;
/* Clear IL bits */
temp1 &= ~ISQ_IL_SET;
/* Set IL bits */
temp2 = Length - 1;
temp1 |= temp2 << 20;
/* Write to ISQ */
ADCx->ISQ = temp1;
}
/**
* @brief Set the offset of the inserted channels conversion value.
* @param ADCx: the ADC interface where x can be 1..3.
* @param ADC_InsertedChannel: one of the four inserted channels to set its offset.
* This parameter can be one of the following values:
* @arg ADC_INSERTEDCHANNEL_1: Inserted Channel1
* @arg ADC_INSERTEDCHANNEL_2: Inserted Channel2
* @arg ADC_INSERTEDCHANNEL_3: Inserted Channel3
* @arg ADC_INSERTEDCHANNEL_4: Inserted Channel4
* @param Offset: the offset value of the selected ADC inserted channel
* This parameter must be a 12bit value.
* @retval None
*/
void ADC_SetInsertedOffset(ADC_TypeDef *ADCx, uint8_t ADC_InsertedChannel, uint16_t Offset)
{
__IO uint32_t temp = 0;
temp = (uint32_t)ADCx;
temp += ADC_InsertedChannel;
/* Set the offset of the selected inserted channel */
*(__IO uint32_t *) temp = (uint32_t)Offset;
}
/**
* @brief Get the ADC inserted channel conversion result
* @param ADCx: the ADC interface where x can be 1..3.
* @param ADC_InsertedChannel: ADC inserted channel.
* This parameter can be one of the following values:
* @arg ADC_INSERTEDCHANNEL_1: Inserted Channel1
* @arg ADC_INSERTEDCHANNEL_2: Inserted Channel2
* @arg ADC_INSERTEDCHANNEL_3: Inserted Channel3
* @arg ADC_INSERTEDCHANNEL_4: Inserted Channel4
* @retval The conversion value.
*/
uint16_t ADC_GetInsertedConversionValue(ADC_TypeDef *ADCx, uint8_t ADC_InsertedChannel)
{
__IO uint32_t temp = 0;
temp = (uint32_t)ADCx;
temp += ADC_InsertedChannel + IDTR_OFFSET;
/* Return the result of the selected inserted channel conversion */
return (uint16_t)(*(__IO uint32_t *) temp);
}
/**
* @brief Enable or disable the analog watchdog.
* @param ADCx: the ADC interface where x can be 1..3.
* @param ADC_AnalogWatchdog: the ADC analog watchdog configuration.
* This parameter can be one of the following values:
* @arg ADC_ANALOGWATCHDOG_SINGLEREGENABLE: single regular channel
* @arg ADC_ANALOGWATCHDOG_SINGLEINSERTENABLE: single inserted channel
* @arg ADC_ANALOGWATCHDOG_SINGLEREGORINSERTENABLE: single regular or inserted channel
* @arg ADC_ANALOGWATCHDOG_ALLREGENABLE: all regular channel
* @arg ADC_ANALOGWATCHDOG_ALLINSERTENABLE: all inserted channel
* @arg ADC_ANALOGWATCHDOG_ALLREGALLINSERTENABLE: all regular and inserted channels
* @arg ADC_ANALOGWATCHDOG_NONE: No channel
* @retval None
*/
void ADC_AnalogWatchdog_Enable(ADC_TypeDef *ADCx, uint32_t ADC_AnalogWatchdog)
{
uint32_t temp = 0;
/* Get CTLR1 value */
temp = ADCx->CTLR1;
/* Clear AWDEN, AWDENJ and AWDSGL bits */
temp &= CTLR1_AWDMODE_RESET;
/* Set the analog watchdog mode */
temp |= ADC_AnalogWatchdog;
/* Write to CTLR1 */
ADCx->CTLR1 = temp;
}
/**
* @brief Configure the high and low thresholds of the analog watchdog.
* @param ADCx: the ADC interface where x can be 1..3.
* @param HighThreshold: the ADC analog watchdog High threshold value.
* This parameter must be a 12bit value.
* @param LowThreshold: the ADC analog watchdog Low threshold value.
* This parameter must be a 12bit value.
* @retval None
*/
void ADC_AnalogWatchdogThresholds_Config(ADC_TypeDef *ADCx, uint16_t HighThreshold,
uint16_t LowThreshold)
{
/* Set the ADCx high threshold */
ADCx->AWHT = HighThreshold;
/* Set the ADCx low threshold */
ADCx->AWLT = LowThreshold;
}
/**
* @brief Configure the analog watchdog on single channel mode.
* @param ADCx: the ADC interface where x can be 1..3.
* @param ADC_Channel: ADC channel.
* This parameter can be as follows:
* @arg ADC_CHANNEL_0: ADC Channel0
* @arg ADC_CHANNEL_1: ADC Channel1
* @arg ADC_CHANNEL_2: ADC Channel2
* @arg ADC_CHANNEL_3: ADC Channel3
* @arg ADC_CHANNEL_4: ADC Channel4
* @arg ADC_CHANNEL_5: ADC Channel5
* @arg ADC_CHANNEL_6: ADC Channel6
* @arg ADC_CHANNEL_7: ADC Channel7
* @arg ADC_CHANNEL_8: ADC Channel8
* @arg ADC_CHANNEL_9: ADC Channel9
* @arg ADC_CHANNEL_10: ADC Channel10
* @arg ADC_CHANNEL_11: ADC Channel11
* @arg ADC_CHANNEL_12: ADC Channel12
* @arg ADC_CHANNEL_13: ADC Channel13
* @arg ADC_CHANNEL_14: ADC Channel14
* @arg ADC_CHANNEL_15: ADC Channel15
* @arg ADC_CHANNEL_16: ADC Channel16
* @arg ADC_CHANNEL_17: ADC Channel17
* @retval None
*/
void ADC_AnalogWatchdogSingleChannel_Config(ADC_TypeDef *ADCx, uint8_t ADC_Channel)
{
uint32_t temp = 0;
/* Get CTLR1 value */
temp = ADCx->CTLR1;
/* Clear AWCS */
temp &= CTLR1_AWCS_RESET;
/* Set the Analog watchdog channel */
temp |= ADC_Channel;
/* Write to CTLR1 */
ADCx->CTLR1 = temp;
}
/**
* @brief Enable or disable the temperature sensor and Vrefint channel.
* @param NewValue: the state of the temperature sensor.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void ADC_TempSensorVrefint_Enable(TypeState NewValue)
{
if (NewValue != DISABLE) {
/* Enable the temperature sensor and Vrefint channel*/
ADC0->CTLR2 |= CTLR2_TSVREN_SET;
} else {
/* Disable the temperature sensor and Vrefint channel*/
ADC0->CTLR2 &= ~CTLR2_TSVREN_SET;
}
}
/**
* @brief Check the ADC flag.
* @param ADCx: the ADC interface where x can be 1..3.
* @param ADC_FLAG: the flag to check.
* This parameter can be as follows:
* @arg ADC_FLAG_AWE: The flag of the analog watchdog
* @arg ADC_FLAG_EOC: The flag of the end of conversion
* @arg ADC_FLAG_EOIC: The flag of the end of inserted group conversion
* @arg ADC_FLAG_STIC: The flag of the start of inserted group conversion
* @arg ADC_FLAG_STRC: The flag of the start of regular group conversion
* @retval ADC_FLAG state(SET or RESET).
*/
TypeState ADC_GetBitState(ADC_TypeDef *ADCx, uint8_t ADC_FLAG)
{
/* Check the specified ADC flag state */
if ((ADCx->STR & ADC_FLAG) != (uint8_t)RESET) {
/* ADC_FLAG is set */
return SET;
} else {
/* ADC_FLAG is reset */
return RESET;
}
}
/**
* @brief Clear the ADCx's pending flags.
* @param ADCx: the ADC interface where x can be 1..3.
* @param ADC_FLAG: the flag to clear.
* This parameter can be any combination of the following values:
* @arg ADC_FLAG_AWE: The flag of the analog watchdog
* @arg ADC_FLAG_EOC: The flag of the end of conversion
* @arg ADC_FLAG_EOIC: The flag of the end of inserted group conversion
* @arg ADC_FLAG_STIC: The flag of the start of inserted group conversion
* @arg ADC_FLAG_STRC: The flag of the start of regular group conversion
* @retval None
*/
void ADC_ClearBitState(ADC_TypeDef *ADCx, uint8_t ADC_FLAG)
{
/* Clear the selected ADC flags */
ADCx->STR = ~(uint32_t)ADC_FLAG;
}
/**
* @brief Check the specified ADC interrupt.
* @param ADCx: the ADC interface where x can be 1..3.
* @param ADC_INT: ADC interrupt source.
* This parameter can be one of the following values:
* @arg ADC_INT_EOC: The interrupt mask of the end of conversion
* @arg ADC_INT_AWE: The interrupt mask of the analog watchdog
* @arg ADC_INT_EOIC: The interrupt mask of the end of inserted conversion
* @retval The new value of ADC_INT (SET or RESET).
*/
TypeState ADC_GetIntState(ADC_TypeDef *ADCx, uint16_t ADC_INT)
{
uint32_t temp_it = 0, temp_enable = 0;
/* Get the ADC interrupt mask index */
temp_it = ADC_INT >> 8;
/* Get the ADC_INT enable bit state */
temp_enable = (ADCx->CTLR1 & (uint8_t)ADC_INT) ;
/* Check the state of the specified ADC interrupt */
if (((ADCx->STR & temp_it) != (uint32_t)RESET) && temp_enable) {
/* ADC_INT is set */
return SET;
} else {
/* ADC_INT is reset */
return RESET;
}
}
/**
* @brief Clear the ADCx's interrupt pending bits.
* @param ADCx: the ADC interface where x can be 1..3.
* @param ADC_INT: the ADC interrupt pending bit.
* This parameter can be any combination of the following values:
* @arg ADC_INT_EOC: The interrupt mask of the end of conversion
* @arg ADC_INT_AWE: The interrupt mask of the analog watchdog
* @arg ADC_INT_EOIC: The interrupt mask of the end of inserted conversion
* @retval None
*/
void ADC_ClearIntBitState(ADC_TypeDef *ADCx, uint16_t ADC_INT)
{
uint8_t temp_it = 0;
/* Get the ADC interrupt mask index */
temp_it = (uint8_t)(ADC_INT >> 8);
/* Clear ADCx interrupt pending bits */
ADCx->STR = ~(uint32_t)temp_it;
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/

View File

@ -0,0 +1,250 @@
/**
******************************************************************************
* @brief BKP functions of the firmware library.
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "gd32f10x_bkp.h"
#include "gd32f10x_rcc.h"
/** @addtogroup GD32F10x_Firmware
* @{
*/
/** @defgroup BKP
* @brief BKP driver modules
* @{
*/
/** @defgroup BKP_Private_Defines
* @{
*/
/* RTCOUTPUT bit is masked in BKP_RCCR register */
#define RTCOUTPUT_MASK ((uint16_t)0xFC7F)
/**
* @}
*/
/** @defgroup BKP_Private_Functions
* @{
*/
/**
* @brief Reset the BKP peripheral registers.
* @param None
* @retval None
*/
void BKP_DeInit(void)
{
RCC_BackupReset_Enable(ENABLE);
RCC_BackupReset_Enable(DISABLE);
}
/**
* @brief Write user data to the BKP_DRx register.
* @param BKP_DR: the Backup Data Register.
* This parameter can be BKP_DRx where x can be (1..42)
* @param Data: data to write
* @retval None
*/
void BKP_WriteBackupRegister(uint16_t BKP_DR, uint16_t Data)
{
__IO uint32_t temp = 0;
temp = (uint32_t)BKP_BASE;
temp += BKP_DR;
/* Store the write data */
*(__IO uint16_t *) temp = Data;
}
/**
* @brief Read data from the BKP_DRx register.
* @param BKP_DR: The Backup Data Register.
* This parameter can be BKP_DRx where x can be (1..42)
* @retval The content of the BKP_DRx register.
*/
uint16_t BKP_ReadBackupRegister(uint16_t BKP_DR)
{
__IO uint32_t temp = 0;
temp = (uint32_t)BKP_BASE;
temp += BKP_DR;
/* Return the BKP_DRx register value */
return (*(__IO uint16_t *) temp);
}
/**
* @brief Configure the RTC output on the Tamper pin.
* @param BKP_RTCOUTPUT: the RTC output.
* This parameter can be one of the following values:
* @arg BKP_RTCOUTPUT_NULL: no RTC output on the TAMPER pin.
* @arg BKP_RTCOUTPUT_CLKCAL: output the RTC clock with frequency
* divided by 64 on the TAMPER pin.
* @arg BKP_RTCOUTPUT_ALARM: output the RTC Alarm pulse signal on
* the TAMPER pin.
* @arg BKP_RTCOUTPUT_SECOND: output the RTC Second pulse signal on
* the TAMPER pin.
* @retval None
*/
void BKP_RTCOutputConfig(uint16_t BKP_RTCOUTPUT)
{
uint16_t temp = 0;
temp = BKP->RCCR;
/* Clear RCCOE, ROE and ROS bits */
temp &= RTCOUTPUT_MASK;
/* Set RCCOE, ROE and ROS bits according to BKP_RTCOUTPUT value */
temp |= BKP_RTCOUTPUT;
/* Store the new value */
BKP->RCCR = temp;
}
/**
* @brief Set RTC Clock Calibration value.
* @param CalibrationValue: the RTC Clock Calibration value.
* This parameter must be a number between 0 and 0x7F.
* @retval None
*/
void BKP_SetRTCCalibrationValue(uint8_t CalibrationValue)
{
uint16_t temp = 0;
temp = BKP->RCCR;
/* Clear RCCV[6:0] bits */
temp &= ~BKP_RCCR_RCCV;
/* Set CAL[6:0] bits according to CalibrationValue */
temp |= CalibrationValue;
/* Store the new value */
BKP->RCCR = temp;
}
/**
* @brief Configure the TAMPER pin active level.
* @param BKP_TPAL: the TAMPER pin active level.
* This parameter can be one of the following values:
* @arg BKP_TPAL_HIGH: TAMPER pin active on high level
* @arg BKP_TPAL_LOW: TAMPER pin active on low level
* @param NewValue: New value of the TAMPER pin state.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void BKP_TamperPinConfig(uint16_t BKP_TPAL, TypeState NewValue)
{
uint16_t temp = 0;
temp = BKP->TPCR;
/* Clear TPE bit */
temp &= ~((uint16_t)BKP_TPCR_TPE);
/* Configure TPAL bit according to BKP_TPAL value */
temp |= BKP_TPAL;
/* Store the new value */
BKP->TPCR = temp;
/* Enable the TAMPER pin */
if (NewValue != DISABLE) {
/* The TAMPER pin is dedicated for the Backup Reset function */
BKP->TPCR |= BKP_TPCR_TPE;
} else {
/* The TAMPER pin is free for GPIO functions */
BKP->TPCR &= ~((uint16_t)BKP_TPCR_TPE);
}
}
/**
* @brief Enable or disable the Tamper Interrupt.
* @param NewValue: New value of the Tamper Interrupt.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void BKP_TamperINT_Enable(TypeState NewValue)
{
if (NewValue != DISABLE) {
/* Enable the tamper interrupt */
BKP->TIER |= BKP_TIER_TIE;
} else {
/* Disable the tamper interrupt */
BKP->TIER &= ~BKP_TIER_TIE;
}
}
/**
* @brief Get the bit flag of Tamper Event.
* @param None
* @retval The new value of Tamper Event flag (SET or RESET).
*/
TypeState BKP_GetBitState(void)
{
/* Check and get the Tamper Event flag */
if ((BKP->TIER & BKP_TIER_TEF) != (uint16_t)RESET) {
/* Tamper Event occured */
return SET;
} else {
/* No Tamper Event occured */
return RESET;
}
}
/**
* @brief Clear the bit flag of Tamper Event.
* @param None
* @retval None
*/
void BKP_ClearBitState(void)
{
/* Set the TER bit to clear Tamper Event flag */
BKP->TIER |= BKP_TIER_TER;
}
/**
* @brief Get the interrupt bit flag of Tamper Interrupt.
* @param None
* @retval The new value of the Tamper Interrupt flag (SET or RESET).
*/
TypeState BKP_GetIntBitState(void)
{
/* Check and get the Tamper Interrupt flag */
if ((BKP->TIER & BKP_TIER_TIF) != (uint16_t)RESET) {
/* Tamper Interrupt occured */
return SET;
} else {
/* No Tamper Interrupt occured */
return RESET;
}
}
/**
* @brief Clear the interrupt bit flag of Tamper Interrupt.
* @param None
* @retval None
*/
void BKP_ClearIntBitState(void)
{
/* Set the TIR bit to clear Tamper Interrupt flag */
BKP->TIER |= BKP_TIER_TIR;
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,101 @@
/**
******************************************************************************
* @brief CRC functions of the firmware library.
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "gd32f10x_crc.h"
/** @addtogroup GD32F10x_Firmware
* @{
*/
/** @defgroup CRC
* @brief CRC driver modules
* @{
*/
/** @defgroup CRC_Private_Functions
* @{
*/
/**
* @brief Reset CRC DTR register to the value of 0xFFFFFFFF.
* @param None
* @retval None
*/
void CRC_ResetDTR(void)
{
CRC->CTLR = CRC_CTLR_RESET;
}
/**
* @brief Compute the 32-bit CRC value of a 32-bit data.
* @param CRC_data: data to compute its CRC value
* @retval 32-bit CRC value
*/
uint32_t CRC_CalcSingleData(uint32_t CRC_data)
{
CRC->DTR = CRC_data;
return (CRC->DTR);
}
/**
* @brief Compute the 32-bit CRC value of a 32-bit data array.
* @param pbuffer[]: pointer to the data array
* @param buffer_length: length of the data array
* @retval 32-bit CRC value
*/
uint32_t CRC_CalcDataFlow(uint32_t pbuffer[], uint32_t buffer_length)
{
uint32_t index = 0;
for (index = 0; index < buffer_length; index++) {
CRC->DTR = pbuffer[index];
}
return (CRC->DTR);
}
/**
* @brief Read current CRC value.
* @param None
* @retval 32-bit CRC value
*/
uint32_t CRC_ReadDTR(void)
{
return (CRC->DTR);
}
/**
* @brief Write an 8-bit data in FDTR.
* @param CRC_fdtr: 8-bit data to write
* @retval None
*/
void CRC_WriteFDTR(uint8_t CRC_fdtr)
{
CRC->FDTR = CRC_fdtr;
}
/**
* @brief Read the 8-bit data stored in FDTR
* @param None
* @retval 8-bit data
*/
uint8_t CRC_ReadFDTR(void)
{
return (CRC->FDTR);
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/

View File

@ -0,0 +1,326 @@
/**
******************************************************************************
* @brief DAC functions of the firmware library.
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "gd32f10x_dac.h"
#include "gd32f10x_rcc.h"
/** @addtogroup GD32F10x_Firmware
* @{
*/
/** @defgroup DAC
* @brief DAC driver modules
* @{
*/
/** @defgroup DAC_Private_Defines
* @{
*/
/* CTLR register bits mask */
#define CTLR_BITS_CLEAR ((uint32_t)0x00000FFE)
/* DAC Dual Channels SWTRIG masks */
#define DUAL_SWTRIG_SET ((uint32_t)0x00000003)
/* DHR registers offsets */
#define DHR12R1_OFFSET ((uint32_t)0x00000008)
#define DHR12R2_OFFSET ((uint32_t)0x00000014)
#define DHR12RD_OFFSET ((uint32_t)0x00000020)
/* DOR register offset */
#define DOR_OFFSET ((uint32_t)0x0000002C)
/**
* @}
*/
/** @defgroup DAC_Private_Functions
* @{
*/
/**
* @brief Deinitialize the DAC peripheral registers.
* @param DAC_InitParaStruct: DAC_InitPara structure that contains the
* configuration information for the selected DAC channel.
* @retval None
*/
void DAC_DeInit(DAC_InitPara *DAC_InitParaStruct)
{
/* Enable DAC reset state */
RCC_APB1PeriphReset_Enable(RCC_APB1PERIPH_DACRST, ENABLE);
/* Release DAC from reset state */
RCC_APB1PeriphReset_Enable(RCC_APB1PERIPH_DACRST, DISABLE);
/* Initialize the DAC_Trigger */
DAC_InitParaStruct->DAC_Trigger = DAC_TRIGGER_NONE;
/* Initialize the DAC_WaveGeneration */
DAC_InitParaStruct->DAC_WaveType = DAC_WAVEGENE_NONE;
/* Initialize the DAC_LFSRUnmask_TriangleAmplitude */
DAC_InitParaStruct->DAC_LFSRNoise_AmplitudeTriangle = DAC_LFSR_BIT0;
/* Initialize the DAC_OutputBuffer */
DAC_InitParaStruct->DAC_OutputBuffer = DAC_OUTPUTBUFFER_ENABLE;
}
/**
* @brief Initialize the DAC peripheral.
* @param DAC_Channel: the selected DAC channel.
* This parameter can be one of the following values:
* @arg DAC_Channel_1: select DAC Channel1
* @arg DAC_Channel_2: select DAC Channel2
* @param DAC_InitStruct: DAC_InitTypeDef structure .
* @retval None
*/
void DAC_Init(uint32_t DAC_Channel, DAC_InitPara *DAC_InitParaStruct)
{
uint32_t temp1 = 0, temp2 = 0;
/* DAC CTLR Configuration */
/* Get the DAC CTLR value */
temp1 = DAC->CTLR;
/* Clear BOFF, TEN, TSEL, WAVE and MAMP bits */
temp1 &= ~(CTLR_BITS_CLEAR << DAC_Channel);
/* Configure for the DAC channel: buffer output, trigger, wave generation,
mask/amplitude for wave generation */
/* Set TSEL and TEN bits according to DAC_Trigger */
/* Set WAVE bits according to DAC_WaveType */
/* Set MAMP bits according to DAC_LFSRNoise_AmplitudeTriangle */
/* Set BOFF bit according to DAC_OutputBuffer */
temp2 = (DAC_InitParaStruct->DAC_Trigger | DAC_InitParaStruct->DAC_OutputBuffer |
DAC_InitParaStruct->DAC_WaveType | DAC_InitParaStruct->DAC_LFSRNoise_AmplitudeTriangle);
/* Calculate CTLR register value */
temp1 |= temp2 << DAC_Channel;
/* Write to DAC CTLR */
DAC->CTLR = temp1;
}
/**
* @brief Enable or disable the DAC channel.
* @param DAC_Channel: the selected DAC channel.
* This parameter can be one of the following values:
* @arg DAC_Channel_1: select DAC Channel1.
* @arg DAC_Channel_2: select DAC Channel2.
* @param NewValue: New value of the DAC channel.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void DAC_Enable(uint32_t DAC_Channel, TypeState NewValue)
{
if (NewValue != DISABLE) {
/* Enable the selected DAC channel */
DAC->CTLR |= (DAC_CTLR_DEN1 << DAC_Channel) ;
} else {
/* Disable the selected DAC channel */
DAC->CTLR &= ~(DAC_CTLR_DEN1 << DAC_Channel);
}
}
/**
* @brief Enable or disable the selected DAC channel software trigger.
* @param DAC_Channel: the selected DAC channel.
* This parameter can be one of the following values:
* @arg DAC_Channel_1: select DAC Channel1
* @arg DAC_Channel_2: select DAC Channel2
* @param NewValue: New value of the selected DAC channel software trigger.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void DAC_SoftwareTrigger_Enable(uint32_t DAC_Channel, TypeState NewValue)
{
if (NewValue != DISABLE) {
/* Enable software trigger for DAC channel1 */
DAC->SWTR |= (uint32_t)DAC_SWTR_SWTR1 << (DAC_Channel >> 4);
} else {
/* Disable software trigger for DAC channel1 */
DAC->SWTR &= ~((uint32_t)DAC_SWTR_SWTR1 << (DAC_Channel >> 4));
}
}
/**
* @brief Enable or disable simultaneously the two DAC channels software
* triggers.
* @param NewValue: new value of the DAC channels software triggers.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void DAC_DualSoftwareTrigger_Enable(TypeState NewValue)
{
if (NewValue != DISABLE) {
/* Enable software trigger */
DAC->SWTR |= DUAL_SWTRIG_SET ;
} else {
/* Disable software trigger */
DAC->SWTR &= ~DUAL_SWTRIG_SET;
}
}
/**
* @brief Enable or disable the selected DAC channel wave generation.
* @param DAC_Channel: the selected DAC channel.
* This parameter can be one of the following values:
* @arg DAC_Channel_1: select DAC Channel1
* @arg DAC_Channel_2: select DAC Channel2
* @param DAC_Wave: the wave type to enable or disable.
* This parameter can be one of the following values:
* @arg DAC_WAVE_NOISE: noise wave generation
* @arg DAC_WAVE_TRIANGLE: triangle wave generation
* @param NewValue: new value of the selected DAC channel wave generation.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void DAC_WaveGeneration_Enable(uint32_t DAC_Channel, uint32_t DAC_Wave, TypeState NewValue)
{
if (NewValue != DISABLE) {
/* Enable the selected DAC channel wave generation */
DAC->CTLR |= DAC_Wave << DAC_Channel;
} else {
/* Disable the selected DAC channel wave generation */
DAC->CTLR &= ~(DAC_Wave << DAC_Channel);
}
}
/**
* @brief Set the specified data holding register value for DAC channel1.
* @param DAC_Align: the data alignment for DAC channel1.
* This parameter can be one of the following values:
* @arg DAC_ALIGN_8B_R: select 8bit right data alignment
* @arg DAC_ALIGN_12B_L: select 12bit left data alignment
* @arg DAC_ALIGN_12B_R: select 12bit right data alignment
* @param Data: Data to be loaded.
* @retval None
*/
void DAC_SetChannel1Data(uint32_t DAC_Align, uint16_t Data)
{
__IO uint32_t temp = 0;
temp = (uint32_t)DAC_BASE;
temp += DHR12R1_OFFSET + DAC_Align;
/* Set the DAC channel1 */
*(__IO uint32_t *) temp = Data;
}
/**
* @brief Set the specified data holding register value for DAC channel2.
* @param DAC_Align: the data alignment for DAC channel2.
* This parameter can be one of the following values:
* @arg DAC_ALIGN_8B_R: select 8bit right data alignment
* @arg DAC_ALIGN_12B_L: select 12bit left data alignment
* @arg DAC_ALIGN_12B_R: select 12bit right data alignment
* @param Data: Data to be loaded.
* @retval None
*/
void DAC_SetChannel2Data(uint32_t DAC_Align, uint16_t Data)
{
__IO uint32_t temp = 0;
temp = (uint32_t)DAC_BASE;
temp += DHR12R2_OFFSET + DAC_Align;
/* Set the DAC channel2 */
*(__IO uint32_t *) temp = Data;
}
/**
* @brief Set the specified data for dual channel
* @param DAC_Align: the data alignment for dual channel DAC.
* This parameter can be one of the following values:
* @arg DAC_Align_8b_R: select 8bit right data alignment
* @arg DAC_Align_12b_L: select 12bit left data alignment
* @arg DAC_Align_12b_R: select 12bit right data alignment
* @param Data2: Data for DAC Channel2.
* @param Data1: Data for DAC Channel1.
* @retval None
*/
void DAC_SetDualChannelData(uint32_t DAC_Align, uint16_t Data2, uint16_t Data1)
{
uint32_t data = 0, temp = 0;
/* set dual DAC data holding register value */
if (DAC_Align == DAC_ALIGN_8B_R) {
data = ((uint32_t)Data2 << 8) | Data1;
} else {
data = ((uint32_t)Data2 << 16) | Data1;
}
temp = (uint32_t)DAC_BASE;
temp += DHR12RD_OFFSET + DAC_Align;
/* Set the dual DAC selected data holding register */
*(__IO uint32_t *)temp = data;
}
/**
* @brief Return the last data output value.
* @param DAC_Channel: the selected DAC channel.
* This parameter can be one of the following values:
* @arg DAC_Channel_1: select DAC Channel1
* @arg DAC_Channel_2: select DAC Channel2
* @retval The DAC channel1 data output value.
*/
uint16_t DAC_GetDataOutputValue(uint32_t DAC_Channel)
{
__IO uint32_t temp = 0;
temp = (uint32_t) DAC_BASE;
temp += DOR_OFFSET + ((uint32_t)DAC_Channel >> 2);
/* Returns the DAC channel data */
return (uint16_t)(*(__IO uint32_t *) temp);
}
/**
* @brief Enable or disable DMA request.
* @param DAC_Channel: the selected DAC channel.
* This parameter can be one of the following values:
* @arg DAC_Channel_1: select DAC Channel1
* @arg DAC_Channel_2: select DAC Channel2
* @param NewValue: New value of the selected DAC channel DMA request.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void DAC_DMA_Enable(uint32_t DAC_Channel, TypeState NewValue)
{
if (NewValue != DISABLE) {
/* Enable DMA request */
DAC->CTLR |= (DAC_CTLR_DDMAEN1 << DAC_Channel);
} else {
/* Disable DMA request */
DAC->CTLR &= ~(DAC_CTLR_DDMAEN1 << DAC_Channel);
}
}
/**
* @brief Enable or disable the specified DAC interrupts.
* @param DAC_Channel: the selected DAC channel.
* This parameter can be one of the following values:
* @arg DAC_Channel_1: DAC Channel1 selected
* @arg DAC_Channel_2: DAC Channel2 selected
* @param NewValue: Alternative state of the specified DAC interrupts.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void DAC_INTConfig(uint32_t DAC_Channel, TypeState NewValue)
{
if (NewValue != DISABLE) {
/* Enable the DAC DMAUDR interrupts */
DAC->CTLR |= (DAC_INT_DMAUDR << DAC_Channel);
} else {
/* Disable the DAC DMAUDR interrupts */
DAC->CTLR &= (~(uint32_t)(DAC_INT_DMAUDR << DAC_Channel));
}
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/

View File

@ -0,0 +1,553 @@
/**
******************************************************************************
* @brief DMA functions of the firmware library.
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "gd32f10x_dma.h"
#include "gd32f10x_rcc.h"
/** @addtogroup GD32F10x_Firmware
* @{
*/
/** @defgroup DMA
* @brief DMA driver modules
* @{
*/
/** @defgroup DMA_Private_Defines
* @{
*/
/* DMA Reset registers mask */
#define DMA_REGISTERS_RESET ((uint32_t)0x00000000)
/* DMA Channel config registers Masks */
#define CTLR_CLEAR_MASK ((uint32_t)0xFFFF800F)
/* DMA Reset registers mask */
#define DMA_INT_RESET ((uint32_t)0x00000000)
/* DMA2 FLAG mask */
#define DMA2_FLAG_Mask ((uint32_t)0x10000000)
/* DMA1 Channelx interrupt pending bit masks */
#define DMA1_Channel1_INT_Mask ((uint32_t)(DMA_IFR_GIF1 | DMA_IFR_TCIF1 | DMA_IFR_HTIF1 | DMA_IFR_ERRIF1))
#define DMA1_Channel2_INT_Mask ((uint32_t)(DMA_IFR_GIF2 | DMA_IFR_TCIF2 | DMA_IFR_HTIF2 | DMA_IFR_ERRIF2))
#define DMA1_Channel3_INT_Mask ((uint32_t)(DMA_IFR_GIF3 | DMA_IFR_TCIF3 | DMA_IFR_HTIF3 | DMA_IFR_ERRIF3))
#define DMA1_Channel4_INT_Mask ((uint32_t)(DMA_IFR_GIF4 | DMA_IFR_TCIF4 | DMA_IFR_HTIF4 | DMA_IFR_ERRIF4))
#define DMA1_Channel5_INT_Mask ((uint32_t)(DMA_IFR_GIF5 | DMA_IFR_TCIF5 | DMA_IFR_HTIF5 | DMA_IFR_ERRIF5))
#define DMA1_Channel6_INT_Mask ((uint32_t)(DMA_IFR_GIF6 | DMA_IFR_TCIF6 | DMA_IFR_HTIF6 | DMA_IFR_ERRIF6))
#define DMA1_Channel7_INT_Mask ((uint32_t)(DMA_IFR_GIF7 | DMA_IFR_TCIF7 | DMA_IFR_HTIF7 | DMA_IFR_ERRIF7))
/* DMA2 Channelx interrupt pending bit masks */
#define DMA2_Channel1_INT_Mask ((uint32_t)(DMA_IFR_GIF1 | DMA_IFR_TCIF1 | DMA_IFR_HTIF1 | DMA_IFR_ERRIF1))
#define DMA2_Channel2_INT_Mask ((uint32_t)(DMA_IFR_GIF2 | DMA_IFR_TCIF2 | DMA_IFR_HTIF2 | DMA_IFR_ERRIF2))
#define DMA2_Channel3_INT_Mask ((uint32_t)(DMA_IFR_GIF3 | DMA_IFR_TCIF3 | DMA_IFR_HTIF3 | DMA_IFR_ERRIF3))
#define DMA2_Channel4_INT_Mask ((uint32_t)(DMA_IFR_GIF4 | DMA_IFR_TCIF4 | DMA_IFR_HTIF4 | DMA_IFR_ERRIF4))
#define DMA2_Channel5_INT_Mask ((uint32_t)(DMA_IFR_GIF5 | DMA_IFR_TCIF5 | DMA_IFR_HTIF5 | DMA_IFR_ERRIF5))
/**
* @}
*/
/** @defgroup DMA_Private_Functions
* @{
*/
/**
* @brief Deinitialize the DMAy Channelx registers
* @param DMAy_Channelx: where y:[1,2] to select the DMA , x:[1,7] for DMA1 and x:[1,5] for DMA2 to select the DMA Channel.
* @retval None
*/
void DMA_DeInit(DMA_Channel_TypeDef *DMAy_Channelx)
{
/* Disable the selected DMAy Channelx */
DMAy_Channelx->CTLR &= (uint16_t)(~DMA_CTLR_CHEN);
/* Reset DMAy Channelx control register */
DMAy_Channelx->CTLR = DMA_REGISTERS_RESET;
/* Reset DMAy Channelx remaining bytes register */
DMAy_Channelx->RCNT = DMA_REGISTERS_RESET;
/* Reset DMAy Channelx peripheral address register */
DMAy_Channelx->PBAR = DMA_REGISTERS_RESET;
/* Reset DMAy Channelx memory address register */
DMAy_Channelx->MBAR = DMA_REGISTERS_RESET;
if (DMAy_Channelx == DMA1_CHANNEL1) {
/* Reset interrupt pending bits for DMA1 Channel1 */
DMA1->ICR |= DMA1_Channel1_INT_Mask;
} else if (DMAy_Channelx == DMA1_CHANNEL2) {
/* Reset interrupt pending bits for DMA1 Channel2 */
DMA1->ICR |= DMA1_Channel2_INT_Mask;
} else if (DMAy_Channelx == DMA1_CHANNEL3) {
/* Reset interrupt pending bits for DMA1 Channel3 */
DMA1->ICR |= DMA1_Channel3_INT_Mask;
} else if (DMAy_Channelx == DMA1_CHANNEL4) {
/* Reset interrupt pending bits for DMA1 Channel4 */
DMA1->ICR |= DMA1_Channel4_INT_Mask;
} else if (DMAy_Channelx == DMA1_CHANNEL5) {
/* Reset interrupt pending bits for DMA1 Channel5 */
DMA1->ICR |= DMA1_Channel5_INT_Mask;
} else if (DMAy_Channelx == DMA1_CHANNEL6) {
/* Reset interrupt pending bits for DMA1 Channel6 */
DMA1->ICR |= DMA1_Channel6_INT_Mask;
} else if (DMAy_Channelx == DMA1_CHANNEL7) {
/* Reset interrupt pending bits for DMA1 Channel7 */
DMA1->ICR |= DMA1_Channel7_INT_Mask;
} else if (DMAy_Channelx == DMA2_CHANNEL1) {
/* Reset interrupt pending bits for DMA2 Channel1 */
DMA2->ICR |= DMA2_Channel1_INT_Mask;
} else if (DMAy_Channelx == DMA2_CHANNEL2) {
/* Reset interrupt pending bits for DMA2 Channel2 */
DMA2->ICR |= DMA2_Channel2_INT_Mask;
} else if (DMAy_Channelx == DMA2_CHANNEL3) {
/* Reset interrupt pending bits for DMA2 Channel3 */
DMA2->ICR |= DMA2_Channel3_INT_Mask;
} else if (DMAy_Channelx == DMA2_CHANNEL4) {
/* Reset interrupt pending bits for DMA2 Channel4 */
DMA2->ICR |= DMA2_Channel4_INT_Mask;
} else {
if (DMAy_Channelx == DMA2_CHANNEL5) {
/* Reset interrupt pending bits for DMA2 Channel5 */
DMA2->ICR |= DMA2_Channel5_INT_Mask;
}
}
}
/**
* @brief Initialize the DMAy Channelx according to the DMA_InitParaStruct.
* @param DMAy_Channelx: where y:[1:2] to select the DMA , x:[1,7] for DMA1 and x:[1,5] for DMA2 to select the DMA Channel.
* @param DMA_InitParaStruct: contain the configuration information for the specified DMA Channel.
* @retval None
*/
void DMA_Init(DMA_Channel_TypeDef *DMAy_Channelx, DMA_InitPara *DMA_InitParaStruct)
{
uint32_t temp = 0;
/* Get the DMAy_Channelx CCR value */
temp = DMAy_Channelx->CTLR;
/* Clear MEMTOMEM, PRIO, MSIZE, PSIZE, MNAGA, PNAGA, CIRC and DIR bits */
temp &= CTLR_CLEAR_MASK;
/* Configure DMAy Channelx: data transfer, data size, priority level and mode */
/* Set MEMTOMEM, PRIO, MSIZE, PSIZE, MNAGA, PNAGA, CIRC and DIR bits according to DMA_InitParaStruct */
temp |= DMA_InitParaStruct->DMA_DIR | DMA_InitParaStruct->DMA_Mode |
DMA_InitParaStruct->DMA_PeripheralInc | DMA_InitParaStruct->DMA_MemoryInc |
DMA_InitParaStruct->DMA_PeripheralDataSize | DMA_InitParaStruct->DMA_MemoryDataSize |
DMA_InitParaStruct->DMA_Priority | DMA_InitParaStruct->DMA_MTOM;
/* Write to DMAy Channelx CTLR */
DMAy_Channelx->CTLR = temp;
/* Write to DMAy Channelx RCNT */
DMAy_Channelx->RCNT = DMA_InitParaStruct->DMA_BufferSize;
/* Write to DMAy Channelx PBAR */
DMAy_Channelx->PBAR = DMA_InitParaStruct->DMA_PeripheralBaseAddr;
/* Write to DMAy Channelx MBAR */
DMAy_Channelx->MBAR = DMA_InitParaStruct->DMA_MemoryBaseAddr;
}
/**
* @brief Set each DMA_InitParaStruct member to its default value.
* @param DMA_InitParaStruct: The structure pointer to DMA_InitParaStruct will be initialized.
* @retval None
*/
void DMA_ParaInit(DMA_InitPara *DMA_InitParaStruct)
{
/* Reset DMA init structure parameters values */
DMA_InitParaStruct->DMA_PeripheralBaseAddr = DMA_INT_RESET;
DMA_InitParaStruct->DMA_MemoryBaseAddr = DMA_INT_RESET;
DMA_InitParaStruct->DMA_DIR = DMA_DIR_PERIPHERALSRC;
DMA_InitParaStruct->DMA_BufferSize = DMA_INT_RESET;
DMA_InitParaStruct->DMA_PeripheralInc = DMA_PERIPHERALINC_DISABLE;
DMA_InitParaStruct->DMA_MemoryInc = DMA_MEMORYINC_DISABLE;
DMA_InitParaStruct->DMA_PeripheralDataSize = DMA_PERIPHERALDATASIZE_BYTE;
DMA_InitParaStruct->DMA_MemoryDataSize = DMA_MEMORYDATASIZE_BYTE;
DMA_InitParaStruct->DMA_Mode = DMA_MODE_NORMAL;
DMA_InitParaStruct->DMA_Priority = DMA_PRIORITY_LOW;
DMA_InitParaStruct->DMA_MTOM = DMA_MEMTOMEM_DISABLE;
}
/**
* @brief Enable or disable the DMAy Channelx.
* @param DMAy_Channelx: where y:[1:2] to select the DMA , x:[1,7] for DMA1 and x:[1,5] for DMA2 to select the DMA Channel.
* @param NewValue: new state of the DMAy Channelx.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void DMA_Enable(DMA_Channel_TypeDef *DMAy_Channelx, TypeState NewValue)
{
if (NewValue != DISABLE) {
/* Enable the DMAy Channelx */
DMAy_Channelx->CTLR |= DMA_CTLR_CHEN;
} else {
/* Disable the DMAy Channelx */
DMAy_Channelx->CTLR &= (uint16_t)(~DMA_CTLR_CHEN);
}
}
/**
* @brief Enable or disable the DMAy Channelx interrupts.
* @param DMAy_Channelx: where y:[1:2] to select the DMA , x:[1,7] for DMA1 and x:[1,5] for DMA2 to select the DMA Channel.
* @param DMA_INT: specify the DMA interrupts sources to be enabled or disabled.
* This parameter can be any combination of the following values:
* @arg DMA_INT_TC: Transfer complete interrupt mask
* @arg DMA_INT_HT: Half transfer interrupt mask
* @arg DMA_INT_ERR: Transfer error interrupt mask
* @param NewValue: new state of the DMA interrupts.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void DMA_INTConfig(DMA_Channel_TypeDef *DMAy_Channelx, uint32_t DMA_INT, TypeState NewValue)
{
if (NewValue != DISABLE) {
/* Enable the DMA interrupts */
DMAy_Channelx->CTLR |= DMA_INT;
} else {
/* Disable the DMA interrupts */
DMAy_Channelx->CTLR &= ~DMA_INT;
}
}
/**
* @brief Set the number of the remaining counter in the current DMAy Channelx transfer.
* @param DMAy_Channelx: where y:[1:2] to select the DMA , x:[1,7] for DMA1 and x:[1,5] for DMA2 to select the DMA Channel.
* @param DataNumber: The number of the remaining counter in the current DMAy Channelx transfer.
* @retval None.
*/
void DMA_SetCurrDataCounter(DMA_Channel_TypeDef *DMAy_Channelx, uint16_t DataNumber)
{
/* Write to DMAy Channelx RCNT */
DMAy_Channelx->RCNT = DataNumber;
}
/**
* @brief Return the number of remaining counter in the current DMAy Channelx transfer.
* @param DMAy_Channelx: where y:[1:2] to select the DMA , x:[1,7] for DMA1 and x:[1,5] for DMA2 to select the DMA Channel.
* @retval The number of remaining counter in the current DMAy Channelx transfer.
*/
uint16_t DMA_GetCurrDataCounter(DMA_Channel_TypeDef *DMAy_Channelx)
{
/* Return the number of remaining counter for DMAy Channelx */
return ((uint16_t)(DMAy_Channelx->RCNT));
}
/**
* @brief Check whether the DMAy Channelx flag is set or not.
* @param DMAy_FLAG: specifies the flag to check.
* This parameter can be one of the following values:
* @arg DMA1_FLAG_GL1: DMA1 Channel1 global flag.
* @arg DMA1_FLAG_TC1: DMA1 Channel1 transfer complete flag.
* @arg DMA1_FLAG_HT1: DMA1 Channel1 half transfer flag.
* @arg DMA1_FLAG_TE1: DMA1 Channel1 transfer error flag.
* @arg DMA1_FLAG_GL2: DMA1 Channel2 global flag.
* @arg DMA1_FLAG_TC2: DMA1 Channel2 transfer complete flag.
* @arg DMA1_FLAG_HT2: DMA1 Channel2 half transfer flag.
* @arg DMA1_FLAG_TE2: DMA1 Channel2 transfer error flag.
* @arg DMA1_FLAG_GL3: DMA1 Channel3 global flag.
* @arg DMA1_FLAG_TC3: DMA1 Channel3 transfer complete flag.
* @arg DMA1_FLAG_HT3: DMA1 Channel3 half transfer flag.
* @arg DMA1_FLAG_TE3: DMA1 Channel3 transfer error flag.
* @arg DMA1_FLAG_GL4: DMA1 Channel4 global flag.
* @arg DMA1_FLAG_TC4: DMA1 Channel4 transfer complete flag.
* @arg DMA1_FLAG_HT4: DMA1 Channel4 half transfer flag.
* @arg DMA1_FLAG_TE4: DMA1 Channel4 transfer error flag.
* @arg DMA1_FLAG_GL5: DMA1 Channel5 global flag.
* @arg DMA1_FLAG_TC5: DMA1 Channel5 transfer complete flag.
* @arg DMA1_FLAG_HT5: DMA1 Channel5 half transfer flag.
* @arg DMA1_FLAG_TE5: DMA1 Channel5 transfer error flag.
* @arg DMA1_FLAG_GL6: DMA1 Channel6 global flag.
* @arg DMA1_FLAG_TC6: DMA1 Channel6 transfer complete flag.
* @arg DMA1_FLAG_HT6: DMA1 Channel6 half transfer flag.
* @arg DMA1_FLAG_TE6: DMA1 Channel6 transfer error flag.
* @arg DMA1_FLAG_GL7: DMA1 Channel7 global flag.
* @arg DMA1_FLAG_TC7: DMA1 Channel7 transfer complete flag.
* @arg DMA1_FLAG_HT7: DMA1 Channel7 half transfer flag.
* @arg DMA1_FLAG_TE7: DMA1 Channel7 transfer error flag.
* @arg DMA2_FLAG_GL1: DMA2 Channel1 global flag.
* @arg DMA2_FLAG_TC1: DMA2 Channel1 transfer complete flag.
* @arg DMA2_FLAG_HT1: DMA2 Channel1 half transfer flag.
* @arg DMA2_FLAG_TE1: DMA2 Channel1 transfer error flag.
* @arg DMA2_FLAG_GL2: DMA2 Channel2 global flag.
* @arg DMA2_FLAG_TC2: DMA2 Channel2 transfer complete flag.
* @arg DMA2_FLAG_HT2: DMA2 Channel2 half transfer flag.
* @arg DMA2_FLAG_TE2: DMA2 Channel2 transfer error flag.
* @arg DMA2_FLAG_GL3: DMA2 Channel3 global flag.
* @arg DMA2_FLAG_TC3: DMA2 Channel3 transfer complete flag.
* @arg DMA2_FLAG_HT3: DMA2 Channel3 half transfer flag.
* @arg DMA2_FLAG_TE3: DMA2 Channel3 transfer error flag.
* @arg DMA2_FLAG_GL4: DMA2 Channel4 global flag.
* @arg DMA2_FLAG_TC4: DMA2 Channel4 transfer complete flag.
* @arg DMA2_FLAG_HT4: DMA2 Channel4 half transfer flag.
* @arg DMA2_FLAG_TE4: DMA2 Channel4 transfer error flag.
* @arg DMA2_FLAG_GL5: DMA2 Channel5 global flag.
* @arg DMA2_FLAG_TC5: DMA2 Channel5 transfer complete flag.
* @arg DMA2_FLAG_HT5: DMA2 Channel5 half transfer flag.
* @arg DMA2_FLAG_TE5: DMA2 Channel5 transfer error flag.
* @retval The new state of DMAy_FLAG (SET or RESET).
*/
TypeState DMA_GetBitState(uint32_t DMAy_FLAG)
{
uint32_t temp = 0;
/* Check the used DMAy */
if ((DMAy_FLAG & DMA2_FLAG_Mask) != (uint32_t)RESET) {
/* Get DMA2 ISR register value */
temp = DMA2->IFR ;
} else {
/* Get DMA1 ISR register value */
temp = DMA1->IFR ;
}
/* Check the status of the DMAy flag */
if ((temp & DMAy_FLAG) != (uint32_t)RESET) {
/* DMAy_FLAG is set */
return SET;
} else {
/* DMAy_FLAG is reset */
return RESET;
}
}
/**
* @brief Clear the DMAy Channelx's bit flags.
* @param DMAy_FLAG: specifies the flag to clear.
* This parameter can be any combination (for the same DMA) of the following values:
* @arg DMA1_FLAG_GL1: DMA1 Channel1 global flag.
* @arg DMA1_FLAG_TC1: DMA1 Channel1 transfer complete flag.
* @arg DMA1_FLAG_HT1: DMA1 Channel1 half transfer flag.
* @arg DMA1_FLAG_TE1: DMA1 Channel1 transfer error flag.
* @arg DMA1_FLAG_GL2: DMA1 Channel2 global flag.
* @arg DMA1_FLAG_TC2: DMA1 Channel2 transfer complete flag.
* @arg DMA1_FLAG_HT2: DMA1 Channel2 half transfer flag.
* @arg DMA1_FLAG_TE2: DMA1 Channel2 transfer error flag.
* @arg DMA1_FLAG_GL3: DMA1 Channel3 global flag.
* @arg DMA1_FLAG_TC3: DMA1 Channel3 transfer complete flag.
* @arg DMA1_FLAG_HT3: DMA1 Channel3 half transfer flag.
* @arg DMA1_FLAG_TE3: DMA1 Channel3 transfer error flag.
* @arg DMA1_FLAG_GL4: DMA1 Channel4 global flag.
* @arg DMA1_FLAG_TC4: DMA1 Channel4 transfer complete flag.
* @arg DMA1_FLAG_HT4: DMA1 Channel4 half transfer flag.
* @arg DMA1_FLAG_TE4: DMA1 Channel4 transfer error flag.
* @arg DMA1_FLAG_GL5: DMA1 Channel5 global flag.
* @arg DMA1_FLAG_TC5: DMA1 Channel5 transfer complete flag.
* @arg DMA1_FLAG_HT5: DMA1 Channel5 half transfer flag.
* @arg DMA1_FLAG_TE5: DMA1 Channel5 transfer error flag.
* @arg DMA1_FLAG_GL6: DMA1 Channel6 global flag.
* @arg DMA1_FLAG_TC6: DMA1 Channel6 transfer complete flag.
* @arg DMA1_FLAG_HT6: DMA1 Channel6 half transfer flag.
* @arg DMA1_FLAG_TE6: DMA1 Channel6 transfer error flag.
* @arg DMA1_FLAG_GL7: DMA1 Channel7 global flag.
* @arg DMA1_FLAG_TC7: DMA1 Channel7 transfer complete flag.
* @arg DMA1_FLAG_HT7: DMA1 Channel7 half transfer flag.
* @arg DMA1_FLAG_TE7: DMA1 Channel7 transfer error flag.
* @arg DMA2_FLAG_GL1: DMA2 Channel1 global flag.
* @arg DMA2_FLAG_TC1: DMA2 Channel1 transfer complete flag.
* @arg DMA2_FLAG_HT1: DMA2 Channel1 half transfer flag.
* @arg DMA2_FLAG_TE1: DMA2 Channel1 transfer error flag.
* @arg DMA2_FLAG_GL2: DMA2 Channel2 global flag.
* @arg DMA2_FLAG_TC2: DMA2 Channel2 transfer complete flag.
* @arg DMA2_FLAG_HT2: DMA2 Channel2 half transfer flag.
* @arg DMA2_FLAG_TE2: DMA2 Channel2 transfer error flag.
* @arg DMA2_FLAG_GL3: DMA2 Channel3 global flag.
* @arg DMA2_FLAG_TC3: DMA2 Channel3 transfer complete flag.
* @arg DMA2_FLAG_HT3: DMA2 Channel3 half transfer flag.
* @arg DMA2_FLAG_TE3: DMA2 Channel3 transfer error flag.
* @arg DMA2_FLAG_GL4: DMA2 Channel4 global flag.
* @arg DMA2_FLAG_TC4: DMA2 Channel4 transfer complete flag.
* @arg DMA2_FLAG_HT4: DMA2 Channel4 half transfer flag.
* @arg DMA2_FLAG_TE4: DMA2 Channel4 transfer error flag.
* @arg DMA2_FLAG_GL5: DMA2 Channel5 global flag.
* @arg DMA2_FLAG_TC5: DMA2 Channel5 transfer complete flag.
* @arg DMA2_FLAG_HT5: DMA2 Channel5 half transfer flag.
* @arg DMA2_FLAG_TE5: DMA2 Channel5 transfer error flag.
* @retval None
*/
void DMA_ClearBitState(uint32_t DMAy_FLAG)
{
/* Check the used DMAy */
if ((DMAy_FLAG & DMA2_FLAG_Mask) != (uint32_t)RESET) {
/* Clear the selected DMAy flags */
DMA2->ICR = DMAy_FLAG;
} else {
/* Clear the selected DMAy flags */
DMA1->ICR = DMAy_FLAG;
}
}
/**
* @brief Check whether the DMAy Channelx interrupt has occurred or not.
* @param DMAy_INT: specify the DMAy interrupt source to check.
* This parameter can be one of the following values:
* @arg DMA1_INT_GL1: DMA1 Channel1 global interrupt.
* @arg DMA1_INT_TC1: DMA1 Channel1 transfer complete interrupt.
* @arg DMA1_INT_HT1: DMA1 Channel1 half transfer interrupt.
* @arg DMA1_INT_TE1: DMA1 Channel1 transfer error interrupt.
* @arg DMA1_INT_GL2: DMA1 Channel2 global interrupt.
* @arg DMA1_INT_TC2: DMA1 Channel2 transfer complete interrupt.
* @arg DMA1_INT_HT2: DMA1 Channel2 half transfer interrupt.
* @arg DMA1_INT_TE2: DMA1 Channel2 transfer error interrupt.
* @arg DMA1_INT_GL3: DMA1 Channel3 global interrupt.
* @arg DMA1_INT_TC3: DMA1 Channel3 transfer complete interrupt.
* @arg DMA1_INT_HT3: DMA1 Channel3 half transfer interrupt.
* @arg DMA1_INT_TE3: DMA1 Channel3 transfer error interrupt.
* @arg DMA1_INT_GL4: DMA1 Channel4 global interrupt.
* @arg DMA1_INT_TC4: DMA1 Channel4 transfer complete interrupt.
* @arg DMA1_INT_HT4: DMA1 Channel4 half transfer interrupt.
* @arg DMA1_INT_TE4: DMA1 Channel4 transfer error interrupt.
* @arg DMA1_INT_GL5: DMA1 Channel5 global interrupt.
* @arg DMA1_INT_TC5: DMA1 Channel5 transfer complete interrupt.
* @arg DMA1_INT_HT5: DMA1 Channel5 half transfer interrupt.
* @arg DMA1_INT_TE5: DMA1 Channel5 transfer error interrupt.
* @arg DMA1_INT_GL6: DMA1 Channel6 global interrupt.
* @arg DMA1_INT_TC6: DMA1 Channel6 transfer complete interrupt.
* @arg DMA1_INT_HT6: DMA1 Channel6 half transfer interrupt.
* @arg DMA1_INT_TE6: DMA1 Channel6 transfer error interrupt.
* @arg DMA1_INT_GL7: DMA1 Channel7 global interrupt.
* @arg DMA1_INT_TC7: DMA1 Channel7 transfer complete interrupt.
* @arg DMA1_INT_HT7: DMA1 Channel7 half transfer interrupt.
* @arg DMA1_INT_TE7: DMA1 Channel7 transfer error interrupt.
* @arg DMA2_INT_GL1: DMA2 Channel1 global interrupt.
* @arg DMA2_INT_TC1: DMA2 Channel1 transfer complete interrupt.
* @arg DMA2_INT_HT1: DMA2 Channel1 half transfer interrupt.
* @arg DMA2_INT_TE1: DMA2 Channel1 transfer error interrupt.
* @arg DMA2_INT_GL2: DMA2 Channel2 global interrupt.
* @arg DMA2_INT_TC2: DMA2 Channel2 transfer complete interrupt.
* @arg DMA2_INT_HT2: DMA2 Channel2 half transfer interrupt.
* @arg DMA2_INT_TE2: DMA2 Channel2 transfer error interrupt.
* @arg DMA2_INT_GL3: DMA2 Channel3 global interrupt.
* @arg DMA2_INT_TC3: DMA2 Channel3 transfer complete interrupt.
* @arg DMA2_INT_HT3: DMA2 Channel3 half transfer interrupt.
* @arg DMA2_INT_TE3: DMA2 Channel3 transfer error interrupt.
* @arg DMA2_INT_GL4: DMA2 Channel4 global interrupt.
* @arg DMA2_INT_TC4: DMA2 Channel4 transfer complete interrupt.
* @arg DMA2_INT_HT4: DMA2 Channel4 half transfer interrupt.
* @arg DMA2_INT_TE4: DMA2 Channel4 transfer error interrupt.
* @arg DMA2_INT_GL5: DMA2 Channel5 global interrupt.
* @arg DMA2_INT_TC5: DMA2 Channel5 transfer complete interrupt.
* @arg DMA2_INT_HT5: DMA2 Channel5 half transfer interrupt.
* @arg DMA2_INT_TE5: DMA2 Channel5 transfer error interrupt.
* @retval The new state of DMAy_IT (SET or RESET).
*/
TypeState DMA_GetIntBitState(uint32_t DMAy_INT)
{
uint32_t temp = 0;
/* Calculate the used DMA */
if ((DMAy_INT & DMA2_FLAG_Mask) != (uint32_t)RESET) {
/* Get DMA2 IFR register value */
temp = DMA2->IFR;
} else {
/* Get DMA1 IFR register value */
temp = DMA1->IFR;
}
/* Check the status of the DMAy interrupt */
if ((temp & DMAy_INT) != (uint32_t)RESET) {
/* DMA_INT is set */
return SET;
} else {
/* DMA_INT is reset */
return RESET;
}
}
/**
* @brief Clear the DMAy Channelx's interrupt bits.
* @param DMAy_INT: specify the DMAy interrupt pending bit to clear.
* This parameter can be any combination (for the same DMA) of the following values:
* @arg DMA1_INT_GL1: DMA1 Channel1 global interrupt.
* @arg DMA1_INT_TC1: DMA1 Channel1 transfer complete interrupt.
* @arg DMA1_INT_HT1: DMA1 Channel1 half transfer interrupt.
* @arg DMA1_INT_TE1: DMA1 Channel1 transfer error interrupt.
* @arg DMA1_INT_GL2: DMA1 Channel2 global interrupt.
* @arg DMA1_INT_TC2: DMA1 Channel2 transfer complete interrupt.
* @arg DMA1_INT_HT2: DMA1 Channel2 half transfer interrupt.
* @arg DMA1_INT_TE2: DMA1 Channel2 transfer error interrupt.
* @arg DMA1_INT_GL3: DMA1 Channel3 global interrupt.
* @arg DMA1_INT_TC3: DMA1 Channel3 transfer complete interrupt.
* @arg DMA1_INT_HT3: DMA1 Channel3 half transfer interrupt.
* @arg DMA1_INT_TE3: DMA1 Channel3 transfer error interrupt.
* @arg DMA1_INT_GL4: DMA1 Channel4 global interrupt.
* @arg DMA1_INT_TC4: DMA1 Channel4 transfer complete interrupt.
* @arg DMA1_INT_HT4: DMA1 Channel4 half transfer interrupt.
* @arg DMA1_INT_TE4: DMA1 Channel4 transfer error interrupt.
* @arg DMA1_INT_GL5: DMA1 Channel5 global interrupt.
* @arg DMA1_INT_TC5: DMA1 Channel5 transfer complete interrupt.
* @arg DMA1_INT_HT5: DMA1 Channel5 half transfer interrupt.
* @arg DMA1_INT_TE5: DMA1 Channel5 transfer error interrupt.
* @arg DMA1_INT_GL6: DMA1 Channel6 global interrupt.
* @arg DMA1_INT_TC6: DMA1 Channel6 transfer complete interrupt.
* @arg DMA1_INT_HT6: DMA1 Channel6 half transfer interrupt.
* @arg DMA1_INT_TE6: DMA1 Channel6 transfer error interrupt.
* @arg DMA1_INT_GL7: DMA1 Channel7 global interrupt.
* @arg DMA1_INT_TC7: DMA1 Channel7 transfer complete interrupt.
* @arg DMA1_INT_HT7: DMA1 Channel7 half transfer interrupt.
* @arg DMA1_INT_TE7: DMA1 Channel7 transfer error interrupt.
* @arg DMA2_INT_GL1: DMA2 Channel1 global interrupt.
* @arg DMA2_INT_TC1: DMA2 Channel1 transfer complete interrupt.
* @arg DMA2_INT_HT1: DMA2 Channel1 half transfer interrupt.
* @arg DMA2_INT_TE1: DMA2 Channel1 transfer error interrupt.
* @arg DMA2_INT_GL2: DMA2 Channel2 global interrupt.
* @arg DMA2_INT_TC2: DMA2 Channel2 transfer complete interrupt.
* @arg DMA2_INT_HT2: DMA2 Channel2 half transfer interrupt.
* @arg DMA2_INT_TE2: DMA2 Channel2 transfer error interrupt.
* @arg DMA2_INT_GL3: DMA2 Channel3 global interrupt.
* @arg DMA2_INT_TC3: DMA2 Channel3 transfer complete interrupt.
* @arg DMA2_INT_HT3: DMA2 Channel3 half transfer interrupt.
* @arg DMA2_INT_TE3: DMA2 Channel3 transfer error interrupt.
* @arg DMA2_INT_GL4: DMA2 Channel4 global interrupt.
* @arg DMA2_INT_TC4: DMA2 Channel4 transfer complete interrupt.
* @arg DMA2_INT_HT4: DMA2 Channel4 half transfer interrupt.
* @arg DMA2_INT_TE4: DMA2 Channel4 transfer error interrupt.
* @arg DMA2_INT_GL5: DMA2 Channel5 global interrupt.
* @arg DMA2_INT_TC5: DMA2 Channel5 transfer complete interrupt.
* @arg DMA2_INT_HT5: DMA2 Channel5 half transfer interrupt.
* @arg DMA2_INT_TE5: DMA2 Channel5 transfer error interrupt.
* @retval None
*/
void DMA_ClearIntBitState(uint32_t DMAy_INT)
{
/* Check the used DMAy */
if ((DMAy_INT & DMA2_FLAG_Mask) != (uint32_t)RESET) {
/* Clear the DMA2 interrupt bits */
DMA2->ICR = DMAy_INT;
} else {
/* Clear the DMA1 interrupt bits */
DMA1->ICR = DMAy_INT;
}
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,758 @@
/**
******************************************************************************
* @brief EXMC functions of the firmware library.
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "gd32f10x_exmc.h"
#include "gd32f10x_rcc.h"
/** @addtogroup GD32F10x_Firmware
* @{
*/
/** @defgroup EXMC
* @brief EXMC driver modules
* @{
*/
/** @defgroup EXMC_Private_Defines
* @{
*/
/* EXMC Bank1 SCTLRx_BAKEN and SCTLRx_NORAEN Mask */
#define SCTLR_BAKEN_SET ((uint32_t)0x00000001)
#define SCTLR_BAKEN_RESET ((uint32_t)0x000FFFFE)
/* EXMC Bank1 SCTLRx_NOREN Mask */
#define SCTLR_NOREN_SET ((uint32_t)0x00000040)
/* EXMC Bank2/3/4 CTLRx_BAKEN Mask */
#define CTLR_BAKEN_SET ((uint32_t)0x00000004)
#define CTLR_BAKEN_RESET ((uint32_t)0x000FFFFB)
/* EXMC Bank2/3/4 CTLRx_ECCEN Mask */
#define CTLR_ECCEN_SET ((uint32_t)0x00000040)
#define CTLR_ECCEN_RESET ((uint32_t)0x000FFFBF)
/* EXMC Bank2/3/4 CTLRx_MTYPE Mask */
#define CTLR_EMTYP_NAND ((uint32_t)0x00000008)
/* EXMC Bank1 Register Reset mask*/
#define BANK1_SCTLR1_RESET ((uint32_t)0x000030DB)
#define BANK1_SCTLR_RESET ((uint32_t)0x000030D2)
#define BANK1_STR_RESET ((uint32_t)0x0FFFFFFF)
#define BANK1_SWTR_RESET ((uint32_t)0x0FFFFFFF)
/* EXMC Bank2/3 Register Reset mask*/
#define BANK2_3_CTLR_RESET ((uint32_t)0x00000018)
#define BANK2_3_SIR_RESET ((uint32_t)0x00000040)
#define BANK2_3_COMTR_RESET ((uint32_t)0xFCFCFCFC)
#define BANK2_3_ATTR_RESET ((uint32_t)0xFCFCFCFC)
/* EXMC Bank4 Register Reset mask*/
#define BANK4_CTLR_RESET ((uint32_t)0x00000018)
#define BANK4_SIR_RESET ((uint32_t)0x00000000)
#define BANK4_COMTR_RESET ((uint32_t)0xFCFCFCFC)
#define BANK4_ATTR_RESET ((uint32_t)0xFCFCFCFC)
#define BANK4_IOTR_RESET ((uint32_t)0xFCFCFCFC)
/* EXMC register bit offset */
#define STR_AHT_OFFSET ((uint32_t)0x00000004)
#define STR_DST_OFFSET ((uint32_t)0x00000008)
#define STR_BUSLAT_OFFSET ((uint32_t)0x00000010)
#define STR_CDIV_OFFSET ((uint32_t)0x00000014)
#define STR_DLAT_OFFSET ((uint32_t)0x00000018)
#define SWTR_AHT_OFFSET ((uint32_t)0x00000004)
#define SWTR_DST_OFFSET ((uint32_t)0x00000008)
#define SWTR_CDIV_OFFSET ((uint32_t)0x00000014)
#define SWTR_DLAT_OFFSET ((uint32_t)0x00000018)
#define CTLR_CTR_OFFSET ((uint32_t)0x00000009)
#define CTLR_ATR_OFFSET ((uint32_t)0x0000000D)
#define COMTR_COMWT_OFFSET ((uint32_t)0x00000008)
#define COMTR_COMHT_OFFSET ((uint32_t)0x00000010)
#define COMTR_COMHIZT_OFFSET ((uint32_t)0x00000018)
#define ATTR_ATTWT_OFFSET ((uint32_t)0x00000008)
#define ATTR_ATTHT_OFFSET ((uint32_t)0x00000010)
#define ATTR_ATTHIZT_OFFSET ((uint32_t)0x00000018)
#define IOTR_IOTWT_OFFSET ((uint32_t)0x00000008)
#define IOTR_IOHT_OFFSET ((uint32_t)0x00000010)
#define IOTR_IOHIZT_OFFSET ((uint32_t)0x00000018)
#define SIR_INTEN_OFFSET ((uint32_t)0x00000003)
/**
* @}
*/
/** @defgroup EXMC_Private_Functions
* @{
*/
/**
* @brief Reset the Bank1 NOR/SRAM registers.
* @param EXMC_NORSRAMBank: specifies the Region of Bank1.
* This parameter can be one of the following values:
* @arg EXMC_BANK1_NORSRAM1: the Region1 of Bank1
* @arg EXMC_BANK1_NORSRAM2: the Region2 of Bank1
* @arg EXMC_BANK1_NORSRAM3: the Region3 of Bank1
* @arg EXMC_BANK1_NORSRAM4: the Region4 of Bank1
* @retval None
*/
void EXMC_NORSRAM_DeInit(uint32_t EXMC_NORSRAMBank)
{
switch (EXMC_NORSRAMBank) {
case EXMC_BANK1_NORSRAM1: {
/* the Region1 of Bank1 */
EXMC_BANK1->SCTLR1 = BANK1_SCTLR1_RESET;
EXMC_BANK1->STR1 = BANK1_STR_RESET;
EXMC_BANK1_WT->SWTR1 = BANK1_SWTR_RESET;
break;
}
case EXMC_BANK1_NORSRAM2: {
/* the Region2 of Bank1 */
EXMC_BANK1->SCTLR2 = BANK1_SCTLR_RESET;
EXMC_BANK1->STR2 = BANK1_STR_RESET;
EXMC_BANK1_WT->SWTR2 = BANK1_SWTR_RESET;
break;
}
case EXMC_BANK1_NORSRAM3: {
/* the Region3 of Bank1 */
EXMC_BANK1->SCTLR3 = BANK1_SCTLR_RESET;
EXMC_BANK1->STR3 = BANK1_STR_RESET;
EXMC_BANK1_WT->SWTR3 = BANK1_SWTR_RESET;
break;
}
case EXMC_BANK1_NORSRAM4: {
/* the Region4 of Bank1 */
EXMC_BANK1->SCTLR4 = BANK1_SCTLR_RESET;
EXMC_BANK1->STR4 = BANK1_STR_RESET;
EXMC_BANK1_WT->SWTR4 = BANK1_SWTR_RESET;
break;
}
default:
break;
}
}
/**
* @brief Reset the Bank2 or Bank3 NAND registers.
* @param EXMC_NANDBank: specifies the Bank2 or Bank3 to be used.
* This parameter can be one of the following values:
* @arg EXMC_BANK2_NAND: Bank2
* @arg EXMC_BANK3_NAND: Bank3
* @retval None
*/
void EXMC_NAND_DeInit(uint32_t EXMC_NANDBank)
{
if (EXMC_NANDBank == EXMC_BANK2_NAND) {
/* Reset the Bank2 NAND registers */
EXMC_BANK2->CTLR2 = BANK2_3_CTLR_RESET;
EXMC_BANK2->SIR2 = BANK2_3_SIR_RESET;
EXMC_BANK2->COMTR2 = BANK2_3_COMTR_RESET;
EXMC_BANK2->ATTR2 = BANK2_3_ATTR_RESET;
}
/* EXMC_Bank3_NAND */
else {
/* Reset the Bank3 NAND registers */
EXMC_BANK3->CTLR3 = BANK2_3_CTLR_RESET;
EXMC_BANK3->SIR3 = BANK2_3_SIR_RESET;
EXMC_BANK3->COMTR3 = BANK2_3_COMTR_RESET;
EXMC_BANK3->ATTR3 = BANK2_3_ATTR_RESET;
}
}
/**
* @brief Reset the Bank4 PCCARD registers.
* @param None
* @retval None
*/
void EXMC_PCCARD_DeInit(void)
{
/* Reset EXMC Bank4 PCCARD registers */
EXMC_BANK4->CTLR4 = BANK4_CTLR_RESET;
EXMC_BANK4->SIR4 = BANK4_SIR_RESET;
EXMC_BANK4->COMTR4 = BANK4_COMTR_RESET;
EXMC_BANK4->ATTR4 = BANK4_ATTR_RESET;
EXMC_BANK4->IOTR4 = BANK4_IOTR_RESET;
}
/**
* @brief Initializes the EXMC Bank1 NOR/SRAM parameters.
* @param EXMC_NORSRAMInitParaStruct : the struct EXMC_NORSRAMInitPara pointer
* @retval None
*/
void EXMC_NORSRAM_Init(EXMC_NORSRAMInitPara *EXMC_NORSRAMInitParaStruct)
{
uint32_t temp_SCTLR = 0x00000000, temp_STR = 0x00000000, temp_SWTR = 0x00000000;
temp_SCTLR = (uint32_t)EXMC_NORSRAMInitParaStruct->EXMC_AddressDataMux |
EXMC_NORSRAMInitParaStruct->EXMC_MemoryType |
EXMC_NORSRAMInitParaStruct->EXMC_DatabusWidth |
EXMC_NORSRAMInitParaStruct->EXMC_BurstMode |
EXMC_NORSRAMInitParaStruct->EXMC_NWAITPolarity |
EXMC_NORSRAMInitParaStruct->EXMC_WrapBurstMode |
EXMC_NORSRAMInitParaStruct->EXMC_NWAITConfig |
EXMC_NORSRAMInitParaStruct->EXMC_MemoryWrite |
EXMC_NORSRAMInitParaStruct->EXMC_NWAITSignal |
EXMC_NORSRAMInitParaStruct->EXMC_ExtendedMode |
EXMC_NORSRAMInitParaStruct->EXMC_AsynWait |
EXMC_NORSRAMInitParaStruct->EXMC_WriteMode;
temp_STR = (uint32_t)EXMC_NORSRAMInitParaStruct->EXMC_ReadWriteTimingParaStruct->EXMC_AsynAddressSetupTime |
(EXMC_NORSRAMInitParaStruct->EXMC_ReadWriteTimingParaStruct->EXMC_AsynAddressHoldTime << STR_AHT_OFFSET) |
(EXMC_NORSRAMInitParaStruct->EXMC_ReadWriteTimingParaStruct->EXMC_AsynDataSetupTime << STR_DST_OFFSET) |
(EXMC_NORSRAMInitParaStruct->EXMC_ReadWriteTimingParaStruct->EXMC_BusLatency << STR_BUSLAT_OFFSET) |
(EXMC_NORSRAMInitParaStruct->EXMC_ReadWriteTimingParaStruct->EXMC_SynCLKDivision << STR_CDIV_OFFSET) |
(EXMC_NORSRAMInitParaStruct->EXMC_ReadWriteTimingParaStruct->EXMC_SynDataLatency << STR_DLAT_OFFSET) |
EXMC_NORSRAMInitParaStruct->EXMC_ReadWriteTimingParaStruct->EXMC_AsynAccessMode;
if (EXMC_NORSRAMInitParaStruct->EXMC_MemoryType == EXMC_MEMORY_TYPE_NOR) {
temp_SCTLR |= (uint32_t)SCTLR_NOREN_SET;
}
if (EXMC_NORSRAMInitParaStruct->EXMC_ExtendedMode == EXMC_EXTENDED_MODE_ENABLE) {
temp_SWTR = (uint32_t)EXMC_NORSRAMInitParaStruct->EXMC_WriteTimingParaStruct->EXMC_AsynAddressSetupTime |
(EXMC_NORSRAMInitParaStruct->EXMC_WriteTimingParaStruct->EXMC_AsynAddressHoldTime << SWTR_AHT_OFFSET) |
(EXMC_NORSRAMInitParaStruct->EXMC_WriteTimingParaStruct->EXMC_AsynDataSetupTime << SWTR_DST_OFFSET) |
(EXMC_NORSRAMInitParaStruct->EXMC_WriteTimingParaStruct->EXMC_SynCLKDivision << SWTR_CDIV_OFFSET) |
(EXMC_NORSRAMInitParaStruct->EXMC_WriteTimingParaStruct->EXMC_SynDataLatency << SWTR_DLAT_OFFSET) |
EXMC_NORSRAMInitParaStruct->EXMC_WriteTimingParaStruct->EXMC_AsynAccessMode;
} else {
temp_SWTR = BANK1_SWTR_RESET;
}
switch (EXMC_NORSRAMInitParaStruct->EXMC_NORSRAMBank) {
case EXMC_BANK1_NORSRAM1: {
/* Bank1 NOR/SRAM Region1 registers configuration */
EXMC_BANK1->SCTLR1 = temp_SCTLR;
EXMC_BANK1->STR1 = temp_STR;
EXMC_BANK1_WT->SWTR1 = temp_SWTR;
break;
}
case EXMC_BANK1_NORSRAM2: {
/* Bank1 NOR/SRAM Region2 registers configuration */
EXMC_BANK1->SCTLR2 = temp_SCTLR;
EXMC_BANK1->STR2 = temp_STR;
EXMC_BANK1_WT->SWTR2 = temp_SWTR;
break;
}
case EXMC_BANK1_NORSRAM3: {
/* Bank1 NOR/SRAM Region3 registers configuration */
EXMC_BANK1->SCTLR3 = temp_SCTLR;
EXMC_BANK1->STR3 = temp_STR;
EXMC_BANK1_WT->SWTR3 = temp_SWTR;
break;
}
case EXMC_BANK1_NORSRAM4: {
/* Bank1 NOR/SRAM Region4 registers configuration */
EXMC_BANK1->SCTLR4 = temp_SCTLR;
EXMC_BANK1->STR4 = temp_STR;
EXMC_BANK1_WT->SWTR4 = temp_SWTR;
break;
}
default:
break;
}
}
/**
* @brief Initialize the EXMC Bank2 or Bank3 NAND parameters.
* @param EXMC_NANDInitParaStruct : the struct EXMC_NANDInitPara pointer
* @retval None
*/
void EXMC_NAND_Init(EXMC_NANDInitPara *EXMC_NANDInitParaStruct)
{
uint32_t temp_CTLR = 0x00000000, temp_COMTR = 0x00000000, temp_ATTR = 0x00000000;
temp_CTLR = (uint32_t)EXMC_NANDInitParaStruct->EXMC_WaitFeature |
CTLR_EMTYP_NAND |
EXMC_NANDInitParaStruct->EXMC_DatabusWidth |
EXMC_NANDInitParaStruct->EXMC_ECCLogic |
EXMC_NANDInitParaStruct->EXMC_ECCSize |
(EXMC_NANDInitParaStruct->EXMC_CTRLatency << CTLR_CTR_OFFSET) |
(EXMC_NANDInitParaStruct->EXMC_ATRLatency << CTLR_ATR_OFFSET);
temp_COMTR = (uint32_t)EXMC_NANDInitParaStruct->EXMC_CommonSpaceTimingParaStruct->EXMC_SetupTime |
(EXMC_NANDInitParaStruct->EXMC_CommonSpaceTimingParaStruct->EXMC_WaitTime << COMTR_COMWT_OFFSET) |
(EXMC_NANDInitParaStruct->EXMC_CommonSpaceTimingParaStruct->EXMC_HoldTime << COMTR_COMHT_OFFSET) |
(EXMC_NANDInitParaStruct->EXMC_CommonSpaceTimingParaStruct->EXMC_DatabusHiZTime << COMTR_COMHIZT_OFFSET);
temp_ATTR = (uint32_t)EXMC_NANDInitParaStruct->EXMC_AttributeSpaceTimingParaStruct->EXMC_SetupTime |
(EXMC_NANDInitParaStruct->EXMC_AttributeSpaceTimingParaStruct->EXMC_WaitTime << ATTR_ATTWT_OFFSET) |
(EXMC_NANDInitParaStruct->EXMC_AttributeSpaceTimingParaStruct->EXMC_HoldTime << ATTR_ATTHT_OFFSET) |
(EXMC_NANDInitParaStruct->EXMC_AttributeSpaceTimingParaStruct->EXMC_DatabusHiZTime << ATTR_ATTHIZT_OFFSET);
if (EXMC_NANDInitParaStruct->EXMC_NANDBank == EXMC_BANK2_NAND) {
/* Configure the EXMC_Bank2 NAND registers using the value of parameters */
EXMC_BANK2->CTLR2 = temp_CTLR;
EXMC_BANK2->COMTR2 = temp_COMTR;
EXMC_BANK2->ATTR2 = temp_ATTR;
} else {
/* EXMC_Bank3_NAND registers configuration */
EXMC_BANK3->CTLR3 = temp_CTLR;
EXMC_BANK3->COMTR3 = temp_COMTR;
EXMC_BANK3->ATTR3 = temp_ATTR;
}
}
/**
* @brief Initialize the EXMC Bank4 PCCARD parameters.
* @param EXMC_PCCARDInitParaStruct : the struct EXMC_PCCARDInitPara pointer.
* @retval None
*/
void EXMC_PCCARD_Init(EXMC_PCCARDInitPara *EXMC_PCCARDInitParaStruct)
{
/* Configure the EXMC_Bank4_PCCARD CTLR4 register using the value of parameters */
EXMC_BANK4->CTLR4 = (uint32_t)EXMC_PCCARDInitParaStruct->EXMC_WaitFeature |
EXMC_DATABUS_WIDTH_16B |
(EXMC_PCCARDInitParaStruct->EXMC_CTRLatency << CTLR_CTR_OFFSET) |
(EXMC_PCCARDInitParaStruct->EXMC_ATRLatency << CTLR_ATR_OFFSET);
/* Configure the EXMC_Bank4_PCCARD COMTR4 register using the value of parameters */
EXMC_BANK4->COMTR4 = (uint32_t)EXMC_PCCARDInitParaStruct->EXMC_CommonSpaceTimingParaStruct->EXMC_SetupTime |
(EXMC_PCCARDInitParaStruct->EXMC_CommonSpaceTimingParaStruct->EXMC_WaitTime << COMTR_COMWT_OFFSET) |
(EXMC_PCCARDInitParaStruct->EXMC_CommonSpaceTimingParaStruct->EXMC_HoldTime << COMTR_COMHT_OFFSET) |
(EXMC_PCCARDInitParaStruct->EXMC_CommonSpaceTimingParaStruct->EXMC_DatabusHiZTime << COMTR_COMHIZT_OFFSET);
/* Configure the EXMC_Bank4_PCCARD ATTR4 register using the value of parameters */
EXMC_BANK4->ATTR4 = (uint32_t)EXMC_PCCARDInitParaStruct->EXMC_AttributeSpaceTimingParaStruct->EXMC_SetupTime |
(EXMC_PCCARDInitParaStruct->EXMC_AttributeSpaceTimingParaStruct->EXMC_WaitTime << ATTR_ATTWT_OFFSET) |
(EXMC_PCCARDInitParaStruct->EXMC_AttributeSpaceTimingParaStruct->EXMC_HoldTime << ATTR_ATTHT_OFFSET) |
(EXMC_PCCARDInitParaStruct->EXMC_AttributeSpaceTimingParaStruct->EXMC_DatabusHiZTime << ATTR_ATTHIZT_OFFSET);
/* Configure the EXMC_Bank4_PCCARD IOTR4 register using the value of parameters */
EXMC_BANK4->IOTR4 = (uint32_t)EXMC_PCCARDInitParaStruct->EXMC_IOSpaceTimingParaStruct->EXMC_SetupTime |
(EXMC_PCCARDInitParaStruct->EXMC_IOSpaceTimingParaStruct->EXMC_WaitTime << IOTR_IOTWT_OFFSET) |
(EXMC_PCCARDInitParaStruct->EXMC_IOSpaceTimingParaStruct->EXMC_HoldTime << IOTR_IOHT_OFFSET) |
(EXMC_PCCARDInitParaStruct->EXMC_IOSpaceTimingParaStruct->EXMC_DatabusHiZTime << IOTR_IOHIZT_OFFSET);
}
/**
* @brief Initialize the struct EXMC_NORSRAMInitPara
* @param EXMC_NORSRAMInitParaStruct: the struct EXMC_NORSRAMInitPara pointer
* @retval None
*/
void EXMC_NORSRAMStruct_Init(EXMC_NORSRAMInitPara *EXMC_NORSRAMInitParaStruct)
{
EXMC_NORSRAMInitParaStruct->EXMC_NORSRAMBank = EXMC_BANK1_NORSRAM1;
EXMC_NORSRAMInitParaStruct->EXMC_AddressDataMux = EXMC_ADDRESS_DATA_MUX_ENABLE;
EXMC_NORSRAMInitParaStruct->EXMC_MemoryType = EXMC_MEMORY_TYPE_SRAM;
EXMC_NORSRAMInitParaStruct->EXMC_DatabusWidth = EXMC_DATABUS_WIDTH_8B;
EXMC_NORSRAMInitParaStruct->EXMC_BurstMode = EXMC_BURST_MODE_DISABLE;
EXMC_NORSRAMInitParaStruct->EXMC_NWAITPolarity = EXMC_NWAIT_POLARITY_LOW;
EXMC_NORSRAMInitParaStruct->EXMC_WrapBurstMode = EXMC_WRAP_BURST_MODE_DISABLE;
EXMC_NORSRAMInitParaStruct->EXMC_NWAITConfig = EXMC_NWAIT_CONFIG_BEFORE;
EXMC_NORSRAMInitParaStruct->EXMC_MemoryWrite = EXMC_MEMORY_WRITE_ENABLE;
EXMC_NORSRAMInitParaStruct->EXMC_NWAITSignal = EXMC_NWAIT_SIGNAL_ENABLE;
EXMC_NORSRAMInitParaStruct->EXMC_ExtendedMode = EXMC_EXTENDED_MODE_DISABLE;
EXMC_NORSRAMInitParaStruct->EXMC_AsynWait = EXMC_ASYN_WAIT_DISABLE;
EXMC_NORSRAMInitParaStruct->EXMC_WriteMode = EXMC_ASYN_WRITE;
EXMC_NORSRAMInitParaStruct->EXMC_ReadWriteTimingParaStruct->EXMC_AsynAddressSetupTime = 0xF;
EXMC_NORSRAMInitParaStruct->EXMC_ReadWriteTimingParaStruct->EXMC_AsynAddressHoldTime = 0xF;
EXMC_NORSRAMInitParaStruct->EXMC_ReadWriteTimingParaStruct->EXMC_AsynDataSetupTime = 0xFF;
EXMC_NORSRAMInitParaStruct->EXMC_ReadWriteTimingParaStruct->EXMC_BusLatency = 0xF;
EXMC_NORSRAMInitParaStruct->EXMC_ReadWriteTimingParaStruct->EXMC_SynCLKDivision = 0xF;
EXMC_NORSRAMInitParaStruct->EXMC_ReadWriteTimingParaStruct->EXMC_SynDataLatency = 0xF;
EXMC_NORSRAMInitParaStruct->EXMC_ReadWriteTimingParaStruct->EXMC_AsynAccessMode = EXMC_ACCESS_MODE_A;
EXMC_NORSRAMInitParaStruct->EXMC_WriteTimingParaStruct->EXMC_AsynAddressSetupTime = 0xF;
EXMC_NORSRAMInitParaStruct->EXMC_WriteTimingParaStruct->EXMC_AsynAddressHoldTime = 0xF;
EXMC_NORSRAMInitParaStruct->EXMC_WriteTimingParaStruct->EXMC_AsynDataSetupTime = 0xFF;
EXMC_NORSRAMInitParaStruct->EXMC_WriteTimingParaStruct->EXMC_BusLatency = 0xF;
EXMC_NORSRAMInitParaStruct->EXMC_WriteTimingParaStruct->EXMC_SynCLKDivision = 0xF;
EXMC_NORSRAMInitParaStruct->EXMC_WriteTimingParaStruct->EXMC_SynDataLatency = 0xF;
EXMC_NORSRAMInitParaStruct->EXMC_WriteTimingParaStruct->EXMC_AsynAccessMode = EXMC_ACCESS_MODE_A;
}
/**
* @brief Initialize the struct EXMC_NANDInitPara
* @param EXMC_NANDInitParaStruct: the struct EXMC_NANDInitPara pointer.
* @retval None
*/
void EXMC_NANDStruct_Init(EXMC_NANDInitPara *EXMC_NANDInitParaStruct)
{
EXMC_NANDInitParaStruct->EXMC_NANDBank = EXMC_BANK2_NAND;
EXMC_NANDInitParaStruct->EXMC_WaitFeature = EXMC_WAIT_FEATURE_DISABLE;
EXMC_NANDInitParaStruct->EXMC_DatabusWidth = EXMC_DATABUS_WIDTH_8B;
EXMC_NANDInitParaStruct->EXMC_ECCLogic = EXMC_ECC_LOGIC_DISABLE;
EXMC_NANDInitParaStruct->EXMC_ECCSize = EXMC_ECC_SIZE_256BYTES;
EXMC_NANDInitParaStruct->EXMC_CTRLatency = 0x0;
EXMC_NANDInitParaStruct->EXMC_ATRLatency = 0x0;
EXMC_NANDInitParaStruct->EXMC_CommonSpaceTimingParaStruct->EXMC_SetupTime = 0xFC;
EXMC_NANDInitParaStruct->EXMC_CommonSpaceTimingParaStruct->EXMC_WaitTime = 0xFC;
EXMC_NANDInitParaStruct->EXMC_CommonSpaceTimingParaStruct->EXMC_HoldTime = 0xFC;
EXMC_NANDInitParaStruct->EXMC_CommonSpaceTimingParaStruct->EXMC_DatabusHiZTime = 0xFC;
EXMC_NANDInitParaStruct->EXMC_AttributeSpaceTimingParaStruct->EXMC_SetupTime = 0xFC;
EXMC_NANDInitParaStruct->EXMC_AttributeSpaceTimingParaStruct->EXMC_WaitTime = 0xFC;
EXMC_NANDInitParaStruct->EXMC_AttributeSpaceTimingParaStruct->EXMC_HoldTime = 0xFC;
EXMC_NANDInitParaStruct->EXMC_AttributeSpaceTimingParaStruct->EXMC_DatabusHiZTime = 0xFC;
}
/**
* @brief Initialize the struct EXMC_PCCARDInitParaStruct
* @param EXMC_PCCARDInitPara: the struct EXMC_PCCARDInitParaStruct pointer.
* @retval None
*/
void EXMC_PCCARDStruct_Init(EXMC_PCCARDInitPara *EXMC_PCCARDInitParaStruct)
{
EXMC_PCCARDInitParaStruct->EXMC_WaitFeature = EXMC_WAIT_FEATURE_DISABLE;
EXMC_PCCARDInitParaStruct->EXMC_CTRLatency = 0x0;
EXMC_PCCARDInitParaStruct->EXMC_ATRLatency = 0x0;
EXMC_PCCARDInitParaStruct->EXMC_CommonSpaceTimingParaStruct->EXMC_SetupTime = 0xFC;
EXMC_PCCARDInitParaStruct->EXMC_CommonSpaceTimingParaStruct->EXMC_WaitTime = 0xFC;
EXMC_PCCARDInitParaStruct->EXMC_CommonSpaceTimingParaStruct->EXMC_HoldTime = 0xFC;
EXMC_PCCARDInitParaStruct->EXMC_CommonSpaceTimingParaStruct->EXMC_DatabusHiZTime = 0xFC;
EXMC_PCCARDInitParaStruct->EXMC_AttributeSpaceTimingParaStruct->EXMC_SetupTime = 0xFC;
EXMC_PCCARDInitParaStruct->EXMC_AttributeSpaceTimingParaStruct->EXMC_WaitTime = 0xFC;
EXMC_PCCARDInitParaStruct->EXMC_AttributeSpaceTimingParaStruct->EXMC_HoldTime = 0xFC;
EXMC_PCCARDInitParaStruct->EXMC_AttributeSpaceTimingParaStruct->EXMC_DatabusHiZTime = 0xFC;
EXMC_PCCARDInitParaStruct->EXMC_IOSpaceTimingParaStruct->EXMC_SetupTime = 0xFC;
EXMC_PCCARDInitParaStruct->EXMC_IOSpaceTimingParaStruct->EXMC_WaitTime = 0xFC;
EXMC_PCCARDInitParaStruct->EXMC_IOSpaceTimingParaStruct->EXMC_HoldTime = 0xFC;
EXMC_PCCARDInitParaStruct->EXMC_IOSpaceTimingParaStruct->EXMC_DatabusHiZTime = 0xFC;
}
/**
* @brief Enable or disable the specified Region of Bank1.
* @param EXMC_NORSRAMBank: specifies the Region of Bank1.
* This parameter can be one of the following values:
* @arg EXMC_BANK1_NORSRAM1: the Region1 of Bank1
* @arg EXMC_BANK1_NORSRAM2: the Region2 of Bank1
* @arg EXMC_BANK1_NORSRAM3: the Region3 of Bank1
* @arg EXMC_BANK1_NORSRAM4: the Region4 of Bank1
* @param NewValue: new value of the specified Region of Bank1.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void EXMC_NORSRAM_Enable(uint32_t EXMC_NORSRAMBank, TypeState NewValue)
{
if (NewValue != DISABLE) {
/* Enable the selected NOR/SRAM Bank by setting the PBKEN bit in the BCRx register */
switch (EXMC_NORSRAMBank) {
case EXMC_BANK1_NORSRAM1:
EXMC_BANK1->SCTLR1 |= SCTLR_BAKEN_SET;
break;
case EXMC_BANK1_NORSRAM2:
EXMC_BANK1->SCTLR2 |= SCTLR_BAKEN_SET;
break;
case EXMC_BANK1_NORSRAM3:
EXMC_BANK1->SCTLR3 |= SCTLR_BAKEN_SET;
break;
case EXMC_BANK1_NORSRAM4:
EXMC_BANK1->SCTLR4 |= SCTLR_BAKEN_SET;
break;
default:
break;
}
} else {
/* Disable the selected NOR/SRAM Bank by clearing the PBKEN bit in the BCRx register */
switch (EXMC_NORSRAMBank) {
case EXMC_BANK1_NORSRAM1:
EXMC_BANK1->SCTLR1 &= SCTLR_BAKEN_RESET;
break;
case EXMC_BANK1_NORSRAM2:
EXMC_BANK1->SCTLR2 &= SCTLR_BAKEN_RESET;
break;
case EXMC_BANK1_NORSRAM3:
EXMC_BANK1->SCTLR3 &= SCTLR_BAKEN_RESET;
break;
case EXMC_BANK1_NORSRAM4:
EXMC_BANK1->SCTLR4 &= SCTLR_BAKEN_RESET;
break;
default:
break;
}
}
}
/**
* @brief Enable or disable the specified NAND Bank2 or Bank3.
* @param EXMC_NANDBank: specifies the NAND Bank.
* This parameter can be one of the following values:
* @arg EXMC_BANK2_NAND: the NAND Bank2
* @arg EXMC_BANK3_NAND: the NAND Bank3
* @param NewValue: new value of the specified Bank.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void EXMC_NAND_Enable(uint32_t EXMC_NANDBank, TypeState NewValue)
{
if (NewValue != DISABLE) {
/* Enable the selected NAND Bank by setting the PBKEN bit in the PCRx register */
if (EXMC_NANDBank == EXMC_BANK2_NAND) {
EXMC_BANK2->CTLR2 |= CTLR_BAKEN_SET;
} else {
EXMC_BANK3->CTLR3 |= CTLR_BAKEN_SET;
}
} else {
/* Disable the selected NAND Bank by clearing the PBKEN bit in the PCRx register */
if (EXMC_NANDBank == EXMC_BANK2_NAND) {
EXMC_BANK2->CTLR2 &= CTLR_BAKEN_RESET;
} else {
EXMC_BANK3->CTLR3 &= CTLR_BAKEN_RESET;
}
}
}
/**
* @brief Enable or disable the Bank4 of PCCARD.
* @param NewValue: new value of the PCCARD Bank.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void EXMC_PCCARD_Enable(TypeState NewValue)
{
if (NewValue != DISABLE) {
/* Enable the PCCARD Bank */
EXMC_BANK4->CTLR4 |= CTLR_BAKEN_SET;
} else {
/* Disable the PCCARD Bank */
EXMC_BANK4->CTLR4 &= CTLR_BAKEN_RESET;
}
}
/**
* @brief Enable or disable the EXMC_CTLR1_ECCEN control bit.
* @param EXMC_NANDBank: specifies the NAND Bank.
* This parameter can be one of the following values:
* @arg EXMC_BANK2_NAND: the NAND Bank2
* @arg EXMC_BANK3_NAND: the NAND Bank3
* @param NewValue: new value of the EXMC Bank2 or Bank3 ECC calculation.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void EXMC_NANDECC_Enable(uint32_t EXMC_NANDBank, TypeState NewValue)
{
if (NewValue != DISABLE) {
/* Enable the selected NAND Bank ECC function by setting the ECCEN bit in the PCRx register */
if (EXMC_NANDBank == EXMC_BANK2_NAND) {
EXMC_BANK2->CTLR2 |= CTLR_ECCEN_SET;
} else {
EXMC_BANK3->CTLR3 |= CTLR_ECCEN_SET;
}
} else {
/* Disable the selected NAND Bank ECC function by clearing the ECCEN bit in the PCRx register */
if (EXMC_NANDBank == EXMC_BANK2_NAND) {
EXMC_BANK2->CTLR2 &= CTLR_ECCEN_RESET;
} else {
EXMC_BANK3->CTLR3 &= CTLR_ECCEN_RESET;
}
}
}
/**
* @brief Get the EXMC_ECCR value.
* @param EXMC_NANDBank: specifies the NAND Bank.
* This parameter can be one of the following values:
* @arg EXMC_BANK2_NAND: the NAND Bank2
* @arg EXMC_BANK3_NAND: the NAND Bank3
* @retval The Error Correction Code (ECC) value.
*/
uint32_t EXMC_GetECC(uint32_t EXMC_NANDBank)
{
if (EXMC_NANDBank == EXMC_BANK2_NAND) {
return (EXMC_BANK2->ECCR2);
} else {
return (EXMC_BANK3->ECCR3);
}
}
/**
* @brief Enable or disable the specified EXMC Bank2/3/4 interrupts.
* @param EXMC_PCNANDBank: specifies the NAND Bank or PCCARD Bank.
* This parameter can be one of the following values:
* @arg EXMC_BANK2_NAND: the NAND Bank2
* @arg EXMC_BANK3_NAND: the NAND Bank3
* @arg EXMC_BANK4_PCCARD: the PCCARD Bank4
* @param EXMC_INT: the EXMC interrupt sources.
* This parameter can be any combination of the following values:
* @arg EXMC_INT_RISE: Rising edge detection interrupt
* @arg EXMC_INT_LEVEL: Level edge detection interrupt
* @arg EXMC_INT_FALL: Falling edge detection interrupt
* @param NewValue: new value of the specified EXMC interrupts.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void EXMC_INTConfig(uint32_t EXMC_PCNANDBank, uint32_t EXMC_INT, TypeState NewValue)
{
if (NewValue != DISABLE) {
/* Enable the specified EXMC_Bank2 interrupts */
if (EXMC_PCNANDBank == EXMC_BANK2_NAND) {
EXMC_BANK2->SIR2 |= EXMC_INT;
}
/* Enable the specified EXMC_Bank3 interrupts */
else if (EXMC_PCNANDBank == EXMC_BANK3_NAND) {
EXMC_BANK3->SIR3 |= EXMC_INT;
}
/* Enable the specified EXMC_Bank4 interrupts */
else {
EXMC_BANK4->SIR4 |= EXMC_INT;
}
} else {
/* Disable the specified EXMC_Bank2 interrupts */
if (EXMC_PCNANDBank == EXMC_BANK2_NAND) {
EXMC_BANK2->SIR2 &= ~((uint32_t)EXMC_INT);
}
/* Disable the specified EXMC_Bank3 interrupts */
else if (EXMC_PCNANDBank == EXMC_BANK3_NAND) {
EXMC_BANK3->SIR3 &= ~((uint32_t)EXMC_INT);
}
/* Disable the specified EXMC_Bank4 interrupts */
else {
EXMC_BANK4->SIR4 &= ~((uint32_t)EXMC_INT);
}
}
}
/**
* @brief Get the bit flag of EXMC_SIRx register.
* @param EXMC_PCNANDBank: specifies the NAND Bank or PCCARD Bank.
* This parameter can be one of the following values:
* @arg EXMC_BANK2_NAND: the NAND Bank2
* @arg EXMC_BANK3_NAND: the NAND Bank3
* @arg EXMC_BANK4_PCCARD: the PCCARD Bank4
* @param EXMC_FLAG: the flag of EXMC_SIRx register.
* This parameter can be one of the following values:
* @arg EXMC_FLAG_RISE: Rising egde detection Flag
* @arg EXMC_FLAG_LEVEL: Level detection Flag
* @arg EXMC_FLAG_FALL: Falling egde detection Flag
* @arg EXMC_FLAG_FIFOE: FIFO empty Flag
* @retval The new value of EXMC_FLAG (SET or RESET).
*/
TypeState EXMC_GetBitState(uint32_t EXMC_PCNANDBank, uint32_t EXMC_FLAG)
{
uint32_t temp_SIR = 0x00000000;
/* the NAND Bank2 */
if (EXMC_PCNANDBank == EXMC_BANK2_NAND) {
temp_SIR = EXMC_BANK2->SIR2;
}
/* the NAND Bank3 */
else if (EXMC_PCNANDBank == EXMC_BANK3_NAND) {
temp_SIR = EXMC_BANK3->SIR3;
}
/* the PCCARD Bank4 */
else {
temp_SIR = EXMC_BANK4->SIR4;
}
if ((temp_SIR & EXMC_FLAG) != (uint16_t)RESET) {
/* EXMC_FLAG is set */
return SET;
} else {
/* EXMC_FLAG is reset */
return RESET;
}
}
/**
* @brief Clear the bit flag of EXMC_SIRx register.
* @param EXMC_PCNANDBank: specifies the NAND Bank or PCCARD Bank.
* This parameter can be one of the following values:
* @arg EXMC_BANK2_NAND: the NAND Bank2
* @arg EXMC_BANK3_NAND: the NAND Bank3
* @arg EXMC_BANK4_PCCARD: the PCCARD Bank4
* @param EXMC_FLAG: the flag of EXMC_SIRx register.
* This parameter can be any combination of the following values:
* @arg EXMC_FLAG_RISE: Rising egde detection Flag
* @arg EXMC_FLAG_LEVEL: Level detection Flag
* @arg EXMC_FLAG_FALL: Falling egde detection Flag
* @retval None
*/
void EXMC_ClearBitState(uint32_t EXMC_PCNANDBank, uint32_t EXMC_FLAG)
{
if (EXMC_PCNANDBank == EXMC_BANK2_NAND) {
EXMC_BANK2->SIR2 &= ~EXMC_FLAG;
} else if (EXMC_PCNANDBank == EXMC_BANK3_NAND) {
EXMC_BANK3->SIR3 &= ~EXMC_FLAG;
}
/* EXMC_Bank4_PCCARD*/
else {
EXMC_BANK4->SIR4 &= ~EXMC_FLAG;
}
}
/**
* @brief Get the interrupt bit flag.
* @param EXMC_PCNANDBank: specifies the NAND Bank or PCCARD Bank.
* This parameter can be one of the following values:
* @arg EXMC_BANK2_NAND: the NAND Bank2
* @arg EXMC_BANK3_NAND: the NAND Bank3
* @arg EXMC_BANK4_PCCARD: the PCCARD Bank4
* @param EXMC_INT: the interrupt bit flag.
* This parameter can be one of the following values:
* @arg EXMC_INT_RISE: Rising edge detection interrupt
* @arg EXMC_INT_LEVEL: Level edge detection interrupt
* @arg EXMC_INT_FALL: Falling edge detection interrupt
* @retval The new value of EXMC_INT (SET or RESET).
*/
TypeState EXMC_GetIntBitState(uint32_t EXMC_PCNANDBank, uint32_t EXMC_INT)
{
uint32_t temp_SIR = 0x00000000, temp_INTState = 0x00000000, temp_INTEnable = 0x00000000;
if (EXMC_PCNANDBank == EXMC_BANK2_NAND) {
temp_SIR = EXMC_BANK2->SIR2;
} else if (EXMC_PCNANDBank == EXMC_BANK3_NAND) {
temp_SIR = EXMC_BANK3->SIR3;
}
/* EXMC_Bank4_PCCARD*/
else {
temp_SIR = EXMC_BANK4->SIR4;
}
temp_INTState = temp_SIR & EXMC_INT;
temp_INTEnable = temp_SIR & (EXMC_INT >> SIR_INTEN_OFFSET);
if ((temp_INTState != (uint32_t)RESET) && (temp_INTEnable != (uint32_t)RESET)) {
return SET;
} else {
return RESET;
}
}
/**
* @brief Clear the interrupt bit flag.
* @param EXMC_PCNANDBank: specifies the NAND Bank or PCCARD Bank.
* This parameter can be one of the following values:
* @arg EXMC_BANK2_NAND: the NAND Bank2
* @arg EXMC_BANK3_NAND: the NAND Bank3
* @arg EXMC_BANK4_PCCARD: the PCCARD Bank4
* @param EXMC_INT: the interrupt bit flag.
* This parameter can be any combination of the following values:
* @arg EXMC_FLAG_RISE: Rising edge detection interrupt
* @arg EXMC_FLAG_LEVEL: Level edge detection interrupt
* @arg EXMC_FLAG_FALL: Falling edge detection interrupt
* @retval None
*/
void EXMC_ClearIntBitState(uint32_t EXMC_PCNANDBank, uint32_t EXMC_INT)
{
if (EXMC_PCNANDBank == EXMC_BANK2_NAND) {
EXMC_BANK2->SIR2 &= ~(EXMC_INT >> SIR_INTEN_OFFSET);
} else if (EXMC_PCNANDBank == EXMC_BANK3_NAND) {
EXMC_BANK3->SIR3 &= ~(EXMC_INT >> SIR_INTEN_OFFSET);
}
/* EXMC_Bank4_PCCARD*/
else {
EXMC_BANK4->SIR4 &= ~(EXMC_INT >> SIR_INTEN_OFFSET);
}
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/

View File

@ -0,0 +1,196 @@
/**
******************************************************************************
* @brief EXTI functions of the firmware library.
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "gd32f10x_exti.h"
/** @addtogroup GD32F10x_Firmware
* @{
*/
/** @defgroup EXTI
* @brief EXTI driver modules
* @{
*/
/** @defgroup EXTI_Private_Defines
* @{
*/
/* No interrupt line is selected */
#define EXTI_LINE_NULL ((uint32_t)0x00000000)
/* ----------------- EXTI Reset Configuration Registers ------------------ */
/* The reset value of EXTI_IER */
#define EXTI_IER_RST ((uint32_t)0x00000000)
/* The reset value of EXTI_EER */
#define EXTI_EER_RST ((uint32_t)0x00000000)
/* The reset value of EXTI_RTE */
#define EXTI_RTE_RST ((uint32_t)0x00000000)
/* The reset value of EXTI_FTE */
#define EXTI_FTE_RST ((uint32_t)0x00000000)
/* The reset value of EXTI_PD */
#define EXTI_PD_RST ((uint32_t)0x000FFFFF)
/**
* @}
*/
/** @defgroup EXTI_Private_Functions
* @{
*/
/**
* @brief Reset the EXTI peripheral registers and the struct EXTI_InitPara.
* @param EXTI_InitParaStruct: the struct EXTI_InitPara pointer.
* @retval None
*/
void EXTI_DeInit(EXTI_InitPara *EXTI_InitParaStruct)
{
/* Reset the EXTI peripheral registers */
EXTI->IER = EXTI_IER_RST;
EXTI->EER = EXTI_EER_RST;
EXTI->RTE = EXTI_RTE_RST;
EXTI->FTE = EXTI_FTE_RST;
EXTI->PD = EXTI_PD_RST;
/* Reset the struct EXTI_InitPara */
EXTI_InitParaStruct->EXTI_LINE = EXTI_LINE_NULL;
EXTI_InitParaStruct->EXTI_Mode = EXTI_Mode_Interrupt;
EXTI_InitParaStruct->EXTI_Trigger = EXTI_Trigger_Falling;
EXTI_InitParaStruct->EXTI_LINEEnable = DISABLE;
}
/**
* @brief Initialize the EXTI peripheral registers.
* @param EXTI_InitParaStruct: the struct EXTI_InitPara pointer.
* @retval None
*/
void EXTI_Init(EXTI_InitPara *EXTI_InitParaStruct)
{
uint32_t temp = 0;
temp = (uint32_t)EXTI_BASE;
if (EXTI_InitParaStruct->EXTI_LINEEnable != DISABLE) {
/* Clear Interrupt and Event from EXTI Lines */
EXTI->IER &= ~EXTI_InitParaStruct->EXTI_LINE;
EXTI->EER &= ~EXTI_InitParaStruct->EXTI_LINE;
temp += EXTI_InitParaStruct->EXTI_Mode;
*(__IO uint32_t *) temp |= EXTI_InitParaStruct->EXTI_LINE;
/* Clear the Rising and Falling edge trigger enable registers */
EXTI->RTE &= ~EXTI_InitParaStruct->EXTI_LINE;
EXTI->FTE &= ~EXTI_InitParaStruct->EXTI_LINE;
/* Select the trigger type for the selected EXTI Lines */
if (EXTI_InitParaStruct->EXTI_Trigger == EXTI_Trigger_Rising_Falling) {
/* Rising and Falling edge trigger are both selected */
EXTI->RTE |= EXTI_InitParaStruct->EXTI_LINE;
EXTI->FTE |= EXTI_InitParaStruct->EXTI_LINE;
} else {
temp = (uint32_t)EXTI_BASE;
temp += EXTI_InitParaStruct->EXTI_Trigger;
*(__IO uint32_t *) temp |= EXTI_InitParaStruct->EXTI_LINE;
}
} else {
temp += EXTI_InitParaStruct->EXTI_Mode;
/* Disable the selected EXTI lines */
*(__IO uint32_t *) temp &= ~EXTI_InitParaStruct->EXTI_LINE;
}
}
/**
* @brief Activate the software interrupt or event request of the selected EXTI Lines.
* @param EXTI_LINE: the selected EXTI lines.
* This parameter can be any combination of EXTI_LINEx where x can be (0..19).
* @retval None
*/
void EXTI_SWINT_Enable(uint32_t EXTI_LINE)
{
/* Enable the software interrupt or event request of the selected EXTI Lines */
EXTI->SIE |= EXTI_LINE;
}
/**
* @brief Get the bit flag of the selected EXTI lines.
* @param EXTI_LINE: the selected EXTI lines.
* This parameter can be any combination of EXTI_LINEx where x can be (0..19).
* @retval The new value of EXTI_LINE (SET or RESET).
*/
TypeState EXTI_GetBitState(uint32_t EXTI_LINE)
{
/* Check and get the selected EXTI lines flag */
if ((EXTI->PD & EXTI_LINE) != (uint32_t)RESET) {
/* EXTI_LINE bit is SET */
return SET;
} else {
/* EXTI_LINE bit is RESET */
return RESET;
}
}
/**
* @brief Clear the bit flag of the selected EXTI lines.
* @param EXTI_LINE: the selected EXTI lines.
* This parameter can be any combination of EXTI_LINEx where x can be (0..19).
* @retval None
*/
void EXTI_ClearBitState(uint32_t EXTI_LINE)
{
/* Clear the bit flag of the selected EXTI lines */
EXTI->PD = EXTI_LINE;
}
/**
* @brief Get the interrupt bit flag of the selected EXTI lines..
* @param EXTI_LINE: the selected EXTI lines.
* This parameter can be any combination of EXTI_LINEx where x can be (0..19).
* @retval The new value of EXTI_LINE (SET or RESET).
*/
TypeState EXTI_GetIntBitState(uint32_t EXTI_LINE)
{
/* Check and get the interrupt source is set or not */
if (((EXTI->PD & EXTI_LINE) != (uint32_t)RESET) && ((EXTI->IER & EXTI_LINE) != (uint32_t)RESET)) {
/* The interrupt bit of EXTI_LINE is SET */
return SET;
} else {
/* The interrupt bit of EXTI_LINE is RESET */
return RESET;
}
}
/**
* @brief Clear the interrupt bit flag of the selected EXTI lines.
* @param EXTI_LINE: the selected EXTI lines.
* This parameter can be any combination of EXTI_LINEx where x can be (0..19).
* @retval None
*/
void EXTI_ClearIntBitState(uint32_t EXTI_LINE)
{
/* Clear the interrupt bit flag of the selected EXTI lines */
EXTI->PD = EXTI_LINE;
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,511 @@
/**
******************************************************************************
* @brief GPIO functions of the firmware library.
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "gd32f10x_gpio.h"
#include "gd32f10x_rcc.h"
/** @addtogroup GD32F10x_Firmware
* @{
*/
/** @defgroup GPIO
* @brief GPIO driver modules
* @{
*/
/** @defgroup GPIO_Private_Defines
* @{
*/
#define ECR_PORTPINCONFIG_MASK ((uint16_t)0xFF80)
#define LSB_MASK ((uint16_t)0xFFFF)
#define DBGAFR_POSITION_MASK ((uint32_t)0x000F0000)
#define DBGAFR_SWJCFG_MASK ((uint32_t)0xF0FFFFFF)
#define DBGAFR_LOCATION_MASK ((uint32_t)0x00200000)
#define DBGAFR_NUMBITS_MASK ((uint32_t)0x00100000)
#define AFIO_PCFR1_MII_RMII ((uint32_t)0x00800000)
#define AFIO_ESSR1_BITS_FIELDS ((uint8_t)0x04)
#define AFIO_ESSR2_BITS_FIELDS ((uint8_t)0x08)
#define AFIO_ESSR3_BITS_FIELDS ((uint8_t)0x0c)
#define AFIO_ESSR_PIN_FIELDS ((uint8_t)0x04)
#define AFIO_ESSR_4BIT_FIELDS ((uint8_t)0x0f)
#define CTLR1_8BIT_FIELDS ((uint32_t)0x00ff)
#define CTLR2_8BIT_FIELDS ((uint32_t)0x00ff)
#define AFIO_PCFR2_FIELDS ((uint32_t)0x80000000)
/**
* @}
*/
/** @defgroup GPIO_Private_Functions
* @{
*/
/**
* @brief Reset the GPIOx peripheral.
* @param GPIOx: where x can be (A..G) to select the GPIO peripheral.
* @retval None
*/
void GPIO_DeInit(GPIO_TypeDef *GPIOx)
{
if (GPIOx == GPIOA) {
/* Enable GPIOA reset state */
RCC_APB2PeriphReset_Enable(RCC_APB2PERIPH_GPIOA, ENABLE);
/* Release GPIOA from reset state */
RCC_APB2PeriphReset_Enable(RCC_APB2PERIPH_GPIOA, DISABLE);
} else if (GPIOx == GPIOB) {
/* Enable GPIOB reset state */
RCC_APB2PeriphReset_Enable(RCC_APB2PERIPH_GPIOB, ENABLE);
/* Release GPIOB from reset state */
RCC_APB2PeriphReset_Enable(RCC_APB2PERIPH_GPIOB, DISABLE);
} else if (GPIOx == GPIOC) {
/* Enable GPIOC reset state */
RCC_APB2PeriphReset_Enable(RCC_APB2PERIPH_GPIOC, ENABLE);
/* Release GPIOC from reset state */
RCC_APB2PeriphReset_Enable(RCC_APB2PERIPH_GPIOC, DISABLE);
} else if (GPIOx == GPIOD) {
/* Enable GPIOD reset state */
RCC_APB2PeriphReset_Enable(RCC_APB2PERIPH_GPIOD, ENABLE);
/* Release GPIOD from reset state */
RCC_APB2PeriphReset_Enable(RCC_APB2PERIPH_GPIOD, DISABLE);
} else if (GPIOx == GPIOE) {
/* Enable GPIOE reset state */
RCC_APB2PeriphReset_Enable(RCC_APB2PERIPH_GPIOE, ENABLE);
/* Release GPIOE from reset state */
RCC_APB2PeriphReset_Enable(RCC_APB2PERIPH_GPIOE, DISABLE);
} else if (GPIOx == GPIOF) {
/* Enable GPIOF reset state */
RCC_APB2PeriphReset_Enable(RCC_APB2PERIPH_GPIOF, ENABLE);
/* Release GPIOF from reset state */
RCC_APB2PeriphReset_Enable(RCC_APB2PERIPH_GPIOF, DISABLE);
} else if (GPIOx == GPIOG) {
/* Enable GPIOG reset state */
RCC_APB2PeriphReset_Enable(RCC_APB2PERIPH_GPIOG, ENABLE);
/* Release GPIOG from reset state */
RCC_APB2PeriphReset_Enable(RCC_APB2PERIPH_GPIOG, DISABLE);
}
}
/**
* @brief Deinitialize the Alternate Functions (remap, event control
* and EXTI configuration) registers to their default reset values.
* @param None
* @retval None
*/
void GPIO_AFDeInit(void)
{
/* Enable AFIO reset state */
RCC_APB2PeriphReset_Enable(RCC_APB2PERIPH_AF, ENABLE);
/* Release AFIO from reset state */
RCC_APB2PeriphReset_Enable(RCC_APB2PERIPH_AF, DISABLE);
}
/**
* @brief Initialize the GPIOx peripheral.
* @param GPIOx: where x can be (A..G) to select the GPIO peripheral.
* @param GPIO_InitStruct: The structuer contains configuration information.
* @retval None
*/
void GPIO_Init(GPIO_TypeDef *GPIOx, GPIO_InitPara *GPIO_InitStruct)
{
uint32_t currentmode = 0x00, currentpin = 0x00, pinpos = 0x00, pos = 0x00;
uint32_t tempreg = 0x00, pinmask = 0x00;
/* GPIO Mode Configuration */
currentmode = ((uint32_t)GPIO_InitStruct->GPIO_Mode) & ((uint32_t)0x0F);
if ((((uint32_t)GPIO_InitStruct->GPIO_Mode) & ((uint32_t)0x10)) != 0x00) {
/* Output mode */
currentmode |= (uint32_t)GPIO_InitStruct->GPIO_Speed;
}
/* GPIO CTLR1 Configuration */
/* Configure the eight low port pins */
if (((uint32_t)GPIO_InitStruct->GPIO_Pin & CTLR1_8BIT_FIELDS) != 0x00) {
tempreg = GPIOx->CTLR1;
for (pinpos = 0x00; pinpos < 0x08; pinpos++) {
pos = ((uint32_t)0x01) << pinpos;
/* Get the port pins position */
currentpin = (GPIO_InitStruct->GPIO_Pin) & pos;
if (currentpin == pos) {
pos = pinpos << 2;
/* Clear the corresponding low control register bits */
pinmask = ((uint32_t)0x0F) << pos;
tempreg &= ~pinmask;
/* Write the mode configuration in the corresponding bits */
tempreg |= (currentmode << pos);
/* Reset the corresponding ODR bit */
if (GPIO_InitStruct->GPIO_Mode == GPIO_MODE_IPD) {
GPIOx->BCR = (((uint32_t)0x01) << pinpos);
} else {
/* Set the corresponding ODR bit */
if (GPIO_InitStruct->GPIO_Mode == GPIO_MODE_IPU) {
GPIOx->BOR = (((uint32_t)0x01) << pinpos);
}
}
}
}
GPIOx->CTLR1 = tempreg;
}
/* GPIO CTLR2 Configuration */
/* Configure the eight high port pins */
if (GPIO_InitStruct->GPIO_Pin > CTLR2_8BIT_FIELDS) {
tempreg = GPIOx->CTLR2;
for (pinpos = 0x00; pinpos < 0x08; pinpos++) {
pos = (((uint32_t)0x01) << (pinpos + 0x08));
/* Get the port pins position */
currentpin = ((GPIO_InitStruct->GPIO_Pin) & pos);
if (currentpin == pos) {
pos = pinpos << 2;
/* Clear the corresponding high control register bits */
pinmask = ((uint32_t)0x0F) << pos;
tempreg &= ~pinmask;
/* Write the mode configuration in the corresponding bits */
tempreg |= (currentmode << pos);
/* Reset the corresponding DOR bit */
if (GPIO_InitStruct->GPIO_Mode == GPIO_MODE_IPD) {
GPIOx->BCR = (((uint32_t)0x01) << (pinpos + 0x08));
}
/* Set the corresponding DOR bit */
if (GPIO_InitStruct->GPIO_Mode == GPIO_MODE_IPU) {
GPIOx->BOR = (((uint32_t)0x01) << (pinpos + 0x08));
}
}
}
GPIOx->CTLR2 = tempreg;
}
}
/**
* @brief Initial GPIO_InitParameter members.
* @param GPIO_InitParameter : pointer to a GPIO_InitPara structure.
* @retval None
*/
void GPIO_ParaInit(GPIO_InitPara *GPIO_InitStruct)
{
/* Reset GPIO init structure parameters values */
GPIO_InitStruct->GPIO_Pin = GPIO_PIN_ALL;
GPIO_InitStruct->GPIO_Speed = GPIO_SPEED_2MHZ;
GPIO_InitStruct->GPIO_Mode = GPIO_MODE_IN_FLOATING;
}
/**
* @brief Read the select input port.
* @param GPIOx: Select the GPIO peripheral.
* @param GPIO_Pin: Select the port.
* @retval The input port pin value.
*/
uint8_t GPIO_ReadInputBit(GPIO_TypeDef *GPIOx, uint16_t GPIO_Pin)
{
uint8_t bitstatus = 0x00;
if ((GPIOx->DIR & GPIO_Pin) != (uint32_t)Bit_RESET) {
bitstatus = (uint8_t)Bit_SET;
} else {
bitstatus = (uint8_t)Bit_RESET;
}
return bitstatus;
}
/**
* @brief Read the specified GPIO input data port.
* @param GPIOx: where x can be (A..G) to select the GPIO peripheral.
* @retval GPIO input data port value.
*/
uint16_t GPIO_ReadInputData(GPIO_TypeDef *GPIOx)
{
return ((uint16_t)GPIOx->DIR);
}
/**
* @brief Read the specified output data port bit.
* @param GPIOx: where x can be (A..G) to select the GPIO peripheral.
* @param GPIO_Pin: where pin can be (GPIO_PIN_0..GPIO_PIN_15) to select the GPIO peripheral.
* @retval The output port pin value.
*/
uint8_t GPIO_ReadOutputBit(GPIO_TypeDef *GPIOx, uint16_t GPIO_Pin)
{
uint8_t bitstatus = 0x00;
if ((GPIOx->DOR & GPIO_Pin) != (uint32_t)Bit_RESET) {
bitstatus = (uint8_t)Bit_SET;
} else {
bitstatus = (uint8_t)Bit_RESET;
}
return bitstatus;
}
/**
* @brief Read the specified GPIO output data port.
* @param GPIOx: where x can be (A..G) to select the GPIO peripheral.
* @retval GPIO output data port value.
*/
uint16_t GPIO_ReadOutputData(GPIO_TypeDef *GPIOx)
{
return ((uint16_t)GPIOx->DOR);
}
/**
* @brief Set the selected data port bits.
* @param GPIOx: where x can be (A..G) to select the GPIO peripheral.
* @param GPIO_Pin: where pin can be (GPIO_PIN_0..GPIO_PIN_15) to select the GPIO peripheral.
* @retval None
*/
void GPIO_SetBits(GPIO_TypeDef *GPIOx, uint16_t GPIO_Pin)
{
GPIOx->BOR = GPIO_Pin;
}
/**
* @brief Clear the selected data port bits.
* @param GPIOx: where x can be (A..G) to select the GPIO peripheral.
* @param GPIO_Pin: where pin can be (GPIO_PIN_0..GPIO_PIN_15) to select the GPIO peripheral.
* @retval None
*/
void GPIO_ResetBits(GPIO_TypeDef *GPIOx, uint16_t GPIO_Pin)
{
GPIOx->BCR = GPIO_Pin;
}
/**
* @brief Set or clear the selected data port bit.
* @param GPIOx: where x can be (A..G) to select the GPIO peripheral.
* @param GPIO_Pin: where pin can be (GPIO_PIN_0..GPIO_PIN_15) to select the GPIO peripheral.
* @param BitVal: specifies the state of the port.Select one of the follwing values :
* @arg Bit_RESET: clear the port pin
* @arg Bit_SET: set the port pin
* @retval None
*/
void GPIO_WriteBit(GPIO_TypeDef *GPIOx, uint16_t GPIO_Pin, BitState BitVal)
{
if (BitVal != Bit_RESET) {
GPIOx->BOR = GPIO_Pin;
} else {
GPIOx->BCR = GPIO_Pin;
}
}
/**
* @brief Write data to the specified GPIO data port.
* @param GPIOx: where x can be (A..G) to select the GPIO peripheral.
* @param PortVal: specifies the value to be written to the port data output register.
* @retval None
*/
void GPIO_WritePort(GPIO_TypeDef *GPIOx, uint16_t PortVal)
{
GPIOx->DOR = PortVal;
}
/**
* @brief Lock GPIO Pins configuration.
* @param GPIOx: where x can be (A..G) to select the GPIO peripheral.
* @param GPIO_Pin: where pin can be (GPIO_PIN_0..GPIO_PIN_15) to select the GPIO peripheral.
* @retval None
*/
void GPIO_PinLockConfig(GPIO_TypeDef *GPIOx, uint16_t GPIO_Pin)
{
uint32_t temp = 0x00010000;
temp |= GPIO_Pin;
/* Set LCKK bit */
GPIOx->LOCKR = temp;
/* Reset LCKK bit */
GPIOx->LOCKR = GPIO_Pin;
/* Set LCKK bit */
GPIOx->LOCKR = temp;
/* Read LCKK bit*/
temp = GPIOx->LOCKR;
/* Read LCKK bit*/
temp = GPIOx->LOCKR;
}
/**
* @brief Select the GPIO pin used as Event output.
* @param GPIO_PortSource: This parameter can be GPIO_PORT_SOURCE_GPIOx where x can be (A..G).
* @param GPIO_PinSource: This parameter can be GPIO_PINSOURCEx where x can be (0..15).
* @retval None
*/
void GPIO_EventOutputConfig(uint8_t GPIO_PortSource, uint8_t GPIO_PinSource)
{
uint32_t temp = 0x00;
temp = AFIO->AFIO_EVR;
/* Clear the PORT[6:4] and PIN[3:0] bits */
temp &= ECR_PORTPINCONFIG_MASK;
temp |= (uint32_t)GPIO_PortSource << 0x04;
temp |= GPIO_PinSource;
AFIO->AFIO_EVR = temp;
}
/**
* @brief Enable or disable the Event Output.
* @param AFIO_Event: AFIO_Event Enable or Disable bit.
* @param NewState: new state of the Event output.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void GPIO_EventOutput_Enable(uint32_t AFIO_Event, TypeState NewState)
{
/* Enable or disable the Event Output */
if (NewState != DISABLE) {
AFIO->AFIO_EVR |= AFIO_ECR_EVOE_SET;
} else {
AFIO->AFIO_EVR &= AFIO_ECR_EVOE_RESET;
}
}
/**
* @brief Change the mapping of the specified pin.
* @param GPIO_Remap: selects the pin to remap.
* This parameter can be one of the following values:
* @arg GPIO_REMAP_SPI1
* @arg GPIO_REMAP_I2C1
* @arg GPIO_REMAP_USART1
* @arg GPIO_REMAP_USART2
* @arg GPIO_PARTIAL_REMAP_USART3
* @arg GPIO_FULL_REMAP_USART3
* @arg GPIO_PARTIAL_REMAP_TIMER1
* @arg GPIO_FULL_REMAP_TIMER1
* @arg GPIO_PARTIAL_REMAP1_TIMER2
* @arg GPIO_PARTIAL_REMAP2_TIMER2
* @arg GPIO_FULL_REMAP_TIMER2
* @arg GPIO_PARTIAL_REMAP_TIMER3
* @arg GPIO_FULL_REMAP_TIMER3
* @arg GPIO_REMAP_TIMER4
* @arg GPIO_REMAP1_CAN1
* @arg GPIO_REMAP2_CAN1
* @arg GPIO_REMAP_PD01
* @arg GPIO_REMAP_TIMER5CH4_LSI
* @arg GPIO_REMAP_ADC1_ETRGINJ
* @arg GPIO_REMAP_ADC1_ETRGREG
* @arg GPIO_REMAP_ADC2_ETRGINJ
* @arg GPIO_REMAP_ADC2_ETRGREG
* @arg GPIO_REMAP_ETH
* @arg GPIO_REMAP_CAN2
* @arg GPIO_REMAP_SWJ_NOJTRST
* @arg GPIO_REMAP_SWJ_JTAGDISABLE
* @arg GPIO_REMAP_SWJ_DISABLE
* @arg GPIO_REMAP_SPI3
* @arg GPIO_REMAP_TIMER2ITR1_PTP_SOF
* @arg GPIO_REMAP_PTP_PPS
* @arg GPIO_REMAP_TIMER15
* @arg GPIO_REMAP_TIMER16
* @arg GPIO_REMAP_TIMER17
* @arg GPIO_REMAP_CEC
* @arg GPIO_REMAP_TIMER1_DMA
* @arg GPIO_REMAP_TIMER9
* @arg GPIO_REMAP_TIMER10
* @arg GPIO_REMAP_TIMER11
* @arg GPIO_REMAP_TIMER13
* @arg GPIO_REMAP_TIMER14
* @arg GPIO_REMAP_EXMC_NADV
* @arg GPIO_REMAP_TIMER67_DAC_DMA
* @arg GPIO_REMAP_TIMER12
* @arg GPIO_REMAP_MISC
* @param NewState: new state of the port pin remapping.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void GPIO_PinRemapConfig(uint32_t GPIO_Remap, TypeState NewState)
{
uint32_t temp = 0x00, temp1 = 0x00, tempreg = 0x00, tempmask = 0x00;
if ((GPIO_Remap & 0x80000000) == 0x80000000) {
tempreg = AFIO->AFIO_PCFR2;
} else {
tempreg = AFIO->AFIO_PCFR1;
}
tempmask = (GPIO_Remap & DBGAFR_POSITION_MASK) >> 0x10;
temp = GPIO_Remap & LSB_MASK;
if ((GPIO_Remap & (DBGAFR_LOCATION_MASK | DBGAFR_NUMBITS_MASK)) == (DBGAFR_LOCATION_MASK | DBGAFR_NUMBITS_MASK)) {
tempreg &= DBGAFR_SWJCFG_MASK;
AFIO->AFIO_PCFR1 &= DBGAFR_SWJCFG_MASK;
} else if ((GPIO_Remap & DBGAFR_NUMBITS_MASK) == DBGAFR_NUMBITS_MASK) {
temp1 = ((uint32_t)0x03) << tempmask;
tempreg &= ~temp1;
tempreg |= ~DBGAFR_SWJCFG_MASK;
} else {
tempreg &= ~(temp << ((GPIO_Remap >> 0x15) * 0x10));
tempreg |= ~DBGAFR_SWJCFG_MASK;
}
if (NewState != DISABLE) {
tempreg |= (temp << ((GPIO_Remap >> 0x15) * 0x10));
}
if ((GPIO_Remap & AFIO_PCFR2_FIELDS) == AFIO_PCFR2_FIELDS) {
AFIO->AFIO_PCFR2 = tempreg;
} else {
AFIO->AFIO_PCFR1 = tempreg;
}
}
/**
* @brief Select the GPIO pin used as EXTI Line.
* @param GPIO_PortSource: selects the GPIO port to be used as source for EXTI lines.
* This parameter can be GPIO_PORT_SOURCE_GPIOx where x can be (A..G).
* @param GPIO_PinSource: specifies the EXTI line to be configured.
* This parameter can be GPIO_PINSOURCEx where x can be (0..15).
* @retval None
*/
void GPIO_EXTILineConfig(uint8_t GPIO_PortSource, uint8_t GPIO_PinSource)
{
uint32_t temp = 0x00;
temp = ((uint32_t)0x0f) << (AFIO_ESSR_PIN_FIELDS * (GPIO_PinSource & (uint8_t)0x03));
/* Select EXTI0->EXTI3 bit */
if (GPIO_PinSource < AFIO_ESSR1_BITS_FIELDS) {
AFIO->AFIO_ESSR1 &= ~temp;
AFIO->AFIO_ESSR1 |= (((uint32_t)GPIO_PortSource) << (AFIO_ESSR_PIN_FIELDS * (GPIO_PinSource & (uint8_t)0x03)));
}
/* Select EXTI4->EXTI7 bit */
else if (GPIO_PinSource < AFIO_ESSR2_BITS_FIELDS) {
AFIO->AFIO_ESSR2 &= ~temp;
AFIO->AFIO_ESSR2 |= (((uint32_t)GPIO_PortSource) << (AFIO_ESSR_PIN_FIELDS * (GPIO_PinSource & (uint8_t)0x03)));
}
/* Select EXTI8->EXTI11 bit */
else if (GPIO_PinSource < AFIO_ESSR3_BITS_FIELDS) {
AFIO->AFIO_ESSR3 &= ~temp;
AFIO->AFIO_ESSR3 |= (((uint32_t)GPIO_PortSource) << (AFIO_ESSR_PIN_FIELDS * (GPIO_PinSource & (uint8_t)0x03)));
}
/* Select EXTI12->EXTI15 bit */
else {
AFIO->AFIO_ESSR4 &= ~temp;
AFIO->AFIO_ESSR4 |= (((uint32_t)GPIO_PortSource) << (AFIO_ESSR_PIN_FIELDS * (GPIO_PinSource & (uint8_t)0x03)));
}
}
/**
* @brief Select the Ethernet media interface.
* @note This function applies only to GD32 Connectivity line devices.
* @param GPIO_ETH_MediaInterface: specifies the Media Interface mode.
* This parameter can be one of the following values:
* @arg GPIO_ETH_MEDIA_INTERFACE_MII: MII mode
* @arg GPIO_ETH_MEDIA_INTERFACE_RMII: RMII mode
* @retval None
*/
void GPIO_ETH_MediaInterfaceConfig(uint32_t GPIO_ETH_MediaInterface)
{
uint32_t temp = 0;
temp = AFIO->AFIO_PCFR1;
/* Clear MII_RMII_SEL bit */
temp &= ~((uint32_t)AFIO_PCFR1_MII_RMII);
/* Configure MII_RMII bit according to GPIO_ETH_MediaInterface value */
temp |= GPIO_ETH_MediaInterface;
/* Store the new value */
AFIO->AFIO_PCFR1 = temp;
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/

View File

@ -0,0 +1,899 @@
/**
******************************************************************************
* @brief I2C functions of the firmware library.
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "gd32f10x_i2c.h"
#include "gd32f10x_rcc.h"
/** @addtogroup GD32F10x_Firmware
* @{
*/
/** @defgroup I2C
* @brief I2C driver modules
* @{
*/
/** @defgroup I2C_Private_Defines
* @{
*/
/* I2C CTLR1_I2CEN mask */
#define CTLR1_I2CEN_SET I2C_CTLR1_I2CEN
#define CTLR1_I2CEN_RESET ((uint16_t)~I2C_CTLR1_I2CEN)
/* I2C CTLR1_GENSTA mask */
#define CTLR1_GENSTA_SET I2C_CTLR1_GENSTA
#define CTLR1_GENSTA_RESET ((uint16_t)~I2C_CTLR1_GENSTA)
/* I2C CTLR1_GENSTP mask */
#define CTLR1_GENSTP_SET I2C_CTLR1_GENSTP
#define CTLR1_GENSTP_RESET ((uint16_t)~I2C_CTLR1_GENSTP)
/* I2C CTLR1_ACKEN mask */
#define CTLR1_ACKEN_SET I2C_CTLR1_ACKEN
#define CTLR1_ACKEN_RESET ((uint16_t)~I2C_CTLR1_ACKEN)
/* I2C CTLR1_GCEN mask */
#define CTLR1_GCEN_SET I2C_CTLR1_GCEN
#define CTLR1_GCEN_RESET ((uint16_t)~I2C_CTLR1_GCEN)
/* I2C CTLR1_SRESET mask */
#define CTLR1_SRESET_SET I2C_CTLR1_SRESET
#define CTLR1_SRESET_RESET ((uint16_t)~I2C_CTLR1_SRESET)
/* I2C CTLR1_SALT mask */
#define CTLR1_SALT_SET I2C_CTLR1_SALT
#define CTLR1_SALT_RESET ((uint16_t)~I2C_CTLR1_SALT)
/* I2C CTLR1_PECTRANS mask */
#define CTLR1_PECTRANS_SET I2C_CTLR1_PECTRANS
#define CTLR1_PECTRANS_RESET ((uint16_t)~I2C_CTLR1_PECTRANS)
/* I2C CTLR1_PECEN mask */
#define CTLR1_PECEN_SET I2C_CTLR1_PECEN
#define CTLR1_PECEN_RESET ((uint16_t)~I2C_CTLR1_PECEN)
/* I2C CTLR1_ARPEN mask */
#define CTLR1_ARPEN_SET I2C_CTLR1_ARPEN
#define CTLR1_ARPEN_RESET ((uint16_t)~I2C_CTLR1_ARPEN)
/* I2C CTLR1_DISSTRC mask */
#define CTLR1_DISSTRC_SET I2C_CTLR1_DISSTRC
#define CTLR1_DISSTRC_RESET ((uint16_t)~I2C_CTLR1_DISSTRC)
/* I2C registers Masks */
#define CTLR1_CLEAR_MASK ((uint16_t)0xFBF5)
/* I2C CTLR2_DMAON mask */
#define CTLR2_DMAON_SET I2C_CTLR2_DMAON
#define CTLR2_DMAON_RESET ((uint16_t)~I2C_CTLR2_DMAON)
/* I2C CTLR2_DMALST mask */
#define CTLR2_DMALST_SET I2C_CTLR2_DMALST
#define CTLR2_DMALST_RESET ((uint16_t)~I2C_CTLR2_DMALST)
/* I2C CTLR2_I2CCLK mask */
#define CTLR2_I2CCLK_RESET ((uint16_t)0xFFC0)
/* I2C I2CCLK_Freq_MAX */
#define I2CCLK_FREQ_MAX I2C_CTLR2_I2CCLK
/* I2C AR1_ADDRESS0 mask */
#define AR1_ADDRESS0_SET I2C_AR1_ADDRESS0
#define AR1_ADDRESS0_RESET ((uint16_t)~I2C_AR1_ADDRESS0)
/* I2C AR2_DUADEN mask */
#define AR2_DUADEN_SET ((uint16_t)0x0001)
#define AR2_DUADEN_RESET ((uint16_t)0xFFFE)
/* I2C AR2_ADDRESS2 mask */
#define AR2_ADDRESS2_RESET ((uint16_t)0xFF01)
/* I2C CLKR_FAST mask */
#define CLKR_FAST_SET ((uint16_t)0x8000)
/* I2C CLKR_CLKC mask */
#define CLKR_CLKC_SET ((uint16_t)0x0FFF)
/* I2C STR_FLAG mask */
#define STR_FLAG_MASK ((uint32_t)0x00FFFFFF)
/* I2C Interrupt Enable mask */
#define INTEN_MASK ((uint32_t)0x07000000)
/**
* @}
*/
/** @defgroup I2C_Private_Functions
* @{
*/
/**
* @brief Reset the I2Cx interface.
* @param I2Cx: the I2C interface where x can be 1 or 2.
* @retval None.
*/
void I2C_DeInit(I2C_TypeDef *I2Cx)
{
if (I2Cx == I2C1) {
/* Enable I2C1 reset state */
RCC_APB1PeriphReset_Enable(RCC_APB1PERIPH_I2C1RST, ENABLE);
/* Release I2C1 from reset state */
RCC_APB1PeriphReset_Enable(RCC_APB1PERIPH_I2C1RST, DISABLE);
} else {
/* Enable I2C2 reset state */
RCC_APB1PeriphReset_Enable(RCC_APB1PERIPH_I2C2RST, ENABLE);
/* Release I2C2 from reset state */
RCC_APB1PeriphReset_Enable(RCC_APB1PERIPH_I2C2RST, DISABLE);
}
}
/**
* @brief Initialize the I2Cx interface parameters.
* @param I2Cx: the I2C interface where x can be 1 or 2.
* @param I2C_InitParaStruct: the sturct I2C_InitPara pointer.
* @retval None.
*/
void I2C_Init(I2C_TypeDef *I2Cx, I2C_InitPara *I2C_InitParaStruct)
{
uint16_t temp = 0, freqrange = 0;
uint16_t result = 0x04;
uint32_t pclk1 = 8000000;
RCC_ClocksPara rcc_clocks;
/* Disable I2C */
I2Cx->CTLR1 &= CTLR1_I2CEN_RESET;
/* CTLR2 */
temp = I2Cx->CTLR2;
/* I2CCLK[5:0] */
temp &= CTLR2_I2CCLK_RESET;
RCC_GetClocksFreq(&rcc_clocks);
pclk1 = rcc_clocks.APB1_Frequency;
freqrange = (uint16_t)(pclk1 / 1000000);
if (freqrange > I2CCLK_FREQ_MAX) {
freqrange = I2CCLK_FREQ_MAX;
}
temp |= freqrange;
I2Cx->CTLR2 = temp;
/* RTR and CLKR */
temp = 0;
if (I2C_InitParaStruct->I2C_BitRate <= 100000) {
/* Standard mode */
result = (uint16_t)(pclk1 / (I2C_InitParaStruct->I2C_BitRate << 1));
if (result < 0x04) {
/* The CLKR.CLKC higher than 0x04 in standard mode*/
result = 0x04;
}
temp |= result;
I2Cx->CLKR = temp;
/* RTR */
if (freqrange >= I2CCLK_FREQ_MAX) {
I2Cx->RTR = I2CCLK_FREQ_MAX;
} else {
I2Cx->RTR = freqrange + 1;
}
} else {
/* Fast mode */
if (I2C_InitParaStruct->I2C_DutyCycle == I2C_DUTYCYCLE_2) {
/* I2C_DutyCycle == 2 */
result = (uint16_t)(pclk1 / (I2C_InitParaStruct->I2C_BitRate * 3));
} else {
/* I2C_DutyCycle == 16/9 */
result = (uint16_t)(pclk1 / (I2C_InitParaStruct->I2C_BitRate * 25));
result |= I2C_DUTYCYCLE_16_9;
}
if ((result & CLKR_CLKC_SET) == 0) {
/* The CLKR.CLKC higher than 0x01 in fast mode*/
result |= (uint16_t)0x0001;
}
temp |= (uint16_t)(result | CLKR_FAST_SET);
/* RTR */
I2Cx->RTR = (uint16_t)(((freqrange * (uint16_t)300) / (uint16_t)1000) + (uint16_t)1);
}
I2Cx->CLKR = temp;
/* CTLR1 */
I2Cx->CTLR1 |= CTLR1_I2CEN_SET;
temp = I2Cx->CTLR1;
temp &= CTLR1_CLEAR_MASK;
temp |= (uint16_t)((uint32_t)I2C_InitParaStruct->I2C_Protocol | CTLR1_ACKEN_SET);
I2Cx->CTLR1 = temp;
/* AR1 */
I2Cx->AR1 = (I2C_InitParaStruct->I2C_AddressingMode | I2C_InitParaStruct->I2C_DeviceAddress);
}
/**
* @brief Initial the sturct I2C_InitPara.
* @param I2C_InitParaStruct: the sturct I2C_InitPara pointer.
* @retval None.
*/
void I2C_ParaInit(I2C_InitPara *I2C_InitParaStruct)
{
I2C_InitParaStruct->I2C_Protocol = I2C_PROTOCOL_I2C;
I2C_InitParaStruct->I2C_DutyCycle = I2C_DUTYCYCLE_2;
I2C_InitParaStruct->I2C_BitRate = 10000;
I2C_InitParaStruct->I2C_AddressingMode = I2C_ADDRESSING_MODE_7BIT;
I2C_InitParaStruct->I2C_DeviceAddress = 0x08;
}
/**
* @brief Enable or disable the I2Cx interface.
* @param I2Cx: the I2C interface where x can be 1 or 2.
* @param NewValue: new value of the I2Cx interface.
* This parameter can be: ENABLE or DISABLE.
* @retval None.
*/
void I2C_Enable(I2C_TypeDef *I2Cx, TypeState NewValue)
{
if (NewValue != DISABLE) {
/* Enable the I2Cx interface */
I2Cx->CTLR1 |= CTLR1_I2CEN_SET;
} else {
/* Disable the I2Cx interface */
I2Cx->CTLR1 &= CTLR1_I2CEN_RESET;
}
}
/**
* @brief Enable or disable the I2Cx DMA requests.
* @param I2Cx: the I2C interface where x can be 1 or 2.
* @param NewValue: new value of the I2C DMA transfer.
* This parameter can be: ENABLE or DISABLE.
* @retval None.
*/
void I2C_DMA_Enable(I2C_TypeDef *I2Cx, TypeState NewValue)
{
if (NewValue != DISABLE) {
/* Enable the I2Cx DMA requests */
I2Cx->CTLR2 |= CTLR2_DMAON_SET;
} else {
/* Disable the I2Cx DMA requests */
I2Cx->CTLR2 &= CTLR2_DMAON_RESET;
}
}
/**
* @brief Enable or disable the DMA last.
* @param I2Cx: the I2C interface where x can be 1 or 2.
* @param NewValue: new value of the I2C DMA last transfer.
* This parameter can be: ENABLE or DISABLE.
* @retval None.
*/
void I2C_DMALastTransfer_Enable(I2C_TypeDef *I2Cx, TypeState NewValue)
{
if (NewValue != DISABLE) {
/* Next DMA transfer is the last transfer */
I2Cx->CTLR2 |= CTLR2_DMALST_SET;
} else {
/* Next DMA transfer is not the last transfer */
I2Cx->CTLR2 &= CTLR2_DMALST_RESET;
}
}
/**
* @brief Enable or disable I2C_CTLR1_GENSTA control bit.
* @param I2Cx: the I2C interface where x can be 1 or 2.
* @param NewValue: new value of the I2C START condition generation.
* This parameter can be: ENABLE or DISABLE.
* @retval None.
*/
void I2C_StartOnBus_Enable(I2C_TypeDef *I2Cx, TypeState NewValue)
{
if (NewValue != DISABLE) {
/* Enable I2C_CTLR1_GENSTA control bit */
I2Cx->CTLR1 |= CTLR1_GENSTA_SET;
} else {
/* Disable I2C_CTLR1_GENSTA control bit */
I2Cx->CTLR1 &= CTLR1_GENSTA_RESET;
}
}
/**
* @brief Enable or disable I2C_CTLR1_GENSTP control bit.
* @param I2Cx: the I2C interface where x can be 1 or 2.
* @param NewValue: new value of the I2C STOP condition generation.
* This parameter can be: ENABLE or DISABLE.
* @retval None.
*/
void I2C_StopOnBus_Enable(I2C_TypeDef *I2Cx, TypeState NewValue)
{
if (NewValue != DISABLE) {
/* Enable I2C_CTLR1_GENSTP control bit */
I2Cx->CTLR1 |= CTLR1_GENSTP_SET;
} else {
/* Disable I2C_CTLR1_GENSTP control bit */
I2Cx->CTLR1 &= CTLR1_GENSTP_RESET;
}
}
/**
* @brief Enable or disable the I2C_CTLR1_ACKEN control bit.
* @param I2Cx: the I2C interface where x can be 1 or 2.
* @param NewValue: new value of the I2C Acknowledgement.
* This parameter can be: ENABLE or DISABLE.
* @retval None.
*/
void I2C_Acknowledge_Enable(I2C_TypeDef *I2Cx, TypeState NewValue)
{
if (NewValue != DISABLE) {
/* Enable I2C_CTLR1_ACKEN control bit */
I2Cx->CTLR1 |= CTLR1_ACKEN_SET;
} else {
/* Disable I2C_CTLR1_ACKEN control bit */
I2Cx->CTLR1 &= CTLR1_ACKEN_RESET;
}
}
/**
* @brief Set the I2Cx own address2.
* @param I2Cx: the I2C interface where x can be 1 or 2.
* @param Address: specifies the 7bit I2C own address2.
* @retval None.
*/
void I2C_OwnAddress2(I2C_TypeDef *I2Cx, uint8_t Address)
{
uint16_t temp = 0;
temp = I2Cx->AR2;
temp &= AR2_ADDRESS2_RESET;
temp |= (uint16_t)((uint16_t)Address & (uint16_t)0x00FE);
/* I2C_AR2_ADDRESS2 */
I2Cx->AR2 = temp;
}
/**
* @brief Enable or disable the I2C_AR2_DUADEN control bit.
* @param I2Cx: the I2C interface where x can be 1 or 2.
* @param NewValue: new value of the I2C dual addressing mode.
* This parameter can be: ENABLE or DISABLE.
* @retval None.
*/
void I2C_DualAddress_Enable(I2C_TypeDef *I2Cx, TypeState NewValue)
{
if (NewValue != DISABLE) {
/* Enable the I2C_AR2_DUADEN control bit */
I2Cx->AR2 |= AR2_DUADEN_SET;
} else {
/* Disable the I2C_AR2_DUADEN control bit */
I2Cx->AR2 &= AR2_DUADEN_RESET;
}
}
/**
* @brief Enable or disable I2C_CTLR1_GCEN control bit.
* @param I2Cx: the I2C interface where x can be 1 or 2.
* @param NewValue: new value of the I2C General call.
* This parameter can be: ENABLE or DISABLE.
* @retval None.
*/
void I2C_GeneralCall_Enable(I2C_TypeDef *I2Cx, TypeState NewValue)
{
if (NewValue != DISABLE) {
/* Enable I2C_CTLR1_GCEN control bit */
I2Cx->CTLR1 |= CTLR1_GCEN_SET;
} else {
/* Disable I2C_CTLR1_GCEN control bit */
I2Cx->CTLR1 &= CTLR1_GCEN_RESET;
}
}
/**
* @brief Enable or disable the specified I2C interrupt.
* @param I2Cx: the I2C interface where x can be 1 or 2.
* @param I2C_INT: the I2C interrupt sources.
* This parameter can be any combination of the following values:
* @arg I2C_INT_EIE: Error interrupt
* @arg I2C_INT_EE: Event interrupt
* @arg I2C_INT_BIE: Buffer interrupt
* @param NewValue: new value of the specified I2C interrupts.
* This parameter can be: ENABLE or DISABLE.
* @retval None.
*/
void I2C_INTConfig(I2C_TypeDef *I2Cx, uint16_t I2C_INT, TypeState NewValue)
{
if (NewValue != DISABLE) {
/* Enable the I2C interrupt */
I2Cx->CTLR2 |= I2C_INT;
} else {
/* Disable the I2C interrupt */
I2Cx->CTLR2 &= (uint16_t)~I2C_INT;
}
}
/**
* @brief Send one byte to bus.
* @param I2Cx: the I2C interface where x can be 1 or 2.
* @param Data: Byte to be transmitted.
* @retval None.
*/
void I2C_SendData(I2C_TypeDef *I2Cx, uint8_t Data)
{
/* Write Data to DTR */
I2Cx->DTR = Data;
}
/**
* @brief Receive one byte from the bus.
* @param I2Cx: the I2C interface where x can be 1 or 2.
* @retval The received data.
*/
uint8_t I2C_ReceiveData(I2C_TypeDef *I2Cx)
{
/* Read the DTR register */
return (uint8_t)I2Cx->DTR;
}
/**
* @brief Addressing a device on the I2C bus.
* @param I2Cx: the I2C interface where x can be 1 or 2.
* @param Address: the slave device's address.
* @param I2C_Direction: Transmitter or a Receiver.
* This parameter can be one of the following values:
* @arg I2C_DIRECTION_TRANSMITTER: Transmitter mode
* @arg I2C_DIRECTION_RECEIVER: Receiver mode
* @retval None.
*/
void I2C_AddressingDevice_7bit(I2C_TypeDef *I2Cx, uint8_t Address, uint8_t I2C_Direction)
{
if (I2C_Direction != I2C_DIRECTION_TRANSMITTER) {
/* Receiver mode */
Address |= AR1_ADDRESS0_SET;
} else {
/* Transmitter mode */
Address &= AR1_ADDRESS0_RESET;
}
I2Cx->DTR = Address;
}
/**
* @brief Read the I2Cx register.
* @param I2Cx: the I2C interface where x can be 1 or 2.
* @param I2C_Register: the I2Cx register.
* This parameter can be one of the following values:
* @arg I2C_REGISTER_CTLR1: CTLR1 register.
* @arg I2C_REGISTER_CTLR2: CTLR2 register.
* @arg I2C_REGISTER_AR1: AR1 register.
* @arg I2C_REGISTER_AR2: AR2 register.
* @arg I2C_REGISTER_DTR: DTR register.
* @arg I2C_REGISTER_STR1: STR1 register.
* @arg I2C_REGISTER_STR2: STR2 register.
* @arg I2C_REGISTER_CLKR: CLKR register.
* @arg I2C_REGISTER_RTR: RTR register.
* @retval The value of the read register.
*/
uint16_t I2C_ReadRegister(I2C_TypeDef *I2Cx, uint8_t I2C_Register)
{
__IO uint32_t temp = 0;
temp = (uint32_t) I2Cx;
temp += I2C_Register;
/* Return the selected register value */
return (*(__IO uint16_t *) temp);
}
/**
* @brief Enable or disable the I2C_CTLR1_SRESET control bit.
* @param I2Cx: the I2C interface where x can be 1 or 2.
* @param NewValue: new value of the I2C software reset.
* This parameter can be: ENABLE or DISABLE.
* @retval None.
*/
void I2C_SoftwareReset_Enable(I2C_TypeDef *I2Cx, TypeState NewValue)
{
if (NewValue != DISABLE) {
/* Enable I2C_CTLR1_SRESET control bit */
I2Cx->CTLR1 |= CTLR1_SRESET_SET;
} else {
/* Disable I2C_CTLR1_SRESET control bit */
I2Cx->CTLR1 &= CTLR1_SRESET_RESET;
}
}
/**
* @brief Enable or disable the I2C_CTLR1_POAP control bit.
* @param I2Cx: the I2C interface where x can be 1 or 2.
* @param I2C_NACKPosition: the position of NACK.
* This parameter can be one of the following values:
* @arg I2C_NACKPOSITION_NEXT: the next byte is the last received byte
* @arg I2C_NACKPOSITION_CURRENT: the current byte is the last received byte
* @retval None.
*/
void I2C_NACKPosition_Enable(I2C_TypeDef *I2Cx, uint16_t I2C_NACKPosition)
{
if (I2C_NACKPosition == I2C_NACKPOSITION_NEXT) {
/* Next byte will be the last received byte */
I2Cx->CTLR1 |= I2C_NACKPOSITION_NEXT;
} else {
/* Current byte is the last received byte */
I2Cx->CTLR1 &= I2C_NACKPOSITION_CURRENT;
}
}
/**
* @brief Enable or disable the I2C_CTLR1_SALT control bit.
* @param I2Cx: the I2C interface where x can be 1 or 2.
* @param NewValue: new value of the I2C software reset.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void I2C_SMBusAlertSend_Enable(I2C_TypeDef *I2Cx, TypeState NewValue)
{
if (NewValue != DISABLE) {
/* Enable I2C_CTLR1_SALT control bit */
I2Cx->CTLR1 |= CTLR1_SALT_SET;
} else {
/* Disable I2C_CTLR1_SALT control bit */
I2Cx->CTLR1 &= CTLR1_SALT_RESET;
}
}
/**
* @brief Enable or disable the I2C_CTLR1_PECTRANS control bit.
* @param I2Cx: the I2C interface where x can be 1 or 2.
* @param NewValue: new value of the I2C PEC transmission.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void I2C_PECTransmit_Enable(I2C_TypeDef *I2Cx, TypeState NewValue)
{
if (NewValue != DISABLE) {
/* Enable I2C_CTLR1_PECTRANS control bit */
I2Cx->CTLR1 |= CTLR1_PECTRANS_SET;
} else {
/* Disable I2C_CTLR1_PECTRANS control bit */
I2Cx->CTLR1 &= CTLR1_PECTRANS_RESET;
}
}
/**
* @brief Enable or disable the I2C_CTLR1_POAP control bit.
* @param I2Cx: the I2C interface where x can be 1 or 2.
* @param I2C_PECPosition: the position of PEC.
* This parameter can be one of the following values:
* @arg I2C_PECPOSITION_NEXT: the next byte is PEC
* @arg I2C_PECPOSITION_CURRENT: the current byte is PEC
* @retval None.
*/
void I2C_PECPosition_Enable(I2C_TypeDef *I2Cx, uint16_t I2C_PECPosition)
{
if (I2C_PECPosition == I2C_PECPOSITION_NEXT) {
/* The next byte is PEC */
I2Cx->CTLR1 |= I2C_PECPOSITION_NEXT;
} else {
/* The current byte is PEC */
I2Cx->CTLR1 &= I2C_PECPOSITION_CURRENT;
}
}
/**
* @brief Enable or disable the I2C_CTLR1_PECEN control bit.
* @param I2Cx: the I2C interface where x can be 1 or 2.
* @param NewValue: new value of the I2Cx PEC value calculation.
* This parameter can be: ENABLE or DISABLE.
* @retval None.
*/
void I2C_PEC_Enable(I2C_TypeDef *I2Cx, TypeState NewValue)
{
if (NewValue != DISABLE) {
/* Enable I2C_CTLR1_PECEN control bit */
I2Cx->CTLR1 |= CTLR1_PECEN_SET;
} else {
/* Disable I2C_CTLR1_PECEN control bit */
I2Cx->CTLR1 &= CTLR1_PECEN_RESET;
}
}
/**
* @brief The Packet Error Checking value.
* @param I2Cx: the I2C interface where x can be 1 or 2.
* @retval The PEC value.
*/
uint8_t I2C_GetPECValue(I2C_TypeDef *I2Cx)
{
/* I2C_STR2_ECV */
return ((I2Cx->STR2) >> 8);
}
/**
* @brief Enable or disable the I2C_CTLR1_ARPEN control bit.
* @param I2Cx: the I2C interface where x can be 1 or 2.
* @param NewValue: new value of the I2Cx ARP.
* This parameter can be: ENABLE or DISABLE.
* @retval None.
*/
void I2C_ARP_Enable(I2C_TypeDef *I2Cx, TypeState NewValue)
{
if (NewValue != DISABLE) {
/* Enable I2C_CTLR1_ARPEN control bit */
I2Cx->CTLR1 |= CTLR1_ARPEN_SET;
} else {
/* Disable I2C_CTLR1_ARPEN control bit */
I2Cx->CTLR1 &= CTLR1_ARPEN_RESET;
}
}
/**
* @brief Enable or disable the I2C_CTLR1_DISSTRC control bit.
* @param I2Cx: the I2C interface where x can be 1 or 2.
* @param NewValue: new value of the I2Cx Clock stretching.
* This parameter can be: ENABLE or DISABLE.
* @retval None.
*/
void I2C_StretchClock_Enable(I2C_TypeDef *I2Cx, TypeState NewValue)
{
if (NewValue == DISABLE) {
/* Enable I2C_CTLR1_DISSTRC control bit */
I2Cx->CTLR1 |= CTLR1_DISSTRC_SET;
} else {
/* Enable I2C_CTLR1_DISSTRC control bit */
I2Cx->CTLR1 &= CTLR1_DISSTRC_RESET;
}
}
/**
* @brief Enable or disable the I2C_CLKR_DTCY control bit.
* @param I2Cx: the I2C interface where x can be 1 or 2.
* @param I2C_DutyCycle: the duty cycle in fast mode.
* This parameter can be one of the following values:
* @arg I2C_DUTYCYCLE_2: I2C fast mode Tlow/Thigh = 2
* @arg I2C_DUTYCYCLE_16_9: I2C fast mode Tlow/Thigh = 16/9
* @retval None.
*/
void I2C_FastModeDutyCycle(I2C_TypeDef *I2Cx, uint16_t I2C_DutyCycle)
{
if (I2C_DutyCycle != I2C_DUTYCYCLE_16_9) {
/* DutyCycle=2:1 */
I2Cx->CLKR &= I2C_DUTYCYCLE_2;
} else {
/* DutyCycle=16:9 */
I2Cx->CLKR |= I2C_DUTYCYCLE_16_9;
}
}
/**
* @brief Detect I2Cx State Machine.
* @param I2Cx: the I2C interface where x can be 1 or 2.
* @param I2C_State: I2Cx State Machine.
* This parameter can be one of the following values:
* @arg I2C_PROGRAMMINGMODE_SLAVE_TRANSMITTER_ADDSEND
* @arg I2C_PROGRAMMINGMODE_SLAVE_RECEIVER_ADDSEND
* @arg I2C_PROGRAMMINGMODE_SLAVE_TRANSMITTER_SECONDADDRESS_SELECTED
* @arg I2C_PROGRAMMINGMODE_SLAVE_RECEIVER_SECONDADDRESS_SELECTED
* @arg I2C_PROGRAMMINGMODE_SLAVE_GENERALCALLADDRESS_SELECTED
* @arg I2C_PROGRAMMINGMODE_SLAVE_BYTE_RECEIVED
* @arg (I2C_PROGRAMMINGMODE_SLAVE_BYTE_RECEIVED | I2C_FLAG_DUMODF)
* @arg (I2C_PROGRAMMINGMODE_SLAVE_BYTE_RECEIVED | I2C_FLAG_RXGC)
* @arg I2C_PROGRAMMINGMODE_SLAVE_BYTE_TRANSMITTED
* @arg (I2C_PROGRAMMINGMODE_SLAVE_BYTE_TRANSMITTED | I2C_FLAG_DUMODF)
* @arg (I2C_PROGRAMMINGMODE_SLAVE_BYTE_TRANSMITTED | I2C_FLAG_RXGC)
* @arg I2C_PROGRAMMINGMODE_SLAVE_ACK_FAILURE
* @arg I2C_PROGRAMMINGMODE_SLAVE_STOP_DETECTED
* @arg I2C_PROGRAMMINGMODE_MASTER_SBSEND
* @arg I2C_PROGRAMMINGMODE_MASTER_TRANSMITTER_ADDSEND
* @arg I2C_PROGRAMMINGMODE_MASTER_RECEIVER_ADDSEND
* @arg I2C_PROGRAMMINGMODE_MASTER_BYTE_RECEIVED
* @arg I2C_PROGRAMMINGMODE_MASTER_BYTE_TRANSMITTING
* @arg I2C_PROGRAMMINGMODE_MASTER_BYTE_TRANSMITTED
* @arg I2C_PROGRAMMINGMODE_MASTER_ADD10SEND
* @retval The detected result(SUCCESS or ERROR).
*/
TypeState I2C_StateDetect(I2C_TypeDef *I2Cx, uint32_t I2C_State)
{
uint32_t currentstate = 0;
uint32_t flag1 = 0, flag2 = 0;
TypeState state = ERROR;
/* Read the I2Cx status register */
flag1 = I2Cx->STR1;
flag2 = I2Cx->STR2;
flag2 = flag2 << 16;
/* Get the state value from I2C status register */
currentstate = (flag1 | flag2) & STR_FLAG_MASK;
if ((currentstate & I2C_State) == I2C_State) {
/* I2C_State is detected */
state = SUCCESS;
} else {
/* I2C_State is not detected */
state = ERROR;
}
return state;
}
/**
* @brief Get the I2Cx Current State.
* @param I2Cx: the I2C interface where x can be 1 or 2.
* @retval The current state.
*/
uint32_t I2C_GetCurrentState(I2C_TypeDef *I2Cx)
{
uint32_t currentstate = 0;
uint32_t flag1 = 0, flag2 = 0;
/* Read the I2Cx status register */
flag1 = I2Cx->STR1;
flag2 = I2Cx->STR2;
flag2 = flag2 << 16;
/* Get the last event value from I2C status register */
currentstate = (flag1 | flag2) & STR_FLAG_MASK;
return currentstate;
}
/**
* @brief Get the bit flag of STRx registers.
* @param I2Cx: the I2C interface where x can be 1 or 2.
* @param I2C_FLAG: the flag of STRx registers.
* This parameter can be one of the following values:
* @arg I2C_FLAG_DUMODF: Dual flag (Slave mode)
* @arg I2C_FLAG_HSTSMB: SMBus host header (Slave mode)
* @arg I2C_FLAG_DEFSMB: SMBus default header (Slave mode)
* @arg I2C_FLAG_RXGC: General call header flag (Slave mode)
* @arg I2C_FLAG_TRS: Transmitter or Receiver flag
* @arg I2C_FLAG_I2CBSY: Bus busy flag
* @arg I2C_FLAG_MASTER: Master or Slave flag
* @arg I2C_FLAG_SMBALTS: SMBus Alert flag
* @arg I2C_FLAG_SMBTO: Timeout or Tlow error flag
* @arg I2C_FLAG_PECE: PEC error in reception flag
* @arg I2C_FLAG_RXORE: Overrun or Underrun flag (Slave mode)
* @arg I2C_FLAG_AE: Acknowledge failure flag
* @arg I2C_FLAG_LOSTARB: Arbitration lost flag (Master mode)
* @arg I2C_FLAG_BE: Bus error flag
* @arg I2C_FLAG_TBE: Data register empty flag (Transmitter)
* @arg I2C_FLAG_RBNE: Data register not empty (Receiver) flag
* @arg I2C_FLAG_STPSEND: Stop detection flag (Slave mode)
* @arg I2C_FLAG_ADD10SEND: 10-bit header sent flag (Master mode)
* @arg I2C_FLAG_BTC: Byte transfer finished flag
* @arg I2C_FLAG_ADDSEND: Address sent flag (Master mode) or Address matched flag (Slave mode)
* @arg I2C_FLAG_SBSEND: Start bit flag (Master mode)
* @retval The new value of I2C_FLAG (SET or RESET).
*/
TypeState I2C_GetBitState(I2C_TypeDef *I2Cx, uint32_t I2C_FLAG)
{
__IO uint32_t i2creg = 0, i2cxbase = 0;
/* Get the I2Cx peripheral base address */
i2cxbase = (uint32_t)I2Cx;
/* Read flag register index */
i2creg = I2C_FLAG >> 28;
/* Get bit[23:0] of the flag */
I2C_FLAG &= STR_FLAG_MASK;
if (i2creg != 0) {
/* Flag in I2Cx STR1 register */
i2cxbase += 0x14;
} else {
/* Flag in I2Cx STR2 Register */
I2C_FLAG = (uint32_t)(I2C_FLAG >> 16);
/* Get the I2Cx STR2 register address */
i2cxbase += 0x18;
}
if (((*(__IO uint32_t *)i2cxbase) & I2C_FLAG) != (uint32_t)RESET) {
/* I2C_FLAG is set */
return SET;
} else {
/* I2C_FLAG is reset */
return RESET;
}
}
/**
* @brief Clear the bit flag of STRx registers.
* @param I2Cx: the I2C interface where x can be 1 or 2.
* @param I2C_FLAG: the flag of STRx registers.
* This parameter can be any combination of the following values:
* @arg I2C_FLAG_SMBALTS: SMBus Alert flag
* @arg I2C_FLAG_SMBTO: Timeout or Tlow error flag
* @arg I2C_FLAG_PECE: PEC error in reception flag
* @arg I2C_FLAG_RXORE: Overrun or Underrun flag (Slave mode)
* @arg I2C_FLAG_AE: Acknowledge failure flag
* @arg I2C_FLAG_LOSTARB: Arbitration lost flag (Master mode)
* @arg I2C_FLAG_BE: Bus error flag
* @retval None.
*/
void I2C_ClearBitState(I2C_TypeDef *I2Cx, uint32_t I2C_FLAG)
{
uint32_t flagpos = 0;
/* Get the I2C flag position */
flagpos = I2C_FLAG & STR_FLAG_MASK;
/* Clear the selected I2C flag */
I2Cx->STR1 = (uint16_t)~flagpos;
}
/**
* @brief Get the interrupt bit flag.
* @param I2Cx: the I2C interface where x can be 1 or 2.
* @param I2C_INT: the interrupt bit flag.
* This parameter can be one of the following values:
* @arg I2C_INT_SMBALTS: SMBus Alert flag
* @arg I2C_INT_SMBTO: Timeout or Tlow error flag
* @arg I2C_INT_PECE: PEC error in reception flag
* @arg I2C_INT_RXORE: Overrun or Underrun flag (Slave mode)
* @arg I2C_INT_AE: Acknowledge failure flag
* @arg I2C_INT_LOSTARB: Arbitration lost flag (Master mode)
* @arg I2C_INT_BE: Bus error flag
* @arg I2C_INT_TBE: Data register empty flag (Transmitter)
* @arg I2C_INT_RBNE: Data register not empty (Receiver) flag
* @arg I2C_INT_STPSEND: Stop detection flag (Slave mode)
* @arg I2C_INT_ADD10SEND: 10-bit header sent flag (Master mode)
* @arg I2C_INT_BTC: Byte transfer finished flag
* @arg I2C_INT_ADDSEND: Address sent flag (Master mode) or Address matched flag (Slave mode)
* @arg I2C_INT_SBSEND: Start bit flag (Master mode)
* @retval The new value of I2C_INT (SET or RESET).
*/
TypeState I2C_GetIntBitState(I2C_TypeDef *I2Cx, uint32_t I2C_INT)
{
uint32_t enablestatus = 0;
/* Check if the interrupt source is enabled or not */
enablestatus = (uint32_t)(((I2C_INT & INTEN_MASK) >> 16) & (I2Cx->CTLR2)) ;
/* Get bit[23:0] of the flag */
I2C_INT &= STR_FLAG_MASK;
if (((I2Cx->STR1 & I2C_INT) != (uint32_t)RESET) && enablestatus) {
/* I2C_INT is set */
return SET;
} else {
/* I2C_INT is reset */
return RESET;
}
}
/**
* @brief Clear the interrupt bit flag.
* @param I2Cx: the I2C interface where x can be 1 or 2.
* @param I2C_INT: the interrupt bit flag.
* This parameter can be any combination of the following values:
* @arg I2C_INT_SMBALTS: SMBus Alert interrupt
* @arg I2C_INT_SMBTO: Timeout or Tlow error interrupt
* @arg I2C_INT_PECE: PEC error in reception interrupt
* @arg I2C_INT_RXORE: Overrun or Underrun interrupt (Slave mode)
* @arg I2C_INT_AE: Acknowledge failure interrupt
* @arg I2C_INT_LOSTARB: Arbitration lost interrupt (Master mode)
* @arg I2C_INT_BE: Bus error interrupt
* @retval None.
*/
void I2C_ClearIntBitState(I2C_TypeDef *I2Cx, uint32_t I2C_INT)
{
uint32_t flagpos = 0;
/* Get the I2C flag position */
flagpos = I2C_INT & STR_FLAG_MASK;
/* Clear the selected I2C flag */
I2Cx->STR1 = (uint16_t)~flagpos;
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/

View File

@ -0,0 +1,130 @@
/**
******************************************************************************
* @brief IWDG functions of the firmware library.
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "gd32f10x_iwdg.h"
/** @addtogroup GD32F10x_Firmware
* @{
*/
/** @defgroup IWDG
* @brief IWDG driver modules
* @{
*/
/** @defgroup IWDG_Private_Variables
* @{
*/
/* CTLR register bit mask */
#define CTLR_KEY_RELOAD ((uint16_t)0xAAAA)
#define CTLR_KEY_ENABLE ((uint16_t)0xCCCC)
/**
* @}
*/
/** @defgroup IWDG_Private_Functions
* @{
*/
/**
* @brief Enable or disable the IWDG_PSR, IWDG_RLDR and IWDG_WND write protection.
* @param IWDG_WriteAccess: value to enable or disable the write access to registers.
* This parameter can be one of the following values:
* @arg IWDG_WRITEACCESS_ENABLE: Enable write access to IWDG_PSR, IWDG_RLDR and IWDG_WND registers
* @arg IWDG_WRITEACCESS_DISABLE: Disable write access to IWDG_PSR, IWDG_RLDR and IWDG_WND registers
* @retval None
*/
void IWDG_Write_Enable(uint16_t IWDG_WriteAccess)
{
IWDG->CTLR = IWDG_WriteAccess;
}
/**
* @brief Set IWDG prescaler value.
* @param PrescalerValue: IWDG Prescaler value.
* This parameter can be one of the following values:
* @arg IWDG_PRESCALER_4: IWDG prescaler set to 4
* @arg IWDG_PRESCALER_8: IWDG prescaler set to 8
* @arg IWDG_PRESCALER_16: IWDG prescaler set to 16
* @arg IWDG_PRESCALER_32: IWDG prescaler set to 32
* @arg IWDG_PRESCALER_64: IWDG prescaler set to 64
* @arg IWDG_PRESCALER_128: IWDG prescaler set to 128
* @arg IWDG_PRESCALER_256: IWDG prescaler set to 256
* @retval None
*/
void IWDG_SetPrescaler(uint8_t PrescalerValue)
{
IWDG->PSR = PrescalerValue;
}
/**
* @brief Set independent watchdog counter reload value.
* @param ReloadValue: IWDG Reload value.
* This parameter must be between 0 and 0x0FFF.
* @retval None
*/
void IWDG_SetReloadValue(uint16_t ReloadValue)
{
IWDG->RLDR = ReloadValue;
}
/**
* @brief Reload the counter.
* @param None
* @retval None
*/
void IWDG_ReloadCounter(void)
{
IWDG->CTLR = CTLR_KEY_RELOAD;
}
/**
* @brief Start the independent watchdog counter.
* @param None
* @retval None
*/
void IWDG_Enable(void)
{
IWDG->CTLR = CTLR_KEY_ENABLE;
}
/**
* @brief Check registers' bit state.
* @param IWDG_FLAG: the flag to check.
* This parameter can be one of the following values:
* @arg IWDG_BIT_PUD: A write operation to IWDG_PSR register on going
* @arg IWDG_BIT_RUD: A write operation to IWDG_RLDR register on going
* @arg IWDG_BIT_WUD: A write operation to IWDG_WND register on going
* @retval The new state of IWDG_FLAG (SET or RESET).
*/
TypeState IWDG_GetBitState(uint16_t IWDG_FLAG)
{
if ((IWDG->STR & IWDG_FLAG) != (uint32_t)RESET) {
return SET;
} else {
return RESET;
}
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/

View File

@ -0,0 +1,105 @@
/**
******************************************************************************
* @brief MCUDBG functions of the firmware library.
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "gd32f10x_mcudbg.h"
/** @addtogroup GD32F10x_Firmware
* @{
*/
/** @defgroup MCUDBG
* @brief MCUDBG driver modules
* @{
*/
/** @defgroup MCUDBG_Private_Defines
* @{
*/
#define IDCODE_DEVID_MASK ((uint32_t)0x00000FFF)
/**
* @}
*/
/** @defgroup MCUDBG_Private_Functions
* @{
*/
/**
* @brief Returns the device revision identifier.
* @param None
* @retval Device revision identifier
*/
uint32_t MCUDBG_GetREVID(void)
{
return (MCUDBG->IDR >> 16);
}
/**
* @brief Returns the device identifier.
* @param None
* @retval Device identifier
*/
uint32_t MCUDBG_GetDEVID(void)
{
return (MCUDBG->IDR & IDCODE_DEVID_MASK);
}
/**
* @brief Configure the specified peripheral and low power mode behavior
* when the MCU under Debug mode.
* @param MCUDBG_Periph: specifies the peripheral and low power mode.
* This parameter can be any combination of the following values:
* @arg MCUDBG_SLEEP_HOLD: Keep debugger connection during SLEEP mode
* @arg MCUDBG_DEEPSLEEP_HOLD: Keep debugger connection during DEEPSLEEP mode
* @arg MCUDBG_STDBY_HOLD: Keep debugger connection during STANDBY mode
* @arg MCUDBG_IWDG_HOLD: Debug IWDG hold when Core is halted
* @arg MCUDBG_WWDG_HOLD: Debug WWDG hold when Core is halted
* @arg MCUDBG_TIMER1_HOLD: TIMER1 counter hold when Core is halted
* @arg MCUDBG_TIMER2_HOLD: TIMER2 counter hold when Core is halted
* @arg MCUDBG_TIMER3_HOLD: TIMER3 counter hold when Core is halted
* @arg MCUDBG_TIMER4_HOLD: TIMER4 counter hold when Core is halted
* @arg MCUDBG_CAN1_HOLD: Debug CAN1 hold when Core is halted
* @arg MCUDBG_I2C1_HOLD: I2C1 SMBUS timeout mode hold when Core is halted
* @arg MCUDBG_I2C2_HOLD: I2C2 SMBUS timeout mode hold when Core is halted
* @arg MCUDBG_TIMER5_HOLD: TIMER5 counter hold when Core is halted
* @arg MCUDBG_TIMER6_HOLD: TIMER6 counter hold when Core is halted
* @arg MCUDBG_TIMER7_HOLD: TIMER7 counter hold when Core is halted
* @arg MCUDBG_TIMER8_HOLD: TIMER8 counter hold when Core is halted
* @arg MCUDBG_CAN2_HOLD: Debug CAN2 hold when Core is halted
* @arg MCUDBG_TIMER12_HOLD: TIMER12 counter hold when Core is halted
* @arg MCUDBG_TIMER13_HOLD: TIMER13 counter hold when Core is halted
* @arg MCUDBG_TIMER14_HOLD: TIMER14 counter hold when Core is halted
* @arg MCUDBG_TIMER9_HOLD: TIMER9 counter hold when Core is halted
* @arg MCUDBG_TIMER10_HOLD: TIMER10 counter hold when Core is halted
* @arg MCUDBG_TIMER11_HOLD: TIMER11 counter hold when Core is halted
* @param NewState: new state of the specified peripheral in Debug mode.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void MCUDBG_PeriphConfig(uint32_t MCUDBG_Periph, TypeState NewValue)
{
if (NewValue != DISABLE) {
MCUDBG->CTLR |= MCUDBG_Periph;
} else {
MCUDBG->CTLR &= ~MCUDBG_Periph;
}
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/

View File

@ -0,0 +1,136 @@
/**
******************************************************************************
* @brief MISC functions of the firmware library.
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "gd32f10x_misc.h"
/** @addtogroup GD32F10x_Firmware
* @{
*/
/** @defgroup MISC
* @brief MISC driver modules
* @{
*/
/** @defgroup MISC_Private_Defines
* @{
*/
#define AIRCR_VECTKEY_MASK ((uint32_t)0x05FA0000)
/**
* @}
*/
/** @defgroup MISC_Private_Functions
* @{
*/
/**
* @brief By the PRIGROUP[10:8] bits of the AIRCR register, Setting the priority grouping:
* pre-emption priority and subpriority.
* @param NVIC_PriGroup: NVIC_PRIGROUP_0, NVIC_PRIGROUP_1,...NVIC_PRIGROUP_4.
* @retval None
*/
void NVIC_PRIGroup_Enable(uint32_t NVIC_PRIGroup)
{
/* Set the priority grouping value */
SCB->AIRCR = AIRCR_VECTKEY_MASK | NVIC_PRIGroup;
}
/**
* @brief The NVIC peripheral Initialization.
* @param NVIC_InitStruct: a NVIC_InitPara structure pointer.
* @retval None
*/
void NVIC_Init(NVIC_InitPara *NVIC_InitStruct)
{
uint32_t temppriority = 0x00, temppreempt = 0x00, tempsub = 0x00;
if (NVIC_InitStruct->NVIC_IRQEnable != DISABLE) {
if (((SCB->AIRCR) & (uint32_t)0x700) == NVIC_PRIGROUP_0) {
temppreempt = 0;
tempsub = 0x4;
} else if (((SCB->AIRCR) & (uint32_t)0x700) == NVIC_PRIGROUP_1) {
temppreempt = 1;
tempsub = 0x3;
} else if (((SCB->AIRCR) & (uint32_t)0x700) == NVIC_PRIGROUP_2) {
temppreempt = 2;
tempsub = 0x2;
} else if (((SCB->AIRCR) & (uint32_t)0x700) == NVIC_PRIGROUP_3) {
temppreempt = 3;
tempsub = 0x1;
} else if (((SCB->AIRCR) & (uint32_t)0x700) == NVIC_PRIGROUP_4) {
temppreempt = 4;
tempsub = 0x0;
}
temppriority = (uint32_t)NVIC_InitStruct->NVIC_IRQPreemptPriority << (0x4 - temppreempt);
temppriority |= NVIC_InitStruct->NVIC_IRQSubPriority & (0x0F >> (0x4 - tempsub));
temppriority = temppriority << 0x04;
NVIC->IP[NVIC_InitStruct->NVIC_IRQ] = temppriority;
/* Enable the Selected IRQ Channels */
NVIC->ISER[NVIC_InitStruct->NVIC_IRQ >> 0x05] = (uint32_t)0x01 << (NVIC_InitStruct->NVIC_IRQ & (uint8_t)0x1F);
} else {
/* Disable the Selected IRQ Channels */
NVIC->ICER[NVIC_InitStruct->NVIC_IRQ >> 0x05] = (uint32_t)0x01 << (NVIC_InitStruct->NVIC_IRQ & (uint8_t)0x1F);
}
}
/**
* @brief Specify the vector table in RAM or FLASH memory and its Offset.
* @param NVIC_VectTab: NVIC_VECTTAB_RAM,NVIC_VECTTAB_FLASH
* @param Offset: Vector Table start address.
* @retval None
*/
void NVIC_VectTableSet(uint32_t NVIC_VectTab, uint32_t Offset)
{
SCB->VTOR = NVIC_VectTab | (Offset & (uint32_t)0x1FFFFF80);
}
/**
* @brief Specify the state of the system to enter low power mode.
* @param LowPowerMode: NVIC_LOWPOWER_SEVONPEND,NVIC_LOWPOWER_SLEEPDEEP,NVIC_LOWPOWER_SLEEPONEXIT.
* @param NewValue: new value of Low Power state. This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void NVIC_SystemLowPowerConfig(uint8_t LowPowerMode, TypeState NewValue)
{
if (NewValue != DISABLE) {
SCB->SCR |= LowPowerMode;
} else {
SCB->SCR &= (~(uint32_t)LowPowerMode);
}
}
/**
* @brief Specify the SysTick clock source.
* @param SysTick_CKSource: SYSTICK_CKSOURCE_HCLK_DIV8,SYSTICK_CKSOURCE_HCLK.
* @retval None
*/
void SysTick_CKSource_Enable(uint32_t SysTick_CKSource)
{
if (SysTick_CKSource == SYSTICK_CKSOURCE_HCLK) {
SysTick->CTRL |= SYSTICK_CKSOURCE_HCLK;
} else {
SysTick->CTRL &= SYSTICK_CKSOURCE_HCLK_DIV8;
}
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/

View File

@ -0,0 +1,333 @@
/**
******************************************************************************
* @brief PWR functions of the firmware library.
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "gd32f10x_pwr.h"
#include "gd32f10x_rcc.h"
/** @addtogroup GD32F10x_Firmware
* @{
*/
/** @defgroup PWR
* @brief PWR driver modules
* @{
*/
/** @defgroup PWR_Private_Defines
* @{
*/
/* Left shift SBF or WUF(PWR_STR) to SBFR or WUFR(PWR_CTLR) */
#define BIT_SHIFT 2
/**
* @}
*/
/** @defgroup PWR_Private_Functions
* @{
*/
/**
* @brief Reset the PWR peripheral registers.
* @param None
* @retval None
*/
void PWR_DeInit(void)
{
RCC_APB1PeriphReset_Enable(RCC_APB1PERIPH_PWRRST, ENABLE);
RCC_APB1PeriphReset_Enable(RCC_APB1PERIPH_PWRRST, DISABLE);
}
/**
* @brief Enable or disable write access to the registers in Backup domain.
* @note After reset, any write access to the registers in Backup domain is disabled.
* This bit has to be set to enable write access to these registers.
* @param NewValue: New value of write access state to the registers in Backup domain.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void PWR_BackupAccess_Enable(TypeState NewValue)
{
if (NewValue != DISABLE) {
/* Enable the Backup Domain Access */
PWR->CTLR |= PWR_CTLR_BKPWE;
} else {
/* Disable the Backup Domain Access */
PWR->CTLR &= ~((uint32_t)PWR_CTLR_BKPWE);
}
}
/**
* @brief Enable or disable the LVD(Low Voltage Detector), and configure the voltage
* threshold detected by the LVD.
* @note The LVDE bit controls whether LVD is enabled or not, while the LVDT[2:0]
* bits select the LVDT from 2.2V to 2.9V.
* @note The LVD is stopped in Standby mode.
* @param PWR_LVDT: the LVD threshold.
* This parameter can be one of the following values:
* @arg PWR_LVDT_0
* @arg PWR_LVDT_1
* @arg PWR_LVDT_2
* @arg PWR_LVDT_3
* @arg PWR_LVDT_4
* @arg PWR_LVDT_5
* @arg PWR_LVDT_6
* @arg PWR_LVDT_7
* @param NewValue: New value of the LVD state.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void PWR_LVDConfig(uint32_t PWR_LVDT, TypeState NewValue)
{
uint32_t temp = 0;
temp = PWR->CTLR;
/* Clear LVDT[7:5] bits */
temp &= ~((uint32_t)PWR_CTLR_LVDT);
/* Set LVDT[7:5] bits according to PWR_LVDT value */
temp |= PWR_LVDT;
/* Store the new value */
PWR->CTLR = temp;
/* Enable or disable the LVD */
if (NewValue != DISABLE) {
/* Enable the LVD */
PWR->CTLR |= PWR_CTLR_LVDE;
} else {
/* Disable the LVD */
PWR->CTLR &= ~((uint32_t)PWR_CTLR_LVDE);
}
}
/**
* @brief Enable or disable the WakeUp Pin(PA0 pin) function.
* @note If WUPE is set before entering the power saving mode,
* a rising edge on the WKUP Pin wakes up the system from the power
* saving mode. As the WKUP pin is active high, it will setup
* an input pull down mode when this bit is high.
* @param NewValue: New value of the WKUP Pin state.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void PWR_WKUP_Pin_Enable(TypeState NewValue)
{
if (NewValue != DISABLE) {
/* Enable the WKUP pin */
PWR->STR |= PWR_STR_WUPE;
} else {
/* Disable the WKUP pin */
PWR->STR &= ~PWR_STR_WUPE;
}
}
/**
*@verbatim
[..] The GD32F10x series of devices provide three types of power saving modes.
*** Sleep mode ***
==================
[..] The Sleep mode is based on the SLEEPING mode of the Cortex-M3. In Sleep
mode, only clock of Cortex-M3 is off.
(+) Entry:
(++) To enter the Sleep mode, it is only necessary to clear SLEEPDEEP bit
in the Cortex-M3 System Control Register, and execute a WFI or WFE
instruction.
(++) The Sleep mode is entered using the PWR_SLEEPMode_Entry() function.
(+) Wakeup:
(++) Any interrupt for WFI or Any event for WFE.
(+) Wakeup Latency:
(++) None
*** Deep-sleep mode ***
=================
[..] The Deep-sleep mode is based on the SLEEPDEEP mode of the Cortex-M3. In
Deep-sleep mode, all clocks in the 1.2V domain are off, and all of HSI,
HSE and PLL are disabled. The LDO can operate normally or in low
power mode depending on the LDOLP bit in the PWR_CTLR register.
(+) Entry:
(++) Before entering the Deep-sleep mode, it is necessary to set the
SLEEPDEEP bit in the Cortex-M3 System Control Register, and clear
the SDBM bit in the PWR_CTLR register.
(++) The Deep-sleep mode is entered using the PWR_DEEPSLEEPMode_Entry()
function.
(+) Wakeup:
(++) Any interrupt or event from EXTI Lines.
(+) Wakeup Latency:
(++) HSI wakeup time; LDO wakeup time if LDO is in low power mode.
*** Standby mode ***
====================
[..] The Standby mode is based on the SLEEPDEEP mode of the Cortex-M3. In Standby
mode, the whole 1.2V domain is power off, the LDO is shut down, and all of
HSI, HSE and PLL are disabled. Besides, the contents of SRAM and
registers(except Backup Registers) are lost in Standby mode.
(+) Entry:
(++) Before entering the Standby mode, it is necessary to set the
SLEEPDEEP bit in the Cortex-M3 System Control Register, and set
the SDBM bit in the PWR_CTLR register, and clear WUF bit in the
PWR_STR register. .
(++) The Standby mode is entered using the PWR_STDBYMode_Entry() function.
(+) Wakeup:
(++) NRST pin, WKUP pin rising edge, RTC alarm, IWDG reset.
(+) Wakeup Latency:
(++) Power on sequence
*@endverbatim
*/
/**
* @brief Enter Sleep mode.
* @note By default, this function selects the Sleep-now entry mechanism (SLEEPONEXIT = 0).
* @param PWR_SLEEPENTRY: WFI or WFE instruction.
* This parameter can be one of the following values:
* @arg PWR_SLEEPENTRY_WFI: enter Sleep mode with WFI instruction
* @arg PWR_SLEEPENTRY_WFE: enter Sleep mode with WFE instruction
* @retval None
*/
void PWR_SLEEPMode_Entry(uint8_t PWR_SLEEPENTRY)
{
/* Clear SLEEPDEEP bit of Cortex-M3 System Control Register */
SCB->SCR &= ~((uint32_t)SCB_SCR_SLEEPDEEP_Msk);
/* Select WFI or WFE to enter Sleep mode */
if (PWR_SLEEPENTRY == PWR_SLEEPENTRY_WFI) {
__WFI();
} else {
__WFE();
}
}
/**
* @brief Enter Deep-sleep mode.
* @note When exiting Deep-sleep mode, the HSI is selected as the system clock.
* @note An additional wakeup delay will be incurred if the LDO operates in
* low power mode.
* @param PWR_LDO: the LDO state in Deep-sleep mode.
* This parameter can be one of the following values:
* @arg PWR_LDO_ON: Deep-sleep mode with LDO ON
* @arg PWR_LDO_LOWPOWER: Deep-sleep mode with LDO in low power mode
* @param PWR_DEEPSLEEPENTRY: WFI or WFE instruction.
* This parameter can be one of the following values:
* @arg PWR_DEEPSLEEPENTRY_WFI: enter Deep-sleep mode with WFI instruction
* @arg PWR_DEEPSLEEPENTRY_WFE: enter Deep-sleep mode with WFE instruction
* @retval None
*/
void PWR_DEEPSLEEPMode_Entry(uint32_t PWR_LDO, uint8_t PWR_DEEPSLEEPENTRY)
{
uint32_t temp = 0;
/* Select the LDO state in Deep-sleep mode */
temp = PWR->CTLR;
/* Clear SDBM and LDOLP bits, and select Deep-sleep mode */
temp &= ~((uint32_t)(PWR_CTLR_SDBM | PWR_CTLR_LDOLP));
/* Set LDOLP bit according to PWR_LDO value, and select the LDO's state */
temp |= PWR_LDO;
/* Store the new value */
PWR->CTLR = temp;
/* Set SLEEPDEEP bit of Cortex-M3 System Control Register */
SCB->SCR |= SCB_SCR_SLEEPDEEP_Msk;
/* Select WFI or WFE to enter Deep-sleep mode */
if (PWR_DEEPSLEEPENTRY == PWR_DEEPSLEEPENTRY_WFI) {
__WFI();
} else {
__SEV();
__WFE();
__WFE();
}
/* Reset SLEEPDEEP bit of Cortex-M3 System Control Register */
SCB->SCR &= ~((uint32_t)SCB_SCR_SLEEPDEEP_Msk);
}
/**
* @brief Enter Standby mode.
* @note The Standby mode achieves the lowest power consumption, but spends
* longest time to wake up.
* @note When exiting from the Standby mode, a power-on reset occurs and the
* Cortex-M3 will execute instructions code from the 0x0000_0000 address.
* @param PWR_STDBYENTRY: WFI or WFE instruction.
* This parameter can be one of the following values:
* @arg PWR_STDBYENTRY_WFI: enter Standby mode with WFI instruction
* @arg PWR_STDBYENTRY_WFE: enter Standby mode with WFE instruction
* @retval None
*/
void PWR_STDBYMode_Entry(uint8_t PWR_STDBYENTRY)
{
/* Set SLEEPDEEP bit of Cortex-M3 System Control Register */
SCB->SCR |= SCB_SCR_SLEEPDEEP_Msk;
/* Set SDBM bit, and select Standby mode */
PWR->CTLR |= PWR_CTLR_SDBM;
/* Reset Wakeup flag */
PWR->CTLR |= PWR_CTLR_WUFR;
/* Select WFI or WFE to enter Standby mode */
if (PWR_STDBYENTRY == PWR_STDBYENTRY_WFI) {
__WFI();
} else {
__WFE();
}
}
/**
* @brief Get the bit flag of some PWR_STR registers.
* @param PWR_FLAG: the flag of PWR_STR registers.
* This parameter can be one of the following values:
* @arg PWR_FLAG_WKUP: WakeUp flag. This flag indicates that a wakeup
* event was received from the WKUP pin or from the RTC alarm,
* IWDG reset or NRST pin.
* @arg PWR_FLAG_STB: StandBy flag. This flag indicates that the
* system has been in Standby mode.
* @arg PWR_FLAG_LVDF: LVD State flag. This flag is valid only if LVD
* is enabled by the PWR_LVD_Config()function.
* @retval The new value of PWR_FLAG (SET or RESET).
*/
TypeState PWR_GetBitState(uint32_t PWR_FLAG)
{
/* Check and get the selected PWR flag */
if ((PWR->STR & PWR_FLAG) != (uint32_t)RESET) {
/* PWR_FLAG bit is SET */
return SET;
} else {
/* PWR_FLAG bit is RESET */
return RESET;
}
}
/**
* @brief Clear the bit flag of some PWR_STR registers.
* @param PWR_FLAG: the flag of PWR_STR registers.
* This parameter can be one of the following values:
* @arg PWR_FLAG_WKUP: Wake_Up flag
* @arg PWR_FLAG_STB: StandBy flag
* @retval None
*/
void PWR_ClearBitState(uint32_t PWR_FLAG)
{
/* Clear the selected PWR flag */
PWR->CTLR |= PWR_FLAG << BIT_SHIFT;
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,263 @@
/**
******************************************************************************
* @brief RTC functions of the firmware library.
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "gd32f10x_rtc.h"
/** @addtogroup GD32F10x_Firmware
* @{
*/
/** @defgroup RTC
* @brief RTC driver modules
* @{
*/
/** @defgroup RTC_Private_Defines
* @{
*/
/* RTC LSB Mask */
#define RTC_LSB_MASK ((uint32_t)0x0000FFFF)
/* RTC Prescaler MSB Mask */
#define PRL1_MSB_MASK ((uint32_t)0x000F0000)
/**
* @}
*/
/** @defgroup RTC_Private_Functions
* @{
*/
/**
* @brief Enable or disable the specified RTC interrupts.
* @param RTC_INT: specify the RTC interrupt sources
* This parameter can be any combination of the following value:
* @arg RTC_INT_OVI: Overflow event interrupt
* @arg RTC_INT_AI: Alarm event interrupt
* @arg RTC_INT_SI: Tamper event interrupt
* @param NewValue: RTC interrupt state to configure
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void RTC_INT_Enable(uint16_t RTC_INT, TypeState NewValue)
{
if (NewValue == ENABLE) {
/* Enable the interrupts in RTC_CTLR register */
RTC->CTLR1 |= RTC_INT;
} else {
/* Disable the interrupts in RTC_CTLR register */
RTC->CTLR1 &= ~((uint16_t)RTC_INT);
}
}
/**
* @brief Enter the RTC configuration mode.
* @param None
* @retval None
*/
void RTC_EnterConfigMode(void)
{
/* Enter in the Configuration Mode by set the CMF flag */
RTC->CTLR2 |= RTC_CTLR2_CMF;
}
/**
* @brief Exit from the RTC configuration mode.
* @param None
* @retval None
*/
void RTC_ExitConfigMode(void)
{
/* Exit from the Configuration Mode by reset the CMF flag */
RTC->CTLR2 &= ~((uint16_t)RTC_CTLR2_CMF);
}
/**
* @brief Get the RTC counter value.
* @param None
* @retval The value of RTC counter.
*/
uint32_t RTC_GetCounter(void)
{
uint16_t temp = 0;
temp = RTC->CNT2;
return (((uint32_t)RTC->CNT1 << 16) | temp) ;
}
/**
* @brief Set the RTC counter value.
* @param CounterValue: New value of the RTC counter.
* @retval None
*/
void RTC_SetCounter(uint32_t CounterValue)
{
RTC_EnterConfigMode();
/* Set the RTC counter MSB word */
RTC->CNT1 = CounterValue >> 16;
/* Set the RTC counter LSB word */
RTC->CNT2 = (CounterValue & RTC_LSB_MASK);
RTC_ExitConfigMode();
}
/**
* @brief Set the RTC prescaler value.
* @param PrescalerValue: New value of the RTC prescaler.
* @retval None
*/
void RTC_SetPrescaler(uint32_t PrescalerValue)
{
RTC_EnterConfigMode();
/* Set the RTC prescaler MSB word */
RTC->PLR1 = (PrescalerValue & PRL1_MSB_MASK) >> 16;
/* Set the RTC prescaler LSB word */
RTC->PLR2 = (PrescalerValue & RTC_LSB_MASK);
RTC_ExitConfigMode();
}
/**
* @brief Set the RTC alarm value.
* @param AlarmValue: New value of the RTC alarm.
* @retval None
*/
void RTC_SetAlarm(uint32_t AlarmValue)
{
RTC_EnterConfigMode();
/* Set the alarm MSB word */
RTC->ALRMR1 = AlarmValue >> 16;
/* Set the alarm LSB word */
RTC->ALRMR2 = (AlarmValue & RTC_LSB_MASK);
RTC_ExitConfigMode();
}
/**
* @brief Get the RTC divider value.
* @param None
* @retval The value of RTC Divider.
*/
uint32_t RTC_GetDivider(void)
{
uint32_t temp = 0x00;
temp = ((uint32_t)RTC->PREDIV1 & (uint32_t)0x000F) << 16;
temp |= RTC->PREDIV2;
return temp;
}
/**
* @brief Wait until last write operation on RTC registers has finished.
* @note This function must be called before any write to RTC registers.
* @param None
* @retval None
*/
void RTC_WaitLWOFF(void)
{
/* Loop until RTOFF flag is set */
while ((RTC->CTLR2 & RTC_FLAG_LWOFF) == (uint16_t)RESET) {
}
}
/**
* @brief Wait until the RTC registers (RTC_CNT, RTC_ALR and RTC_PRL)
* are synchronized with RTC APB clock.
* @note This function must be called before any read operation after an APB reset
* or an APB clock stop.
* @param None
* @retval None
*/
void RTC_WaitRSF(void)
{
/* Clear RSF flag */
RTC->CTLR2 &= ~((uint16_t)RTC_FLAG_RSF);
/* Loop until RSF flag is set */
while ((RTC->CTLR2 & RTC_FLAG_RSF) == (uint16_t)RESET) {
}
}
/**
* @brief Check whether the specified RTC flag is set or not.
* @param RTC_FLAG: specifie the flag to check.
* This parameter can be one the following values:
* @arg RTC_FLAG_LWOFF: RTC Operation Off flag
* @arg RTC_FLAG_RSF: Registers Synchronized flag
* @arg RTC_FLAG_OVF: Overflow flag
* @arg RTC_FLAG_AF: Alarm flag
* @arg RTC_FLAG_SF: Second flag
* @retval The new bitstate of RTC_FLAG (SET or RESET).
*/
TypeState RTC_GetBitState(uint16_t RTC_FLAG)
{
if ((RTC->CTLR2 & RTC_FLAG) != (uint16_t)RESET) {
return SET;
} else {
return RESET;
}
}
/**
* @brief Clear the RTC's pending flags.
* @param RTC_FLAG: specifie the flag to clear.
* This parameter can be any combination of the following values:
* @arg RTC_FLAG_RSF: Registers Synchronized flag. This flag is cleared only after
* an APB reset or an APB Clock stop.
* @arg RTC_FLAG_OVF: Overflow flag
* @arg RTC_FLAG_AF: Alarm flag
* @arg RTC_FLAG_SF: Second flag
* @retval None
*/
void RTC_ClearBitState(uint16_t RTC_flag)
{
/* Clear the corresponding RTC flag */
RTC->CTLR2 &= ~((uint16_t)RTC_flag);
}
/**
* @brief Check whether the specified RTC interrupt has occurred or not.
* @param RTC_INT: specifie the RTC interrupts sources to check.
* This parameter can be one of the following values:
* @arg RTC_INT_OVI: Overflow event interrupt
* @arg RTC_INT_AI: Alarm event interrupt
* @arg RTC_INT_SI: Tamper event interrupt
* @retval The new state of the RTC_IT (SET or RESET).
*/
TypeState RTC_GetIntBitState(uint16_t RTC_INT)
{
if (((RTC->CTLR1 & RTC_INT) != (uint16_t)RESET) && ((RTC->CTLR2 & RTC_INT) != (uint16_t)RESET)) {
return SET;
} else {
return RESET;
}
}
/**
* @brief Clear the RTC's interrupt bit.
* @param RTC_INT: specifie the interrupt bit to clear.
* This parameter can be any combination of the following values:
* @arg RTC_INT_OVI: Overflow event interrupt
* @arg RTC_INT_AI: Alarm event interrupt
* @arg RTC_INT_SI: Tamper event interrupt
* @retval None
*/
void RTC_ClearIntBitState(uint16_t RTC_INT)
{
/* Clear the RTC's interrupt bitstate */
RTC->CTLR2 &= ~((uint16_t)RTC_INT);
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/

View File

@ -0,0 +1,636 @@
/**
******************************************************************************
* @brief SDIO functions of the firmware library.
******************************************************************************
*/
#ifdef GD32F10X_HD
/* Includes ------------------------------------------------------------------*/
#include "gd32f10x_sdio.h"
#include "gd32f10x_rcc.h"
/** @addtogroup GD32F10x_Firmware
* @{
*/
/** @defgroup SDIO
* @brief SDIO driver modules
* @{
*/
/** @defgroup SDIO_Private_Defines
* @{
*/
/* SDIO registers bit mask */
/* CLKCTLR register mask */
#define CLKCTLR_CLEAR_MASK ((uint32_t)0xFFFF8100)
/* POWER_PWRSTATE mask */
#define POWER_PWRSTATE_MASK ((uint32_t)0xFFFFFFFC)
/* DTCTLR register mask */
#define DTCTLR_CLEAR_MASK ((uint32_t)0xFFFFFF08)
/* CMD register mask */
#define CMD_CLEAR_MASK ((uint32_t)0xFFFFF800)
/* SDIO RESP Registers Address */
#define SDIO_RESP_ADDR ((uint32_t)(SDIO_BASE + 0x14))
/**
* @}
*/
/** @defgroup SDIO_Private_Functions
* @{
*/
/**
* @brief Deinitialize the SDIO .
* @param None
* @retval None
*/
void SDIO_DeInit(void)
{
SDIO->POWER = 0x00000000;
SDIO->CLKCTLR = 0x00000000;
SDIO->PARA = 0x00000000;
SDIO->CMD = 0x00000000;
SDIO->DTTR = 0x00000000;
SDIO->DTLEN = 0x00000000;
SDIO->DTCTLR = 0x00000000;
SDIO->ICR = 0x00C007FF;
SDIO->IER = 0x00000000;
}
/**
* @brief Initialize the SDIO .
* @param SDIO_InitParaStruct : pointer to a SDIO_InitPara structure .
* @retval None
*/
void SDIO_Init(SDIO_InitPara *SDIO_InitParaStruct)
{
uint32_t temp = 0;
/* SDIO CLKCTLR Configuration */
/* Get the SDIO CLKCTLR value */
temp = SDIO->CLKCTLR;
/* Clear CLKCTLR register */
temp &= CLKCTLR_CLEAR_MASK;
/* Configure the SDIO_ClockDiv value */
/* Configure the SDIO_ClockPWRSave value */
/* Configure the SDIO_ClockBypassState value */
/* Configure the SDIO_BusMode value */
/* Configure the SDIO_ClockEdge value */
/* Configure the SDIO_HWFlowCtrlState value */
temp |= (SDIO_InitParaStruct->SDIO_ClockDiv | SDIO_InitParaStruct->SDIO_ClockPWRSave |
SDIO_InitParaStruct->SDIO_ClockBypassState | SDIO_InitParaStruct->SDIO_BusMode |
SDIO_InitParaStruct->SDIO_ClockEdge | SDIO_InitParaStruct->SDIO_HWFlowCtrlState);
/* Update the SDIO CLKCTLR */
SDIO->CLKCTLR = temp;
}
/**
* @brief Fill each SDIO_InitParaStruct Struct member with a default value.
* @param SDIO_InitParaStruct: pointer to an SDIO_InitPara structure.
* @retval None
*/
void SDIO_ParaInit(SDIO_InitPara *SDIO_InitParaStruct)
{
/* Fill the default value */
SDIO_InitParaStruct->SDIO_ClockDiv = 0x00;
SDIO_InitParaStruct->SDIO_ClockEdge = SDIO_CLOCKEDGE_RISING;
SDIO_InitParaStruct->SDIO_ClockBypassState = SDIO_CLOCKBYPASSSTATE_DISABLE;
SDIO_InitParaStruct->SDIO_ClockPWRSave = SDIO_CLOCKPWRSAVE_DISABLE;
SDIO_InitParaStruct->SDIO_BusMode = SDIO_BUSMODE_1B;
SDIO_InitParaStruct->SDIO_HWFlowCtrlState = SDIO_HWFLOWCTRLSTATE_DISABLE;
}
/**
* @brief ENABLE or DISABLE the SDIO Clock.
* @param NewValue: ENABLE or DISABLE.
* @retval None
*/
void SDIO_Clock_Enable(TypeState NewValue)
{
if (NewValue != DISABLE) {
SDIO->CLKCTLR |= SDIO_CLKCTLR_CKEN;
} else {
SDIO->CLKCTLR &= (uint16_t)~(SDIO_CLKCTLR_CKEN);
}
}
/**
* @brief Configure the power state of SDIO.
* @param SDIO_PwrState: new Power state for SDIO.
* This value will be :
* @arg SDIO_PWRSTATE_ON
* @arg SDIO_PWRSTATE_OFF
* @retval None
*/
void SDIO_SetPWRState(uint32_t SDIO_PwrState)
{
/* Update the SDIO POWER */
SDIO->POWER |= SDIO_PwrState;
}
/**
* @brief Get the power state of SDIO.
* @param None
* @retval Power state for SDIO.
* This value will be :
* - 0x00: Power OFF
* - 0x02: Power UP
* - 0x03: Power ON
*/
uint32_t SDIO_GetPWRState(void)
{
return (SDIO->POWER & (~POWER_PWRSTATE_MASK));
}
/**
* @brief Configure interrupts enables.
* @param SDIO_INT: The interrupts sources to configure.
* This value will be :
* @arg SDIO_INT_CCRCFAIL: Command response CRC failed interrupt
* @arg SDIO_INT_DTCRCFAIL: Data CRC failed interrupt
* @arg SDIO_INT_CMDTMOUT: Command response timeout interrupt
* @arg SDIO_INT_DTTMOUT: Data timeout interrupt
* @arg SDIO_INT_TXURE: Transmit FIFO underrun error interrupt
* @arg SDIO_INT_RXORE: Received FIFO overrun error interrupt
* @arg SDIO_INT_CMDREND: Command response received (CRC check passed) interrupt
* @arg SDIO_INT_CMDSENT: Command sent (no response required) interrupt
* @arg SDIO_INT_DTEND: Data end (data counter, SDIDTCNT, is zero) interrupt
* @arg SDIO_INT_STBITE: Start bit not detected on all data signals in wide bus mode interrupt
* @arg SDIO_INT_DTBLKEND: Data block sent/received (CRC check passed) interrupt
* @arg SDIO_INT_CMDRUN: Command transfer in progress interrupt
* @arg SDIO_INT_TXRUN: Data transmit in progress interrupt
* @arg SDIO_INT_RXRUN: Data receive in progress interrupt
* @arg SDIO_INT_TXFIFOHE: Transmit FIFO Half Empty interrupt
* @arg SDIO_INT_RXFIFOHF: Receive FIFO Half Full interrupt
* @arg SDIO_INT_TXFIFOF: Transmit FIFO full interrupt
* @arg SDIO_INT_RXFIFOF: Receive FIFO full interrupt
* @arg SDIO_INT_TXFIFOE: Transmit FIFO empty interrupt
* @arg SDIO_INT_RXFIFOE: Receive FIFO empty interrupt
* @arg SDIO_INT_TXDTVAL: Data valid in transmit FIFO interrupt
* @arg SDIO_INT_RXDTVAL: Data valid in receive FIFO interrupt
* @arg SDIO_INT_SDIOINT: SD I/O interrupt received interrupt
* @arg SDIO_INT_ATAEND: CE-ATA command completion signal received for CMD61 interrupt
* @param NewValue: ENABLE or DISABLE.
* @retval None
*/
void SDIO_INTConfig(uint32_t SDIO_INT, TypeState NewValue)
{
if (NewValue != DISABLE) {
/* Enable the interrupt */
SDIO->IER |= SDIO_INT;
} else {
/* Disable the interrupt */
SDIO->IER &= ~SDIO_INT;
}
}
/**
* @brief Enable or disable the DMA request for SDIO.
* @param NewValue: ENABLE or DISABLE.
* @retval None
*/
void SDIO_DMA_Enable(TypeState NewValue)
{
if (NewValue != DISABLE) {
/* Enable DMA request */
SDIO->DTCTLR |= SDIO_DTCTLR_DMAEN;
} else {
/* Disenable DMA request */
SDIO->DTCTLR &= (uint16_t)~((uint16_t)SDIO_DTCTLR_DMAEN);
}
}
/**
* @brief Initialize the SDIO Command.
* @param SDIO_CmdInitParaStruct : pointer to a SDIO_CmdInitPara structure.
* @retval None
*/
void SDIO_SendCMD(SDIO_CmdInitPara *SDIO_CmdInitParaStruct)
{
uint32_t temp = 0;
/* SDIO PARA Configuration */
/* Configure the SDIO_CMDParameter value */
SDIO->PARA = SDIO_CmdInitParaStruct->SDIO_CMDParameter;
/* SDIO CMD Configuration */
/* Get the SDIO CMD value */
temp = SDIO->CMD;
/* Clear CMD register */
temp &= CMD_CLEAR_MASK;
/* Configure the SDIO_CMDIndex value */
/* Configure the SDIO_ResponseType value */
/* Configure the SDIO_WaitINTState value */
/* Configure the SDIO_CSMState value */
temp |= (uint32_t)SDIO_CmdInitParaStruct->SDIO_CMDIndex | SDIO_CmdInitParaStruct->SDIO_ResponseType
| SDIO_CmdInitParaStruct->SDIO_WaitINTState | SDIO_CmdInitParaStruct->SDIO_CSMState;
/* Update the SDIO CMD */
SDIO->CMD = temp;
}
/**
* @brief Fill SDIO_CmdInitStruct member with a default value.
* @param SDIO_CmdInitParaStruct: pointer to an SDIO_CmdInitPara structure.
* @retval None
*/
void SDIO_CMDParaInit(SDIO_CmdInitPara *SDIO_CmdInitParaStruct)
{
/* Fill the default value */
SDIO_CmdInitParaStruct->SDIO_CMDParameter = 0x00;
SDIO_CmdInitParaStruct->SDIO_CMDIndex = 0x00;
SDIO_CmdInitParaStruct->SDIO_ResponseType = SDIO_RESPONSETYPE_NO ;
SDIO_CmdInitParaStruct->SDIO_WaitINTState = SDIO_WAITINTSTATE_NO;
SDIO_CmdInitParaStruct->SDIO_CSMState = SDIO_CSMSTATE_DISABLE;
}
/**
* @brief Return last response command index.
* @param None
* @retval Return last response command index.
*/
uint8_t SDIO_GetCMDResponse(void)
{
return (uint8_t)(SDIO->RESPCMD);
}
/**
* @brief Return the response for the last received command.
* @param SDIO_RESP: The SDIO response registers.
* This value will be :
* @arg SDIO_RESP1: Response Register 1
* @arg SDIO_RESP2: Response Register 2
* @arg SDIO_RESP3: Response Register 3
* @arg SDIO_RESP4: Response Register 4
* @retval The Corresponding response register value.
*/
uint32_t SDIO_GetResponse(uint32_t SDIO_RESP)
{
__IO uint32_t temp = 0;
temp = SDIO_RESP_ADDR + SDIO_RESP;
return (*(__IO uint32_t *) temp);
}
/**
* @brief Initialize the SDIO SDIO_DataInitParaStruct members.
* @param SDIO_DataInitParaStruct : pointer to a SDIO_DataInitPara structure.
* @retval None
*/
void SDIO_DataConfig(SDIO_DataInitPara *SDIO_DataInitParaStruct)
{
uint32_t temp = 0;
/* SDIO DTTR Configuration */
/* Set the SDIO SDIO_DataTimeOut value */
SDIO->DTTR = SDIO_DataInitParaStruct->SDIO_DataTimeOut;
/* SDIO DTLEN Configuration */
/* Set the SDIO SDIO_DataLength value */
SDIO->DTLEN = SDIO_DataInitParaStruct->SDIO_DataLength;
/* SDIO DTCTLR Configuration */
/* Get the SDIO DTCTLR value */
temp = SDIO->DTCTLR;
/* Clear DTCTLR register */
temp &= DTCTLR_CLEAR_MASK;
/* Configure the SDIO_DataBlockSize value */
/* Configure the SDIO_TransDirection value */
/* Configure the SDIO_TransMode value */
/* Configure the SDIO_DSMState value */
temp |= (uint32_t)SDIO_DataInitParaStruct->SDIO_DataBlockSize | SDIO_DataInitParaStruct->SDIO_TransDirection
| SDIO_DataInitParaStruct->SDIO_TransMode | SDIO_DataInitParaStruct->SDIO_DSMState;
/* Update the SDIO DTCTLR */
SDIO->DTCTLR = temp;
}
/**
* @brief Fill each SDIO_DataInitParaStruct member with a default value.
* @param SDIO_DataInitParaStruct: pointer to an SDIO_DataInitPara structure.
* @retval None
*/
void SDIO_DataParaInit(SDIO_DataInitPara *SDIO_DataInitParaStruct)
{
/* Fill the default value */
SDIO_DataInitParaStruct->SDIO_DataTimeOut = 0xFFFFFFFF;
SDIO_DataInitParaStruct->SDIO_DataLength = 0x00;
SDIO_DataInitParaStruct->SDIO_DataBlockSize = SDIO_DATABLOCKSIZE_1B;
SDIO_DataInitParaStruct->SDIO_TransDirection = SDIO_TRANSDIRECTION_TOCARD;
SDIO_DataInitParaStruct->SDIO_TransMode = SDIO_TRANSMODE_BLOCK;
SDIO_DataInitParaStruct->SDIO_DSMState = SDIO_DSMSTATE_DISABLE;
}
/**
* @brief Return the number of remaining data bytes to be transferred to card.
* @param None
* @retval Number of remaining data bytes to be transferred
*/
uint32_t SDIO_GetDataCount(void)
{
return SDIO->DTCNT;
}
/**
* @brief Read one word from receive FIFO.
* @param None
* @retval Data received
*/
uint32_t SDIO_ReadData(void)
{
return SDIO->FIFO;
}
/**
* @brief Write one word to transmit FIFO.
* @param Data: 32-bit data write to the card.
* @retval None
*/
void SDIO_WriteData(uint32_t Data)
{
SDIO->FIFO = Data;
}
/**
* @brief Return the number of words remaining to be written or read from FIFO.
* @param None
* @retval Remaining number of words.
*/
uint32_t SDIO_GetFIFOCount(void)
{
return SDIO->FIFOCNT;
}
/**
* @brief Start SD I/O Read Wait operation.
* @param NewValue: ENABLE or DISABLE.
* @retval None
*/
void SDIO_StartSDIOReadWait(TypeState NewValue)
{
if (NewValue != DISABLE) {
/* Start Read Wait operation */
SDIO->DTCTLR |= SDIO_DTCTLR_RWSTART;
} else {
SDIO->DTCTLR &= (uint16_t)~((uint16_t)SDIO_DTCTLR_RWSTART);
}
}
/**
* @brief Stop the SD I/O Read Wait operation.
* @param NewValue: ENABLE or DISABLE.
* @retval None
*/
void SDIO_StopSDIOReadWait(TypeState NewValue)
{
if (NewValue != DISABLE) {
SDIO->DTCTLR |= SDIO_DTCTLR_RWSTOP;
} else {
/* Stop Read Wait operation */
SDIO->DTCTLR &= (uint16_t)~((uint16_t)SDIO_DTCTLR_RWSTOP);
}
}
/**
* @brief Configure the SD I/O read wait mode.
* @param SDIO_ReadWaitMode: SD I/O Read Wait operation mode.
* This value will be :
* @arg SDIO_READWAITMODE_CLK: Read Wait operation realize by stopping SDIOCLK
* @arg SDIO_READWAITMODE_DAT2: Read Wait operation use SDIO_DAT2
* @retval None
*/
void SDIO_SetSDIOReadWaitMode(uint32_t SDIO_ReadWaitMode)
{
if (SDIO_ReadWaitMode == SDIO_READWAITMODE_CLK) {
/* Read Wait operation stop SDIOCLK */
SDIO->DTCTLR |= SDIO_DTCTLR_RWMODE;
} else {
/* Read Wait operation use SDIO_DAT2 */
SDIO->DTCTLR &= (uint16_t)~((uint16_t)SDIO_DTCTLR_RWMODE);
}
}
/**
* @brief SD I/O Mode Operation configuration.
* @param NewValue: ENABLE or DISABLE.
* @retval None
*/
void SDIO_SetSDIOOperation(TypeState NewValue)
{
if (NewValue != DISABLE) {
/* Enable I/O Mode Operation */
SDIO->DTCTLR |= SDIO_DTCTLR_SDIOEN;
} else {
/* Disenable I/O Mode Operation */
SDIO->DTCTLR &= (uint16_t)~((uint16_t)SDIO_DTCTLR_SDIOEN);
}
}
/**
* @brief Enable or disable the SD I/O suspend operation.
* @param NewValue: ENABLE or DISABLE.
* @retval None
*/
void SDIO_SendSDIOSuspend_Enable(TypeState NewValue)
{
if (NewValue != DISABLE) {
/* Enable suspend operation */
SDIO->CMD |= SDIO_CMD_SDIOSUSPEND;
} else {
/* Disenable suspend operation */
SDIO->CMD &= (uint16_t)~((uint16_t)SDIO_CMD_SDIOSUSPEND);
}
}
/**
* @brief Enable or disable the CE-ATA command completion signal.
* @param NewValue: ENABLE or DISABLE.
* @retval None
*/
void SDIO_CMDCompletion_Enable(TypeState NewValue)
{
if (NewValue != DISABLE) {
/* Enable CE-ATA command completion signal */
SDIO->CMD |= SDIO_CMD_ENCMDC;
} else {
/* Disenable CE-ATA command completion signal */
SDIO->CMD &= (uint16_t)~((uint16_t)SDIO_CMD_ENCMDC);
}
}
/**
* @brief Enable or disable the CE-ATA interrupt.
* @param NewValue: ENABLE or DISABLE.
* @retval None
*/
void SDIO_CEATAInt_Enable(TypeState NewValue)
{
if (NewValue != ENABLE) {
/* Enable CE-ATA interrupt */
SDIO->CMD |= SDIO_CMD_NIEN;
} else {
/* Disenable CE-ATA interrupt */
SDIO->CMD &= (uint16_t)~((uint16_t)SDIO_CMD_NIEN);
}
}
/**
* @brief Send CE-ATA command (CMD61).
* @param NewValue: ENABLE or DISABLE.
* @retval None
*/
void SDIO_SendCEATA_Enable(TypeState NewValue)
{
if (NewValue != DISABLE) {
SDIO->CMD |= SDIO_CMD_ATACMD;
} else {
SDIO->CMD &= (uint16_t)~((uint16_t)SDIO_CMD_ATACMD);
}
}
/**
* @brief Check whether the flag is set or not.
* @param SDIO_FLAG: the flag to check.
* This value will be :
* @arg SDIO_FLAG_CCRCFAIL: Command response received (CRC failed)
* @arg SDIO_FLAG_DTCRCFAIL: Data block sent/received (CRC failed)
* @arg SDIO_FLAG_CMDTMOUT: Command response timeout
* @arg SDIO_FLAG_DTTMOUT: Data timeout
* @arg SDIO_FLAG_TXURE: Transmit FIFO underrun error
* @arg SDIO_FLAG_RXORE: Received FIFO overrun error
* @arg SDIO_FLAG_CMDREND: Command response received (CRC check passed)
* @arg SDIO_FLAG_CMDSENT: Command sent (no response required)
* @arg SDIO_FLAG_DTEND: Data end (data counter, SDIDTCNT, is zero)
* @arg SDIO_FLAG_STBITE: Start bit not detected on all data signals in wide
* bus mode.
* @arg SDIO_FLAG_DTBLKEND: Data block sent/received (CRC check passed)
* @arg SDIO_FLAG_CMDRUN: Command transfer in progress
* @arg SDIO_FLAG_TXRUN: Data transmit in progress
* @arg SDIO_FLAG_RXRUN: Data receive in progress
* @arg SDIO_FLAG_TXFIFOHE: Transmit FIFO Half Empty
* @arg SDIO_FLAG_RXFIFOHF: Receive FIFO Half Full
* @arg SDIO_FLAG_TXFIFOF: Transmit FIFO full
* @arg SDIO_FLAG_RXFIFOF: Receive FIFO full
* @arg SDIO_FLAG_TXFIFOE: Transmit FIFO empty
* @arg SDIO_FLAG_RXFIFOE: Receive FIFO empty
* @arg SDIO_FLAG_TXDTVAL: Data available in transmit FIFO
* @arg SDIO_FLAG_RXDTVAL: Data available in receive FIFO
* @arg SDIO_FLAG_SDIOINT: SD I/O interrupt received
* @arg SDIO_FLAG_ATAEND: CE-ATA command completion signal received for CMD61
* @retval The new state of SDIO_FLAG (SET or RESET).
*/
TypeState SDIO_GetBitState(uint32_t SDIO_FLAG)
{
if ((SDIO->STR & SDIO_FLAG) != (uint32_t)RESET) {
return SET;
} else {
return RESET;
}
}
/**
* @brief Clear the pending flags.
* @param SDIO_FLAG: the flag to clear.
* This value will be :
* @arg SDIO_FLAG_CCRCFAIL: Command response received (CRC check failed)
* @arg SDIO_FLAG_DTCRCFAIL: Data block sent/received (CRC check failed)
* @arg SDIO_FLAG_CMDTMOUT: Command response timeout
* @arg SDIO_FLAG_DTTMOUT: Data timeout
* @arg SDIO_FLAG_TXURE: Transmit FIFO underrun error
* @arg SDIO_FLAG_RXORE: Received FIFO overrun error
* @arg SDIO_FLAG_CMDREND: Command response received (CRC check passed)
* @arg SDIO_FLAG_CMDSENT: Command sent (no response required)
* @arg SDIO_FLAG_DTEND: Data end (data counter, SDIO_DTCNT, is zero)
* @arg SDIO_FLAG_STBITE: Start bit not detected on all data signals in wide bus mode
* @arg SDIO_FLAG_DTBLKEND: Data block sent/received (CRC check passed)
* @arg SDIO_FLAG_SDIOINT: SD I/O interrupt received
* @arg SDIO_FLAG_ATAEND: CE-ATA command completion signal received for CMD61
* @retval None
*/
void SDIO_ClearBitState(uint32_t SDIO_FLAG)
{
SDIO->ICR = SDIO_FLAG;
}
/**
* @brief Check whether the interrupt is pending or not.
* @param SDIO_INT: the SDIO interrupt source to check.
* This value will be :
* @arg SDIO_INT_CCRCFAIL: Command response received (CRC check failed) interrupt
* @arg SDIO_INT_DTCRCFAIL: Data block sent/received (CRC check failed) interrupt
* @arg SDIO_INT_CMDTMOUT: Command response timeout interrupt
* @arg SDIO_INT_DTTMOUT: Data timeout interrupt
* @arg SDIO_INT_TXURE: Transmit FIFO underrun error interrupt
* @arg SDIO_INT_RXORE: Received FIFO overrun error interrupt
* @arg SDIO_INT_CMDREND: Command response received (CRC check passed) interrupt
* @arg SDIO_INT_CMDSENT: Command sent (no response required) interrupt
* @arg SDIO_INT_DTEND: Data end (data counter, SDIDTCNT, is zero) interrupt
* @arg SDIO_INT_STBITE: Start bit not detected on all data signals in wide bus mode interrupt
* @arg SDIO_INT_DTBLKEND: Data block sent/received (CRC check passed) interrupt
* @arg SDIO_INT_CMDRUN: Command transfer in progress interrupt
* @arg SDIO_INT_TXRUN: Data transmit in progress interrupt
* @arg SDIO_INT_RXRUN: Data receive in progress interrupt
* @arg SDIO_INT_TXFIFOHE: Transmit FIFO Half Empty interrupt
* @arg SDIO_INT_RXFIFOHF: Receive FIFO Half Full interrupt
* @arg SDIO_INT_TXFIFOF: Transmit FIFO full interrupt
* @arg SDIO_INT_RXFIFOF: Receive FIFO full interrupt
* @arg SDIO_INT_TXFIFOE: Transmit FIFO empty interrupt
* @arg SDIO_INT_RXFIFOE: Receive FIFO empty interrupt
* @arg SDIO_INT_TXDTVAL: Data available in transmit FIFO interrupt
* @arg SDIO_INT_RXDTVAL: Data available in receive FIFO interrupt
* @arg SDIO_INT_SDIOINT: SD I/O interrupt received interrupt
* @arg SDIO_INT_ATAEND: CE-ATA command completion signal received for CMD61 interrupt
* @retval The new state of SDIO_INT (SET or RESET).
*/
TypeState SDIO_GetIntBitState(uint32_t SDIO_INT)
{
if ((SDIO->STR & SDIO_INT) != (uint32_t)RESET) {
return SET;
} else {
return RESET;
}
}
/**
* @brief Clear the interrupt pending bits.
* @param SDIO_INT: the interrupt pending bit to clear.
* This value will be :
* @arg SDIO_INT_CCRCFAIL: Command response received (CRC check failed) interrupt
* @arg SDIO_INT_DTCRCFAIL: Data block sent/received (CRC check failed) interrupt
* @arg SDIO_INT_CMDTMOUT: Command response timeout interrupt
* @arg SDIO_INT_DTTMOUT: Data timeout interrupt
* @arg SDIO_INT_TXURE: Transmit FIFO underrun error interrupt
* @arg SDIO_INT_RXORE: Received FIFO overrun error interrupt
* @arg SDIO_INT_CMDREND: Command response received (CRC check passed) interrupt
* @arg SDIO_INT_CMDSENT: Command sent (no response required) interrupt
* @arg SDIO_INT_DTEND: Data end (data counter, SDIDTCNT, is zero) interrupt
* @arg SDIO_INT_STBITE: Start bit not detected on all data signals in wide
* bus mode interrupt
* @arg SDIO_INT_SDIOINT: SD I/O interrupt received interrupt
* @arg SDIO_INT_ATAEND: CE-ATA command completion signal received for CMD61
* @retval None
*/
void SDIO_ClearIntBitState(uint32_t SDIO_INT)
{
SDIO->ICR = SDIO_INT;
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
#endif

View File

@ -0,0 +1,554 @@
/**
******************************************************************************
* @brief SPI functions of the firmware library.
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "gd32f10x_spi.h"
#include "gd32f10x_rcc.h"
/** @addtogroup GD32F10x_Firmware
* @{
*/
/** @defgroup SPI
* @brief SPI driver modules
* @{
*/
/** @defgroup SPI_Private_Defines
* @{
*/
/* SPI registers Masks */
#define CTLR1_CLEAR_MASK ((uint16_t)0x3040)
#define I2SCTLR_CLEAR_MASK ((uint16_t)0xF040)
/* I2S clock source selection Masks */
#define I2S2_CLOCK_SRC ((uint32_t)(0x00020000))
#define I2S3_CLOCK_SRC ((uint32_t)(0x00040000))
#define I2S_MUL_MASK ((uint32_t)(0x0000F000))
#define I2S_DIV_MASK ((uint32_t)(0x000000F0))
/**
* @}
*/
/** @defgroup SPI_Private_Functions
* @{
*/
/**
* @brief Reset the SPIx and the I2Sx peripheral.
* @param SPIx: the SPI/I2S peripheral where x can be 1..3.
* @retval None
*/
void SPI_I2S_DeInit(SPI_TypeDef *SPIx)
{
if (SPIx == SPI1) {
/* Reset SPI1 */
RCC_APB2PeriphReset_Enable(RCC_APB2PERIPH_SPI1RST, ENABLE);
RCC_APB2PeriphReset_Enable(RCC_APB2PERIPH_SPI1RST, DISABLE);
} else if (SPIx == SPI2) {
/* Reset SPI2 and I2S2 peripheral */
RCC_APB1PeriphReset_Enable(RCC_APB1PERIPH_SPI2RST, ENABLE);
RCC_APB1PeriphReset_Enable(RCC_APB1PERIPH_SPI2RST, DISABLE);
} else if (SPIx == SPI3) {
/* Reset SPI3 and I2S3 peripheral */
RCC_APB1PeriphReset_Enable(RCC_APB1PERIPH_SPI3RST, ENABLE);
RCC_APB1PeriphReset_Enable(RCC_APB1PERIPH_SPI3RST, DISABLE);
}
}
/**
* @brief Initialize the SPIx peripheral.
* @param SPIx: the SPI/I2S peripheral where x can be 1..3.
* @param SPI_InitParameter: The structuer contains configuration information.
* @retval None
*/
void SPI_Init(SPI_TypeDef *SPIx, SPI_InitPara *SPI_InitParameter)
{
uint16_t temp_ctrl1 = 0;
/* Configure SPIx CTRL1 according to the SPI_InitParameter */
temp_ctrl1 = SPIx->CTLR1;
temp_ctrl1 &= CTLR1_CLEAR_MASK;
temp_ctrl1 |= (uint16_t)((uint32_t)SPI_InitParameter->SPI_TransType | SPI_InitParameter->SPI_Mode |
SPI_InitParameter->SPI_FrameFormat | SPI_InitParameter->SPI_SCKPL |
SPI_InitParameter->SPI_SCKPH | SPI_InitParameter->SPI_SWNSSEN |
SPI_InitParameter->SPI_PSC | SPI_InitParameter->SPI_FirstBit);
SPIx->CTLR1 = temp_ctrl1;
/* Configure SPIx CRC Polynomial */
SPIx->CPR = SPI_InitParameter->SPI_CRCPOL;
/* Configure the I2SSEL bit in I2SCTLR register as SPI mode */
SPIx->I2SCTLR &= ~SPI_I2SCTLR_I2SSEL;
}
/**
* @brief Initialize the I2Sx peripheral.
* @param SPIx: the SPI/I2S peripheral where x can be 2 or 3.
* @param I2S_InitParameter: The structuer contains configuration information.
* @retval None
*/
void I2S_Init(SPI_TypeDef *SPIx, I2S_InitPara *I2S_InitParameter)
{
uint16_t temp_i2sctrl = 0, div = 2, of = 0;
uint32_t temp = 0;
RCC_ClocksPara RCC_Clocks;
uint32_t sourceclock = 0;
/* SPIx I2SCTLR & I2SCKP Configuration */
/* Deinit I2SCTLR I2SCKP register */
SPIx->I2SCTLR &= I2SCTLR_CLEAR_MASK;
SPIx->I2SCKP = 0x0002;
/* Default config of the prescaler*/
if (I2S_InitParameter->I2S_AudioFreq == I2S_AUDIOFREQ_DEFAULT) {
of = (uint16_t)0;
div = (uint16_t)2;
} else {
/* Get the I2S clock source */
if (((uint32_t)SPIx) == SPI2_BASE) {
temp = I2S2_CLOCK_SRC;
} else {
temp = I2S3_CLOCK_SRC;
}
/* I2S clock source configuration depend on different device */
#ifdef GD32F10X_CL
if ((RCC->GCFGR2 & temp) != 0) {
/* Get RCC PLL3 multiplier */
temp = (uint32_t)((RCC->GCFGR2 & I2S_MUL_MASK) >> 12);
if ((temp > 5) && (temp < 15)) {
/* Multiplier is between 8 and 14 (value 15 is forbidden) */
temp += 2;
} else {
if (temp == 15) {
/* Multiplier is 20 */
temp = 20;
}
}
/* Get the PREDV2 value */
sourceclock = (uint32_t)(((RCC->GCFGR2 & I2S_DIV_MASK) >> 4) + 1);
/* Calculate sourceclock based on PLL3 and PREDV2 */
sourceclock = (uint32_t)((HSE_VALUE / sourceclock) * temp * 2);
} else {
/* Get system clock */
RCC_GetClocksFreq(&RCC_Clocks);
sourceclock = RCC_Clocks.CK_SYS_Frequency;
}
#else
/* Get system clock */
RCC_GetClocksFreq(&RCC_Clocks);
sourceclock = RCC_Clocks.CK_SYS_Frequency;
#endif /* GD32F10X_CL */
/* Calculate the prescaler depending on the MCLK output state and the data format with a flaoting point. */
if (I2S_InitParameter->I2S_MCKOE == I2S_MCK_ENABLE) {
temp = (uint16_t)(((((sourceclock / 256) * 10) / I2S_InitParameter->I2S_AudioFreq)) + 5);
} else {
if (I2S_InitParameter->I2S_FrameFormat == I2S_FRAMEFORMAT_DL16b_CL16b) {
temp = (uint16_t)(((((sourceclock / 32) * 10) / I2S_InitParameter->I2S_AudioFreq)) + 5);
} else {
temp = (uint16_t)(((((sourceclock / 64) * 10) / I2S_InitParameter->I2S_AudioFreq)) + 5);
}
}
/* Remove the flaoting point */
temp = temp / 10;
of = (uint16_t)(temp & (uint16_t)0x0001);
div = (uint16_t)((temp - of) / 2);
of = (uint16_t)(of << 8);
}
/* Inappropriate prescaler, Set the default values */
if ((div < 1) || (div > 0xFF)) {
div = 2;
of = 0;
}
/* Configure SPIx I2SCKP */
SPIx->I2SCKP = (uint16_t)(div | (uint16_t)(of | (uint16_t)I2S_InitParameter->I2S_MCKOE));
/* Configure SPIx I2SCTLR according to the I2S_InitParameter */
temp_i2sctrl = SPIx->I2SCTLR;
temp_i2sctrl |= (uint16_t)(SPI_I2SCTLR_I2SSEL | (uint16_t)(I2S_InitParameter->I2S_Mode | \
(uint16_t)(I2S_InitParameter->I2S_STD | (uint16_t)(I2S_InitParameter->I2S_FrameFormat | \
(uint16_t)I2S_InitParameter->I2S_CKPL))));
SPIx->I2SCTLR = temp_i2sctrl;
}
/**
* @brief Initial SPI_InitParameter members.
* @param SPI_InitParameter : pointer to a SPI_InitPara structure.
* @retval None
*/
void SPI_ParaInit(SPI_InitPara *SPI_InitParameter)
{
/* Reset SPI init structure parameters values */
SPI_InitParameter->SPI_TransType = SPI_TRANSTYPE_FULLDUPLEX;
SPI_InitParameter->SPI_Mode = SPI_MODE_SLAVE;
SPI_InitParameter->SPI_FrameFormat = SPI_FRAMEFORMAT_8BIT;
SPI_InitParameter->SPI_SCKPL = SPI_SCKPL_LOW;
SPI_InitParameter->SPI_SCKPH = SPI_SCKPH_1EDGE;
SPI_InitParameter->SPI_SWNSSEN = SPI_SWNSS_HARD;
SPI_InitParameter->SPI_PSC = SPI_PSC_2;
SPI_InitParameter->SPI_FirstBit = SPI_FIRSTBIT_MSB;
SPI_InitParameter->SPI_CRCPOL = 7;
}
/**
* @brief Initial I2S_InitParameter members.
* @param I2S_InitParameter : pointer to a I2S_InitPara structure.
* @retval None
*/
void I2S_ParaInit(I2S_InitPara *I2S_InitParameter)
{
/* Reset I2S init structure parameters values */
I2S_InitParameter->I2S_Mode = I2S_MODE_SLAVETX;
I2S_InitParameter->I2S_STD = I2S_STD_PHILLIPS;
I2S_InitParameter->I2S_FrameFormat = I2S_FRAMEFORMAT_DL16b_CL16b;
I2S_InitParameter->I2S_MCKOE = I2S_MCK_DISABLE;
I2S_InitParameter->I2S_AudioFreq = I2S_AUDIOFREQ_DEFAULT;
I2S_InitParameter->I2S_CKPL = I2S_CKPL_LOW;
}
/**
* @brief Enable or disable the SPI peripheral.
* @param SPIx: the SPI/I2S peripheral where x can be 1..3.
* @param NewValue: ENABLE or DISABLE.
* @retval None
*/
void SPI_Enable(SPI_TypeDef *SPIx, TypeState NewValue)
{
if (NewValue != DISABLE) {
SPIx->CTLR1 |= SPI_CTLR1_SPIEN;
} else {
SPIx->CTLR1 &= ~SPI_CTLR1_SPIEN;
}
}
/**
* @brief Enable or disable the I2S peripheral.
* @param SPIx: the SPI/I2S peripheral where x can be 2 or 3.
* @param NewValue: ENABLE or DISABLE.
* @retval None
*/
void I2S_Enable(SPI_TypeDef *SPIx, TypeState NewValue)
{
if (NewValue != DISABLE) {
SPIx->I2SCTLR |= SPI_I2SCTLR_I2SEN;
} else {
SPIx->I2SCTLR &= ~SPI_I2SCTLR_I2SEN;
}
}
/**
* @brief Enable or disable the SPI or I2S interrupts.
* @param SPIx: the SPI/I2S peripheral where x can be 1..3.
* @param SPI_I2S_INT: specifies the SPI or I2S interrupt source. Select one of the follwing values :
* @arg SPI_I2S_INT_TBE: Tx buffer empty interrupt mask
* @arg SPI_I2S_INT_RBNE: Rx buffer not empty interrupt mask
* @arg SPI_I2S_INT_ERR: Error interrupt mask
* @param NewValue: ENABLE or DISABLE.
* @retval None
*/
void SPI_I2S_INTConfig(SPI_TypeDef *SPIx, uint8_t SPI_I2S_INT, TypeState NewValue)
{
uint16_t intmask = 0 ;
/* Get the interrupt enable bit in CTRL2 */
intmask = (uint16_t)1 << (uint16_t)(SPI_I2S_INT >> 4);
/* Enable or disable the selected interrupt */
if (NewValue != DISABLE) {
SPIx->CTLR2 |= intmask;
} else {
SPIx->CTLR2 &= (uint16_t)~intmask;
}
}
/**
* @brief Enable or disable the SPIx or I2Sx DMA transfer request.
* @param SPIx: the SPI/I2S peripheral where x can be 1..3.
* @param SPI_I2S_DMAReq: Select the SPI or I2S DMA transfer request. Select one of the follwing values :
* @arg SPI_I2S_DMA_TX: Tx buffer DMA transfer request
* @arg SPI_I2S_DMA_RX: Rx buffer DMA transfer request
* @param NewValue: ENABLE or DISABLE.
* @retval None
*/
void SPI_I2S_DMA_Enable(SPI_TypeDef *SPIx, uint16_t SPI_I2S_DMAReq, TypeState NewValue)
{
if (NewValue != DISABLE) {
SPIx->CTLR2 |= SPI_I2S_DMAReq;
} else {
SPIx->CTLR2 &= (uint16_t)~SPI_I2S_DMAReq;
}
}
/**
* @brief Send a Data by the SPIx or I2Sx peripheral.
* @param SPIx: the SPI/I2S peripheral where x can be 1..3.
* @param Data : Data to be Send.
* @retval None
*/
void SPI_I2S_SendData(SPI_TypeDef *SPIx, uint16_t Data)
{
SPIx->DTR = Data;
}
/**
* @brief Return the received data by the SPIx or I2Sx peripheral.
* @param SPIx: the SPI/I2S peripheral where x can be 1..3.
* @retval The value of the received data.
*/
uint16_t SPI_I2S_ReceiveData(SPI_TypeDef *SPIx)
{
return SPIx->DTR;
}
/**
* @brief NSS pin internal software management.
* @param SPIx: the SPI/I2S peripheral where x can be 1..3.
* @param SPI_SWNSS: specifies the SPI NSS internal state. Select one of the follwing values :
* @arg SPI_SWNSS_SET: Set NSS pin internally
* @arg SPI_SWNSS_RESET: Reset NSS pin internally
* @retval None
*/
void SPI_SWNSSConfig(SPI_TypeDef *SPIx, uint16_t SPI_SWNSS)
{
if (SPI_SWNSS != SPI_SWNSS_RESET) {
/* Set NSS pin */
SPIx->CTLR1 |= SPI_CTLR1_SWNSS;
} else {
/* Reset NSS pin */
SPIx->CTLR1 &= ~SPI_CTLR1_SWNSS;
}
}
/**
* @brief Enable or disable the NSS output.
* @param SPIx: the SPI/I2S peripheral where x can be 1..3.
* @param NewValue: ENABLE or DISABLE.
* @retval None
*/
void SPI_NSSDRV(SPI_TypeDef *SPIx, TypeState NewValue)
{
if (NewValue != DISABLE) {
SPIx->CTLR2 |= SPI_CTLR2_NSSDRV;
} else {
SPIx->CTLR2 &= ~SPI_CTLR2_NSSDRV;
}
}
/**
* @brief Configure the data frame format.
* @param SPIx: the SPI/I2S peripheral where x can be 1..3.
* @param SPI_FrameFormat: Select the data frame format. Select one of the follwing values :
* @arg SPI_FRAMEFORMAT_16BIT: Set data frame format to 16bit
* @arg SPI_FRAMEFORMAT_8BIT: Set data frame format to 8bit
* @retval None
*/
void SPI_FrameFormatConfig(SPI_TypeDef *SPIx, uint16_t SPI_FrameFormat)
{
/* Clear FF16 bit */
SPIx->CTLR1 &= (uint16_t)~SPI_FRAMEFORMAT_16BIT;
/* Set new FF16 bit value */
SPIx->CTLR1 |= SPI_FrameFormat;
}
/**
* @brief Send the SPIx CRC value.
* @param SPIx: the SPI/I2S peripheral where x can be 1..3.
* @retval None
*/
void SPI_SendCRCNext(SPI_TypeDef *SPIx)
{
/* Enable the CRC transmission */
SPIx->CTLR1 |= SPI_CTLR1_CRCNT;
}
/**
* @brief Enable or disable the CRC calculation.
* @param SPIx: the SPI/I2S peripheral where x can be 1..3.
* @param NewValue: ENABLE or DISABLE.
* @retval None
*/
void SPI_CRC_Enable(SPI_TypeDef *SPIx, TypeState NewValue)
{
if (NewValue != DISABLE) {
/* Enable the CRC calculation */
SPIx->CTLR1 |= SPI_CTLR1_CRCEN;
} else {
/* Disable the CRC calculation */
SPIx->CTLR1 &= ~SPI_CTLR1_CRCEN;
}
}
/**
* @brief Get the transmit or the receive CRC register value.
* @param SPIx: the SPI/I2S peripheral where x can be 1..3.
* @param SPI_CRC: Select the transmit or the receive CRC register. Select one of the follwing values :
* @arg SPI_CRC_TX: Selects Tx CRC register
* @arg SPI_CRC_RX: Selects Rx CRC register
* @retval The selected CRC register value.
*/
uint16_t SPI_GetCRC(SPI_TypeDef *SPIx, uint8_t SPI_CRC)
{
if (SPI_CRC != SPI_CRC_RX) {
/* Transmit CRC value */
return SPIx->TCR;
} else {
/* Receive CRC value */
return SPIx->RCR;
}
}
/**
* @brief Get the CRC Polynomial value.
* @param SPIx: the SPI/I2S peripheral where x can be 1..3.
* @retval The CRC Polynomial value.
*/
uint16_t SPI_GetCRCPolynomial(SPI_TypeDef *SPIx)
{
return SPIx->CPR;
}
/**
* @brief Select the transfer direction in bidirectional mode.
* @param SPIx: the SPI/I2S peripheral where x can be 1..3.
* @param SPI_BDOE: The transfer direction in bi-directional mode. Select one of the follwing values :
* @arg SPI_BDOE_TX: Selects Tx transmission direction
* @arg SPI_BDOE_RX: Selects Rx receive direction
* @retval None
*/
void SPI_BDOEConfig(SPI_TypeDef *SPIx, uint16_t SPI_BDOE)
{
if (SPI_BDOE == SPI_BDOE_TX) {
/* Transmit only mode*/
SPIx->CTLR1 |= SPI_BDOE_TX;
} else {
/* Receive only mode */
SPIx->CTLR1 &= SPI_BDOE_RX;
}
}
/**
* @brief Check whether the flag is set or not.
* @param SPIx: the SPI/I2S peripheral where x can be 1..3.
* @param SPI_I2S_FLAG: Select the flag. Select one of the follwing values :
* @arg SPI_FLAG_TBE: Transmit buffer empty flag.
* @arg SPI_FLAG_RBNE: Receive buffer not empty flag.
* @arg SPI_FLAG_BSY: Busy flag.
* @arg SPI_FLAG_OVR: Overrun flag.
* @arg SPI_FLAG_MODF: Mode Fault flag.
* @arg SPI_FLAG_CRCERR: CRC Error flag.
* @arg I2S_FLAG_TBE: Transmit buffer empty flag.
* @arg I2S_FLAG_RBNE: Receive buffer not empty flag.
* @arg I2S_FLAG_BSY: Busy flag.
* @arg I2S_FLAG_OVR: Overrun flag.
* @arg I2S_FLAG_UDR: Underrun Error flag.
* @arg I2S_FLAG_CHSIDE: Channel Side flag.
* @retval The new state of SPI_I2S_FLAG.
*/
TypeState SPI_I2S_GetBitState(SPI_TypeDef *SPIx, uint16_t SPI_I2S_FLAG)
{
/* Check the status of the selected flag */
if ((SPIx->STR & SPI_I2S_FLAG) != (uint16_t)RESET) {
return SET;
} else {
return RESET;
}
}
/**
* @brief Clear the flag, only used for clear CRCERR flag.
* @param SPIx: the SPI/I2S peripheral where x can be 1..3.
* @param SPI_I2S_FLAG: Select the flag. This parametric only can be SPI_FLAG_CRCERR.
* @note
* The other flags are cleared by software sequences:
* - OVR (OverRun error) flag is cleared by software sequence: a read
* operation to SPI_DTR register (SPI_I2S_ReceiveData()) followed by a read
* operation to SPI_STR register (SPI_I2S_GetBitState()).
* - UDR (UnderRun error) flag is cleared by a read operation to
* SPI_STR register (SPI_I2S_GetBitState()).
* - MODF (Mode Fault) flag is cleared by software sequence: a read/write
* operation to SPI_STR register (SPI_I2S_GetBitState()) followed by a
* write operation to SPI_CTLR1 register (SPI_Enable() to enable the SPI).
* @retval None
*/
void SPI_I2S_ClearBitState(SPI_TypeDef *SPIx, uint16_t SPI_I2S_FLAG)
{
SPIx->STR = (uint16_t)~SPI_I2S_FLAG;
}
/**
* @brief Check whether interrupt has occurred.
* @param SPIx: the SPI/I2S peripheral where x can be 1..3.
* @param SPI_I2S_INT: Select the SPI/I2S interrupt. Select one of the follwing values :
* @arg SPI_I2S_INT_TBE: Transmit buffer empty interrupt.
* @arg SPI_I2S_INT_RBNE: Receive buffer not empty interrupt.
* @arg SPI_I2S_INT_OVR: Overrun interrupt.
* @arg SPI_INT_MODF: Mode Fault interrupt.
* @arg SPI_INT_CRCERR: CRC Error interrupt.
* @arg I2S_INT_UDR: Underrun Error interrupt.
* @retval The new state of SPI_I2S_INT.
*/
TypeState SPI_I2S_GetIntBitState(SPI_TypeDef *SPIx, uint8_t SPI_I2S_INT)
{
uint16_t intposition = 0, intmask = 0;
/* Get the interrupt pending bit and enable bit */
intposition = 0x01 << (SPI_I2S_INT & 0x0F);
intmask = 0x01 << (SPI_I2S_INT >> 4);
/* Check the status of the interrupt */
if (((SPIx->STR & intposition) != (uint16_t)RESET) && (SPIx->CTLR2 & intmask)) {
return SET;
} else {
return RESET;
}
}
/**
* @brief Clear the SPIx or I2S interrupt pending bit, only uesd for clear CRCERR interrupt.
* @param SPIx: the SPI/I2S peripheral where x can be 1..3.
* @param SPI_I2S_INT: Select the SPI or I2S interrupt. This parametric only can be SPI_INT_CRCERR.
* @note
* The other flags are cleared by software sequences:
* - OVR (OverRun error) flag is cleared by software sequence: a read
* operation to SPI_DTR register (SPI_I2S_ReceiveData()) followed by a read
* operation to SPI_STR register (SPI_I2S_GetBitState()).
* - UDR (UnderRun error) flag is cleared by a read operation to
* SPI_STR register (SPI_I2S_GetBitState()).
* - MODF (Mode Fault) flag is cleared by software sequence: a read/write
* operation to SPI_STR register (SPI_I2S_GetBitState()) followed by a
* write operation to SPI_CTLR1 register (SPI_Enable() to enable the SPI).
* @retval None
*/
void SPI_I2S_ClearIntBitState(SPI_TypeDef *SPIx, uint8_t SPI_I2S_INT)
{
uint16_t itpos = 0;
/* Clear the select interrupt pending bit. */
itpos = 0x01 << (SPI_I2S_INT & 0x0F);
SPIx->STR = (uint16_t)~itpos;
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,784 @@
/**
******************************************************************************
* @brief USART functions of the firmware library.
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "gd32f10x_usart.h"
#include "gd32f10x_rcc.h"
/** @addtogroup GD32F10x_Firmware
* @{
*/
/** @defgroup USART
* @brief USART driver modules
* @{
*/
/** @defgroup USART_Private_Defines
* @{
*/
/* USART Interrupts mask */
#define INT_MASK ((uint16_t)(0x001F))
/* USART CTLR1 initializes bit mask */
#define CTLR1_CLEAR_MASK ((uint16_t)(0x160C))
/* USART CTLR2 CLOCK initializes bit mask */
#define CTLR2_CLOCK_CLEAR_MASK ((uint16_t)(0x0F00))
/* USART CTLR3 initializes bit mask */
#define CTLR3_CLEAR_MASK ((uint16_t)(0x0300))
/**
* @}
*/
/** @defgroup USART_Private_Functions
* @{
*/
/**
* @brief Reset the USART peripheral.
* @param USARTx: the USART peripheral.
* This parameter can be one of the following values
* @arg USART1
* @arg USART2
* @arg USART3
* @arg UART4
* @arg UART5
* @param NewValue: new value of the USARTx peripheral.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void USART_DeInit(USART_TypeDef *USARTx)
{
if (USARTx == USART0) {
RCC_APB2PeriphReset_Enable(RCC_APB2PERIPH_USART0RST, ENABLE);
RCC_APB2PeriphReset_Enable(RCC_APB2PERIPH_USART0RST, DISABLE);
} else if (USARTx == USART1) {
RCC_APB1PeriphReset_Enable(RCC_APB1PERIPH_USART1RST, ENABLE);
RCC_APB1PeriphReset_Enable(RCC_APB1PERIPH_USART1RST, DISABLE);
} else if (USARTx == USART2) {
RCC_APB1PeriphReset_Enable(RCC_APB1PERIPH_USART2RST, ENABLE);
RCC_APB1PeriphReset_Enable(RCC_APB1PERIPH_USART2RST, DISABLE);
} else if (USARTx == UART3) {
RCC_APB1PeriphReset_Enable(RCC_APB1PERIPH_UART3RST, ENABLE);
RCC_APB1PeriphReset_Enable(RCC_APB1PERIPH_UART3RST, DISABLE);
} else {
if (USARTx == UART4) {
RCC_APB1PeriphReset_Enable(RCC_APB1PERIPH_UART4RST, ENABLE);
RCC_APB1PeriphReset_Enable(RCC_APB1PERIPH_UART4RST, DISABLE);
}
}
}
/**
* @brief Initialize the USART peripheral interface parameters.
* @param USARTx: the USART peripheral.
* This parameter can be one of the following values
* @arg USART1
* @arg USART2
* @arg USART3
* @arg UART4
* @arg UART5
* @param USART_InitParaStruct: the struct USART_InitPara pointer.
* @retval None
*/
void USART_Init(USART_TypeDef *USARTx, USART_InitPara *USART_InitParaStruct)
{
uint32_t divider = 0, apbclock = 0, temp = 0;
RCC_ClocksPara RCC_ClocksState;
USARTx->CTLR1 &= ~((uint32_t)USART_CTLR1_UEN);
/* Initialize CTLR2 */
temp = USARTx->CTLR2;
/* Reset stop bits then set it use USART_STBits */
temp &= ~((uint32_t)USART_CTLR2_STB);
temp |= (uint32_t)USART_InitParaStruct->USART_STBits;
USARTx->CTLR2 = temp;
/*Initialize CTLR1*/
temp = USARTx->CTLR1;
/* Reset WL, PCEN, PM, TEN and REN bits */
temp &= ~((uint32_t)CTLR1_CLEAR_MASK);
/* According to USART_WL,USART_Parity,USART_RxorTx to configure the CTLR1 */
temp |= (uint32_t)USART_InitParaStruct->USART_WL | USART_InitParaStruct->USART_Parity |
USART_InitParaStruct->USART_RxorTx;
USARTx->CTLR1 = temp;
/*Initialize CTLR3*/
temp = USARTx->CTLR3;
/* Reset CTSEN and RTSEN bits */
temp &= ~((uint32_t)CTLR3_CLEAR_MASK);
/* According to USART_HardwareFlowControl to configure the CTLR3 */
temp |= USART_InitParaStruct->USART_HardwareFlowControl;
USARTx->CTLR3 = temp;
/*Initialize USART BRR*/
RCC_GetClocksFreq(&RCC_ClocksState);
if (USARTx == USART0) {
apbclock = RCC_ClocksState.APB2_Frequency;
} else {
apbclock = RCC_ClocksState.APB1_Frequency;
}
/* Get integer of baud-rate divide and raction of baud-rate divider */
divider = (uint32_t)((apbclock) / ((USART_InitParaStruct->USART_BRR)));
temp = (uint32_t)((apbclock) % ((USART_InitParaStruct->USART_BRR)));
/* Round the divider : if fractional part i greater than 0.5 increment divider */
if (temp >= (USART_InitParaStruct->USART_BRR) / 2) {
divider++;
}
USARTx->BRR = (uint16_t)divider;
}
/**
* @brief Initial the struct USART_InitPara
* @param USART_InitParaStruct: the struct USART_InitPara pointer
* @retval None
*/
void USART_ParaInit(USART_InitPara *USART_InitParaStruct)
{
/* USART_InitStruct members default value */
USART_InitParaStruct->USART_BRR = 9600;
USART_InitParaStruct->USART_WL = USART_WL_8B;
USART_InitParaStruct->USART_STBits = USART_STBITS_1;
USART_InitParaStruct->USART_Parity = USART_PARITY_RESET;
USART_InitParaStruct->USART_RxorTx = USART_RXORTX_RX | USART_RXORTX_TX;
USART_InitParaStruct->USART_HardwareFlowControl = USART_HARDWAREFLOWCONTROL_NONE;
}
/**
* @brief Initialize the USARTx peripheral Clock according to the
* specified parameters in the USART_ClockInitStruct.
* @param USARTx: the USART peripheral.
* This parameter can be one of the following values
* @arg USART1
* @arg USART2
* @arg USART3
* @param USART_ClockInitStruct: pointer to a USART_ClockInitTypeDef structure that contains
* the configuration information for the specified USART peripheral.
* @retval None
*/
void USART_ClockInit(USART_TypeDef *USARTx, USART_ClockInitPara *USART_ClockInitStruct)
{
uint32_t temp = 0;
temp = USARTx->CTLR2;
/* Clear CKEN, CPL, CPH, LBCP and SSM bits */
temp &= ~(CTLR2_CLOCK_CLEAR_MASK);
/* Reset hen set it usethe USART Clock, CPL, CPH, LBCP */
temp |= (uint32_t)(USART_ClockInitStruct->USART_CKEN | USART_ClockInitStruct->USART_CPL |
USART_ClockInitStruct->USART_CPH | USART_ClockInitStruct->USART_LBCP);
/* Write to USART CTLR2 */
USARTx->CTLR2 = (uint16_t)temp;
}
/**
* @brief Initial the struct USART_ClockInitPara.
* @param USART_ClockInitParaStruct: the struct USART_ClockInitPara pointer
* @retval None
*/
void USART_ClockStructInit(USART_ClockInitPara *USART_ClockInitParaStruct)
{
/*Reset USART_ClockInitStruct members default value */
USART_ClockInitParaStruct->USART_CKEN = USART_CKEN_RESET;
USART_ClockInitParaStruct->USART_CPL = USART_CPL_LOW;
USART_ClockInitParaStruct->USART_CPH = USART_CPH_1EDGE;
USART_ClockInitParaStruct->USART_LBCP = USART_LBCP_DISABLE;
}
/**
* @brief Enable or disable the specified USART peripheral.
* @param USARTx: the USART peripheral.
* This parameter can be one of the following values
* @arg USART1
* @arg USART2
* @arg USART3
* @arg UART4
* @arg UART5
* @param NewValue: new value of the USARTx peripheral.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void USART_Enable(USART_TypeDef *USARTx, TypeState NewValue)
{
/* Enable or disable the specified USART peripheral by setting the UEN bit in the CTLR1 register */
if (NewValue != DISABLE) {
USARTx->CTLR1 |= USART_CTLR1_UEN;
} else {
USARTx->CTLR1 &= ~((uint16_t)USART_CTLR1_UEN);
}
}
/**
* @brief Set the system clock prescaler.
* @param USARTx: the USART peripheral.
* This parameter can be one of the following values
* @arg USART1
* @arg USART2
* @arg USART3
* @arg UART4
* @arg UART5
* @param USART_Prescaler: specifies the prescaler clock.
* @note This function has to be called before calling USART_Enable() function.
* @retval None
*/
void USART_SetPrescaler(USART_TypeDef *USARTx, uint8_t USART_Prescaler)
{
/* Clear and set the USART prescaler */
USARTx->GTPR &= ~((uint16_t)USART_GTPR_PSC);
USARTx->GTPR |= USART_Prescaler;
}
/**
* @brief Send data by the USART peripheral.
* @param USARTx: the USART peripheral.
* This parameter can be one of the following values
* @arg USART1
* @arg USART2
* @arg USART3
* @arg UART4
* @arg UART5
* @param Data: the data will be sent.
* @retval None
*/
void USART_DataSend(USART_TypeDef *USARTx, uint16_t Data)
{
USARTx->DR = (Data & (uint16_t)0x01FF);
}
/**
* @brief Receive data by the USART peripheral.
* @param USARTx: the USART peripheral.
* This parameter can be one of the following values
* @arg USART1
* @arg USART2
* @arg USART3
* @arg UART4
* @arg UART5
* @retval The received data.
*/
uint16_t USART_DataReceive(USART_TypeDef *USARTx)
{
return (uint16_t)(USARTx->DR & (uint16_t)0x01FF);
}
/**
* @brief Set the address of the USART terminal.
* @param USARTx: the USART peripheral.
* This parameter can be one of the following values
* @arg USART1
* @arg USART2
* @arg USART3
* @arg UART4
* @arg UART5
* @param USART_Address: Indicates the address of the USART node.
* @retval None
*/
void USART_Address(USART_TypeDef *USARTx, uint8_t USART_Address)
{
/* Clear the USART address and Set the USART terminal*/
USARTx->CTLR2 &= ~USART_CTLR2_ADD;
USARTx->CTLR2 |= USART_Address;
}
/**
* @brief Enable or disable the USART's mute mode.
* @param USARTx: the USART peripheral.
* This parameter can be one of the following values
* @arg USART1
* @arg USART2
* @arg USART3
* @arg UART4
* @arg UART5
* @param NewValue: the USART mute mode.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void USART_MuteMode_Enable(USART_TypeDef *USARTx, TypeState NewValue)
{
/* By setting the MEN bit in the CTLR1 register enable or disable the USART's mute mode*/
if (NewValue != DISABLE) {
USARTx->CTLR1 |= USART_CTLR1_RWU;
} else {
USARTx->CTLR1 &= ~USART_CTLR1_RWU;
}
}
/**
* @brief Set the USART WakeUp method from mute mode.
* @param USARTx: the USART peripheral.
* This parameter can be one of the following values
* @arg USART1
* @arg USART2
* @arg USART3
* @arg UART4
* @arg UART5
* @param USART_WakeUp
* This parameter can be one of the following values
* @arg USART_WAKEUP_IDLELINE
* @arg USART_WAKEUP_ADDRESSMARK
* @retval None
*/
void USART_MuteModeWakeUp_Set(USART_TypeDef *USARTx, uint16_t USART_WakeUp)
{
USARTx->CTLR1 &= ~((uint16_t)USART_CTLR1_WM);
USARTx->CTLR1 |= USART_WakeUp;
}
/**
* @brief Set the USART LIN Break detection length.
* @param USARTx: the USART peripheral.
* This parameter can be one of the following values
* @arg USART1
* @arg USART2
* @arg USART3
* @arg UART4
* @arg UART5
* @param USART_LINBreakDetectLength
* This parameter can be one of the following values
* @arg USART_LINBREAKDETECTLENGTH_10B
* @arg USART_LINBREAKDETECTLENGTH_11B
* @retval None
*/
void USART_SetLINBDLength(USART_TypeDef *USARTx, uint16_t USART_LINBreakDetectLength)
{
USARTx->CTLR2 &= ~((uint16_t)USART_CTLR2_LBDL);
USARTx->CTLR2 |= USART_LINBreakDetectLength;
}
/**
* @brief Enable or disable the USART's LIN mode.
* @param USARTx: the USART peripheral.
* This parameter can be one of the following values
* @arg USART1
* @arg USART2
* @arg USART3
* @arg UART4
* @arg UART5
* @param NewValue: the USART LIN mode value.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void USART_LIN_Enable(USART_TypeDef *USARTx, TypeState NewValue)
{
/* By setting the LINEN bit in the CTLR2 register enable or disable the USART's LIN mode */
if (NewValue != DISABLE) {
USARTx->CTLR2 |= USART_CTLR2_LMEN;
} else {
USARTx->CTLR2 &= ~((uint16_t)USART_CTLR2_LMEN);
}
}
/**
* @brief Enable or disable the Half-duplex mode.
* @param USARTx: the USART peripheral.
* This parameter can be one of the following values
* @arg USART1
* @arg USART2
* @arg USART3
* @arg UART4
* @arg UART5
* @param NewValue: the USART Half-duplex mode value.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void USART_HalfDuplex_Enable(USART_TypeDef *USARTx, TypeState NewValue)
{
/* By setting the HDEN bit in the CTLR3 register enable or disable the Half-duplex mode */
if (NewValue != DISABLE) {
USARTx->CTLR3 |= USART_CTLR3_HDEN;
} else {
USARTx->CTLR3 &= ~USART_CTLR3_HDEN;
}
}
/**
* @brief Set the the USART guard time.
* @param USARTx: the USART peripheral.
* This parameter can be one of the following values
* @arg USART1
* @arg USART2
* @arg USART3
* @param USART_GuardTime: the USART guard time.
* @retval None
*/
void USART_GuardTime_Set(USART_TypeDef *USARTx, uint8_t USART_GuardTime)
{
/* Set the USART guard time */
USARTx->GTPR &= ~((uint16_t)USART_GTPR_GT);
USARTx->GTPR |= (uint16_t)((uint16_t)USART_GuardTime << 0x08);
}
/**
* @brief Enable or disable the USART's Smart Card mode.
* @param USARTx: the USART peripheral.
* This parameter can be one of the following values
* @arg USART1
* @arg USART2
* @arg USART3
* @param NewValue: the Smart Card mode value.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void USART_SmartCard_Enable(USART_TypeDef *USARTx, TypeState NewValue)
{
/* By setting the SCEN bit in the CTLR3 register enable or disable the USART's Smart Card mode */
if (NewValue != DISABLE) {
USARTx->CTLR3 |= USART_CTLR3_SCEN;
} else {
USARTx->CTLR3 &= ~((uint16_t)USART_CTLR3_SCEN);
}
}
/**
* @brief Enable or disable NACK transmission.
* @param USARTx: the USART peripheral.
* This parameter can be one of the following values
* @arg USART1
* @arg USART2
* @arg USART3
* @arg UART4
* @arg UART5
* @param NewValue: the NACK transmission state.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void USART_SmartCardNACK_Enable(USART_TypeDef *USARTx, TypeState NewValue)
{
/* By setting the NACK bit in the CTLR3 register Enable or disable NACK transmission */
if (NewValue != DISABLE) {
USARTx->CTLR3 |= USART_CTLR3_NACK;
} else {
USARTx->CTLR3 &= ~((uint32_t)USART_CTLR3_NACK);
}
}
/**
* @brief DMA enable for transmission or reception.
* @param USARTx: the USART peripheral.
* This parameter can be one of the following values
* @arg USART1
* @arg USART2
* @arg USART3
* @arg UART4
* @arg UART5
* @param USART_DMAEnable: the DMA request.
* This parameter can be one of the following values
* @arg USART_DMAREQ_RX
* @arg USART_DMAREQ_TX
* @param NewValue: the DMA Request sources state.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void USART_DMA_Enable(USART_TypeDef *USARTx, uint16_t USART_DMAEnable, TypeState NewValue)
{
/* Enable or disable the DMA transfer for transmission or reception by setting the DENT and/or
DENR bits in the USART CTLR3 register */
if (NewValue != DISABLE) {
USARTx->CTLR3 |= USART_DMAEnable;
} else {
USARTx->CTLR3 &= ~USART_DMAEnable;
}
}
/**
* @brief Set the USARTX IrDA low-power.
* @param USARTx: the USART peripheral.
* This parameter can be one of the following values
* @arg USART1
* @arg USART2
* @arg USART3
* @arg UART4
* @arg UART5
* @param USART_IrDAMode
* This parameter can be one of the following values
* @arg USART_IRDAMODE_LOWPOWER
* @arg USART_IRDAMODE_NORMAL.
* @retval None
*/
void USART_IrDA_Set(USART_TypeDef *USARTx, uint16_t USART_IrDAMode)
{
USARTx->CTLR3 &= ~((uint16_t)USART_CTLR3_IRLP);
USARTx->CTLR3 |= USART_IrDAMode;
}
/**
* @brief Enable or disable the USART's IrDA interface.
* @param USARTx: the USART peripheral.
* This parameter can be one of the following values
* @arg USART1
* @arg USART2
* @arg USART3
* @arg UART4
* @arg UART5
* @param NewValue: the IrDA mode value.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void USART_IrDA_Enable(USART_TypeDef *USARTx, TypeState NewValue)
{
/* By setting the IREN bit in the CTLR3 register enable or disable the USART's IrDA interface */
if (NewValue != DISABLE) {
USARTx->CTLR3 |= USART_CTLR3_IREN;
} else {
USARTx->CTLR3 &= ~((uint16_t)USART_CTLR3_IREN);
}
}
/**
* @brief Detect the bit flag of STR register.
* @param USARTx: the USART peripheral.
* This parameter can be one of the following values
* @arg USART1
* @arg USART2
* @arg USART3
* @arg UART4
* @arg UART5
* @param USART_FLAG: the flag of STR register.
* This parameter can be one of the following values:
* @arg USART_FLAG_CTSF: CTS Change flag.(not available for UART4 and UART5)
* @arg USART_FLAG_LBDF: LIN Break detection flag
* @arg USART_FLAG_TBE: Transmit data register empty flag.
* @arg USART_FLAG_TC: Transmission Complete flag.
* @arg USART_FLAG_RBNE: Receive data register not empty flag.
* @arg USART_FLAG_IDLEF:Idle Line detection flag.
* @arg USART_FLAG_ORE: OverRun Error flag.
* @arg USART_FLAG_NE: Noise Error flag.
* @arg USART_FLAG_FE: Framing Error flag.
* @arg USART_FLAG_PE: Parity Error flag.
* @retval The new state of USART_FLAG (SET or RESET).
*/
TypeState USART_GetBitState(USART_TypeDef *USARTx, uint16_t USART_FLAG)
{
if ((USARTx->STR & USART_FLAG) != (uint16_t)RESET) {
return SET;
} else {
return RESET;
}
}
/**
* @brief Enable or disable USART interrupt.
* @param USARTx: the USART peripheral.
* This parameter can be one of the following values
* @arg USART1
* @arg USART2
* @arg USART3
* @arg UART4
* @arg UART5
* @param USART_INT: the USART interrupt
* This parameter can be one of the following values:
* @arg USART_INT_PE
* @arg USART_INT_TBE
* @arg USART_INT_TC
* @arg USART_INT_RBNE
* @arg USART_INT_IDLEF
* @arg USART_INT_LBDF
* @arg USART_INT_CTSF (not available for UART4 and UART5)
* @arg USART_INT_ERIE
* @param NewValue: the USART interrupt State.
* This parameter can be: ENABLE or DISABLE.
* @retval None
*/
void USART_INT_Set(USART_TypeDef *USARTx, uint16_t USART_INT, TypeState NewValue)
{
uint32_t intpos = 0, usartreg = 0;
uint32_t usartxbase = 0;
usartxbase = (uint32_t)USARTx;
/* Get the USART register index and the interrupt position */
usartreg = ((uint8_t)(USART_INT) >> 0x05);
intpos = USART_INT & INT_MASK;
/* Get the interrupt from which register: CTLR1,CTLR2 OR CTLR3 */
if (usartreg == 0x01) {
usartxbase += 0x0C;
} else if (usartreg == 0x02) {
usartxbase += 0x10;
} else {
usartxbase += 0x14;
}
if (NewValue != DISABLE) {
*(__IO uint32_t *)usartxbase |= (((uint32_t)0x01) << intpos);
} else {
*(__IO uint32_t *)usartxbase &= ~(((uint32_t)0x01) << intpos);
}
}
/**
* @brief Clear the bit flag.
* @param USARTx: the USART peripheral.
* This parameter can be one of the following values
* @arg USART1
* @arg USART2
* @arg USART3
* @arg UART4
* @arg UART5
* @param USART_FLAG: the bit flag usart .
* This parameter can be one of the following values:
* @arg USART_FLAG_CTSF: CTS Change flag.(not available for UART4 and UART5)
* @arg USART_FLAG_LBDF: LIN Break detection flag
* @arg USART_FLAG_TC: Transmission Complete flag.
* @arg USART_FLAG_RBNE: Receive data register not empty flag.
* @note
* - PE (Parity error), FE (Framing error), NE (Noise error), ORE (OverRun
* error) and IDLEF (Idle line detected) flag bits are cleared by
* software sequence: a read operation to USART_STR register
* (USART_GetBitState()) followed by a read operation to USART_DR register
* (USART_DataReceive()).
* - RBNE flag bit can be also cleared by a read to the USART_DR register
* (USART_DataReceive()).
* - TC flag bit can be also cleared by software sequence: a read
* operation to USART_STR register (USART_GetBitState()) followed by a write
* operation to USART_DR register (USART_DataSend()).
* - TBE flag bit is cleared only by a write to the USART_DR register
* (USART_DataSend()).
* @retval None
*/
void USART_ClearBitState(USART_TypeDef *USARTx, uint16_t USART_FLAG)
{
USARTx->STR = (uint16_t)~ USART_FLAG;
}
/**
* @brief Detect the interrupt bit flag.
* @param USARTx: the USART peripheral.
* This parameter can be one of the following values
* @arg USART1
* @arg USART2
* @arg USART3
* @arg UART4
* @arg UART5
* @param USART_INT: the USART interrupt bit flag.
* This parameter can be one of the following values:
* @arg USART_INT_PE
* @arg USART_INT_TBE
* @arg USART_INT_TC
* @arg USART_INT_RBNE
* @arg USART_INT_IDLEF
* @arg USART_INT_LBDF
* @arg USART_INT_CTSF: CTS flag interrupt (not available for UART4 and UART5)
* @arg USART_INT_ORE
* @arg USART_INT_NE
* @arg USART_INT_FE
* @retval The new state of USART_INT (SET or RESET).
*/
TypeState USART_GetIntBitState(USART_TypeDef *USARTx, uint16_t USART_INT)
{
uint16_t bitpos = 0, itmask = 0, usartreg = 0;
/* Get the USART register index and the interrupt position */
usartreg = (((uint8_t)USART_INT) >> 0x05);
itmask = (USART_INT) & (INT_MASK);
itmask = (uint16_t)0x01 << itmask;
if (usartreg == 0x01) {
itmask &= USARTx->CTLR1;
} else {
if (usartreg == 0x02) {
itmask &= USARTx->CTLR2;
} else {
itmask &= USARTx->CTLR3;
}
}
bitpos = USART_INT >> 0x08;
bitpos = (uint32_t)0x01 << bitpos;
bitpos &= USARTx->STR;
if ((itmask != (uint16_t)RESET) && (bitpos != (uint16_t)RESET)) {
return SET;
} else {
return RESET;
}
}
/**
* @brief Clear the interrupt bit flag.
* @param USARTx: the USART peripheral.
* This parameter can be one of the following values
* @arg USART1
* @arg USART2
* @arg USART3
* @arg UART4
* @arg UART5
* @param USART_INT: the interrupt bit flag.
* This parameter can be one of the following values: * @arg USART_INT_TC
* @arg USART_INT_LBDF
* @arg USART_INT_CTSF: CTS Flag interrupt (not available for UART4 and UART5)
* @arg USART_INT_RBNE
* @arg USART_INT_TC
* @note
* - PE (Parity error), FE (Framing error), NE (Noise error), ORE (OverRun
* error) and IDLEF (Idle line detected flag) interrupt bits are cleared by
* software sequence: a read operation to USART_STR register
* (USART_GetINTState()) followed by a read operation to USART_DR register
* (USART_DataReceive()).
* - RBNE interrupt bit can be also cleared by a read to the USART_DR register
* (USART_DataReceive()).
* - TC interrupt bit can be also cleared by software sequence: a read
* operation to USART_STR register (USART_GetINTState()) followed by a write
* operation to USART_DR register (USART_DataSend()).
* - TBE interrupt bit is cleared only by a write to the USART_DR register
* (USART_DataSend()).
* @retval None
*/
void USART_ClearIntBitState(USART_TypeDef *USARTx, uint16_t USART_INT)
{
uint16_t bitpos = 0, itmask = 0;
bitpos = USART_INT >> 0x08;
itmask = ((uint16_t)0x01 << (uint16_t)bitpos);
USARTx->STR = (uint16_t)~itmask;
}
/**
* @brief Send break command.
* @param USARTx: the USART peripheral
* This parameter can be one of the following values
* @arg USART1
* @arg USART2
* @arg USART3
* @arg UART4
* @arg UART5
* @retval None
*/
void USART_SendBreak(USART_TypeDef *USARTx)
{
/* Send break command */
USARTx->CTLR1 |= USART_CTLR1_SBKCMD;
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/

View File

@ -0,0 +1,155 @@
/**
******************************************************************************
* @brief WWDG functions of the firmware library.
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "gd32f10x_wwdg.h"
#include "gd32f10x_rcc.h"
/** @addtogroup GD32F10x_Firmware
* @{
*/
/** @defgroup WWDG
* @brief WWDG driver modules
* @{
*/
/** @defgroup WWDG_Private_Variables
* @{
*/
/* CFR register bit mask */
#define CFR_PS_MASK ((uint32_t)0xFFFFFE7F)
#define CFR_WIN_MASK ((uint32_t)0xFFFFFF80)
#define BIT_MASK ((uint8_t)0x7F)
/**
* @}
*/
/** @defgroup WWDG_Private_Functions
* @{
*/
/**
* @brief Reset the WWDG configuration.
* @param None
* @retval None
*/
void WWDG_DeInit(void)
{
RCC_APB1PeriphReset_Enable(RCC_APB1PERIPH_WWDG, ENABLE);
RCC_APB1PeriphReset_Enable(RCC_APB1PERIPH_WWDG, DISABLE);
}
/**
* @brief Set WWDG prescaler value.
* @param PrescalerValue: WWDG Prescaler value.
* This parameter can be one of the following values:
* @arg WWDG_PRESCALER_1: the time base of watchdog counter = (PCLK1/4096)/1
* @arg WWDG_PRESCALER_2: the time base of watchdog counter = (PCLK1/4096)/2
* @arg WWDG_PRESCALER_4: the time base of watchdog counter = (PCLK1/4096)/4
* @arg WWDG_PRESCALER_8: the time base of watchdog counter = (PCLK1/4096)/8
* @retval None
*/
void WWDG_SetPrescalerValue(uint32_t PrescalerValue)
{
uint32_t temp = 0;
/* Clear PS[1:0] bits */
temp = WWDG->CFR & CFR_PS_MASK;
/* Set PS[1:0] bits */
temp |= PrescalerValue;
WWDG->CFR = temp;
}
/**
* @brief Set watchdog window value.
* @param WindowValue: the window value to be compared to the downcounter.
* @retval None
*/
void WWDG_SetWindowValue(uint8_t WindowValue)
{
__IO uint32_t temp = 0;
/* Clear WIN[6:0] bits */
temp = WWDG->CFR & CFR_WIN_MASK;
/* Set WIN[6:0] bits */
temp |= WindowValue & (uint32_t) BIT_MASK;
WWDG->CFR = temp;
}
/**
* @brief Enable the WWDG Early wakeup interrupt(EWI).
* @note An interrupt occurs when the counter reaches 0x40 if the bit is set.
* It's cleared by a hardware reset. A write of 0 has no effect.
* @param None
* @retval None
*/
void WWDG_EnableInt(void)
{
WWDG->CFR |= WWDG_CFR_EWI;
}
/**
* @brief Set the value of the watchdog counter.
* @param CounterValue: the watchdog counter value.
* @retval None
*/
void WWDG_SetCounterValue(uint8_t CounterValue)
{
/* Write to CNT[6:0] bits */
WWDG->CTLR = CounterValue & BIT_MASK;
}
/**
* @brief Start the window watchdog counter.
* @param CounterValue: The value of the watchdog counter.
* @retval None
*/
void WWDG_Enable(uint8_t CounterValue)
{
WWDG->CTLR = WWDG_CTLR_WDGEN | CounterValue;
}
/**
* @brief Check the Early Wakeup interrupt bit state.
* @param None
* @retval The new state of the Early Wakeup interrupt (SET or RESET).
*/
TypeState WWDG_GetBitState(void)
{
if ((WWDG->STR) != (uint32_t)RESET) {
return SET;
} else {
return RESET;
}
}
/**
* @brief Clear Early Wakeup interrupt flag.
* @param None
* @retval None
*/
void WWDG_ClearBitState(void)
{
WWDG->STR = (uint32_t)RESET;
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/

View File

@ -0,0 +1,26 @@
import rtconfig
from building import *
# get current directory
cwd = GetCurrentDir()
# The set of source files associated with this SConscript file.
src = Glob('GD32F1xx_standard_peripheral/Source/*.c')
src += [cwd + '/CMSIS/GD/GD32F1xx/Source/system_gd32f1xx.c']
#add for startup script
if rtconfig.CROSS_TOOL == 'gcc':
src += [cwd + '/CMSIS/GD/GD32F1xx/Source/GCC/startup_gd32.s']
src += [cwd + '/CMSIS/GD/GD32F1xx/Source/GCC/isr_tab.s']
path = [
cwd + '/CMSIS/GD/GD32F1xx/Include',
cwd + '/CMSIS',
cwd + '/GD32F1xx_standard_peripheral/Include',]
CPPDEFINES = ['USE_STDPERIPH_DRIVER', 'GD32F1XX']
group = DefineGroup('GD32_Lib', src, depend = [''], CPPPATH = path, CPPDEFINES = CPPDEFINES)
Return('group')

View File

@ -0,0 +1,71 @@
# GD32103C-EVAL
## 简介
GD32103C-EVAL是-兆易创新推出的一款GD32F103VCT6系列的评估板板载资源主要如下
| 硬件 | 描述 |
| --------- | ------------- |
| 芯片型号 | GD32F103VCT6 |
| CPU | ARM Cortex M3 |
| 主频 | 108M |
| 片内SRAM | 48K |
| 片内FLASH | 256K |
| 片外FLASH | 1Gb |
## 编译说明
GD32103C-EVAL板级包支持MDK4﹑MDK5﹑IAR开发环境和GCC编译器以下是具体版本信息
| IDE/编译器 | 已测试版本 |
| ---------- | ---------------------------- |
| GCC |gcc version 6.2.1 20161205 (release) |
## 烧写及执行
供电方式:开发板使用 Mini USB 接口或者 DC-005 连接器提供 5V 电源。
下载程序:下载程序到开发板需要一套 JLink 或者使用 GD-Link 工具。
串口连接使用串口线连接到COM1(UART0)或者使用USB转TTL模块连接PA9(MCU TX)和PA10(MCU RX)。
### 运行结果
如果编译 & 烧写无误当复位设备后会在串口上看到RT-Thread的启动logo信息
```bash
\ | /
- RT - Thread Operating System
/ | \ 4.0.3 build Jan 4 2021
2006 - 2021 Copyright by rt-thread team
msh />
```
## 驱动支持情况及计划
| 驱动 | 支持情况 | 备注 |
| --------- | -------- | :------------------------: |
| UART | 支持 | UART0~4 |
| GPIO | 支持 | GPIOA~G |
| ADC | 支持 | ADC0~1 |
| IIC | 未支持 | I2C0~1 |
| SPI | 未支持 | SPI0~2 |
| ETH | 未支持 | |
| LCD | 未支持 | |
| SDRAM | 未支持 | |
| SPI FLASH | 未支持 | |
### IO在板级支持包中的映射情况
| IO号 | 板级包中的定义 |
| ---- | -------------- |
| PC0 | LED1 |
| PC2 | LED2 |
| PE0 | LED3 |
| PE1 | LED4 |
| PA0 | KEY1 |
| PC13 | KEY2 |
| PB14 | KEY3 |
## 联系人信息
维护人:[iysheng](https://github.com/iysheng)

View File

@ -0,0 +1,14 @@
# for module compiling
import os
Import('RTT_ROOT')
cwd = str(Dir('#'))
objs = []
list = os.listdir(cwd)
for d in list:
path = os.path.join(cwd, d)
if os.path.isfile(os.path.join(path, 'SConscript')):
objs = objs + SConscript(os.path.join(d, 'SConscript'))
Return('objs')

View File

@ -0,0 +1,40 @@
import os
import sys
import rtconfig
if os.getenv('RTT_ROOT'):
RTT_ROOT = os.getenv('RTT_ROOT')
else:
RTT_ROOT = os.path.normpath(os.getcwd() + '/../..')
sys.path = sys.path + [os.path.join(RTT_ROOT, 'tools')]
try:
from building import *
except:
print('Cannot found RT-Thread root directory, please check RTT_ROOT')
print(RTT_ROOT)
exit(-1)
TARGET = 'rtthread-gd32f4xx.' + rtconfig.TARGET_EXT
DefaultEnvironment(tools=[])
env = Environment(tools = ['mingw'],
AS = rtconfig.AS, ASFLAGS = rtconfig.AFLAGS,
CC = rtconfig.CC, CCFLAGS = rtconfig.CFLAGS,
AR = rtconfig.AR, ARFLAGS = '-rc',
LINK = rtconfig.LINK, LINKFLAGS = rtconfig.LFLAGS)
env.PrependENVPath('PATH', rtconfig.EXEC_PATH)
if rtconfig.PLATFORM == 'iar':
env.Replace(CCCOM = ['$CC $CCFLAGS $CPPFLAGS $_CPPDEFFLAGS $_CPPINCFLAGS -o $TARGET $SOURCES'])
env.Replace(ARFLAGS = [''])
env.Replace(LINKCOM = env["LINKCOM"] + ' --map project.map')
Export('RTT_ROOT')
Export('rtconfig')
# prepare building environment
objs = PrepareBuilding(env, RTT_ROOT, has_libcpu=False)
# make a building
DoBuilding(TARGET, objs)

View File

@ -0,0 +1,11 @@
Import('RTT_ROOT')
Import('rtconfig')
from building import *
cwd = os.path.join(str(Dir('#')), 'applications')
src = Glob('*.c')
CPPPATH = [cwd, str(Dir('#'))]
group = DefineGroup('Applications', src, depend = [''], CPPPATH = CPPPATH)
Return('group')

View File

@ -0,0 +1,33 @@
/*
* Copyright (c) 2006-2021, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2021-01-04 iysheng first version
*/
#include <board.h>
#include <drivers/adc.h>
#include <rtdbg.h>
#include <stdio.h>
#include <rtthread.h>
#include "board.h"
#define LED1 GET_PIN(C, 0)
int main(void)
{
rt_pin_mode(LED1, PIN_MODE_OUTPUT);
while (1)
{
rt_pin_write(LED1, PIN_HIGH);
rt_thread_mdelay(500);
rt_pin_write(LED1, PIN_LOW);
rt_thread_mdelay(500);
}
return 0;
}

View File

@ -0,0 +1,26 @@
Import('RTT_ROOT')
Import('rtconfig')
from building import *
cwd = os.path.join(str(Dir('#')), 'drivers')
# add the general drivers.
src = Split("""
board.c
""")
CPPPATH = [cwd]
# add uart drivers.
if GetDepend('RT_USING_SERIAL'):
src += ['drv_usart.c']
if GetDepend('RT_USING_PIN'):
src += ['drv_gpio.c']
if GetDepend('RT_USING_ADC'):
src += ['drv_adc.c']
group = DefineGroup('Drivers', src, depend = [''], CPPPATH = CPPPATH)
Return('group')

View File

@ -0,0 +1,74 @@
/*
* Copyright (c) 2006-2021, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2021-01-04 iysheng first version
*/
#include <stdint.h>
#include <rthw.h>
#include <rtthread.h>
#include <gd32f10x.h>
#include <board.h>
#include <drv_usart.h>
/*
* System Clock Configuration
*/
void SystemClock_Config(void)
{
SysTick_Config(SystemCoreClock / RT_TICK_PER_SECOND);
NVIC_SetPriority(SysTick_IRQn, 0);
}
/*
* This is the timer interrupt service routine.
*/
void SysTick_Handler(void)
{
/* enter interrupt */
rt_interrupt_enter();
rt_tick_increase();
/* leave interrupt */
rt_interrupt_leave();
}
/**
* This function will initial GD32 board.
*/
void rt_hw_board_init()
{
/* NVIC Configuration */
#define NVIC_VTOR_MASK 0x3FFFFF80
#ifdef VECT_TAB_RAM
/* Set the Vector Table base location at 0x10000000 */
SCB->VTOR = (0x10000000 & NVIC_VTOR_MASK);
#else /* VECT_TAB_FLASH */
/* Set the Vector Table base location at 0x08000000 */
SCB->VTOR = (0x08000000 & NVIC_VTOR_MASK);
#endif
SystemClock_Config();
#ifdef RT_USING_COMPONENTS_INIT
rt_components_board_init();
#endif
#ifdef RT_USING_CONSOLE
rt_console_set_device(RT_CONSOLE_DEVICE_NAME);
#endif
#ifdef BSP_USING_SDRAM
rt_system_heap_init((void *)EXT_SDRAM_BEGIN, (void *)EXT_SDRAM_END);
#else
rt_system_heap_init((void *)HEAP_BEGIN, (void *)HEAP_END);
#endif
}
/*@}*/

View File

@ -0,0 +1,26 @@
/*
* Copyright (c) 2006-2021, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2021-01-04 iysheng first version
*/
#ifndef __BOARD_H__
#define __BOARD_H__
#include <gd32f10x.h>
#include "drv_gpio.h"
#define GD32_SRAM_SIZE 48
#define GD32_SRAM_END (0x20000000 + GD32_SRAM_SIZE * 1024)
extern int __bss_end;
#define HEAP_BEGIN (&__bss_end)
#define HEAP_END GD32_SRAM_END
#endif

View File

@ -0,0 +1,168 @@
/*
* Copyright (c) 2006-2021, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2021-01-03 iysheng first version
*/
#include <board.h>
#include <drivers/adc.h>
#include <rtdbg.h>
#ifdef RT_USING_ADC
//#define DRV_DEBUG
#define LOG_TAG "drv.adc"
#ifndef ARRAY_SIZE
#define ARRAY_SIZE(x) (sizeof(x) / sizeof(x[0]))
#endif
#define MAX_EXTERN_ADC_CHANNEL 16
typedef struct {
struct rt_adc_device adc_dev;
char name[8];
rt_base_t adc_pins[16];
void *private_data;
} gd32_adc_device;
static gd32_adc_device g_gd32_devs[] = {
#ifdef BSP_USING_ADC0
{
{},
"adc0",
{
GET_PIN(A, 0), GET_PIN(A, 1), GET_PIN(A, 2), GET_PIN(A, 3),
GET_PIN(A, 4), GET_PIN(A, 5), GET_PIN(A, 6), GET_PIN(A, 7),
GET_PIN(B, 0), GET_PIN(B, 1), GET_PIN(C, 0), GET_PIN(C, 1),
GET_PIN(C, 2), GET_PIN(C, 3), GET_PIN(C, 4), GET_PIN(C, 5),
},
ADC0,
},
#endif
#ifdef BSP_USING_ADC1
{
{},
"adc1",
{
GET_PIN(A, 0), GET_PIN(A, 1), GET_PIN(A, 2), GET_PIN(A, 3),
GET_PIN(A, 4), GET_PIN(A, 5), GET_PIN(A, 6), GET_PIN(A, 7),
GET_PIN(B, 0), GET_PIN(B, 1), GET_PIN(C, 0), GET_PIN(C, 1),
GET_PIN(C, 2), GET_PIN(C, 3), GET_PIN(C, 4), GET_PIN(C, 5),
},
ADC1,
},
#endif
};
/*
* static void init_pin4adc
*
* analog
* @ rt_uint32_t pin: pin information
* return: N/A
*/
static void init_pin4adc(rt_base_t pin)
{
GPIO_InitPara GPIO_InitStruct = {0};
GPIO_InitStruct.GPIO_Pin = PIN_GDPIN(pin);
GPIO_InitStruct.GPIO_Speed = GPIO_SPEED_50MHZ;
GPIO_InitStruct.GPIO_Mode = GPIO_MODE_AIN;
GPIO_Init(PIN_GDPORT(pin), &GPIO_InitStruct);
}
static rt_err_t gd32_adc_enabled(struct rt_adc_device *device, rt_uint32_t channel, rt_bool_t enabled)
{
ADC_TypeDef *ADCx;
ADC_InitPara ADC_InitParaStruct = {0};
gd32_adc_device * gd32_adc = (gd32_adc_device *)device;
if (channel >= MAX_EXTERN_ADC_CHANNEL)
{
LOG_E("invalid channel");
return -E2BIG;
}
ADCx = (ADC_TypeDef *)(device->parent.user_data);
if (enabled == ENABLE)
{
init_pin4adc(gd32_adc->adc_pins[channel]);
ADC_InitParaStruct.ADC_Trig_External = ADC_EXTERNAL_TRIGGER_MODE_NONE;
/* Fix the channel number to fit the firmware library */
ADC_InitParaStruct.ADC_Channel_Number = 1 + channel;
ADC_InitParaStruct.ADC_Data_Align = ADC_DATAALIGN_RIGHT;
ADC_InitParaStruct.ADC_Mode_Scan = DISABLE;
ADC_InitParaStruct.ADC_Mode = ADC_MODE_INDEPENDENT;
ADC_InitParaStruct.ADC_Mode_Continuous = ENABLE;
ADC_Init(ADCx, &ADC_InitParaStruct);
ADC_RegularChannel_Config(ADCx, channel, 1, ADC_SAMPLETIME_13POINT5);
ADC_Enable(ADCx, ENABLE);
ADC_SoftwareStartConv_Enable(ADCx, ENABLE);
}
else
{
ADC_Enable(ADCx, DISABLE);
}
return 0;
}
static rt_err_t gd32_adc_convert(struct rt_adc_device *device, rt_uint32_t channel, rt_uint32_t *value)
{
ADC_TypeDef *ADCx;
if (!value)
{
LOG_E("invalid param");
return -EINVAL;
}
ADCx = (ADC_TypeDef *)(device->parent.user_data);
*value = ADC_GetConversionValue(ADCx);
return 0;
}
static struct rt_adc_ops g_gd32_adc_ops = {
gd32_adc_enabled,
gd32_adc_convert,
};
static int rt_hw_adc_init(void)
{
int ret, i = 0;
#ifdef BSP_USING_ADC0
rcu_periph_clock_enable(RCU_ADC0);
#endif
#ifdef BSP_USING_ADC1
rcu_periph_clock_enable(RCU_ADC1);
#endif
for (; i < ARRAY_SIZE(g_gd32_devs); i++)
{
ret = rt_hw_adc_register(&g_gd32_devs[i].adc_dev, \
(const char *)g_gd32_devs[i].name, \
&g_gd32_adc_ops, g_gd32_devs[i].private_data);
if (ret != RT_EOK)
{
/* TODO err handler */
LOG_E("failed register %s, err=%d", g_gd32_devs[i].name, ret);
}
}
return ret;
}
INIT_BOARD_EXPORT(rt_hw_adc_init);
#endif

View File

@ -0,0 +1,23 @@
/*
* Copyright (c) 2006-2021, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2021-01-03 iysheng first release
*/
#ifndef __DRV_ADC_H__
#define __DRV_ADC_H__
#ifdef __cplusplus
extern "C" {
#endif
#ifdef __cplusplus
}
#endif
#endif /* __DRV_ADC_H__ */

View File

@ -0,0 +1,512 @@
/*
* Copyright (c) 2006-2021, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2020-12-27 iysheng first version
* 2021-01-01 iysheng support exti interrupt
*/
#include <board.h>
#include "drv_gpio.h"
#ifdef RT_USING_PIN
#if defined(GPIOG)
#define __GD32_PORT_MAX 7u
#elif defined(GPIOF)
#define __GD32_PORT_MAX 6u
#elif defined(GPIOE)
#define __GD32_PORT_MAX 5u
#elif defined(GPIOD)
#define __GD32_PORT_MAX 4u
#elif defined(GPIOC)
#define __GD32_PORT_MAX 3u
#elif defined(GPIOB)
#define __GD32_PORT_MAX 2u
#elif defined(GPIOA)
#define __GD32_PORT_MAX 1u
#else
#define __GD32_PORT_MAX 0u
#error Unsupported GD32 GPIO peripheral.
#endif
#define PIN_GDPORT_MAX __GD32_PORT_MAX
static const struct pin_irq_map pin_irq_map[] =
{
#if defined(SOC_SERIES_GD32F1)
{GPIO_PIN_0, EXTI0_IRQn},
{GPIO_PIN_1, EXTI1_IRQn},
{GPIO_PIN_2, EXTI2_IRQn},
{GPIO_PIN_3, EXTI3_IRQn},
{GPIO_PIN_4, EXTI4_IRQn},
{GPIO_PIN_5, EXTI9_5_IRQn},
{GPIO_PIN_6, EXTI9_5_IRQn},
{GPIO_PIN_7, EXTI9_5_IRQn},
{GPIO_PIN_8, EXTI9_5_IRQn},
{GPIO_PIN_9, EXTI9_5_IRQn},
{GPIO_PIN_10, EXTI15_10_IRQn},
{GPIO_PIN_11, EXTI15_10_IRQn},
{GPIO_PIN_12, EXTI15_10_IRQn},
{GPIO_PIN_13, EXTI15_10_IRQn},
{GPIO_PIN_14, EXTI15_10_IRQn},
{GPIO_PIN_15, EXTI15_10_IRQn},
#else
#error "Unsupported soc series"
#endif
};
static struct rt_pin_irq_hdr pin_irq_hdr_tab[] =
{
{-1, 0, RT_NULL, RT_NULL},
{-1, 0, RT_NULL, RT_NULL},
{-1, 0, RT_NULL, RT_NULL},
{-1, 0, RT_NULL, RT_NULL},
{-1, 0, RT_NULL, RT_NULL},
{-1, 0, RT_NULL, RT_NULL},
{-1, 0, RT_NULL, RT_NULL},
{-1, 0, RT_NULL, RT_NULL},
{-1, 0, RT_NULL, RT_NULL},
{-1, 0, RT_NULL, RT_NULL},
{-1, 0, RT_NULL, RT_NULL},
{-1, 0, RT_NULL, RT_NULL},
{-1, 0, RT_NULL, RT_NULL},
{-1, 0, RT_NULL, RT_NULL},
{-1, 0, RT_NULL, RT_NULL},
{-1, 0, RT_NULL, RT_NULL},
};
static uint32_t pin_irq_enable_mask = 0;
#define ITEM_NUM(items) sizeof(items) / sizeof(items[0])
static rt_base_t gd32_pin_get(const char *name)
{
rt_base_t pin = 0;
int hw_port_num, hw_pin_num = 0;
int i, name_len;
name_len = rt_strlen(name);
if ((name_len < 4) || (name_len >= 6))
{
return -RT_EINVAL;
}
if ((name[0] != 'P') || (name[2] != '.'))
{
return -RT_EINVAL;
}
if ((name[1] >= 'A') && (name[1] <= 'Z'))
{
hw_port_num = (int)(name[1] - 'A');
}
else
{
return -RT_EINVAL;
}
for (i = 3; i < name_len; i++)
{
hw_pin_num *= 10;
hw_pin_num += name[i] - '0';
}
pin = PIN_NUM(hw_port_num, hw_pin_num);
return pin;
}
static void gd32_pin_write(rt_device_t dev, rt_base_t pin, rt_base_t value)
{
GPIO_TypeDef *gpio_port;
uint16_t gpio_pin;
if (PIN_PORT(pin) < PIN_GDPORT_MAX)
{
gpio_port = PIN_GDPORT(pin);
gpio_pin = PIN_GDPIN(pin);
GPIO_WriteBit(gpio_port, gpio_pin, (BitState)value);
}
}
static int gd32_pin_read(rt_device_t dev, rt_base_t pin)
{
GPIO_TypeDef *gpio_port;
uint16_t gpio_pin;
int value = PIN_LOW;
if (PIN_PORT(pin) < PIN_GDPORT_MAX)
{
gpio_port = PIN_GDPORT(pin);
gpio_pin = PIN_GDPIN(pin);
value = GPIO_ReadInputBit(gpio_port, gpio_pin);
}
return value;
}
static void gd32_pin_mode(rt_device_t dev, rt_base_t pin, rt_base_t mode)
{
GPIO_InitPara GPIO_InitStruct = {0};
if (PIN_PORT(pin) >= PIN_GDPORT_MAX)
{
return;
}
/* Configure GPIO_InitStructure */
GPIO_InitStruct.GPIO_Pin = PIN_GDPIN(pin);
GPIO_InitStruct.GPIO_Speed = GPIO_SPEED_2MHZ;
GPIO_InitStruct.GPIO_Mode = GPIO_MODE_IN_FLOATING;
switch (mode)
{
case PIN_MODE_OUTPUT:
GPIO_InitStruct.GPIO_Mode = GPIO_MODE_OUT_PP;
break;
case PIN_MODE_INPUT:
GPIO_InitStruct.GPIO_Mode = GPIO_MODE_IN_FLOATING;
break;
case PIN_MODE_INPUT_PULLUP:
GPIO_InitStruct.GPIO_Mode = GPIO_MODE_IPD;
break;
case PIN_MODE_INPUT_PULLDOWN:
GPIO_InitStruct.GPIO_Mode = GPIO_MODE_IPU;
break;
case PIN_MODE_OUTPUT_OD:
GPIO_InitStruct.GPIO_Mode = GPIO_MODE_OUT_OD;
break;
default:
break;
}
GPIO_Init(PIN_GDPORT(pin), &GPIO_InitStruct);
}
rt_inline rt_int32_t bit2bitno(rt_uint32_t bit)
{
int i;
for (i = 0; i < 32; i++)
{
if ((0x01 << i) == bit)
{
return i;
}
}
return -1;
}
rt_inline const struct pin_irq_map *get_pin_irq_map(uint32_t pinbit)
{
rt_int32_t mapindex = bit2bitno(pinbit);
if (mapindex < 0 || mapindex >= ITEM_NUM(pin_irq_map))
{
return RT_NULL;
}
return &pin_irq_map[mapindex];
};
static rt_err_t gd32_pin_attach_irq(struct rt_device *device, rt_int32_t pin,
rt_uint32_t mode, void (*hdr)(void *args), void *args)
{
rt_base_t level;
rt_int32_t irqindex = -1;
if (PIN_PORT(pin) >= PIN_GDPORT_MAX)
{
return -RT_ENOSYS;
}
irqindex = bit2bitno(PIN_GDPIN(pin));
if (irqindex < 0 || irqindex >= ITEM_NUM(pin_irq_map))
{
return RT_ENOSYS;
}
level = rt_hw_interrupt_disable();
if (pin_irq_hdr_tab[irqindex].pin == pin &&
pin_irq_hdr_tab[irqindex].hdr == hdr &&
pin_irq_hdr_tab[irqindex].mode == mode &&
pin_irq_hdr_tab[irqindex].args == args)
{
rt_hw_interrupt_enable(level);
return RT_EOK;
}
if (pin_irq_hdr_tab[irqindex].pin != -1)
{
rt_hw_interrupt_enable(level);
return RT_EBUSY;
}
pin_irq_hdr_tab[irqindex].pin = pin;
pin_irq_hdr_tab[irqindex].hdr = hdr;
pin_irq_hdr_tab[irqindex].mode = mode;
pin_irq_hdr_tab[irqindex].args = args;
rt_hw_interrupt_enable(level);
return RT_EOK;
}
static rt_err_t gd32_pin_dettach_irq(struct rt_device *device, rt_int32_t pin)
{
rt_base_t level;
rt_int32_t irqindex = -1;
if (PIN_PORT(pin) >= PIN_GDPORT_MAX)
{
return -RT_ENOSYS;
}
irqindex = bit2bitno(PIN_GDPIN(pin));
if (irqindex < 0 || irqindex >= ITEM_NUM(pin_irq_map))
{
return RT_ENOSYS;
}
level = rt_hw_interrupt_disable();
if (pin_irq_hdr_tab[irqindex].pin == -1)
{
rt_hw_interrupt_enable(level);
return RT_EOK;
}
pin_irq_hdr_tab[irqindex].pin = -1;
pin_irq_hdr_tab[irqindex].hdr = RT_NULL;
pin_irq_hdr_tab[irqindex].mode = 0;
pin_irq_hdr_tab[irqindex].args = RT_NULL;
rt_hw_interrupt_enable(level);
return RT_EOK;
}
static rt_err_t gd32_pin_irq_enable(struct rt_device *device, rt_base_t pin,
rt_uint32_t enabled)
{
const struct pin_irq_map *irqmap;
rt_base_t level;
rt_int32_t irqindex = -1;
GPIO_InitPara GPIO_InitStruct = {0};
EXTI_InitPara EXTI_InitParaStruct = {0};
if (PIN_PORT(pin) >= PIN_GDPORT_MAX)
{
return -RT_ENOSYS;
}
GPIO_InitStruct.GPIO_Pin = PIN_GDPIN(pin);
EXTI_InitParaStruct.EXTI_LINE = PIN_GDPIN(pin);
EXTI_InitParaStruct.EXTI_Mode = EXTI_Mode_Interrupt;
if (enabled == PIN_IRQ_ENABLE)
{
irqindex = bit2bitno(PIN_GDPIN(pin));
if (irqindex < 0 || irqindex >= ITEM_NUM(pin_irq_map))
{
return RT_ENOSYS;
}
level = rt_hw_interrupt_disable();
if (pin_irq_hdr_tab[irqindex].pin == -1)
{
rt_hw_interrupt_enable(level);
return RT_ENOSYS;
}
irqmap = &pin_irq_map[irqindex];
/* Configure GPIO_InitStructure */
GPIO_InitStruct.GPIO_Speed = GPIO_SPEED_10MHZ;
GPIO_InitStruct.GPIO_Mode = GPIO_MODE_IN_FLOATING;
EXTI_InitParaStruct.EXTI_LINEEnable = ENABLE;
GPIO_EXTILineConfig(PIN_PORT(pin), PIN_NO(pin));
switch (pin_irq_hdr_tab[irqindex].mode)
{
case PIN_IRQ_MODE_RISING:
EXTI_InitParaStruct.EXTI_Trigger = EXTI_Trigger_Rising;
GPIO_InitStruct.GPIO_Mode = GPIO_MODE_IPD;
EXTI_Init(&EXTI_InitParaStruct);
break;
case PIN_IRQ_MODE_FALLING:
GPIO_InitStruct.GPIO_Mode = GPIO_MODE_IPU;
EXTI_InitParaStruct.EXTI_Trigger = EXTI_Trigger_Falling;
EXTI_Init(&EXTI_InitParaStruct);
break;
case PIN_IRQ_MODE_RISING_FALLING:
EXTI_InitParaStruct.EXTI_Trigger = EXTI_Trigger_Rising_Falling;
EXTI_Init(&EXTI_InitParaStruct);
break;
default:
break;
}
GPIO_Init(PIN_GDPORT(pin), &GPIO_InitStruct);
NVIC_SetPriority(irqmap->irqno, 0);
NVIC_EnableIRQ(irqmap->irqno);
pin_irq_enable_mask |= irqmap->pinbit;
rt_hw_interrupt_enable(level);
}
else if (enabled == PIN_IRQ_DISABLE)
{
irqmap = get_pin_irq_map(PIN_GDPIN(pin));
if (irqmap == RT_NULL)
{
return RT_ENOSYS;
}
level = rt_hw_interrupt_disable();
EXTI_InitParaStruct.EXTI_LINEEnable = DISABLE;
EXTI_Init(&EXTI_InitParaStruct);
pin_irq_enable_mask &= ~irqmap->pinbit;
if ((irqmap->pinbit >= GPIO_PIN_5) && (irqmap->pinbit <= GPIO_PIN_9))
{
if (!(pin_irq_enable_mask & (GPIO_PIN_5 | GPIO_PIN_6 | GPIO_PIN_7 | GPIO_PIN_8 | GPIO_PIN_9)))
{
NVIC_DisableIRQ(irqmap->irqno);
}
}
else if ((irqmap->pinbit >= GPIO_PIN_10) && (irqmap->pinbit <= GPIO_PIN_15))
{
if (!(pin_irq_enable_mask & (GPIO_PIN_10 | GPIO_PIN_11 | GPIO_PIN_12 | GPIO_PIN_13 | GPIO_PIN_14 | GPIO_PIN_15)))
{
NVIC_DisableIRQ(irqmap->irqno);
}
}
else
{
NVIC_DisableIRQ(irqmap->irqno);
}
rt_hw_interrupt_enable(level);
}
else
{
return -RT_ENOSYS;
}
return RT_EOK;
}
const static struct rt_pin_ops _gd32_pin_ops =
{
gd32_pin_mode,
gd32_pin_write,
gd32_pin_read,
gd32_pin_attach_irq,
gd32_pin_dettach_irq,
gd32_pin_irq_enable,
gd32_pin_get,
};
rt_inline void pin_irq_hdr(int irqno)
{
if (pin_irq_hdr_tab[irqno].hdr)
{
pin_irq_hdr_tab[irqno].hdr(pin_irq_hdr_tab[irqno].args);
}
}
/**
* @brief This function handles EXTI interrupt request.
* @param gpio_pin: Specifies the pins connected EXTI line
* @retval none
*/
void gd32_pin_exti_irqhandler(uint16_t gpio_pin)
{
if (SET == EXTI_GetIntBitState(gpio_pin))
{
EXTI_ClearIntBitState(gpio_pin);
pin_irq_hdr(bit2bitno(gpio_pin));
}
}
void EXTI0_IRQHandler(void)
{
rt_interrupt_enter();
gd32_pin_exti_irqhandler(GPIO_PIN_0);
rt_interrupt_leave();
}
void EXTI1_IRQHandler(void)
{
rt_interrupt_enter();
gd32_pin_exti_irqhandler(GPIO_PIN_1);
rt_interrupt_leave();
}
void EXTI2_IRQHandler(void)
{
rt_interrupt_enter();
gd32_pin_exti_irqhandler(GPIO_PIN_2);
rt_interrupt_leave();
}
void EXTI3_IRQHandler(void)
{
rt_interrupt_enter();
gd32_pin_exti_irqhandler(GPIO_PIN_3);
rt_interrupt_leave();
}
void EXTI4_IRQHandler(void)
{
rt_interrupt_enter();
gd32_pin_exti_irqhandler(GPIO_PIN_4);
rt_interrupt_leave();
}
void EXTI5_9_IRQHandler(void)
{
rt_interrupt_enter();
gd32_pin_exti_irqhandler(GPIO_PIN_5);
gd32_pin_exti_irqhandler(GPIO_PIN_6);
gd32_pin_exti_irqhandler(GPIO_PIN_7);
gd32_pin_exti_irqhandler(GPIO_PIN_8);
gd32_pin_exti_irqhandler(GPIO_PIN_9);
rt_interrupt_leave();
}
void EXTI10_15_IRQHandler(void)
{
rt_interrupt_enter();
gd32_pin_exti_irqhandler(GPIO_PIN_10);
gd32_pin_exti_irqhandler(GPIO_PIN_11);
gd32_pin_exti_irqhandler(GPIO_PIN_12);
gd32_pin_exti_irqhandler(GPIO_PIN_13);
gd32_pin_exti_irqhandler(GPIO_PIN_14);
gd32_pin_exti_irqhandler(GPIO_PIN_15);
rt_interrupt_leave();
}
int rt_hw_pin_init(void)
{
#if defined(GPIOG)
rcu_periph_clock_enable(RCU_GPIOG);
#endif
#if defined(GPIOF)
rcu_periph_clock_enable(RCU_GPIOF);
#endif
#if defined(GPIOE)
rcu_periph_clock_enable(RCU_GPIOE);
#endif
#if defined(GPIOD)
rcu_periph_clock_enable(RCU_GPIOD);
#endif
#if defined(GPIOC)
rcu_periph_clock_enable(RCU_GPIOC);
#endif
#if defined(GPIOB)
rcu_periph_clock_enable(RCU_GPIOB);
#endif
#if defined(GPIOA)
rcu_periph_clock_enable(RCU_GPIOA);
#endif
rcu_periph_clock_enable(RCU_AF);
return rt_device_pin_register("pin", &_gd32_pin_ops, RT_NULL);
}
INIT_BOARD_EXPORT(rt_hw_pin_init);
#endif /* RT_USING_PIN */

View File

@ -0,0 +1,45 @@
/*
* Copyright (c) 2006-2020, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2020-12-27 iysheng first release
*/
#ifndef __DRV_GPIO_H__
#define __DRV_GPIO_H__
#include <rtthread.h>
#include <rthw.h>
#include <rtdevice.h>
#include <board.h>
#ifdef __cplusplus
extern "C" {
#endif
#define __GD32_PORT(port) GPIO##port##_BASE
#define GET_PIN(PORTx,PIN) (rt_base_t)((16 * ( ((rt_base_t)__GD32_PORT(PORTx) - (rt_base_t)GPIOA_BASE)/(0x0400UL) )) + PIN)
#define PIN_NUM(port, no) (((((port) & 0xFu) << 4) | ((no) & 0xFu)))
#define PIN_PORT(pin) ((uint8_t)(((pin) >> 4) & 0xFu))
#define PIN_NO(pin) ((uint8_t)((pin) & 0xFu))
#define PIN_GDPORT(pin) ((GPIO_TypeDef *)(GPIOA_BASE + (0x400u * PIN_PORT(pin))))
#define PIN_GDPIN(pin) ((uint16_t)(1u << PIN_NO(pin)))
struct pin_irq_map
{
rt_uint16_t pinbit;
IRQn_Type irqno;
};
#ifdef __cplusplus
}
#endif
#endif /* __DRV_GPIO_H__ */

View File

@ -0,0 +1,358 @@
/*
* Copyright (c) 2006-2021, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2021-01-04 iysheng first version
*/
#include <gd32f10x.h>
#include <drv_usart.h>
#include <board.h>
#ifdef RT_USING_SERIAL
#if !defined(BSP_USING_UART0) && !defined(BSP_USING_UART1) && \
!defined(BSP_USING_UART2) && !defined(BSP_USING_UART3) && \
!defined(BSP_USING_UART4)
#error "Please define at least one UARTx"
#endif
#include <rtdevice.h>
static void uart_isr(struct rt_serial_device *serial);
#if defined(BSP_USING_UART0)
struct rt_serial_device serial0;
void USART0_IRQHandler(void)
{
/* enter interrupt */
rt_interrupt_enter();
uart_isr(&serial0);
/* leave interrupt */
rt_interrupt_leave();
}
#endif /* BSP_USING_UART0 */
#if defined(BSP_USING_UART1)
struct rt_serial_device serial1;
void USART1_IRQHandler(void)
{
/* enter interrupt */
rt_interrupt_enter();
uart_isr(&serial1);
/* leave interrupt */
rt_interrupt_leave();
}
#endif /* BSP_USING_UART1 */
#if defined(BSP_USING_UART2)
struct rt_serial_device serial2;
void USART2_IRQHandler(void)
{
/* enter interrupt */
rt_interrupt_enter();
uart_isr(&serial2);
/* leave interrupt */
rt_interrupt_leave();
}
#endif /* BSP_USING_UART2 */
#if defined(BSP_USING_UART3)
struct rt_serial_device serial3;
void UART3_IRQHandler(void)
{
/* enter interrupt */
rt_interrupt_enter();
uart_isr(&serial3);
/* leave interrupt */
rt_interrupt_leave();
}
#endif /* BSP_USING_UART3 */
#if defined(BSP_USING_UART4)
struct rt_serial_device serial4;
void UART4_IRQHandler(void)
{
/* enter interrupt */
rt_interrupt_enter();
uart_isr(&serial4);
/* leave interrupt */
rt_interrupt_leave();
}
#endif /* BSP_USING_UART4 */
static const struct gd32_uart uarts[] = {
#ifdef BSP_USING_UART0
{
USART0, /* uart peripheral index */
USART0_IRQn, /* uart iqrn */
RCU_USART0, RCU_GPIOA, RCU_GPIOA, /* periph clock, tx gpio clock, rt gpio clock */
GPIOA, GPIOA, /* tx port, tx alternate, tx pin */
GPIO_PIN_9, GPIO_PIN_10, /* rx port, rx alternate, rx pin */
&serial0,
"uart0",
},
#endif
#ifdef BSP_USING_UART1
{
USART1, /* uart peripheral index */
USART1_IRQn, /* uart iqrn */
RCU_USART1, RCU_GPIOA, RCU_GPIOA, /* periph clock, tx gpio clock, rt gpio clock */
GPIOA, GPIOA, /* tx port, tx alternate, tx pin */
GPIO_PIN_2, GPIO_PIN_3, /* rx port, rx alternate, rx pin */
&serial1,
"uart1",
},
#endif
#ifdef BSP_USING_UART2
{
USART2, /* uart peripheral index */
USART2_IRQn, /* uart iqrn */
RCU_USART2, RCU_GPIOB, RCU_GPIOB, /* periph clock, tx gpio clock, rt gpio clock */
GPIOB, GPIOB, /* tx port, tx alternate, tx pin */
GPIO_PIN_10, GPIO_PIN_11, /* rx port, rx alternate, rx pin */
&serial2,
"uart2",
},
#endif
#ifdef BSP_USING_UART3
{
UART3, /* uart peripheral index */
UART3_IRQn, /* uart iqrn */
RCU_UART3, RCU_GPIOC, RCU_GPIOC, /* periph clock, tx gpio clock, rt gpio clock */
GPIOC, GPIOC, /* tx port, tx alternate, tx pin */
GPIO_PIN_10, GPIO_PIN_11, /* rx port, rx alternate, rx pin */
&serial3,
"uart3",
},
#endif
#ifdef BSP_USING_UART4
{
UART4, /* uart peripheral index */
UART4_IRQn, /* uart iqrn */
RCU_UART4, RCU_GPIOC, RCU_GPIOD, /* periph clock, tx gpio clock, rt gpio clock */
GPIOC, GPIOD, /* tx port, tx alternate, tx pin */
GPIO_PIN_12, GPIO_PIN_2, /* rx port, rx alternate, rx pin */
&serial4,
"uart4",
},
#endif
};
/**
* @brief UART MSP Initialization
* This function configures the hardware resources used in this example:
* - Peripheral's clock enable
* - Peripheral's GPIO Configuration
* - NVIC configuration for UART interrupt request enable
* @param huart: UART handle pointer
* @retval None
*/
void gd32_uart_gpio_init(struct gd32_uart *uart)
{
GPIO_TypeDef *GPIOx;
GPIO_InitPara GPIO_InitStructure = {0};
/* enable USART clock */
rcu_periph_clock_enable(uart->tx_gpio_clk);
rcu_periph_clock_enable(uart->rx_gpio_clk);
rcu_periph_clock_enable(uart->per_clk);
GPIOx = (GPIO_TypeDef *)uart->tx_port;
GPIO_InitStructure.GPIO_Pin = uart->tx_pin;
GPIO_InitStructure.GPIO_Mode = GPIO_MODE_AF_PP;
GPIO_InitStructure.GPIO_Speed = GPIO_SPEED_10MHZ;
GPIO_Init(GPIOx, &GPIO_InitStructure);
/* TODO 初始化 RX */
GPIOx = (GPIO_TypeDef *)uart->rx_port;
GPIO_InitStructure.GPIO_Pin = uart->rx_pin;
GPIO_InitStructure.GPIO_Mode = GPIO_MODE_IN_FLOATING;
GPIO_InitStructure.GPIO_Speed = GPIO_SPEED_10MHZ;
GPIO_Init(GPIOx, &GPIO_InitStructure);
NVIC_SetPriority(uart->irqn, 0);
NVIC_EnableIRQ(uart->irqn);
}
static rt_err_t gd32_configure(struct rt_serial_device *serial, struct serial_configure *cfg)
{
struct gd32_uart *uart;
USART_TypeDef *USARTx;
USART_InitPara USART_InitParaStruct = {0};
RT_ASSERT(serial != RT_NULL);
RT_ASSERT(cfg != RT_NULL);
uart = (struct gd32_uart *)serial->parent.user_data;
gd32_uart_gpio_init(uart);
USARTx = (USART_TypeDef *)uart->uart_periph;
USART_InitParaStruct.USART_BRR = cfg->baud_rate;
switch (cfg->data_bits) {
case DATA_BITS_9:
USART_InitParaStruct.USART_WL = USART_WL_9B;
break;
default:
USART_InitParaStruct.USART_WL = USART_WL_8B;
break;
}
switch (cfg->stop_bits) {
case STOP_BITS_2:
USART_InitParaStruct.USART_STBits = USART_STBITS_2;
break;
default:
USART_InitParaStruct.USART_STBits = USART_STBITS_1;
break;
}
switch (cfg->parity) {
case PARITY_ODD:
USART_InitParaStruct.USART_Parity = USART_PARITY_SETODD;
break;
case PARITY_EVEN:
USART_InitParaStruct.USART_Parity = USART_PARITY_SETEVEN;
break;
default:
USART_InitParaStruct.USART_Parity = USART_PARITY_RESET;
break;
}
USART_InitParaStruct.USART_HardwareFlowControl = USART_HARDWAREFLOWCONTROL_NONE;
USART_InitParaStruct.USART_RxorTx = USART_RXORTX_RX | USART_RXORTX_TX;
USART_Init(USARTx, &USART_InitParaStruct);
USART_Enable(USARTx, ENABLE);
return RT_EOK;
}
static rt_err_t gd32_control(struct rt_serial_device *serial, int cmd, void *arg)
{
struct gd32_uart *uart;
USART_TypeDef *USARTx;
RT_ASSERT(serial != RT_NULL);
uart = (struct gd32_uart *)serial->parent.user_data;
USARTx = (USART_TypeDef *)uart->uart_periph;
switch (cmd) {
case RT_DEVICE_CTRL_CLR_INT:
/* disable rx irq */
NVIC_DisableIRQ(uart->irqn);
/* disable interrupt */
USART_INT_Set(USARTx, USART_INT_RBNE, DISABLE);
break;
case RT_DEVICE_CTRL_SET_INT:
/* enable rx irq */
NVIC_EnableIRQ(uart->irqn);
/* enable interrupt */
USART_INT_Set(USARTx, USART_INT_RBNE, ENABLE);
break;
}
return RT_EOK;
}
static int gd32_putc(struct rt_serial_device *serial, char ch)
{
struct gd32_uart *uart;
RT_ASSERT(serial != RT_NULL);
uart = (struct gd32_uart *)serial->parent.user_data;
USART_DataSend((USART_TypeDef *)uart->uart_periph, ch);
while ((USART_GetBitState(uart->uart_periph, USART_FLAG_TC) == RESET));
return 1;
}
static int gd32_getc(struct rt_serial_device *serial)
{
int ch;
struct gd32_uart *uart;
RT_ASSERT(serial != RT_NULL);
uart = (struct gd32_uart *)serial->parent.user_data;
ch = -1;
if (USART_GetBitState(uart->uart_periph, USART_FLAG_RBNE) != RESET)
ch = USART_DataReceive(uart->uart_periph);
return ch;
}
/**
* Uart common interrupt process. This need add to uart ISR.
*
* @param serial serial device
*/
static void uart_isr(struct rt_serial_device *serial)
{
struct gd32_uart *uart = (struct gd32_uart *) serial->parent.user_data;
RT_ASSERT(uart != RT_NULL);
if ((USART_GetIntBitState((USART_TypeDef *)uart->uart_periph, USART_INT_RBNE) != RESET) &&
(USART_GetBitState((USART_TypeDef *)uart->uart_periph, USART_FLAG_RBNE) != RESET)) {
rt_hw_serial_isr(serial, RT_SERIAL_EVENT_RX_IND);
/* Clear RXNE interrupt flag */
USART_ClearBitState(uart->uart_periph, USART_FLAG_RBNE);
}
}
static const struct rt_uart_ops gd32_uart_ops = {
gd32_configure,
gd32_control,
gd32_putc,
gd32_getc,
};
int gd32_hw_usart_init(void)
{
struct serial_configure config = RT_SERIAL_CONFIG_DEFAULT;
int i;
for (i = 0; i < sizeof(uarts) / sizeof(uarts[0]); i++) {
uarts[i].serial->ops = &gd32_uart_ops;
uarts[i].serial->config = config;
/* register UART device */
rt_hw_serial_register(uarts[i].serial,
uarts[i].device_name,
RT_DEVICE_FLAG_RDWR | RT_DEVICE_FLAG_INT_RX,
(void *)&uarts[i]);
}
return 0;
}
INIT_BOARD_EXPORT(gd32_hw_usart_init);
#endif

View File

@ -0,0 +1,33 @@
/*
* Copyright (c) 2006-2021, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2021-01-04 iysheng first version
*/
#ifndef __USART_H__
#define __USART_H__
#include <rthw.h>
#include <rtthread.h>
/* GD32 uart driver */
struct gd32_uart {
USART_TypeDef * uart_periph;
IRQn_Type irqn;
rcu_periph_enum per_clk;
rcu_periph_enum tx_gpio_clk;
rcu_periph_enum rx_gpio_clk;
GPIO_TypeDef * tx_port;
GPIO_TypeDef * rx_port;
uint16_t tx_pin;
uint16_t rx_pin;
struct rt_serial_device *serial;
char *device_name;
};
#endif

View File

@ -0,0 +1,146 @@
/*
* linker script for GD32F1xx with GNU ld
*
* Change Logs:
* Date Author Notes
* 2009-10-14 bernard.xiong first implementation
* 2021-01-02 iysheng modify to suite gd32f103c
*/
/* Program Entry, set to mark it as "used" and avoid gc */
MEMORY
{
CODE (rx) : ORIGIN = 0x08000000, LENGTH = 256k /* 256KB flash */
DATA (rw) : ORIGIN = 0x20000000, LENGTH = 48k /* 48KB sram */
}
ENTRY(Reset_Handler)
_system_stack_size = 0x200;
SECTIONS
{
.text :
{
. = ALIGN(4);
_stext = .;
KEEP(*(.isr_vector)) /* Startup code */
. = ALIGN(4);
*(.text) /* remaining code */
*(.text.*) /* remaining code */
*(.rodata) /* read-only data (constants) */
*(.rodata*)
*(.glue_7)
*(.glue_7t)
*(.gnu.linkonce.t*)
/* section information for finsh shell */
. = ALIGN(4);
__fsymtab_start = .;
KEEP(*(FSymTab))
__fsymtab_end = .;
. = ALIGN(4);
__vsymtab_start = .;
KEEP(*(VSymTab))
__vsymtab_end = .;
. = ALIGN(4);
/* section information for initial. */
. = ALIGN(4);
__rt_init_start = .;
KEEP(*(SORT(.rti_fn*)))
__rt_init_end = .;
. = ALIGN(4);
. = ALIGN(4);
_etext = .;
} > CODE = 0
/* .ARM.exidx is sorted, so has to go in its own output section. */
__exidx_start = .;
.ARM.exidx :
{
*(.ARM.exidx* .gnu.linkonce.armexidx.*)
/* This is used by the startup in order to initialize the .data secion */
_sidata = .;
} > CODE
__exidx_end = .;
/* .data section which is used for initialized data */
.data : AT (_sidata)
{
. = ALIGN(4);
/* This is used by the startup in order to initialize the .data secion */
_sdata = . ;
*(.data)
*(.data.*)
*(.gnu.linkonce.d*)
. = ALIGN(4);
/* This is used by the startup in order to initialize the .data secion */
_edata = . ;
} >DATA
.stack :
{
. = . + _system_stack_size;
. = ALIGN(4);
_estack = .;
} >DATA
__bss_start = .;
.bss :
{
. = ALIGN(4);
/* This is used by the startup in order to initialize the .bss secion */
_sbss = .;
*(.bss)
*(.bss.*)
*(COMMON)
. = ALIGN(4);
/* This is used by the startup in order to initialize the .bss secion */
_ebss = . ;
*(.bss.init)
} > DATA
__bss_end = .;
_end = .;
/* Stabs debugging sections. */
.stab 0 : { *(.stab) }
.stabstr 0 : { *(.stabstr) }
.stab.excl 0 : { *(.stab.excl) }
.stab.exclstr 0 : { *(.stab.exclstr) }
.stab.index 0 : { *(.stab.index) }
.stab.indexstr 0 : { *(.stab.indexstr) }
.comment 0 : { *(.comment) }
/* DWARF debug sections.
* Symbols in the DWARF debugging sections are relative to the beginning
* of the section so we begin them at 0. */
/* DWARF 1 */
.debug 0 : { *(.debug) }
.line 0 : { *(.line) }
/* GNU DWARF 1 extensions */
.debug_srcinfo 0 : { *(.debug_srcinfo) }
.debug_sfnames 0 : { *(.debug_sfnames) }
/* DWARF 1.1 and DWARF 2 */
.debug_aranges 0 : { *(.debug_aranges) }
.debug_pubnames 0 : { *(.debug_pubnames) }
/* DWARF 2 */
.debug_info 0 : { *(.debug_info .gnu.linkonce.wi.*) }
.debug_abbrev 0 : { *(.debug_abbrev) }
.debug_line 0 : { *(.debug_line) }
.debug_frame 0 : { *(.debug_frame) }
.debug_str 0 : { *(.debug_str) }
.debug_loc 0 : { *(.debug_loc) }
.debug_macinfo 0 : { *(.debug_macinfo) }
/* SGI/MIPS DWARF 2 extensions */
.debug_weaknames 0 : { *(.debug_weaknames) }
.debug_funcnames 0 : { *(.debug_funcnames) }
.debug_typenames 0 : { *(.debug_typenames) }
.debug_varnames 0 : { *(.debug_varnames) }
}

View File

@ -0,0 +1,167 @@
#ifndef RT_CONFIG_H__
#define RT_CONFIG_H__
/* Automatically generated file; DO NOT EDIT. */
/* RT-Thread Configuration */
/* RT-Thread Kernel */
#define RT_NAME_MAX 8
#define RT_ALIGN_SIZE 4
#define RT_THREAD_PRIORITY_32
#define RT_THREAD_PRIORITY_MAX 32
#define RT_TICK_PER_SECOND 100
#define RT_USING_OVERFLOW_CHECK
#define RT_USING_HOOK
#define RT_USING_IDLE_HOOK
#define RT_IDLE_HOOK_LIST_SIZE 4
#define IDLE_THREAD_STACK_SIZE 256
#define RT_USING_TIMER_SOFT
#define RT_TIMER_THREAD_PRIO 4
#define RT_TIMER_THREAD_STACK_SIZE 512
#define RT_DEBUG
/* Inter-Thread communication */
#define RT_USING_SEMAPHORE
#define RT_USING_MUTEX
#define RT_USING_EVENT
#define RT_USING_MAILBOX
#define RT_USING_MESSAGEQUEUE
/* Memory Management */
#define RT_USING_MEMPOOL
#define RT_USING_SMALL_MEM
#define RT_USING_HEAP
/* Kernel Device Object */
#define RT_USING_DEVICE
#define RT_USING_CONSOLE
#define RT_CONSOLEBUF_SIZE 128
#define RT_CONSOLE_DEVICE_NAME "uart0"
#define RT_VER_NUM 0x40003
/* RT-Thread Components */
#define RT_USING_COMPONENTS_INIT
#define RT_USING_USER_MAIN
#define RT_MAIN_THREAD_STACK_SIZE 2048
#define RT_MAIN_THREAD_PRIORITY 10
/* C++ features */
/* Command shell */
#define RT_USING_FINSH
#define FINSH_THREAD_NAME "tshell"
#define FINSH_USING_HISTORY
#define FINSH_HISTORY_LINES 5
#define FINSH_USING_SYMTAB
#define FINSH_USING_DESCRIPTION
#define FINSH_THREAD_PRIORITY 20
#define FINSH_THREAD_STACK_SIZE 4096
#define FINSH_CMD_SIZE 80
#define FINSH_USING_MSH
#define FINSH_USING_MSH_DEFAULT
#define FINSH_ARG_MAX 10
/* Device virtual file system */
#define RT_USING_DFS
#define DFS_USING_WORKDIR
#define DFS_FILESYSTEMS_MAX 2
#define DFS_FILESYSTEM_TYPES_MAX 2
#define DFS_FD_MAX 16
#define RT_USING_DFS_DEVFS
/* Device Drivers */
#define RT_USING_DEVICE_IPC
#define RT_PIPE_BUFSZ 512
#define RT_USING_SERIAL
#define RT_SERIAL_USING_DMA
#define RT_SERIAL_RB_BUFSZ 64
#define RT_USING_PIN
#define RT_USING_ADC
/* Using USB */
/* POSIX layer and C standard library */
#define RT_USING_LIBC
#define RT_USING_POSIX
/* Network */
/* Socket abstraction layer */
/* Network interface device */
/* light weight TCP/IP stack */
/* AT commands */
/* VBUS(Virtual Software BUS) */
/* Utilities */
/* RT-Thread online packages */
/* IoT - internet of things */
/* Wi-Fi */
/* Marvell WiFi */
/* Wiced WiFi */
/* IoT Cloud */
/* security packages */
/* language packages */
/* multimedia packages */
/* tools packages */
/* system packages */
/* peripheral libraries and drivers */
/* miscellaneous packages */
/* samples: kernel and components samples */
#define SOC_SERIES_GD32F1
#define SOC_GD32103C
/* On-chip Peripheral Drivers */
#define BSP_USING_UART
#define BSP_USING_UART0
#define BSP_USING_ADC
#define BSP_USING_ADC0
#endif

View File

@ -0,0 +1,126 @@
import os
# toolchains options
ARCH='arm'
CPU='cortex-m3'
CROSS_TOOL='gcc'
if os.getenv('RTT_CC'):
CROSS_TOOL = os.getenv('RTT_CC')
# cross_tool provides the cross compiler
# EXEC_PATH is the compiler execute path, for example, CodeSourcery, Keil MDK, IAR
if CROSS_TOOL == 'gcc':
PLATFORM = 'gcc'
EXEC_PATH = r'D:/toolchain/gnu_tools_arm_embedded/5.4_2016q3/bin'
elif CROSS_TOOL == 'keil':
PLATFORM = 'armcc'
EXEC_PATH = r'C:/Keil_v5'
elif CROSS_TOOL == 'iar':
PLATFORM = 'iar'
EXEC_PATH = r'C:/Program Files (x86)/IAR Systems/Embedded Workbench 8.0'
if os.getenv('RTT_EXEC_PATH'):
EXEC_PATH = os.getenv('RTT_EXEC_PATH')
BUILD = 'debug'
if PLATFORM == 'gcc':
# tool-chains
PREFIX = 'arm-none-eabi-'
CC = PREFIX + 'gcc'
AS = PREFIX + 'gcc'
AR = PREFIX + 'ar'
LINK = PREFIX + 'gcc'
TARGET_EXT = 'elf'
SIZE = PREFIX + 'size'
OBJDUMP = PREFIX + 'objdump'
OBJCPY = PREFIX + 'objcopy'
DEVICE = ' -mcpu=cortex-m3 -mthumb -ffunction-sections -fdata-sections'
CFLAGS = DEVICE + ' -Dgcc' # -D' + PART_TYPE
AFLAGS = ' -c' + DEVICE + ' -x assembler-with-cpp -Wa,-mimplicit-it=thumb '
LFLAGS = DEVICE + ' -Wl,--gc-sections,-Map=rtthread-gd32.map,-cref,-u,Reset_Handler -T gd32_rom.ld'
CPATH = ''
LPATH = ''
if BUILD == 'debug':
CFLAGS += ' -O0 -gdwarf-2 -g'
AFLAGS += ' -gdwarf-2'
else:
CFLAGS += ' -O2'
POST_ACTION = OBJCPY + ' -O binary $TARGET rtthread.bin\n' + SIZE + ' $TARGET \n'
elif PLATFORM == 'armcc':
# toolchains
CC = 'armcc'
AS = 'armasm'
AR = 'armar'
LINK = 'armlink'
TARGET_EXT = 'axf'
DEVICE = ' --cpu Cortex-M4'
CFLAGS = DEVICE + ' --apcs=interwork'
AFLAGS = DEVICE
LFLAGS = DEVICE + ' --info sizes --info totals --info unused --info veneers --list rtthread-gd32.map --scatter gd32_rom.sct'
LFLAGS += ' --keep *.o(.rti_fn.*) --keep *.o(FSymTab) --keep *.o(VSymTab)'
EXEC_PATH += '/ARM/ARMCC/bin'
print(EXEC_PATH)
CFLAGS += ' --c99'
if BUILD == 'debug':
CFLAGS += ' -g -O0'
AFLAGS += ' -g'
else:
CFLAGS += ' -O2'
POST_ACTION = 'fromelf --bin $TARGET --output rtthread.bin \nfromelf -z $TARGET'
elif PLATFORM == 'iar':
# toolchains
CC = 'iccarm'
AS = 'iasmarm'
AR = 'iarchive'
LINK = 'ilinkarm'
TARGET_EXT = 'out'
DEVICE = ' -D USE_STDPERIPH_DRIVER' + ' -D GD32F30X_HD'
CFLAGS = DEVICE
CFLAGS += ' --diag_suppress Pa050'
CFLAGS += ' --no_cse'
CFLAGS += ' --no_unroll'
CFLAGS += ' --no_inline'
CFLAGS += ' --no_code_motion'
CFLAGS += ' --no_tbaa'
CFLAGS += ' --no_clustering'
CFLAGS += ' --no_scheduling'
CFLAGS += ' --debug'
CFLAGS += ' --endian=little'
CFLAGS += ' --cpu=Cortex-M4'
CFLAGS += ' -e'
CFLAGS += ' --fpu=None'
CFLAGS += ' --dlib_config "' + EXEC_PATH + '/arm/INC/c/DLib_Config_Normal.h"'
CFLAGS += ' -Ol'
CFLAGS += ' --use_c++_inline'
AFLAGS = ''
AFLAGS += ' -s+'
AFLAGS += ' -w+'
AFLAGS += ' -r'
AFLAGS += ' --cpu Cortex-M4'
AFLAGS += ' --fpu None'
LFLAGS = ' --config gd32_rom.icf'
LFLAGS += ' --redirect _Printf=_PrintfTiny'
LFLAGS += ' --redirect _Scanf=_ScanfSmall'
LFLAGS += ' --entry __iar_program_start'
EXEC_PATH += '/arm/bin/'
POST_ACTION = ''