diff --git a/bsp/tkm32F499/Libraries/CMSIS_and_startup/startup_Tk499.s b/bsp/tkm32F499/Libraries/CMSIS_and_startup/startup_Tk499.s
index 96e5f7d11d..032d289789 100644
--- a/bsp/tkm32F499/Libraries/CMSIS_and_startup/startup_Tk499.s
+++ b/bsp/tkm32F499/Libraries/CMSIS_and_startup/startup_Tk499.s
@@ -4,7 +4,7 @@
; Stack Configuration
; Stack Size (in Bytes) <0x0-0xFFFFFFFF:8>
;
-;//============== 版本 EK V1.0 20190801 ==============//
+;//============== 鐗堟湰 EK V1.0 20190801 ==============//
Stack_Size EQU 0x00002000
@@ -153,7 +153,7 @@ __Vectors_Size EQU __Vectors_End - __Vectors
Reset_Handler PROC
EXPORT Reset_Handler [WEAK]
IMPORT __main
- LDR R0, =0xE000ED88 ; 使能浮点运算 CP10,CP11
+ LDR R0, =0xE000ED88 ; 浣胯兘娴偣杩愮畻 CP10,CP11
LDR R1,[R0]
ORR R1,R1,#(0xF << 20)
STR R1,[R0]
diff --git a/bsp/tkm32F499/Libraries/CMSIS_and_startup/sys.c b/bsp/tkm32F499/Libraries/CMSIS_and_startup/sys.c
index ce76891dcb..d2c6fa6d35 100644
--- a/bsp/tkm32F499/Libraries/CMSIS_and_startup/sys.c
+++ b/bsp/tkm32F499/Libraries/CMSIS_and_startup/sys.c
@@ -1,14 +1,14 @@
-#include "sys.h"
+#include "sys.h"
#include "HAL_misc.h"
void RemapVtorTable(void)
-{
+{
int i;
RCC->AHB1ENR |= 1<<13;//bkp clk,enable sram
- //关ROM区中断
+ //鍏砇OM鍖轰腑鏂
for(i = 0;i<90;i++)
- {
- NVIC_DisableIRQ((IRQn_Type)i);
+ {
+ NVIC_DisableIRQ((IRQn_Type)i);
}
SCB->VTOR = 0;
SCB->VTOR |= 0x1<<29;
@@ -32,110 +32,110 @@ void AI_Responder_disable(void)
}
-//外部中断配置函数
-//只针对GPIOA~E
-//参数:
-//GPIOx:0~4,代表GPIOA~E
-//BITx:需要使能的位,例如PB12,就填 12;
-//TRIM:触发模式,1,下降沿;2,上升沿;3,任意电平触发
-//该函数一次只能配置1个IO口,多个IO口,需多次调用
-//该函数会自动开启对应中断,以及屏蔽线
-void Ex_NVIC_Config(u8 GPIOx,u8 BITx,u8 TRIM)
-{
- u8 EXTOFFSET=(BITx%4)*4;
- RCC->APB2ENR|=1<<14; //使能SYSCFG时钟
- SYSCFG->EXTICR[BITx/4]&=~(0x000F<EXTICR[BITx/4]|=GPIOx<IMR|=1<FTSR|=1<RTSR|=1<APB2ENR|=1<<14; //浣胯兘SYSCFG鏃堕挓
+ SYSCFG->EXTICR[BITx/4]&=~(0x000F<EXTICR[BITx/4]|=GPIOx<IMR|=1<FTSR|=1<RTSR|=1<SCR|=1<<2; //使能SLEEPDEEP位 (SYS->CTRL)
- RCC->APB1ENR|=1<<28;//使能电源时钟
- PWR->CSR|=1<<8; //设置WKUP用于唤醒
- PWR->CR|=1<<2; //清除Wake-up 标志
- PWR->CR|=1<<1; //PDDS置位
- WFI_SET(); //执行WFI指令,进入待机模式
-}
-//系统软复位
-void Sys_Soft_Reset(void)
-{
- SCB->AIRCR =0X05FA0000|(u32)0x04;
-}
-
-// TK499_NVIC_Init(2,2,TK80_IRQn,2);
-//设置NVIC
-//NVIC_PreemptionPriority:抢占优先级
-//NVIC_SubPriority :响应优先级
-//NVIC_Channel :中断编号
-//NVIC_Group :中断分组 0~4
-//注意优先级不能超过设定的组的范围!否则会有意想不到的错误
-//组划分:
-//组0:0位抢占优先级,4位响应优先级
-//组1:1位抢占优先级,3位响应优先级
-//组2:2位抢占优先级,2位响应优先级
-//组3:3位抢占优先级,1位响应优先级
-//组4:4位抢占优先级,0位响应优先级
-//NVIC_SubPriority和NVIC_PreemptionPriority的原则是,数值越小,越优先
-void TK499_NVIC_Init(u8 NVIC_PreemptionPriority,u8 NVIC_SubPriority,u8 NVIC_Channel,u8 NVIC_Group)
{
- u32 temp;
- NVIC_SetPriorityGrouping(NVIC_Group);//设置分组
- temp=NVIC_PreemptionPriority<<(4-NVIC_Group);
+ SCB->SCR|=1<<2; //浣胯兘SLEEPDEEP浣 (SYS->CTRL)
+ RCC->APB1ENR|=1<<28;//浣胯兘鐢垫簮鏃堕挓
+ PWR->CSR|=1<<8; //璁剧疆WKUP鐢ㄤ簬鍞ら啋
+ PWR->CR|=1<<2; //娓呴櫎Wake-up 鏍囧織
+ PWR->CR|=1<<1; //PDDS缃綅
+ WFI_SET(); //鎵цWFI鎸囦护,杩涘叆寰呮満妯″紡
+}
+//绯荤粺杞浣
+void Sys_Soft_Reset(void)
+{
+ SCB->AIRCR =0X05FA0000|(u32)0x04;
+}
+
+// TK499_NVIC_Init(2,2,TK80_IRQn,2);
+//璁剧疆NVIC
+//NVIC_PreemptionPriority:鎶㈠崰浼樺厛绾
+//NVIC_SubPriority :鍝嶅簲浼樺厛绾
+//NVIC_Channel :涓柇缂栧彿
+//NVIC_Group :涓柇鍒嗙粍 0~4
+//娉ㄦ剰浼樺厛绾т笉鑳借秴杩囪瀹氱殑缁勭殑鑼冨洿!鍚﹀垯浼氭湁鎰忔兂涓嶅埌鐨勯敊璇
+//缁勫垝鍒:
+//缁0:0浣嶆姠鍗犱紭鍏堢骇,4浣嶅搷搴斾紭鍏堢骇
+//缁1:1浣嶆姠鍗犱紭鍏堢骇,3浣嶅搷搴斾紭鍏堢骇
+//缁2:2浣嶆姠鍗犱紭鍏堢骇,2浣嶅搷搴斾紭鍏堢骇
+//缁3:3浣嶆姠鍗犱紭鍏堢骇,1浣嶅搷搴斾紭鍏堢骇
+//缁4:4浣嶆姠鍗犱紭鍏堢骇,0浣嶅搷搴斾紭鍏堢骇
+//NVIC_SubPriority鍜孨VIC_PreemptionPriority鐨勫師鍒欐槸,鏁板艰秺灏,瓒婁紭鍏
+void TK499_NVIC_Init(u8 NVIC_PreemptionPriority,u8 NVIC_SubPriority,u8 NVIC_Channel,u8 NVIC_Group)
+{
+ u32 temp;
+ NVIC_SetPriorityGrouping(NVIC_Group);//璁剧疆鍒嗙粍
+ temp=NVIC_PreemptionPriority<<(4-NVIC_Group);
temp|=NVIC_SubPriority&(0x0f>>NVIC_Group);
- temp&=0xf; //取低四位
- NVIC->ISER[NVIC_Channel/32]|=1<IP[NVIC_Channel]|=temp<<4; //设置响应优先级和抢断优先级
+ temp&=0xf; //鍙栦綆鍥涗綅
+ NVIC->ISER[NVIC_Channel/32]|=1<IP[NVIC_Channel]|=temp<<4; //璁剧疆鍝嶅簲浼樺厛绾у拰鎶㈡柇浼樺厛绾
}
void TK80_IRQHandler(void)
{
if(TK80->SR & 0x1)
{
-
+
}
if(TK80->SR & 0x2)
{
-
+
}
if(TK80->SR & 0x4)
{
-
+
}
if(TK80->SR & 0x8)
{
-
+
}
TK80->SR |= 0;
}
-//备用函数
+//澶囩敤鍑芥暟
//#define T_SRAM_FUN1 0x20000400
-//copyAtoB((u32)LCD_PutPixel&0xFFFFFFFE,T_SRAM_FUN1,800);//加载函数到SRAM
+//copyAtoB((u32)LCD_PutPixel&0xFFFFFFFE,T_SRAM_FUN1,800);//鍔犺浇鍑芥暟鍒癝RAM
//void copyAtoB(u32 srcAdd,u32 dstAdd,u16 len)
//{
// len = (len + 3)/4;
diff --git a/bsp/tkm32F499/Libraries/CMSIS_and_startup/sys.h b/bsp/tkm32F499/Libraries/CMSIS_and_startup/sys.h
index 1d9adacad9..05863e8b4f 100644
--- a/bsp/tkm32F499/Libraries/CMSIS_and_startup/sys.h
+++ b/bsp/tkm32F499/Libraries/CMSIS_and_startup/sys.h
@@ -1,28 +1,28 @@
#ifndef __SYS_H
-#define __SYS_H
-#include "tk499.h"
+#define __SYS_H
+#include "tk499.h"
#include "HAL_conf.h"
-//位带操作,实现51类似的GPIO控制功能
-//具体实现思想,参考<>第五章(87页~92页).M4同M3类似,只是寄存器地址变了.
-//IO口操作宏定义
-//#define BITBAND(addr, bitnum) ((addr & 0xF0000000)+0x2000000+((addr &0xFFFFF)<<5)+(bitnum<<2))
-//#define MEM_ADDR(addr) *((volatile unsigned long *)(addr))
-//#define BIT_ADDR(addr, bitnum) MEM_ADDR(BITBAND(addr, bitnum))
+//浣嶅甫鎿嶄綔,瀹炵幇51绫讳技鐨凣PIO鎺у埗鍔熻兘
+//鍏蜂綋瀹炵幇鎬濇兂,鍙傝<>绗簲绔(87椤祣92椤).M4鍚孧3绫讳技,鍙槸瀵勫瓨鍣ㄥ湴鍧鍙樹簡.
+//IO鍙f搷浣滃畯瀹氫箟
+//#define BITBAND(addr, bitnum) ((addr & 0xF0000000)+0x2000000+((addr &0xFFFFF)<<5)+(bitnum<<2))
+//#define MEM_ADDR(addr) *((volatile unsigned long *)(addr))
+//#define BIT_ADDR(addr, bitnum) MEM_ADDR(BITBAND(addr, bitnum))
void RemapVtorTable(void);
void AI_Responder_enable(void);
void AI_Responder_disable(void);
-void Sys_Soft_Reset(void); //系统软复位
-void Sys_Standby(void); //待机模式
+void Sys_Soft_Reset(void); //绯荤粺杞浣
+void Sys_Standby(void); //寰呮満妯″紡
-void TK499_NVIC_Init(u8 NVIC_PreemptionPriority,u8 NVIC_SubPriority,u8 NVIC_Channel,u8 NVIC_Group);
-void Ex_NVIC_Config(u8 GPIOx,u8 BITx,u8 TRIM); //外部中断配置函数(只对GPIOA~I)
+void TK499_NVIC_Init(u8 NVIC_PreemptionPriority,u8 NVIC_SubPriority,u8 NVIC_Channel,u8 NVIC_Group);
+void Ex_NVIC_Config(u8 GPIOx,u8 BITx,u8 TRIM); //澶栭儴涓柇閰嶇疆鍑芥暟(鍙GPIOA~I)
-//以下为汇编函数
-void WFI_SET(void); //执行WFI指令
-void INTX_DISABLE(void);//关闭所有中断
-void INTX_ENABLE(void); //开启所有中断
+//浠ヤ笅涓烘眹缂栧嚱鏁
+void WFI_SET(void); //鎵цWFI鎸囦护
+void INTX_DISABLE(void);//鍏抽棴鎵鏈変腑鏂
+void INTX_ENABLE(void); //寮鍚墍鏈変腑鏂
void TIM3_Config(u16 arr,u16 psc);
#endif
diff --git a/bsp/tkm32F499/Libraries/CMSIS_and_startup/tk499.h b/bsp/tkm32F499/Libraries/CMSIS_and_startup/tk499.h
index a9c1d4f827..ee03c9d7e9 100644
--- a/bsp/tkm32F499/Libraries/CMSIS_and_startup/tk499.h
+++ b/bsp/tkm32F499/Libraries/CMSIS_and_startup/tk499.h
@@ -1,9 +1,9 @@
/**
******************************************************************************
* @file TK499.h
-* @brief CMSIS Cortex-M4 Device Peripheral Access Layer Header File.
-* This file contains all the peripheral register's definitions, bits
-* definitions and memory mapping for TK499 High Density, Medium
+* @brief CMSIS Cortex-M4 Device Peripheral Access Layer Header File.
+* This file contains all the peripheral register's definitions, bits
+* definitions and memory mapping for TK499 High Density, Medium
* Density and Low Density devices.
* @author IC Applications Department
* @version V0.8
@@ -21,7 +21,7 @@
******************************************************************************
*/
-//============== 版本 EK V1.0 20190818 ==============//
+//============== 锟芥本 EK V1.0 20190818 ==============//
#define T_SRAM_BASE 0X20000000
@@ -39,21 +39,21 @@
#if !defined USE_STDPERIPH_DRIVER
/**
* @brief Comment the line below if you will not use the peripherals drivers.
-In this case, these drivers will not be included and the application code will
-be based on direct access to peripherals registers
+In this case, these drivers will not be included and the application code will
+be based on direct access to peripherals registers
*/
/*#define USE_STDPERIPH_DRIVER*/
#endif
/**
* @brief In the following line adjust the value of External High Speed oscillator (HSE)
-used in your application
+used in your application
*/
#define HSE_Value ((uint32_t)8000000) /*!< Value of the External oscillator in Hz*/
-#define HSE_VALUE HSE_Value
+#define HSE_VALUE HSE_Value
/**
-* @brief In the following line adjust the External High Speed oscillator (HSE) Startup
-Timeout value
+* @brief In the following line adjust the External High Speed oscillator (HSE) Startup
+Timeout value
*/
#define HSEStartUp_TimeOut ((uint16_t)0x0500) /*!< Time out for HSE start up */
#define HSE_STARTUP_TIMEOUT HSEStartUp_TimeOut
@@ -74,7 +74,7 @@ Timeout value
*/
/**
-* @brief Configuration of the Cortex-M3 Processor and Core Peripherals
+* @brief Configuration of the Cortex-M3 Processor and Core Peripherals
*/
#define __CM4_REV 0x0001 /*!< Core revision r0p1 */
#define __MPU_PRESENT 1 /*!< tk499 provides an MPU */
@@ -94,9 +94,9 @@ typedef enum IRQn
DebugMonitor_IRQn = -4, /*!< 12 Cortex-M3 Debug Monitor Interrupt */
PendSV_IRQn = -2, /*!< 14 Cortex-M3 Pend SV Interrupt */
SysTick_IRQn = -1, /*!< 15 Cortex-M3 System Tick Interrupt */
-
+
/****** TK499 CM3 specific Interrupt Numbers *********************************************************/
-
+
WWDG_IRQn = 0, /*!< Window WatchDog Interrupt */
//PVD_IRQn = 1, /*!< PVD through EXTI Line detection Interrupt */
TAMPER_IRQn = 2, /*!< Tamper Interrupt */
@@ -117,25 +117,25 @@ typedef enum IRQn
DMA1_Channel7_IRQn = 17, /*!< DMA1 Channel 7 global Interrupt */
ADC1_IRQn = 18, /*!< ADC1 et ADC2 global Interrupt */
CAN1_IRQn = 19, /*!< USB High Priority or CAN1 TX Interrupts */
-
+
//CAN1_RX1_IRQn = 21, /*!< CAN1 RX1 Interrupt */
-
+
EXTI9_5_IRQn = 23, /*!< External Line[9:5] Interrupts */
TIM1_BRK_IRQn = 24, /*!< TIM1 Break Interrupt */
TIM1_UP_IRQn = 25, /*!< TIM1 Update Interrupt */
TIM1_TRG_COM_IRQn = 26, /*!< TIM1 Trigger and Commutation Interrupt */
TIM1_CC_IRQn = 27, /*!< TIM1 Capture Compare Interrupt */
-
+
//TIM2_IRQn = 28, /*!< TIM2 global Interrupt */
TIM3_IRQn = 28, /*!< TIM3 global Interrupt */
TIM4_IRQn = 29, /*!< TIM4 global Interrupt */
TIM5_IRQn = 30, /*!< TIM4 global Interrupt */
TIM6_IRQn = 31, /*!< TIM4 global Interrupt */
TIM7_IRQn = 32, /*!< TIM4 global Interrupt */
-
+
I2C1_IRQn = 33, /*!< I2C1 Event Interrupt */
I2C2_IRQn = 34, /*!< I2C2 Event Interrupt */
-
+
SPI1_IRQn = 35, /*!< SPI1 global Interrupt */
SPI2_IRQn = 36, /*!< SPI2 global Interrupt */
UART1_IRQn = 37, /*!< UART1 global Interrupt */
@@ -150,7 +150,7 @@ typedef enum IRQn
TIM2_CC_IRQn = 46, /**/
DMA1_Channel8_IRQn = 47, /**/
TK80_IRQn = 48, /**/
-
+
SDIO1_IRQn = 49, /**/
SDIO2_IRQn = 50, /**/
SPI3_IRQn = 51, /**/
@@ -177,7 +177,7 @@ typedef enum IRQn
QSPI_IRQn = 87, /**/
LTDC_IRQn = 88, /**/
I2S1_IRQn = 90, /**/
-
+
} IRQn_Type;
@@ -193,7 +193,7 @@ typedef enum IRQn
/** @addtogroup Exported_types
* @{
-*/
+*/
/*!< TK499 Standard Peripheral Library old types (maintained for legacy prupose) */
typedef int32_t s32;
@@ -241,25 +241,25 @@ typedef enum {ERROR = 0, SUCCESS = !ERROR} ErrorStatus;
/** @addtogroup Peripheral_registers_structures
* @{
-*/
+*/
typedef struct
{
- __IO uint32_t CCR;
- __IO uint32_t SR;
- __IO uint32_t IRQMASKR;
- __IO uint32_t IRQSTATR;
- __IO uint32_t RESERVED0;
- __IO uint32_t CSHR;
- __IO uint32_t CSMR;
- __IO uint32_t RESERVED1;
+ __IO uint32_t CCR;
+ __IO uint32_t SR;
+ __IO uint32_t IRQMASKR;
+ __IO uint32_t IRQSTATR;
+ __IO uint32_t RESERVED0;
+ __IO uint32_t CSHR;
+ __IO uint32_t CSMR;
+ __IO uint32_t RESERVED1;
__IO uint32_t ADDR0;
__IO uint32_t ADDR1;
__IO uint32_t ADDR2;
__IO uint32_t ADDR3;
} AI_Responder_TypeDef;
-/**
-* @brief Analog to Digital Converter
+/**
+* @brief Analog to Digital Converter
*/
typedef struct
@@ -281,8 +281,8 @@ typedef struct
__IO uint32_t ADDR8;
} ADC_TypeDef;
-/**
-* @brief Backup Registers
+/**
+* @brief Backup Registers
*/
typedef struct
@@ -307,7 +307,7 @@ typedef struct
__IO uint16_t DR9;
uint16_t RESERVED9;
__IO uint16_t DR10;
- uint16_t RESERVED10;
+ uint16_t RESERVED10;
__IO uint16_t RTCCR;
uint16_t RESERVED11;
__IO uint16_t CR;
@@ -315,7 +315,7 @@ typedef struct
__IO uint16_t CSR;
} BKP_TypeDef;
-/**
+/**
* @brief CAN basic
*/
typedef struct
@@ -354,7 +354,7 @@ typedef struct
__IO uint32_t CDR; //0x7c
}CAN_TypeDef;
-/**
+/**
* @brief CAN Peli
*/
typedef struct
@@ -394,8 +394,8 @@ typedef struct
}CAN_Peli_TypeDef;
-/**
-* @brief CRC calculation unit
+/**
+* @brief CRC calculation unit
*/
typedef struct
@@ -407,7 +407,7 @@ typedef struct
__IO uint32_t CR;
} CRC_TypeDef;
-/**
+/**
* @brief Digital to Analog Converter
*/
@@ -429,17 +429,17 @@ typedef struct
} DAC_TypeDef;
-/**
+/**
* @brief Debug MCU
*/
typedef struct
{
__IO uint32_t IDCODE;
- __IO uint32_t CR;
+ __IO uint32_t CR;
}DBGMCU_TypeDef;
-/**
+/**
* @brief DMA Controller
*/
@@ -457,7 +457,7 @@ typedef struct
__IO uint32_t IFCR;
} DMA_TypeDef;
-/**
+/**
* @brief External Interrupt/Event Controller
*/
@@ -471,7 +471,7 @@ typedef struct
__IO uint32_t PR;
} EXTI_TypeDef;
-/**
+/**
* @brief FLASH Registers
*/
@@ -488,7 +488,7 @@ typedef struct
__IO uint32_t WRPR;
} FLASH_TypeDef;
-/**
+/**
* @brief Option Bytes Registers
*/
@@ -506,7 +506,7 @@ typedef struct
-/**
+/**
* @brief General Purpose IO
*/
@@ -538,7 +538,7 @@ typedef struct
__IO uint32_t AFRH_EXT;
} GPIO_TypeDef;
-/**
+/**
* @brief Alternate Function IO
*/
@@ -549,7 +549,7 @@ typedef struct
// __IO uint32_t EXTICR[4];
//} AFIO_TypeDef;
-
+
typedef struct
{
__IO uint32_t CSR; /*!< OPAMP control and status register, Address offset: 0x00 */
@@ -562,7 +562,7 @@ typedef struct
__IO uint32_t EXTICR[4]; /*!< SYSCFG external interrupt configuration registers, Address offset: 0x14-0x08 */
} SYSCFG_TypeDef;
-/**
+/**
* @brief Inter-integrated Circuit Interface
*/
@@ -624,8 +624,8 @@ typedef struct
uint16_t RESERVED26;
__IO uint16_t IC_ENABLE; //RESERVED
uint16_t RESERVED27;
-
- __IO uint32_t IC_STATUS;
+
+ __IO uint32_t IC_STATUS;
__IO uint32_t IC_TXFLR; //RESERVED
__IO uint32_t IC_RXFLR; //RESERVED
__IO uint32_t IC_SDA_HOLD; //RESERVED
@@ -636,19 +636,19 @@ typedef struct
__IO uint32_t IC_DMA_RDLR; //RESERVED
__IO uint32_t IC_SDA_SETUP; //RESERVED
__IO uint32_t IC_ACK_GENERAL_CALL; //RESERVED
-
+
__IO uint32_t IC_FS_SPKLEN;
__IO uint32_t IC_HS_SPKLEN;
-
+
__IO uint16_t IC_CLR_RESTART_DET;
uint16_t RESERVED28;
__IO uint32_t IC_COMP_PARAM_1;
__IO uint32_t IC_COMP_VERSION;
__IO uint32_t IC_COMP_TYPE;
-
+
} I2C_TypeDef;
-/**
+/**
* @brief Independent WATCHDOG
*/
@@ -660,7 +660,7 @@ typedef struct
__IO uint32_t SR;
} IWDG_TypeDef;
-/**
+/**
* @brief Power Control
*/
@@ -670,7 +670,7 @@ typedef struct
__IO uint32_t CSR;
} PWR_TypeDef;
-/**
+/**
* @brief Reset and Clock Control
*/
@@ -688,7 +688,7 @@ typedef struct
// __IO uint32_t CSR;
//} RCC_TypeDef;
-
+
typedef struct
{
@@ -704,15 +704,15 @@ typedef struct
__IO uint32_t AHB2ENR; /*!< RCC AHB peripheral clock register, Address offset: 0x24 */
__IO uint32_t APB1ENR; /*!< RCC APB1 peripheral clock enable register, Address offset: 0x28 */
__IO uint32_t APB2ENR; /*!< RCC APB1 peripheral clock enable register, Address offset: 0x2C */
- __IO uint32_t BDCR; /*!< RCC Backup domain control register, Address offset: 0x30 */
+ __IO uint32_t BDCR; /*!< RCC Backup domain control register, Address offset: 0x30 */
__IO uint32_t CSR; /*!< RCC clock control & status register, Address offset: 0x34 */
__IO uint32_t PLLLCDCFGR; /*!< RCC clock configuration register 2, Address offset: 0x38 */
- __IO uint32_t PLLDCKCFGR; /*!< RCC clock configuration register 3, Address offset: 0x3C */
+ __IO uint32_t PLLDCKCFGR; /*!< RCC clock configuration register 3, Address offset: 0x3C */
} RCC_TypeDef;
-
-/**
+
+/**
* @brief Real-Time Clock
*/
@@ -741,31 +741,31 @@ typedef struct
} RTC_TypeDef;
-/**
+/**
* @brief Serial Peripheral Interface
*/
typedef struct
{
- __IO uint32_t TXREG; //0
+ __IO uint32_t TXREG; //0
__IO uint32_t RXREG;
__IO uint32_t CSTAT; //10
__IO uint32_t INTSTAT;//14
__IO uint32_t INTEN;
- __IO uint32_t INTCLR;
+ __IO uint32_t INTCLR;
__IO uint32_t GCTL; //20
__IO uint32_t CCTL;
__IO uint32_t SPBRG;
__IO uint32_t RXDNR;
__IO uint32_t SCSR; //30
- __IO uint32_t TXREGBH;
- __IO uint32_t TXREGBL;
+ __IO uint32_t TXREGBH;
+ __IO uint32_t TXREGBL;
} SPI_TypeDef;
-/**
+/**
* @brief TIM
*/
@@ -794,7 +794,7 @@ typedef struct
__IO uint32_t OR; /*!< TIM option register, Address offset: 0x50 */
} TIM_TypeDef;
-/**
+/**
* @brief Universal Synchronous Asynchronous Receiver Transmitter
*/
@@ -810,10 +810,10 @@ typedef struct
__IO uint32_t CCR;
__IO uint32_t BRR;
__IO uint32_t FRABRG;
-
+
} UART_TypeDef;
-/**
+/**
* @brief Window WATCHDOG
*/
@@ -825,8 +825,8 @@ typedef struct
} WWDG_TypeDef;
-/**
-* @brief USB
+/**
+* @brief USB
*/
typedef struct
{
@@ -835,144 +835,144 @@ typedef struct
__IO uint32_t rEP_INT_STATE; /*! Address offset: 0x08 */
__IO uint32_t rEP0_INT_STATE; /*! Address offset: 0x0C */
__IO uint32_t rINT_EN; /*! Address offset: 0x10 */
- __IO uint32_t rEP_INT_EN; /*! Address offset: 0x14 */
+ __IO uint32_t rEP_INT_EN; /*! Address offset: 0x14 */
__IO uint32_t rEP0_INT_EN; /*! Address offset: 0x18 */
-
- __IO uint32_t RESERVED0;
-
- //__IO uint32_t rEP1_4_INT_STATE[4]; /*! Address offset: 0x20 */
-
+
+ __IO uint32_t RESERVED0;
+
+ //__IO uint32_t rEP1_4_INT_STATE[4]; /*! Address offset: 0x20 */
+
__IO uint32_t rEP1_INT_STATE; /*! Address offset: 0x20 */
- __IO uint32_t rEP2_INT_STATE; /*! Address offset: 0x24 */
+ __IO uint32_t rEP2_INT_STATE; /*! Address offset: 0x24 */
__IO uint32_t rEP3_INT_STATE; /*! Address offset: 0x28 */
__IO uint32_t rEP4_INT_STATE; /*! Address offset: 0x2C */
-
+
__IO uint32_t RESERVED1; /*! Address offset: 0x30 */
__IO uint32_t RESERVED2; /*! Address offset: 0x34 */
__IO uint32_t RESERVED3; /*! Address offset: 0x38 */
__IO uint32_t RESERVED4; /*! Address offset: 0x3C */
-
- __IO uint32_t rEP1_INT_EN; /*! Address offset: 0x40 */
+
+ __IO uint32_t rEP1_INT_EN; /*! Address offset: 0x40 */
__IO uint32_t rEP2_INT_EN; /*! Address offset: 0x44 */
__IO uint32_t rEP3_INT_EN; /*! Address offset: 0x48 */
- __IO uint32_t rEP4_INT_EN; /*! Address offset: 0x4C */
-
+ __IO uint32_t rEP4_INT_EN; /*! Address offset: 0x4C */
+
__IO uint32_t RESERVED5; /*! Address offset: 0x50 */
__IO uint32_t RESERVED6; /*! Address offset: 0x54 */
__IO uint32_t RESERVED7; /*! Address offset: 0x58 */
__IO uint32_t RESERVED8; /*! Address offset: 0x5C */
-
+
__IO uint32_t rADDR; /*! Address offset: 0x60 */
__IO uint32_t rEP_EN; /*! Address offset: 0x64 */
-
+
__IO uint32_t RESERVED9; /*! Address offset: 0x68 */
__IO uint32_t RESERVED10; /*! Address offset: 0x6C */
__IO uint32_t RESERVED11; /*! Address offset: 0x70 */
__IO uint32_t RESERVED12; /*! Address offset: 0x74 */
-
+
__IO uint32_t rTOG_CTRL1_4; /*! Address offset: 0x78 */
-
+
__IO uint32_t RESERVED13; /*! Address offset: 0x7C */
-
+
__IO uint32_t rSETUP[8]; /*! Address offset: 0x80 */
//__IO uint32_t rSETUP0; /*! Address offset: 0x80 */
//__IO uint32_t rSETUP1; /*! Address offset: 0x84 */
- //__IO uint32_t rSETUP2; /*! Address offset: 0x88 */
+ //__IO uint32_t rSETUP2; /*! Address offset: 0x88 */
//__IO uint32_t rSETUP3; /*! Address offset: 0x8C */
//__IO uint32_t rSETUP4; /*! Address offset: 0x90 */
- //__IO uint32_t rSETUP5; /*! Address offset: 0x94 */
+ //__IO uint32_t rSETUP5; /*! Address offset: 0x94 */
//__IO uint32_t rSETUP6; /*! Address offset: 0x98 */
//__IO uint32_t rSETUP7; /*! Address offset: 0x9C */
- __IO uint32_t rPAKET_SIZE0; /*! Address offset: 0xA0 */
- __IO uint32_t rPAKET_SIZE1; /*! Address offset: 0xA4 */
-
+ __IO uint32_t rPAKET_SIZE0; /*! Address offset: 0xA0 */
+ __IO uint32_t rPAKET_SIZE1; /*! Address offset: 0xA4 */
+
__IO uint32_t RESERVED14; /*! Address offset: 0xA8 */
__IO uint32_t RESERVED15; /*! Address offset: 0xAC */
-
+
__IO uint32_t RESERVED16; /*! Address offset: 0xB0 */
__IO uint32_t RESERVED17; /*! Address offset: 0xB4 */
__IO uint32_t RESERVED18; /*! Address offset: 0xB8 */
__IO uint32_t RESERVED19; /*! Address offset: 0xBC */
-
+
__IO uint32_t RESERVED20; /*! Address offset: 0xC0 */
__IO uint32_t RESERVED21; /*! Address offset: 0xC4 */
__IO uint32_t RESERVED22; /*! Address offset: 0xC8 */
__IO uint32_t RESERVED23; /*! Address offset: 0xCC */
-
+
__IO uint32_t RESERVED24; /*! Address offset: 0xD0 */
__IO uint32_t RESERVED25; /*! Address offset: 0xD4 */
__IO uint32_t RESERVED26; /*! Address offset: 0xD8 */
__IO uint32_t RESERVED27; /*! Address offset: 0xDC */
-
+
__IO uint32_t RESERVED28; /*! Address offset: 0xE0 */
__IO uint32_t RESERVED29; /*! Address offset: 0xE4 */
__IO uint32_t RESERVED30; /*! Address offset: 0xE8 */
__IO uint32_t RESERVED31; /*! Address offset: 0xEC */
-
+
__IO uint32_t RESERVED32; /*! Address offset: 0xF0 */
__IO uint32_t RESERVED33; /*! Address offset: 0xF4 */
__IO uint32_t RESERVED34; /*! Address offset: 0xF8 */
__IO uint32_t RESERVED35; /*! Address offset: 0xFC */
-
+
__IO uint32_t rEP0_AVIL; /*! Address offset: 0x100 */
__IO uint32_t rEP1_AVIL; /*! Address offset: 0x104 */
__IO uint32_t rEP2_AVIL; /*! Address offset: 0x108 */
__IO uint32_t rEP3_AVIL; /*! Address offset: 0x10C */
__IO uint32_t rEP4_AVIL; /*! Address offset: 0x110 */
-
+
__IO uint32_t RESERVED36; /*! Address offset: 0x114 */
__IO uint32_t RESERVED37; /*! Address offset: 0x118 */
__IO uint32_t RESERVED38; /*! Address offset: 0x11C */
__IO uint32_t RESERVED39; /*! Address offset: 0x120 */
-
+
__IO uint32_t RESERVED40; /*! Address offset: 0x124 */
__IO uint32_t RESERVED41; /*! Address offset: 0x128 */
__IO uint32_t RESERVED42; /*! Address offset: 0x12C */
__IO uint32_t RESERVED43; /*! Address offset: 0x130 */
-
+
__IO uint32_t RESERVED44; /*! Address offset: 0x134 */
__IO uint32_t RESERVED45; /*! Address offset: 0x138 */
__IO uint32_t RESERVED46; /*! Address offset: 0x13C */
-
+
__IO uint32_t rEP0_CTRL; /*! Address offset: 0x140 */
__IO uint32_t rEP1_CTRL; /*! Address offset: 0x144 */
__IO uint32_t rEP2_CTRL; /*! Address offset: 0x148 */
__IO uint32_t rEP3_CTRL; /*! Address offset: 0x14C */
__IO uint32_t rEP4_CTRL; /*! Address offset: 0x150 */
-
+
__IO uint32_t RESERVED47; /*! Address offset: 0x154 */
__IO uint32_t RESERVED48; /*! Address offset: 0x158 */
__IO uint32_t RESERVED49; /*! Address offset: 0x15C */
//__IO uint32_t RESERVED50; /*! Address offset: 0x15C */
-
+
//__IO uint32_t rEPn_FIFO[5]; /*! Address offset: 0x160 */
-
+
__IO uint32_t rEP0_FIFO; /*! Address offset: 0x160 */
__IO uint32_t rEP1_FIFO; /*! Address offset: 0x164 */
__IO uint32_t rEP2_FIFO; /*! Address offset: 0x168 */
__IO uint32_t rEP3_FIFO; /*! Address offset: 0x16C */
__IO uint32_t rEP4_FIFO; /*! Address offset: 0x170 */
-
+
__IO uint32_t RESERVED51; /*! Address offset: 0x174 */
__IO uint32_t RESERVED52; /*! Address offset: 0x178 */
__IO uint32_t RESERVED53; /*! Address offset: 0x17C */
-
+
__IO uint32_t RESERVED54; /*! Address offset: 0x180 */
-
+
__IO uint32_t rEP_DMA; /*! Address offset: 0x184 */
__IO uint32_t rEP_HALT; /*! Address offset: 0x188 */
__IO uint32_t RESERVED55; /*! Address offset: 0x18C */
-
+
__IO uint32_t RESERVED56; /*! Address offset: 0x190 */
__IO uint32_t RESERVED57; /*! Address offset: 0x194 */
__IO uint32_t RESERVED58; /*! Address offset: 0x198 */
__IO uint32_t RESERVED59; /*! Address offset: 0x19C */
-
+
__IO uint32_t RESERVED60; /*! Address offset: 0x1A0 */
__IO uint32_t RESERVED61; /*! Address offset: 0x1A4 */
__IO uint32_t RESERVED62; /*! Address offset: 0x1A8 */
__IO uint32_t RESERVED63; /*! Address offset: 0x1AC */
-
+
__IO uint32_t RESERVED64; /*! Address offset: 0x1B0 */
__IO uint32_t RESERVED65; /*! Address offset: 0x1B4 */
__IO uint32_t RESERVED66; /*! Address offset: 0x1B8 */
@@ -982,108 +982,108 @@ typedef struct
typedef struct
{
- u32 sHsyncStart;
- u32 sHsyncEnd;
- u32 aHorLen;
+ u32 sHsyncStart;
+ u32 sHsyncEnd;
+ u32 aHorLen;
u32 blkHorEnd;
- u32 sVsyncStart;
- u32 sVsyncEnd;
- u32 aVerLen;
- u32 blkVerEnd;
+ u32 sVsyncStart;
+ u32 sVsyncEnd;
+ u32 aVerLen;
+ u32 blkVerEnd;
} LCD_FORM_TypeDef;
//2017 for tk499 ADD
typedef struct
{
- __IO uint32_t DP_ADDR0;
- __IO uint32_t DP_ADDR1;
- __IO uint32_t P_HOR;
- __IO uint32_t HSYNC;
- __IO uint32_t A_HOR;
- __IO uint32_t A_HOR_LEN;
- __IO uint32_t BLK_HOR;
- __IO uint32_t P_VER;
- __IO uint32_t VSYNC;
- __IO uint32_t A_VER;
- __IO uint32_t A_VER_LEN;
- __IO uint32_t BLK_VER;
- __IO uint32_t BLK_DATA;
- __IO uint32_t POL_CTL;
- __IO uint32_t OUT_EN;
- __IO uint32_t INTR_STA;
- __IO uint32_t INTR_EN;
- __IO uint32_t INTR_CLR;
- __IO uint32_t DP_SWT;
- __IO uint32_t VI_FORMAT;
+ __IO uint32_t DP_ADDR0;
+ __IO uint32_t DP_ADDR1;
+ __IO uint32_t P_HOR;
+ __IO uint32_t HSYNC;
+ __IO uint32_t A_HOR;
+ __IO uint32_t A_HOR_LEN;
+ __IO uint32_t BLK_HOR;
+ __IO uint32_t P_VER;
+ __IO uint32_t VSYNC;
+ __IO uint32_t A_VER;
+ __IO uint32_t A_VER_LEN;
+ __IO uint32_t BLK_VER;
+ __IO uint32_t BLK_DATA;
+ __IO uint32_t POL_CTL;
+ __IO uint32_t OUT_EN;
+ __IO uint32_t INTR_STA;
+ __IO uint32_t INTR_EN;
+ __IO uint32_t INTR_CLR;
+ __IO uint32_t DP_SWT;
+ __IO uint32_t VI_FORMAT;
} LCD_TypeDef;
typedef struct
{
- __IO uint32_t IER;
- __IO uint32_t IRER;
- __IO uint32_t ITER;
- __IO uint32_t CER;
- __IO uint32_t RXFFR;
- __IO uint32_t TXFFR;
- __IO uint32_t LRBR0;
- __IO uint32_t RRBR0;
- __IO uint32_t RER0;
- __IO uint32_t TER0;
- __IO uint32_t RCR0;
- __IO uint32_t TCR0;
- __IO uint32_t ISR0;
- __IO uint32_t IMR0;
- __IO uint32_t ROR0;
- __IO uint32_t TOR0;
- __IO uint32_t RFCR0;
- __IO uint32_t TFCR0;
- __IO uint32_t RFF0;
- __IO uint32_t TFF0;
+ __IO uint32_t IER;
+ __IO uint32_t IRER;
+ __IO uint32_t ITER;
+ __IO uint32_t CER;
+ __IO uint32_t RXFFR;
+ __IO uint32_t TXFFR;
+ __IO uint32_t LRBR0;
+ __IO uint32_t RRBR0;
+ __IO uint32_t RER0;
+ __IO uint32_t TER0;
+ __IO uint32_t RCR0;
+ __IO uint32_t TCR0;
+ __IO uint32_t ISR0;
+ __IO uint32_t IMR0;
+ __IO uint32_t ROR0;
+ __IO uint32_t TOR0;
+ __IO uint32_t RFCR0;
+ __IO uint32_t TFCR0;
+ __IO uint32_t RFF0;
+ __IO uint32_t TFF0;
} I2S_TypeDef;
//typedef struct
//{
-// __IO uint32_t WR;
-// __IO uint32_t RD;
-// __IO uint32_t CSR;
-// __IO uint32_t GCR;
-// __IO uint32_t DFR;
-// __IO uint32_t ISR;
-// __IO uint32_t IER;
-// __IO uint32_t ICR;
+// __IO uint32_t WR;
+// __IO uint32_t RD;
+// __IO uint32_t CSR;
+// __IO uint32_t GCR;
+// __IO uint32_t DFR;
+// __IO uint32_t ISR;
+// __IO uint32_t IER;
+// __IO uint32_t ICR;
//} I2S_TypeDef;
typedef struct
{
- __IO uint32_t MMC_CTRL;
- __IO uint32_t MMC_IO;
- __IO uint32_t MMC_BYTECNTL;
- __IO uint32_t MMC_TR_BLOCKCNT;
- __IO uint32_t MMC_CRCCTL;
- __IO uint32_t CMD_CRC;
- __IO uint32_t DAT_CRCL;
- __IO uint32_t DAT_CRCH;
- __IO uint32_t MMC_PORT;
- __IO uint32_t MMC_INT_MASK;
- __IO uint32_t CLR_MMC_INT;
- __IO uint32_t MMC_CARDSEL;
- __IO uint32_t MMC_SIG;
- __IO uint32_t MMC_IO_MBCTL;
- __IO uint32_t MMC_BLOCKCNT;
- __IO uint32_t MMC_TIMEOUTCNT;
- __IO uint32_t CMD_BUF[16];
- __IO uint32_t BUF_CTL;
- __IO uint32_t RESERVED[31];
- __IO uint32_t DATA_BUF0;
- __IO uint32_t DATA_BUF1;
- __IO uint32_t DATA_BUF2;
- __IO uint32_t DATA_BUF3;
- __IO uint32_t DATA_BUF4;
+ __IO uint32_t MMC_CTRL;
+ __IO uint32_t MMC_IO;
+ __IO uint32_t MMC_BYTECNTL;
+ __IO uint32_t MMC_TR_BLOCKCNT;
+ __IO uint32_t MMC_CRCCTL;
+ __IO uint32_t CMD_CRC;
+ __IO uint32_t DAT_CRCL;
+ __IO uint32_t DAT_CRCH;
+ __IO uint32_t MMC_PORT;
+ __IO uint32_t MMC_INT_MASK;
+ __IO uint32_t CLR_MMC_INT;
+ __IO uint32_t MMC_CARDSEL;
+ __IO uint32_t MMC_SIG;
+ __IO uint32_t MMC_IO_MBCTL;
+ __IO uint32_t MMC_BLOCKCNT;
+ __IO uint32_t MMC_TIMEOUTCNT;
+ __IO uint32_t CMD_BUF[16];
+ __IO uint32_t BUF_CTL;
+ __IO uint32_t RESERVED[31];
+ __IO uint32_t DATA_BUF0;
+ __IO uint32_t DATA_BUF1;
+ __IO uint32_t DATA_BUF2;
+ __IO uint32_t DATA_BUF3;
+ __IO uint32_t DATA_BUF4;
} SDIO_TypeDef;
-typedef struct
+typedef struct
{
__IO uint32_t DP_ADDR0;//0
__IO uint32_t DP_ADDR1;//4
@@ -1122,28 +1122,28 @@ typedef struct
__IO uint32_t BRDR;//24
__IO uint32_t RESERVE1;//28
__IO uint32_t RESERVE2;//2C
- __IO uint32_t CFGR3;//30
+ __IO uint32_t CFGR3;//30
} TK80_TypeDef;
typedef struct
{
- uint32_t TXREG; /*!< Reserved, 0x22 */
- uint32_t RXREG; /*!< Reserved, 0x22 */
- uint32_t CSTAT; /*!< Reserved, 0x22 */
- uint32_t INTSTAT; /*!< Reserved, 0x22 */
- uint32_t INTEN; /*!< Reserved, 0x22 */
- uint32_t INTCLR; /*!< Reserved, 0x22 */
- uint32_t GCTL; /*!< Reserved, 0x22 */
- uint32_t CCTL; /*!< Reserved, 0x22 */
- uint32_t SPBRG; /*!< Reserved, 0x22 */
- uint32_t RXDNR; /*!< Reserved, 0x22 */
- uint32_t SCSR; /*!< Reserved, 0x22 */
- uint32_t MODE; /*!< Reserved, 0x22 */
+ uint32_t TXREG; /*!< Reserved, 0x22 */
+ uint32_t RXREG; /*!< Reserved, 0x22 */
+ uint32_t CSTAT; /*!< Reserved, 0x22 */
+ uint32_t INTSTAT; /*!< Reserved, 0x22 */
+ uint32_t INTEN; /*!< Reserved, 0x22 */
+ uint32_t INTCLR; /*!< Reserved, 0x22 */
+ uint32_t GCTL; /*!< Reserved, 0x22 */
+ uint32_t CCTL; /*!< Reserved, 0x22 */
+ uint32_t SPBRG; /*!< Reserved, 0x22 */
+ uint32_t RXDNR; /*!< Reserved, 0x22 */
+ uint32_t SCSR; /*!< Reserved, 0x22 */
+ uint32_t MODE; /*!< Reserved, 0x22 */
} QSPI_TypeDef;
-/**
+/**
* @brief Touch Sensing Controller (TSC)
*/
typedef struct
@@ -1167,26 +1167,26 @@ typedef struct
typedef struct
{
__IO uint32_t ADDATA; /*!< ADC status register, Address offset: 0x00 */
- __IO uint32_t ADCFG; /*!< ADC control register 1, Address offset: 0x04 */
+ __IO uint32_t ADCFG; /*!< ADC control register 1, Address offset: 0x04 */
__IO uint32_t ADCR; /*!< ADC control register 2, Address offset: 0x08 */
__IO uint32_t ADCHS; /*!< ADC sample time register 1, Address offset: 0x0C */
__IO uint32_t ADCMPR; //10
- __IO uint32_t ADSTA;
+ __IO uint32_t ADSTA;
__IO uint32_t ADDR0; //18
- __IO uint32_t ADDR1;
+ __IO uint32_t ADDR1;
__IO uint32_t ADDR2; //20
- __IO uint32_t ADDR3;
- __IO uint32_t ADDR4;
- __IO uint32_t ADDR5;
+ __IO uint32_t ADDR3;
+ __IO uint32_t ADDR4;
+ __IO uint32_t ADDR5;
__IO uint32_t ADDR6; //30
- __IO uint32_t ADDR7;
- __IO uint32_t ADDR8;
- __IO uint32_t ADDR9;
+ __IO uint32_t ADDR7;
+ __IO uint32_t ADDR8;
+ __IO uint32_t ADDR9;
__IO uint32_t RESERVED0;//40
__IO uint32_t RESERVED1;
- __IO uint32_t TPXDR;
- __IO uint32_t TPYDR;
- __IO uint32_t TPCR;
+ __IO uint32_t TPXDR;
+ __IO uint32_t TPYDR;
+ __IO uint32_t TPCR;
__IO uint32_t TPFR;
__IO uint32_t TPCSR;
@@ -1222,7 +1222,7 @@ typedef struct
#define GPIOB_BASE (AHB1PERIPH_BASE + 0x0400)
#define GPIOC_BASE (AHB1PERIPH_BASE + 0x0800)
#define GPIOD_BASE (AHB1PERIPH_BASE + 0x0C00)
-#define GPIOE_BASE (AHB1PERIPH_BASE + 0x1000)
+#define GPIOE_BASE (AHB1PERIPH_BASE + 0x1000)
#define RTC_BASE (APB1PERIPH_BASE + 0x2800)
#define CRC_BASE (AHB1PERIPH_BASE + 0x3000)
#define RCC_BASE (AHB1PERIPH_BASE + 0x3800)
@@ -1256,7 +1256,7 @@ typedef struct
#define SDRAM_BANK_BASE (AHB3PERIPH_BASE + 0x00000000) //0xc0000000
#define SDRAM_CONTROL_BASE (0xD0000000)
-
+
/*!< APB2 peripherals */
#define TIM1_BASE (APB2PERIPH_BASE + 0x0000) //0x40010000
#define TIM2_BASE (APB2PERIPH_BASE + 0x0400)
@@ -1308,7 +1308,7 @@ typedef struct
/** @addtogroup Peripheral_declaration
* @{
-*/
+*/
#define TIM1 ((TIM_TypeDef *) TIM1_BASE)
#define TIM2 ((TIM_TypeDef *) TIM2_BASE)
@@ -1388,7 +1388,7 @@ typedef struct
#define WWDG ((WWDG_TypeDef *) WWDG_BASE)
#define IWDG ((IWDG_TypeDef *) IWDG_BASE)
-#define OB ((OB_TypeDef *) OB_BASE)
+#define OB ((OB_TypeDef *) OB_BASE)
#define DBGMCU ((DBGMCU_TypeDef *) DBGMCU_BASE)
@@ -1630,7 +1630,7 @@ typedef struct
/*!< MCO configuration */
#define RCC_CFGR_MCO_NOCLOCK ((uint32_t)0x00000000) /*!< No clock */
#define RCC_CFGR_MCO_LSI ((uint32_t)0x02000000) //
-#define RCC_CFGR_MCO_LSE ((uint32_t)0x03000000)
+#define RCC_CFGR_MCO_LSE ((uint32_t)0x03000000)
#define RCC_CFGR_MCO_SYSCLK ((uint32_t)0x04000000) /*!< System clock selected */
#define RCC_CFGR_MCO_HSI ((uint32_t)0x05000000) /*!< Internal 48 MHz RC oscillator clock selected */
#define RCC_CFGR_MCO_HSE ((uint32_t)0x06000000) /*!< External 1-25 MHz oscillator clock selected */
@@ -1741,7 +1741,7 @@ typedef struct
#define RCC_BDCR_RTCEN ((uint32_t)0x00008000) /*!< RTC clock enable */
#define RCC_BDCR_BDRST ((uint32_t)0x00010000) /*!< Backup domain software reset */
-/******************* Bit definition for RCC_CSR register ********************/
+/******************* Bit definition for RCC_CSR register ********************/
#define RCC_CSR_LSION ((uint32_t)0x00000001) /*!< Internal Low Speed oscillator enable */
#define RCC_CSR_LSIRDY ((uint32_t)0x00000002) /*!< Internal Low Speed oscillator Ready */
#define RCC_CSR_RMVF ((uint32_t)0x01000000) /*!< Remove reset flag */
@@ -2033,8 +2033,8 @@ typedef struct
#define SYSCFG_EXTICR1_EXTI2 ((uint16_t)0x0F00) /*!< EXTI 2 configuration */
#define SYSCFG_EXTICR1_EXTI3 ((uint16_t)0xF000) /*!< EXTI 3 configuration */
-/**
-* @brief EXTI0 configuration
+/**
+* @brief EXTI0 configuration
*/
#define SYSCFG_EXTICR1_EXTI0_PA ((uint16_t)0x0000) /*!< PA[0] pin */
#define SYSCFG_EXTICR1_EXTI0_PB ((uint16_t)0x0001) /*!< PB[0] pin */
@@ -2043,9 +2043,9 @@ typedef struct
#define SYSCFG_EXTICR1_EXTI0_PE ((uint16_t)0x0004) /*!< PE[0] pin */
#define SYSCFG_EXTICR1_EXTI0_PF ((uint16_t)0x0005) /*!< PF[0] pin */
-/**
-* @brief EXTI1 configuration
-*/
+/**
+* @brief EXTI1 configuration
+*/
#define SYSCFG_EXTICR1_EXTI1_PA ((uint16_t)0x0000) /*!< PA[1] pin */
#define SYSCFG_EXTICR1_EXTI1_PB ((uint16_t)0x0010) /*!< PB[1] pin */
#define SYSCFG_EXTICR1_EXTI1_PC ((uint16_t)0x0020) /*!< PC[1] pin */
@@ -2053,8 +2053,8 @@ typedef struct
#define SYSCFG_EXTICR1_EXTI1_PE ((uint16_t)0x0040) /*!< PE[1] pin */
#define SYSCFG_EXTICR1_EXTI1_PF ((uint16_t)0x0050) /*!< PF[1] pin */
-/**
-* @brief EXTI2 configuration
+/**
+* @brief EXTI2 configuration
*/
#define SYSCFG_EXTICR1_EXTI2_PA ((uint16_t)0x0000) /*!< PA[2] pin */
#define SYSCFG_EXTICR1_EXTI2_PB ((uint16_t)0x0100) /*!< PB[2] pin */
@@ -2063,8 +2063,8 @@ typedef struct
#define SYSCFG_EXTICR1_EXTI2_PE ((uint16_t)0x0400) /*!< PE[2] pin */
#define SYSCFG_EXTICR1_EXTI2_PF ((uint16_t)0x0500) /*!< PF[2] pin */
-/**
-* @brief EXTI3 configuration
+/**
+* @brief EXTI3 configuration
*/
#define SYSCFG_EXTICR1_EXTI3_PA ((uint16_t)0x0000) /*!< PA[3] pin */
#define SYSCFG_EXTICR1_EXTI3_PB ((uint16_t)0x1000) /*!< PB[3] pin */
@@ -2079,8 +2079,8 @@ typedef struct
#define SYSCFG_EXTICR2_EXTI6 ((uint16_t)0x0F00) /*!< EXTI 6 configuration */
#define SYSCFG_EXTICR2_EXTI7 ((uint16_t)0xF000) /*!< EXTI 7 configuration */
-/**
-* @brief EXTI4 configuration
+/**
+* @brief EXTI4 configuration
*/
#define SYSCFG_EXTICR2_EXTI4_PA ((uint16_t)0x0000) /*!< PA[4] pin */
#define SYSCFG_EXTICR2_EXTI4_PB ((uint16_t)0x0001) /*!< PB[4] pin */
@@ -2089,8 +2089,8 @@ typedef struct
#define SYSCFG_EXTICR2_EXTI4_PE ((uint16_t)0x0004) /*!< PE[4] pin */
#define SYSCFG_EXTICR2_EXTI4_PF ((uint16_t)0x0005) /*!< PF[4] pin */
-/**
-* @brief EXTI5 configuration
+/**
+* @brief EXTI5 configuration
*/
#define SYSCFG_EXTICR2_EXTI5_PA ((uint16_t)0x0000) /*!< PA[5] pin */
#define SYSCFG_EXTICR2_EXTI5_PB ((uint16_t)0x0010) /*!< PB[5] pin */
@@ -2099,8 +2099,8 @@ typedef struct
#define SYSCFG_EXTICR2_EXTI5_PE ((uint16_t)0x0040) /*!< PE[5] pin */
#define SYSCFG_EXTICR2_EXTI5_PF ((uint16_t)0x0050) /*!< PF[5] pin */
-/**
-* @brief EXTI6 configuration
+/**
+* @brief EXTI6 configuration
*/
#define SYSCFG_EXTICR2_EXTI6_PA ((uint16_t)0x0000) /*!< PA[6] pin */
#define SYSCFG_EXTICR2_EXTI6_PB ((uint16_t)0x0100) /*!< PB[6] pin */
@@ -2109,8 +2109,8 @@ typedef struct
#define SYSCFG_EXTICR2_EXTI6_PE ((uint16_t)0x0400) /*!< PE[6] pin */
#define SYSCFG_EXTICR2_EXTI6_PF ((uint16_t)0x0500) /*!< PF[6] pin */
-/**
-* @brief EXTI7 configuration
+/**
+* @brief EXTI7 configuration
*/
#define SYSCFG_EXTICR2_EXTI7_PA ((uint16_t)0x0000) /*!< PA[7] pin */
#define SYSCFG_EXTICR2_EXTI7_PB ((uint16_t)0x1000) /*!< PB[7] pin */
@@ -2125,8 +2125,8 @@ typedef struct
#define SYSCFG_EXTICR3_EXTI10 ((uint16_t)0x0F00) /*!< EXTI 10 configuration */
#define SYSCFG_EXTICR3_EXTI11 ((uint16_t)0xF000) /*!< EXTI 11 configuration */
-/**
-* @brief EXTI8 configuration
+/**
+* @brief EXTI8 configuration
*/
#define SYSCFG_EXTICR3_EXTI8_PA ((uint16_t)0x0000) /*!< PA[8] pin */
#define SYSCFG_EXTICR3_EXTI8_PB ((uint16_t)0x0001) /*!< PB[8] pin */
@@ -2134,8 +2134,8 @@ typedef struct
#define SYSCFG_EXTICR3_EXTI8_PD ((uint16_t)0x0003) /*!< PD[8] pin */
#define SYSCFG_EXTICR3_EXTI8_PE ((uint16_t)0x0004) /*!< PE[8] pin */
-/**
-* @brief EXTI9 configuration
+/**
+* @brief EXTI9 configuration
*/
#define SYSCFG_EXTICR3_EXTI9_PA ((uint16_t)0x0000) /*!< PA[9] pin */
#define SYSCFG_EXTICR3_EXTI9_PB ((uint16_t)0x0010) /*!< PB[9] pin */
@@ -2144,8 +2144,8 @@ typedef struct
#define SYSCFG_EXTICR3_EXTI9_PE ((uint16_t)0x0040) /*!< PE[9] pin */
#define SYSCFG_EXTICR3_EXTI9_PF ((uint16_t)0x0050) /*!< PF[9] pin */
-/**
-* @brief EXTI10 configuration
+/**
+* @brief EXTI10 configuration
*/
#define SYSCFG_EXTICR3_EXTI10_PA ((uint16_t)0x0000) /*!< PA[10] pin */
#define SYSCFG_EXTICR3_EXTI10_PB ((uint16_t)0x0100) /*!< PB[10] pin */
@@ -2154,8 +2154,8 @@ typedef struct
#define SYSCFG_EXTICR3_EXTI10_PE ((uint16_t)0x0400) /*!< PD[10] pin */
#define SYSCFG_EXTICR3_EXTI10_PF ((uint16_t)0x0500) /*!< PF[10] pin */
-/**
-* @brief EXTI11 configuration
+/**
+* @brief EXTI11 configuration
*/
#define SYSCFG_EXTICR3_EXTI11_PA ((uint16_t)0x0000) /*!< PA[11] pin */
#define SYSCFG_EXTICR3_EXTI11_PB ((uint16_t)0x1000) /*!< PB[11] pin */
@@ -2169,8 +2169,8 @@ typedef struct
#define SYSCFG_EXTICR4_EXTI14 ((uint16_t)0x0F00) /*!< EXTI 14 configuration */
#define SYSCFG_EXTICR4_EXTI15 ((uint16_t)0xF000) /*!< EXTI 15 configuration */
-/**
-* @brief EXTI12 configuration
+/**
+* @brief EXTI12 configuration
*/
#define SYSCFG_EXTICR4_EXTI12_PA ((uint16_t)0x0000) /*!< PA[12] pin */
#define SYSCFG_EXTICR4_EXTI12_PB ((uint16_t)0x0001) /*!< PB[12] pin */
@@ -2178,8 +2178,8 @@ typedef struct
#define SYSCFG_EXTICR4_EXTI12_PD ((uint16_t)0x0003) /*!< PD[12] pin */
#define SYSCFG_EXTICR4_EXTI12_PE ((uint16_t)0x0004) /*!< PE[12] pin */
-/**
-* @brief EXTI13 configuration
+/**
+* @brief EXTI13 configuration
*/
#define SYSCFG_EXTICR4_EXTI13_PA ((uint16_t)0x0000) /*!< PA[13] pin */
#define SYSCFG_EXTICR4_EXTI13_PB ((uint16_t)0x0010) /*!< PB[13] pin */
@@ -2187,8 +2187,8 @@ typedef struct
#define SYSCFG_EXTICR4_EXTI13_PD ((uint16_t)0x0030) /*!< PD[13] pin */
#define SYSCFG_EXTICR4_EXTI13_PE ((uint16_t)0x0040) /*!< PE[13] pin */
-/**
-* @brief EXTI14 configuration
+/**
+* @brief EXTI14 configuration
*/
#define SYSCFG_EXTICR4_EXTI14_PA ((uint16_t)0x0000) /*!< PA[14] pin */
#define SYSCFG_EXTICR4_EXTI14_PB ((uint16_t)0x0100) /*!< PB[14] pin */
@@ -2196,8 +2196,8 @@ typedef struct
#define SYSCFG_EXTICR4_EXTI14_PD ((uint16_t)0x0300) /*!< PD[14] pin */
#define SYSCFG_EXTICR4_EXTI14_PE ((uint16_t)0x0400) /*!< PE[14] pin */
-/**
-* @brief EXTI15 configuration
+/**
+* @brief EXTI15 configuration
*/
#define SYSCFG_EXTICR4_EXTI15_PA ((uint16_t)0x0000) /*!< PA[15] pin */
#define SYSCFG_EXTICR4_EXTI15_PB ((uint16_t)0x1000) /*!< PB[15] pin */
@@ -2743,8 +2743,8 @@ typedef struct
#define EXTI_PR_PR16 ((uint32_t)0x00010000) /*!< Pending bit 16 */
#define EXTI_PR_PR17 ((uint32_t)0x00020000) /*!< Pending bit 17 */
#define EXTI_PR_PR18 ((uint32_t)0x00040000) /*!< Trigger request occurred on the external interrupt line 18 */
-#define EXTI_PR_PR19 ((uint32_t)0x00080000)
-#define EXTI_PR_PR20 ((uint32_t)0x00100000)
+#define EXTI_PR_PR19 ((uint32_t)0x00080000)
+#define EXTI_PR_PR20 ((uint32_t)0x00100000)
/******************************************************************************/
/* */
/* DMA Controller */
@@ -3085,40 +3085,40 @@ typedef struct
#define ADCR_TRGSEL_1 ((uint32_t)0x00000020) /*!© COPYRIGHT 2016 HOLOCENE
-*/
+*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __HAL_ADC_H
@@ -38,15 +38,15 @@
* @{
*/
-/**
-* @brief ADC Init structure definition
+/**
+* @brief ADC Init structure definition
*/
/*
typedef struct
{
uint32_t ADC_Mode;
-FunctionalState ADC_ScanConvMode;
+FunctionalState ADC_ScanConvMode;
FunctionalState ADC_ContinuousConvMode;
uint32_t ADC_ExternalTrigConv;
uint32_t ADC_DataAlign;
@@ -55,12 +55,12 @@ uint8_t ADC_NbrOfChannel;
*/
typedef struct
{
- uint32_t ADC_Resolution;
+ uint32_t ADC_Resolution;
uint32_t ADC_PRESCARE;
uint32_t ADC_Mode;
FunctionalState ADC_ContinuousConvMode;
uint32_t ADC_TRGEN;
- uint32_t ADC_ExternalTrigConv;
+ uint32_t ADC_ExternalTrigConv;
uint32_t ADC_DataAlign;
}ADC_InitTypeDef;
/**
@@ -79,7 +79,7 @@ typedef struct
/** @defgroup ADC_Resolution
* @{
-*/
+*/
#define ADC_Resolution_12b ((uint32_t)0x00000000)
#define ADC_Resolution_11b ((uint32_t)0x00000080)
#define ADC_Resolution_10b ((uint32_t)0x00000100)
@@ -91,7 +91,7 @@ typedef struct
((RESOLUTION) == ADC_Resolution_8b) || \
((RESOLUTION) == ADC_Resolution_6b))
-/**
+/**
* @brief for ADC1, ADC2
*/
@@ -106,7 +106,7 @@ typedef struct
-/** @defgroup ADC_dual_mode
+/** @defgroup ADC_dual_mode
* @{
*/
@@ -125,12 +125,12 @@ typedef struct
#define ADC_TRG_Disable ((uint32_t)0xfffffffB)
#define ADC_TRG_Enable ((uint32_t)0x00000004)
-/** @defgroup ADC_extrenal_trigger_sources_for_regular_channels_conversion
+/** @defgroup ADC_extrenal_trigger_sources_for_regular_channels_conversion
* @{
*/
-/**
-* @brief for ADC1
+/**
+* @brief for ADC1
*/
#define ADC_ExternalTrigConv_T1_CC1 ((uint32_t)0x00000000)
@@ -142,7 +142,7 @@ typedef struct
#define ADC_ExternalTrigConv_T3_CC1 ((uint32_t)0x00000060)
#define ADC_ExternalTrigConv_EXTI_11 ((uint32_t)0x00000070)
-/**
+/**
* @brief for ADC2
*/
@@ -177,7 +177,7 @@ typedef struct
* @}
*/
-/** @defgroup ADC_data_align
+/** @defgroup ADC_data_align
* @{
*/
@@ -189,7 +189,7 @@ typedef struct
* @}
*/
-/** @defgroup ADC_channels
+/** @defgroup ADC_channels
* @{
*/
@@ -216,16 +216,16 @@ typedef struct
/**
* @}
-*/
+*/
#define ADC_SMPR_SMP ((uint32_t)0x00000007) /*!< SMP[2:0] bits (Sampling time selection) */
#define ADC_SMPR_SMP_0 ((uint32_t)0x00000001) /*!< Bit 0 */
#define ADC_SMPR_SMP_1 ((uint32_t)0x00000002) /*!< Bit 1 */
#define ADC_SMPR_SMP_2 ((uint32_t)0x00000004) /*!< Bit 2 */
-/** @defgroup ADC_sampling_times
+/** @defgroup ADC_sampling_times
* @{
-*/
+*/
#define ADC_SampleTime_1_5Cycles ((uint32_t)0x00000000)
#define ADC_SampleTime_7_5Cycles ((uint32_t)0x00000001)
@@ -247,7 +247,7 @@ typedef struct
-/** @defgroup ADC_injected_channel_selection
+/** @defgroup ADC_injected_channel_selection
* @{
*/
@@ -272,7 +272,7 @@ typedef struct
* @}
*/
-/** @defgroup ADC_analog_watchdog_selection
+/** @defgroup ADC_analog_watchdog_selection
* @{
*/
@@ -285,7 +285,7 @@ typedef struct
* @}
*/
-/** @defgroup ADC_interrupts_definition
+/** @defgroup ADC_interrupts_definition
* @{
*/
@@ -294,18 +294,18 @@ typedef struct
#define IS_ADC_IT(IT) ((((IT) & (uint16_t)0xFFFC) == 0x00) && ((IT) != 0x00))
-#define IS_ADC_GET_IT(IT) (((IT) == ADC_IT_EOC) || ((IT) == ADC_IT_AWD))
+#define IS_ADC_GET_IT(IT) (((IT) == ADC_IT_EOC) || ((IT) == ADC_IT_AWD))
/**
* @}
*/
-/** @defgroup ADC_flags_definition
+/** @defgroup ADC_flags_definition
* @{
*/
-#define ADC_FLAG_AWD ((uint8_t)0x02) //ADWIF 比较标志位
-#define ADC_FLAG_EOC ((uint8_t)0x01) //ADIF 转换结束标志位
+#define ADC_FLAG_AWD ((uint8_t)0x02) //ADWIF 姣旇緝鏍囧織浣
+#define ADC_FLAG_EOC ((uint8_t)0x01) //ADIF 杞崲缁撴潫鏍囧織浣
#define IS_ADC_CLEAR_FLAG(FLAG) ((((FLAG) & (uint8_t)0xF0) == 0x00) && ((FLAG) != 0x00))
#define IS_ADC_GET_FLAG(FLAG) (((FLAG) == ADC_FLAG_AWD) || ((FLAG) == ADC_FLAG_EOC))
@@ -313,7 +313,7 @@ typedef struct
* @}
*/
-/** @defgroup ADC_thresholds
+/** @defgroup ADC_thresholds
* @{
*/
@@ -323,7 +323,7 @@ typedef struct
* @}
*/
-/** @defgroup ADC_injected_offset
+/** @defgroup ADC_injected_offset
* @{
*/
@@ -333,7 +333,7 @@ typedef struct
* @}
*/
-/** @defgroup ADC_injected_length
+/** @defgroup ADC_injected_length
* @{
*/
@@ -343,7 +343,7 @@ typedef struct
* @}
*/
-/** @defgroup ADC_injected_rank
+/** @defgroup ADC_injected_rank
* @{
*/
@@ -351,10 +351,10 @@ typedef struct
/**
* @}
-*/
+*/
-/** @defgroup ADC_regular_length
+/** @defgroup ADC_regular_length
* @{
*/
@@ -363,7 +363,7 @@ typedef struct
* @}
*/
-/** @defgroup ADC_regular_rank
+/** @defgroup ADC_regular_rank
* @{
*/
@@ -373,7 +373,7 @@ typedef struct
* @}
*/
-/** @defgroup ADC_regular_discontinuous_mode_number
+/** @defgroup ADC_regular_discontinuous_mode_number
* @{
*/
diff --git a/bsp/tkm32F499/Libraries/Hal_lib/inc/HAL_conf.h b/bsp/tkm32F499/Libraries/Hal_lib/inc/HAL_conf.h
index 3872b63a37..ee32d0941a 100644
--- a/bsp/tkm32F499/Libraries/Hal_lib/inc/HAL_conf.h
+++ b/bsp/tkm32F499/Libraries/Hal_lib/inc/HAL_conf.h
@@ -16,11 +16,11 @@
* CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*
* © COPYRIGHT 2016 HOLOCENE
-*/
+*/
#ifndef __HAL_CONF_H__
#define __HAL_CONF_H__
-/*此处可添加或删除外设*/
+/*姝ゅ鍙坊鍔犳垨鍒犻櫎澶栬*/
#include "HAL_device.h"
#include "HAL_adc.h"
#include "HAL_dma.h"
diff --git a/bsp/tkm32F499/Libraries/Hal_lib/inc/HAL_gpio.h b/bsp/tkm32F499/Libraries/Hal_lib/inc/HAL_gpio.h
index 2c1d4a9ad2..6289e7c1ac 100644
--- a/bsp/tkm32F499/Libraries/Hal_lib/inc/HAL_gpio.h
+++ b/bsp/tkm32F499/Libraries/Hal_lib/inc/HAL_gpio.h
@@ -4,7 +4,7 @@
* @author IC Applications Department
* @version V0.8
* @date 2019_08_02
-* @brief This file contains all the functions prototypes for the GPIO
+* @brief This file contains all the functions prototypes for the GPIO
* firmware library.
******************************************************************************
* @copy
@@ -17,7 +17,7 @@
* CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*
* © COPYRIGHT 2016 HOLOCENE
-*/
+*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __HAL_GPIO_H
@@ -46,33 +46,33 @@
((*(uint32_t*)&(PERIPH)) == GPIOF_BASE) || \
((*(uint32_t*)&(PERIPH)) == GPIOG_BASE))
-/**
-* @brief Output Maximum frequency selection
+/**
+* @brief Output Maximum frequency selection
*/
typedef enum
-{
+{
GPIO_Speed_10MHz = 1,
- GPIO_Speed_2MHz,
+ GPIO_Speed_2MHz,
GPIO_Speed_50MHz
}GPIOSpeed_TypeDef;
#define IS_GPIO_SPEED(SPEED) (((SPEED) == GPIO_Speed_10MHz) || ((SPEED) == GPIO_Speed_2MHz) || \
((SPEED) == GPIO_Speed_50MHz))
-/**
-* @brief Configuration Mode enumeration
+/**
+* @brief Configuration 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_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 //澶嶇敤鎺ㄥ厤杈撳嚭
}GPIOMode_TypeDef;
#define IS_GPIO_MODE(MODE) (((MODE) == GPIO_Mode_AIN) || ((MODE) == GPIO_Mode_IN_FLOATING) || \
@@ -80,8 +80,8 @@ GPIO_Mode_AF_PP = 0x18 //
((MODE) == GPIO_Mode_Out_OD) || ((MODE) == GPIO_Mode_Out_PP) || \
((MODE) == GPIO_Mode_AF_OD) || ((MODE) == GPIO_Mode_AF_PP))
-/**
-* @brief GPIO Init structure definition
+/**
+* @brief GPIO Init structure definition
*/
typedef struct
@@ -91,8 +91,8 @@ typedef struct
GPIOMode_TypeDef GPIO_Mode;
}GPIO_InitTypeDef;
-/**
-* @brief Bit_SET and Bit_RESET enumeration
+/**
+* @brief Bit_SET and Bit_RESET enumeration
*/
typedef enum
@@ -110,7 +110,7 @@ typedef enum
* @{
*/
-/** @defgroup GPIO_pins_define
+/** @defgroup GPIO_pins_define
* @{
*/
@@ -164,7 +164,7 @@ typedef enum
* @}
*/
-/** @defgroup GPIO_Remap_define
+/** @defgroup GPIO_Remap_define
* @{
*/
@@ -209,7 +209,7 @@ typedef enum
* @}
*/
-/** @defgroup GPIO_Alternate_function_selection_define
+/** @defgroup GPIO_Alternate_function_selection_define
* @{
*/
diff --git a/bsp/tkm32F499/Libraries/Hal_lib/src/HAL_can.c b/bsp/tkm32F499/Libraries/Hal_lib/src/HAL_can.c
index 578d487c7a..ff8bce1cc0 100644
--- a/bsp/tkm32F499/Libraries/Hal_lib/src/HAL_can.c
+++ b/bsp/tkm32F499/Libraries/Hal_lib/src/HAL_can.c
@@ -16,7 +16,7 @@
* CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*
* © COPYRIGHT 2016 HOLOCENE
-*/
+*/
/* Includes ------------------------------------------------------------------*/
#include "HAL_can.h"
@@ -518,7 +518,7 @@ void CAN_Peli_Init(CAN_TypeDef* CANx, CAN_Peli_InitTypeDef* CAN_Peli_InitStruct)
assert_param(IS_FUNCTIONAL_STATE(CAN_InitStruct->SAM));
assert_param(IS_FUNCTIONAL_STATE(CAN_InitStruct->TESG2));
assert_param(IS_FUNCTIONAL_STATE(CAN_InitStruct->TESG1));
-
+
switch (*(uint32_t*)&CANx)
{
case CAN1_BASE:
@@ -559,7 +559,7 @@ void CAN_Peli_Init(CAN_TypeDef* CANx, CAN_Peli_InitTypeDef* CAN_Peli_InitStruct)
break;
default:
break;
- }
+ }
}
@@ -610,7 +610,7 @@ void CAN_Peli_FilterInit(CAN_TypeDef* CANx, CAN_Peli_FilterInitTypeDef* CAN_Peli
default:
break;
}
-
+
}
/**
@@ -850,7 +850,7 @@ void CAN_Peli_TransmitRepeat(CAN_TypeDef* CANx, CanPeliTxMsg* PeliTxMessage)
default:
break;
}
-
+
}
/** @defgroup CAN_Group3 CAN Frames Reception functions
@@ -957,7 +957,7 @@ void CAN_Peli_Receive(CAN_TypeDef* CANx, CanPeliRxMsg* PeliRxMessage)
break;
default:
break;
- }
+ }
}
@@ -977,8 +977,8 @@ uint32_t CAN_Peli_GetRxFIFOInfo(CAN_TypeDef* CANx)
break;
default:
break;
- }
-
+ }
+
}
@@ -1009,7 +1009,7 @@ uint32_t CAN_Peli_GetRxFIFOInfo(CAN_TypeDef* CANx)
uint8_t CAN_Peli_GetLastErrorCode(CAN_TypeDef* CANx)
{
uint8_t errorcode = 0;
-
+
switch (*(uint32_t*)&CANx)
{
case CAN1_BASE:
@@ -1022,7 +1022,7 @@ uint8_t CAN_Peli_GetLastErrorCode(CAN_TypeDef* CANx)
break;
default:
break;
- }
+ }
/* Return the error code*/
return errorcode;
}
@@ -1056,7 +1056,7 @@ uint8_t CAN_Peli_GetReceiveErrorCounter(CAN_TypeDef* CANx)
default:
break;
}
-
+
/* Return the Receive Error Counter*/
return counter;
}
@@ -1072,7 +1072,7 @@ uint8_t CAN_Peli_GetLSBTransmitErrorCounter(CAN_TypeDef* CANx)
/* Check the parameters */
assert_param(IS_CAN_ALL_PERIPH(CANx));
-
+
switch (*(uint32_t*)&CANx)
{
case CAN1_BASE:
@@ -1126,7 +1126,7 @@ void CAN_Peli_ITConfig(CAN_TypeDef* CANx,uint32_t CAN_IT, FunctionalState NewSta
/* Check the parameters */
assert_param(IS_CAN_IT(CAN_IT));
assert_param(IS_FUNCTIONAL_STATE(NewState));
-
+
switch (*(uint32_t*)&CANx)
{
case CAN1_BASE:
@@ -1156,7 +1156,7 @@ void CAN_Peli_ITConfig(CAN_TypeDef* CANx,uint32_t CAN_IT, FunctionalState NewSta
default:
break;
}
-
+
}
@@ -1180,7 +1180,7 @@ ITStatus CAN_Peli_GetITStatus(CAN_TypeDef* CANx, uint32_t CAN_IT)
ITStatus itstatus = RESET;
/* Check the parameters */
assert_param(IS_CAN_IT(CAN_IT));
-
+
switch (*(uint32_t*)&CANx)
{
case CAN1_BASE:
@@ -1223,13 +1223,13 @@ void CAN_AutoCfg_BaudParam(CAN_Peli_InitTypeDef *CAN_Peli_InitStruct, unsigned
{
unsigned int i, value = baud, record = 1;
unsigned int remain = 0, sumPrescaler = 0;
- while(( baud == 0 ) || ( SrcClk == 0 )); //防止波特率及时钟为0
- sumPrescaler = SrcClk / baud; //总分频
+ while(( baud == 0 ) || ( SrcClk == 0 )); //闃叉娉㈢壒鐜囧強鏃堕挓涓0
+ sumPrescaler = SrcClk / baud; //鎬诲垎棰
sumPrescaler = sumPrescaler / 2; //
for( i = 25; i > 3; i -- )
{
remain = sumPrescaler - ((sumPrescaler / i) * i);
- if( remain == 0 ) //整除
+ if( remain == 0 ) //鏁撮櫎
{
record = i;
break;
diff --git a/bsp/tkm32F499/Libraries/Hal_lib/src/HAL_dma_bak.c b/bsp/tkm32F499/Libraries/Hal_lib/src/HAL_dma_bak.c
index 8e4d885de3..9393998d8a 100644
--- a/bsp/tkm32F499/Libraries/Hal_lib/src/HAL_dma_bak.c
+++ b/bsp/tkm32F499/Libraries/Hal_lib/src/HAL_dma_bak.c
@@ -480,7 +480,7 @@ ITStatus DMA_GetITStatus(uint32_t DMA_IT)
}
/**
-* @brief Clears the DMAy Channelx抯 interrupt pending bits.
+* @brief Clears the DMAy Channelx鈥檚 interrupt pending bits.
* @param DMA_IT: specifies the DMA interrupt pending bit to clear.
* This parameter can be any combination (for the same DMA) of
* the following values:
diff --git a/bsp/tkm32F499/Libraries/Hal_lib/src/HAL_exti.c b/bsp/tkm32F499/Libraries/Hal_lib/src/HAL_exti.c
index 087e3b993b..a0c3897e4f 100644
--- a/bsp/tkm32F499/Libraries/Hal_lib/src/HAL_exti.c
+++ b/bsp/tkm32F499/Libraries/Hal_lib/src/HAL_exti.c
@@ -16,7 +16,7 @@
* CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*
* © COPYRIGHT 2016 HOLOCENE
-*/
+*/
/* Includes ------------------------------------------------------------------*/
#include "HAL_exti.h"
@@ -25,7 +25,7 @@
* @{
*/
-/** @defgroup EXTI
+/** @defgroup EXTI
* @brief EXTI driver modules
* @{
*/
@@ -77,7 +77,7 @@
*/
/**
-* @brief Deinitializes the EXTI peripheral registers to their default
+* @brief Deinitializes the EXTI peripheral registers to their default
* reset values.
* @param None
* @retval : None
@@ -86,8 +86,8 @@ void EXTI_DeInit(void)
{
EXTI->IMR = 0x00000000;
EXTI->EMR = 0x00000000;
- EXTI->RTSR = 0x00000000;
- EXTI->FTSR = 0x00000000;
+ EXTI->RTSR = 0x00000000;
+ EXTI->FTSR = 0x00000000;
EXTI->PR = 0x001FFFFF;
}
@@ -105,24 +105,24 @@ void EXTI_Init(EXTI_InitTypeDef* EXTI_InitStruct)
/* Check the parameters */
assert_param(IS_EXTI_MODE(EXTI_InitStruct->EXTI_Mode));
assert_param(IS_EXTI_TRIGGER(EXTI_InitStruct->EXTI_Trigger));
- assert_param(IS_EXTI_LINE(EXTI_InitStruct->EXTI_Line));
+ assert_param(IS_EXTI_LINE(EXTI_InitStruct->EXTI_Line));
assert_param(IS_FUNCTIONAL_STATE(EXTI_InitStruct->EXTI_LineCmd));
-
- tmp = (uint32_t)EXTI_BASE;
-
+
+ tmp = (uint32_t)EXTI_BASE;
+
if (EXTI_InitStruct->EXTI_LineCmd != DISABLE)
{
/* Clear EXTI line configuration */
EXTI->IMR &= ~EXTI_InitStruct->EXTI_Line;
EXTI->EMR &= ~EXTI_InitStruct->EXTI_Line;
-
+
tmp += EXTI_InitStruct->EXTI_Mode;
*(__IO uint32_t *) tmp |= EXTI_InitStruct->EXTI_Line;
-
+
/* Clear Rising Falling edge configuration */
EXTI->RTSR &= ~EXTI_InitStruct->EXTI_Line;
EXTI->FTSR &= ~EXTI_InitStruct->EXTI_Line;
-
+
/* Select the trigger for the selected external interrupts */
if (EXTI_InitStruct->EXTI_Trigger == EXTI_Trigger_Rising_Falling)
{
@@ -134,7 +134,7 @@ void EXTI_Init(EXTI_InitTypeDef* EXTI_InitStruct)
{
tmp = (uint32_t)EXTI_BASE;
tmp += EXTI_InitStruct->EXTI_Trigger;
-
+
*(__IO uint32_t *) tmp |= EXTI_InitStruct->EXTI_Line;
}
}
@@ -165,7 +165,7 @@ void EXTI_StructInit(EXTI_InitTypeDef* EXTI_InitStruct)
* @brief Generates a Software interrupt.
* @param EXTI_Line: specifies the EXTI lines to be enabled or
* disabled.
-* This parameter can be any combination of EXTI_Linex where
+* This parameter can be any combination of EXTI_Linex where
* x can be (0..18).
* @retval : None
*/
@@ -173,7 +173,7 @@ void EXTI_GenerateSWInterrupt(uint32_t EXTI_Line)
{
/* Check the parameters */
assert_param(IS_EXTI_LINE(EXTI_Line));
-
+
EXTI->SWIER |= EXTI_Line;
}
@@ -189,7 +189,7 @@ FlagStatus EXTI_GetFlagStatus(uint32_t EXTI_Line)
FlagStatus bitstatus = RESET;
/* Check the parameters */
assert_param(IS_GET_EXTI_LINE(EXTI_Line));
-
+
if ((EXTI->PR & EXTI_Line) != (uint32_t)RESET)
{
bitstatus = SET;
@@ -202,9 +202,9 @@ FlagStatus EXTI_GetFlagStatus(uint32_t EXTI_Line)
}
/**
-* @brief Clears the EXTI抯 line pending flags.
+* @brief Clears the EXTI鈥檚 line pending flags.
* @param EXTI_Line: specifies the EXTI lines flags to clear.
-* This parameter can be any combination of EXTI_Linex where
+* This parameter can be any combination of EXTI_Linex where
* x can be (0..18).
* @retval : None
*/
@@ -212,7 +212,7 @@ void EXTI_ClearFlag(uint32_t EXTI_Line)
{
/* Check the parameters */
assert_param(IS_EXTI_LINE(EXTI_Line));
-
+
EXTI->PR = EXTI_Line;
}
@@ -229,7 +229,7 @@ ITStatus EXTI_GetITStatus(uint32_t EXTI_Line)
uint32_t enablestatus = 0;
/* Check the parameters */
assert_param(IS_GET_EXTI_LINE(EXTI_Line));
-
+
enablestatus = EXTI->IMR & EXTI_Line;
if (((EXTI->PR & EXTI_Line) != (uint32_t)RESET) && (enablestatus != (uint32_t)RESET))
{
@@ -243,9 +243,9 @@ ITStatus EXTI_GetITStatus(uint32_t EXTI_Line)
}
/**
-* @brief Clears the EXTI抯 line pending bits.
+* @brief Clears the EXTI鈥檚 line pending bits.
* @param EXTI_Line: specifies the EXTI lines to clear.
-* This parameter can be any combination of EXTI_Linex where
+* This parameter can be any combination of EXTI_Linex where
* x can be (0..18).
* @retval : None
*/
@@ -253,7 +253,7 @@ void EXTI_ClearITPendingBit(uint32_t EXTI_Line)
{
/* Check the parameters */
assert_param(IS_EXTI_LINE(EXTI_Line));
-
+
EXTI->PR = EXTI_Line;
}
diff --git a/bsp/tkm32F499/Libraries/Hal_lib/src/HAL_gpio.c b/bsp/tkm32F499/Libraries/Hal_lib/src/HAL_gpio.c
index a6842f9607..89c1bbe1a3 100644
--- a/bsp/tkm32F499/Libraries/Hal_lib/src/HAL_gpio.c
+++ b/bsp/tkm32F499/Libraries/Hal_lib/src/HAL_gpio.c
@@ -16,7 +16,7 @@
* CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*
* © COPYRIGHT 2016 HOLOCENE
-*/
+*/
/* Includes ------------------------------------------------------------------*/
#include "HAL_gpio.h"
@@ -26,10 +26,10 @@
* @{
*/
-/** @defgroup GPIO
+/** @defgroup GPIO
* @brief GPIO driver modules
* @{
-*/
+*/
/** @defgroup GPIO_Private_TypesDefinitions
* @{
@@ -101,7 +101,7 @@ void GPIO_DeInit(GPIO_TypeDef* GPIOx)
{
/* Check the parameters */
assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
-
+
switch (*(uint32_t*)&GPIOx)
{
case GPIOA_BASE:
@@ -142,12 +142,12 @@ void GPIO_Init(GPIO_TypeDef* GPIOx, GPIO_InitTypeDef* GPIO_InitStruct)
/* Check the parameters */
assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
assert_param(IS_GPIO_MODE(GPIO_InitStruct->GPIO_Mode));
- assert_param(IS_GPIO_PIN(GPIO_InitStruct->GPIO_Pin));
-
+ assert_param(IS_GPIO_PIN(GPIO_InitStruct->GPIO_Pin));
+
/*---------------------------- GPIO Mode Configuration -----------------------*/
currentmode = ((uint32_t)GPIO_InitStruct->GPIO_Mode) & ((uint32_t)0x0F);
if ((((uint32_t)GPIO_InitStruct->GPIO_Mode) & ((uint32_t)0x10)) != 0x00)
- {
+ {
/* Check the parameters */
assert_param(IS_GPIO_SPEED(GPIO_InitStruct->GPIO_Speed));
/* Output mode */
@@ -221,7 +221,7 @@ void GPIO_Init(GPIO_TypeDef* GPIOx, GPIO_InitTypeDef* GPIO_InitStruct)
GPIOx->CRH = tmpreg;
}
/*---------------------------- GPIOE_CRH_EXT Configuration ------------------------*/
- if(GPIO_InitStruct->GPIO_Pin>>16) //说明是GPIOE的16~23位
+ if(GPIO_InitStruct->GPIO_Pin>>16) //璇存槑鏄疓PIOE鐨16~23浣
{
GPIO_InitStruct->GPIO_Pin = GPIO_InitStruct->GPIO_Pin>>16;
tmpreg = GPIOE->CRH_EXT;
@@ -281,11 +281,11 @@ void GPIO_StructInit(GPIO_InitTypeDef* GPIO_InitStruct)
uint8_t GPIO_ReadInputDataBit(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin)
{
uint8_t bitstatus = 0x00;
-
+
/* Check the parameters */
assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
- assert_param(IS_GET_GPIO_PIN(GPIO_Pin));
-
+ assert_param(IS_GET_GPIO_PIN(GPIO_Pin));
+
if ((GPIOx->IDR & GPIO_Pin) != (uint32_t)Bit_RESET)
{
bitstatus = (uint8_t)Bit_SET;
@@ -306,7 +306,7 @@ uint16_t GPIO_ReadInputData(GPIO_TypeDef* GPIOx)
{
/* Check the parameters */
assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
-
+
return ((uint16_t)GPIOx->IDR);
}
@@ -322,8 +322,8 @@ uint8_t GPIO_ReadOutputDataBit(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin)
uint8_t bitstatus = 0x00;
/* Check the parameters */
assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
- assert_param(IS_GET_GPIO_PIN(GPIO_Pin));
-
+ assert_param(IS_GET_GPIO_PIN(GPIO_Pin));
+
if ((GPIOx->ODR & GPIO_Pin) != (uint32_t)Bit_RESET)
{
bitstatus = (uint8_t)Bit_SET;
@@ -344,7 +344,7 @@ uint16_t GPIO_ReadOutputData(GPIO_TypeDef* GPIOx)
{
/* Check the parameters */
assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
-
+
return ((uint16_t)GPIOx->ODR);
}
@@ -352,7 +352,7 @@ uint16_t GPIO_ReadOutputData(GPIO_TypeDef* GPIOx)
* @brief Sets the selected data port bits.
* @param GPIOx: where x can be (A..G) to select the GPIO peripheral.
* @param GPIO_Pin: specifies the port bits to be written.
-* This parameter can be any combination of GPIO_Pin_x where
+* This parameter can be any combination of GPIO_Pin_x where
* x can be (0..15).
* @retval : None
*/
@@ -364,14 +364,14 @@ void GPIO_SetBits(GPIO_TypeDef* GPIOx, uint32_t GPIO_Pin)
if(GPIO_Pin>GPIO_Pin_15)GPIOE->BSRR_EXT=GPIO_Pin>>16;
else
GPIOx->BSRR = GPIO_Pin;
-
+
}
/**
* @brief Clears the selected data port bits.
* @param GPIOx: where x can be (A..G) to select the GPIO peripheral.
* @param GPIO_Pin: specifies the port bits to be written.
-* This parameter can be any combination of GPIO_Pin_x where
+* This parameter can be any combination of GPIO_Pin_x where
* x can be (0..15).
* @retval : None
*/
@@ -399,8 +399,8 @@ void GPIO_WriteBit(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin, BitAction BitVal)
/* Check the parameters */
assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
assert_param(IS_GET_GPIO_PIN(GPIO_Pin));
- assert_param(IS_GPIO_BIT_ACTION(BitVal));
-
+ assert_param(IS_GPIO_BIT_ACTION(BitVal));
+
if (BitVal != Bit_RESET)
{
GPIOx->BSRR = GPIO_Pin;
@@ -422,7 +422,7 @@ void GPIO_Write(GPIO_TypeDef* GPIOx, uint16_t PortVal)
{
/* Check the parameters */
assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
-
+
GPIOx->ODR = PortVal;
}
@@ -430,18 +430,18 @@ void GPIO_Write(GPIO_TypeDef* GPIOx, uint16_t PortVal)
* @brief Locks GPIO Pins configuration registers.
* @param GPIOx: where x can be (A..G) to select the GPIO peripheral.
* @param GPIO_Pin: specifies the port bit to be written.
-* This parameter can be any combination of GPIO_Pin_x where
+* This parameter can be any combination of GPIO_Pin_x where
* x can be (0..15).
* @retval : None
*/
void GPIO_PinLockConfig(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin)
{
uint32_t tmp = 0x00010000;
-
+
/* Check the parameters */
assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
assert_param(IS_GPIO_PIN(GPIO_Pin));
-
+
tmp |= GPIO_Pin;
/* Set LCKK bit */
GPIOx->LCKR = tmp;
@@ -461,25 +461,25 @@ void GPIO_PinLockConfig(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin)
* @param GPIOx: where x can be (A, B, C, D ) to select the GPIO peripheral.
* @param GPIO_PinSource: specifies the pin for the Alternate function.
* This parameter can be GPIO_PinSourcex where x can be (0..15) for GPIOA, GPIOB, GPIOD
-* and (0..12) for GPIOC .
+* and (0..12) for GPIOC .
* @param GPIO_AF: selects the pin to used as Alternate function.
* This parameter can be one of the following value:
* @arg GPIO_AF_0: SPI1, MC0, TIM17_BKIN, SWDIO,SWCLK,
UART1
* @arg GPIO_AF_1: UART1, TIM3_CH1, TIM3_CH2, TIM3_CH3,
-TIM3_CH4, I2C1
-* @arg GPIO_AF_2: TIM2_CH1_ETR, TIM2_CH2, TIM2_CH3,
+TIM3_CH4, I2C1
+* @arg GPIO_AF_2: TIM2_CH1_ETR, TIM2_CH2, TIM2_CH3,
TIM2_CH3, TIM2_CH4, TIM1_BKIN,
TIM1_CH1N, TIM1_CH1, TIM1_CH2,
TIM1_CH3, TIM1_CH4, TIM1_ETR,
TIM1_CH2N, TIM1_CH3N, TIM2_CH2,
TIM1 6_BKIN, TIM16_CH1N, TIM17_CH1N,
-TIM1 6_CH1, TIM17_CH1
+TIM1 6_CH1, TIM17_CH1
* @arg GPIO_AF_4: TIM14_CH1, I2C1
* @note The pin should already been configured in Alternate Function mode(AF)
* using GPIO_InitStruct->GPIO_Mode = GPIO_Mode_AF
-* @note Refer to the Alternate function mapping table in the device datasheet
-* for the detailed mapping of the system and peripherals'alternate
+* @note Refer to the Alternate function mapping table in the device datasheet
+* for the detailed mapping of the system and peripherals'alternate
* function I/O pins.
* @retval None
*/
@@ -487,45 +487,45 @@ void GPIO_PinAFConfig(GPIO_TypeDef* GPIOx, uint32_t GPIO_Pin, uint8_t GPIO_AF)
{
uint32_t temp;
unsigned char i;
-
+
/* Check the parameters */
assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
assert_param(IS_GPIO_PIN_SOURCE(GPIO_PinSource));
assert_param(IS_GPIO_AF(GPIO_AF));
-
- if(GPIO_Pin>>16) //说明是GPIOE的16~23位
+
+ if(GPIO_Pin>>16) //璇存槑鏄疓PIOE鐨16~23浣
{
temp = GPIO_Pin>>16;
for(i=0;i<8;i++)
{
if(temp&0x01)
{
- GPIOE->AFRH_EXT &= ~((uint32_t)0xF << ((uint32_t)(i<<2))); //AF配置占半字节,要x4,即<<2
+ GPIOE->AFRH_EXT &= ~((uint32_t)0xF << ((uint32_t)(i<<2))); //AF閰嶇疆鍗犲崐瀛楄妭锛岃x4,鍗<<2
GPIOE->AFRH_EXT |= ((uint32_t)GPIO_AF << ((uint32_t)(i<<2)));
}
temp = temp>>1;
}
}
- if(GPIO_Pin&0XFF00) //说明是GPIOE的8~15位
+ if(GPIO_Pin&0XFF00) //璇存槑鏄疓PIOE鐨8~15浣
{
temp = GPIO_Pin>>8;
for(i=0;i<8;i++)
{
if(temp&0x01)
{
- GPIOx->AFRH &= ~((uint32_t)0xF << ((uint32_t)(i<<2))); //AF配置占半字节,要x4,即<<2
+ GPIOx->AFRH &= ~((uint32_t)0xF << ((uint32_t)(i<<2))); //AF閰嶇疆鍗犲崐瀛楄妭锛岃x4,鍗<<2
GPIOx->AFRH |= ((uint32_t)GPIO_AF << ((uint32_t)(i<<2)));
}
temp = temp>>1;
}
}
- if(GPIO_Pin&0XFF) //说明是GPIOE的0~7位
+ if(GPIO_Pin&0XFF) //璇存槑鏄疓PIOE鐨0~7浣
{
for(i=0;i<8;i++)
{
if(temp&0x01)
{
- GPIOx->AFRL &= ~((uint32_t)0xF << ((uint32_t)(i<<2))); //AF配置占半字节,要x4,即<<2
+ GPIOx->AFRL &= ~((uint32_t)0xF << ((uint32_t)(i<<2))); //AF閰嶇疆鍗犲崐瀛楄妭锛岃x4,鍗<<2
GPIOx->AFRL |= ((uint32_t)GPIO_AF << ((uint32_t)(i<<2)));
}
temp = temp>>1;
diff --git a/bsp/tkm32F499/Libraries/Hal_lib/src/HAL_i2c.c b/bsp/tkm32F499/Libraries/Hal_lib/src/HAL_i2c.c
index 73cd8d2205..13dd8495b3 100644
--- a/bsp/tkm32F499/Libraries/Hal_lib/src/HAL_i2c.c
+++ b/bsp/tkm32F499/Libraries/Hal_lib/src/HAL_i2c.c
@@ -16,7 +16,7 @@
* CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*
* © COPYRIGHT 2016 HOLOCENE
-*/
+*/
/* Includes ------------------------------------------------------------------*/
#include "HAL_i2c.h"
@@ -27,10 +27,10 @@
* @{
*/
-/** @defgroup I2C
+/** @defgroup I2C
* @brief I2C driver modules
* @{
-*/
+*/
/** @defgroup I2C_Private_TypesDefinitions
* @{
@@ -44,7 +44,7 @@
* @{
*/
-/*I2c Enable disable*/
+/*I2c Enable disable*/
#define IC_ENABLE_Reset ((uint16_t)0xFFFE)
#define IC_ENABLE_Set ((uint16_t)0x0001)
#define IC_CON_RESET ((uint16_t)0xFE8A)
@@ -68,7 +68,7 @@
#define IC_TAR_ENDUAL_Set ((uint16_t)0x1000)
#define IC_TAR_ENDUAL_Reset ((uint16_t)0xEFFF)
-/* I2C SPECIAL、GC_OR_START bits mask */
+/* I2C SPECIAL銆丟C_OR_START bits mask */
#define IC_TAR_GC_Set ((uint16_t)0x0800)
#define IC_TAR_GC_Reset ((uint16_t)0xF7FF)
@@ -78,10 +78,10 @@
//static
uint8_t I2C_CMD_DIR = 0;
-/*新增加的用户变量,外部调用时需要更新该变量值*/
-uint16_t I2C_DMA_DIR = 0;
+/*鏂板鍔犵殑鐢ㄦ埛鍙橀噺锛屽閮ㄨ皟鐢ㄦ椂闇瑕佹洿鏂拌鍙橀噺鍊*/
+uint16_t I2C_DMA_DIR = 0;
-/**
+/**
* @}
*/
@@ -131,14 +131,14 @@ void I2C_DeInit(I2C_TypeDef* I2Cx)
/* Release I2C1 from reset state */
RCC_APB1PeriphResetCmd(RCC_APB1Periph_I2C1, DISABLE);
break;
-
+
default:
break;
}
}
/**
-* @brief Initializes the I2Cx peripheral according to the specified
+* @brief Initializes the I2Cx peripheral according to the specified
* parameters in the I2C_InitStruct.
* @param I2Cx: where x can be 1 or 2 to select the I2C peripheral.
* @param I2C_InitStruct: pointer to a I2C_InitTypeDef structure that
@@ -148,7 +148,7 @@ void I2C_DeInit(I2C_TypeDef* I2Cx)
*/
void I2C_Init(I2C_TypeDef* I2Cx, I2C_InitTypeDef* I2C_InitStruct)
{
-
+
uint16_t tmpreg = 0;
uint32_t pclk1 = 8000000;
uint32_t minSclLowTime = 0;
@@ -162,25 +162,25 @@ void I2C_Init(I2C_TypeDef* I2Cx, I2C_InitTypeDef* I2C_InitStruct)
/*---------------------------- I2Cx IC_ENABLE Configuration ------------------------*/
/* Disable the selected I2C peripheral */
I2Cx->IC_ENABLE &= IC_ENABLE_Reset;
-
+
/* Get pclk1 frequency value */
RCC_GetClocksFreq(&rcc_clocks);
pclk1 = rcc_clocks.PCLK1_Frequency;
/* Set pclk1 period value */
pclk1Period = 1000000000/pclk1;
-
+
i2cPeriod = 1000000000/I2C_InitStruct->I2C_ClockSpeed; //ns unit
tmpreg = 0;
-
+
/*Get the I2Cx IC_CON value */
tmpreg = I2Cx->IC_CON;
/*Clear TX_EMPTY_CTRL,IC_SLAVE_DISABLE,IC_RESTART_EN,IC_10BITADDR_SLAVE,SPEED,MASTER_MODE bits*/
tmpreg &= IC_CON_RESET;
-
+
/* Configure speed in standard mode */
if (I2C_InitStruct->I2C_ClockSpeed <= 100000)
- {
+ {
minSclLowTime = i2cPeriod/pclk1Period;
I2Cx->IC_SS_SCL_LCNT = minSclLowTime/2;
I2Cx->IC_SS_SCL_HCNT = minSclLowTime - I2Cx->IC_SS_SCL_LCNT;
@@ -193,13 +193,13 @@ void I2C_Init(I2C_TypeDef* I2Cx, I2C_InitTypeDef* I2C_InitStruct)
I2Cx->IC_FS_SCL_HCNT = minSclLowTime - I2Cx->IC_FS_SCL_LCNT;
I2C_InitStruct->I2C_Speed = I2C_Speed_FAST;
}
-
-
+
+
/*Set TX_EMPTY_CTRL,IC_SLAVE_DISABLE,IC_RESTART_EN,IC_10BITADDR_SLAVE,SPEED,MASTER_MODE bits*/
tmpreg = TX_EMPTY_CTRL | IC_SLAVE_DISABLE | IC_RESTART_EN |IC_7BITADDR_MASTER | I2C_InitStruct->I2C_Speed | I2C_InitStruct->I2C_Mode;
/* Write to I2Cx IC_CON */
I2Cx->IC_CON = tmpreg;
-
+
/*---------------------------- I2Cx IC_INTR_MASK Configuration ------------------------*/
/* Get the I2Cx IC_INTR_MASK value */
tmpreg = I2Cx->IC_INTR_MASK;
@@ -207,12 +207,12 @@ void I2C_Init(I2C_TypeDef* I2Cx, I2C_InitTypeDef* I2C_InitStruct)
tmpreg &= INTR_MASK;
/* Write to IC_INTR_MASK */
I2Cx->IC_INTR_MASK = tmpreg;
-
+
/* Write to IC_RX_TL */
I2Cx->IC_RX_TL = 0x0; //rxfifo depth is 1
/* Write to IC_TX_TL */
I2Cx->IC_TX_TL = 0x1; //tcfifo depth is 1
-
+
}
/**
@@ -418,20 +418,20 @@ void I2C_GeneralCallCmd(I2C_TypeDef* I2Cx, FunctionalState NewState)
* @brief Enables or disables the specified I2C interrupts.
* @param I2Cx: where x can be 1 or 2 to select the I2C peripheral.
* @param I2C_IT: specifies the I2C interrupts sources to be enabled
-* or disabled.
+* or disabled.
* This parameter can be any combination of the following values:
-* @arg I2C_IT_RX_UNDER: Rx Buffer is empty interrupt mask
-* @arg I2C_IT_RX_OVER : RX Buffer Overrun interrupt mask
-* @arg I2C_IT_RX_FULL : Rx buffer full interrupt mask
-* @arg I2C_IT_TX_OVER : TX Buffer Overrun interrupt mask
-* @arg I2C_IT_TX_EMPTY : TX_FIFO empty interrupt mask
-* @arg I2C_IT_RD_REQ : I2C work as slave or master interrupt mask
-* @arg I2C_IT_TX_ABRT : TX error interrupt mask(Master mode)
-* @arg I2C_IT_RX_DONE : Master not ack interrupt mask(slave mode)
-* @arg I2C_IT_ACTIVITY : I2C activity interrupt mask
-* @arg I2C_IT_STOP_DET : stop condition interrupt mask
-* @arg I2C_IT_START_DET : start condition interrupt mask
-* @arg I2C_IT_GEN_CALL : a general call address and ack interrupt mask
+* @arg I2C_IT_RX_UNDER: Rx Buffer is empty interrupt mask
+* @arg I2C_IT_RX_OVER : RX Buffer Overrun interrupt mask
+* @arg I2C_IT_RX_FULL : Rx buffer full interrupt mask
+* @arg I2C_IT_TX_OVER : TX Buffer Overrun interrupt mask
+* @arg I2C_IT_TX_EMPTY : TX_FIFO empty interrupt mask
+* @arg I2C_IT_RD_REQ : I2C work as slave or master interrupt mask
+* @arg I2C_IT_TX_ABRT : TX error interrupt mask(Master mode)
+* @arg I2C_IT_RX_DONE : Master not ack interrupt mask(slave mode)
+* @arg I2C_IT_ACTIVITY : I2C activity interrupt mask
+* @arg I2C_IT_STOP_DET : stop condition interrupt mask
+* @arg I2C_IT_START_DET : start condition interrupt mask
+* @arg I2C_IT_GEN_CALL : a general call address and ack interrupt mask
* @param NewState: new state of the specified I2C interrupts.
* This parameter can be: ENABLE or DISABLE.
* @retval : None
@@ -442,12 +442,12 @@ void I2C_ITConfig(I2C_TypeDef* I2Cx, uint16_t I2C_IT, FunctionalState NewState)
assert_param(IS_I2C_ALL_PERIPH(I2Cx));
assert_param(IS_FUNCTIONAL_STATE(NewState));
assert_param(IS_I2C_CONFIG_IT(I2C_IT));
-
+
if(I2C_IT == I2C_IT_RX_FULL)
{
I2C1->IC_DATA_CMD = CMD_READ;
}
-
+
if (NewState != DISABLE)
{
/* Enable the selected I2C interrupts */
@@ -484,7 +484,7 @@ void I2C_ReadCmd(I2C_TypeDef* I2Cx)
{
/* Check the parameters */
assert_param(IS_I2C_ALL_PERIPH(I2Cx));
-
+
I2Cx->IC_DATA_CMD = CMD_READ;
}
@@ -507,7 +507,7 @@ uint8_t I2C_ReceiveData(I2C_TypeDef* I2Cx)
* @param I2Cx: where x can be 1 or 2 to select the I2C peripheral.
* @param Address: specifies the slave address which will be transmitted
* @param I2C_Direction: specifies whether the I2C device will be a
-* Transmitter or a Receiver.
+* 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
@@ -547,7 +547,7 @@ uint32_t I2C_GetLastEvent(I2C_TypeDef* I2Cx)
assert_param(IS_I2C_ALL_PERIPH(I2Cx));
/* Read the I2Cx status register */
flag1 = I2Cx->IC_RAW_INTR_STAT;
-
+
/* Get the last event value from I2C status register */
lastevent = (flag1 ) & FLAG_Mask;
/* Return status */
@@ -560,20 +560,20 @@ uint32_t I2C_GetLastEvent(I2C_TypeDef* I2Cx)
* @brief Checks whether the last I2Cx Event is equal to the one passed
* as parameter.
* @param I2Cx: where x can be 1 or 2 to select the I2C peripheral.
-* @param I2C_EVENT: specifies the event to be checked.
+* @param I2C_EVENT: specifies the event to be checked.
* This parameter can be one of the following values:
-* @arg I2C_EVENT_RX_UNDER: Rx Buffer is empty event
-* @arg I2C_EVENT_RX_OVER : RX Buffer Overrun event
-* @arg I2C_EVENTT_RX_FULL : Rx buffer full event
-* @arg I2C_EVENT_TX_OVER : TX Buffer Overrun event
-* @arg I2C_EVENT_TX_EMPTY : TX_FIFO empty event
-* @arg I2C_EVENT_RD_REQ : I2C work as slave or master event
-* @arg I2C_EVENT_TX_ABRT : TX error event(Master mode)
-* @arg I2C_EVENT_RX_DONE : Master not ack event(slave mode)
-* @arg I2C_EVENT_ACTIVITY : I2C activity event
-* @arg I2C_EVENT_STOP_DET : stop condition event
-* @arg I2C_EVENT_START_DET : start condition event
-* @arg I2C_EVENT_GEN_CALL : a general call address and ack event
+* @arg I2C_EVENT_RX_UNDER: Rx Buffer is empty event
+* @arg I2C_EVENT_RX_OVER : RX Buffer Overrun event
+* @arg I2C_EVENTT_RX_FULL : Rx buffer full event
+* @arg I2C_EVENT_TX_OVER : TX Buffer Overrun event
+* @arg I2C_EVENT_TX_EMPTY : TX_FIFO empty event
+* @arg I2C_EVENT_RD_REQ : I2C work as slave or master event
+* @arg I2C_EVENT_TX_ABRT : TX error event(Master mode)
+* @arg I2C_EVENT_RX_DONE : Master not ack event(slave mode)
+* @arg I2C_EVENT_ACTIVITY : I2C activity event
+* @arg I2C_EVENT_STOP_DET : stop condition event
+* @arg I2C_EVENT_START_DET : start condition event
+* @arg I2C_EVENT_GEN_CALL : a general call address and ack event
* - SUCCESS: Last event is equal to the I2C_EVENT
* - ERROR: Last event is different from the I2C_EVENT
*/
@@ -585,7 +585,7 @@ ErrorStatus I2C_CheckEvent(I2C_TypeDef* I2Cx, uint32_t I2C_EVENT)
/* Check the parameters */
assert_param(IS_I2C_ALL_PERIPH(I2Cx));
assert_param(IS_I2C_EVENT(I2C_EVENT));
-
+
if((I2C_EVENT == I2C_EVENT_RX_FULL)&&(I2C_CMD_DIR==0))
{
I2C1->IC_DATA_CMD = CMD_READ;
@@ -596,7 +596,7 @@ ErrorStatus I2C_CheckEvent(I2C_TypeDef* I2Cx, uint32_t I2C_EVENT)
//flag1 = I2Cx->IC_INTR_STAT;
/* Get the last event value from I2C status register */
lastevent = (flag1 ) & I2C_EVENT;
-
+
/* Check whether the last event is equal to I2C_EVENT */
if (lastevent == I2C_EVENT )
//if((I2Cx->IC_RAW_INTR_STAT & I2C_EVENT) != (uint32_t)RESET)
@@ -611,26 +611,26 @@ ErrorStatus I2C_CheckEvent(I2C_TypeDef* I2Cx, uint32_t I2C_EVENT)
}
/* Return status */
return status;
-
+
}
/**
* @brief Checks whether the specified I2C flag is set or not.
* @param I2Cx: where x can be 1 or 2 to select the I2C peripheral.
-* @param I2C_FLAG: specifies the flag to check.
+* @param I2C_FLAG: specifies the flag to check.
* This parameter can be one of the following values:
-* @arg I2C_FLAG_RX_UNDER: Rx Buffer is empty flag
-* @arg I2C_FLAG_RX_OVER : RX Buffer Overrun flag
-* @arg I2C_FLAG_RX_FULL : Rx buffer full flag
-* @arg I2C_FLAG_TX_OVER : TX Buffer Overrun flag
-* @arg I2C_FLAG_TX_EMPTY: TX_FIFO empty flag
-* @arg I2C_FLAG_RD_REQ : I2C work as slave or master flag
-* @arg I2C_FLAG_TX_ABRT : TX error flag(Master mode)
-* @arg I2C_FLAG_RX_DONE : Master not ack flag(slave mode)
-* @arg I2C_FLAG_ACTIVITY: I2C activity flag
-* @arg I2C_FLAG_STOP_DET: stop condition flag
-* @arg I2C_FLAG_START_DET: start condition flag
-* @arg I2C_FLAG_GEN_CALL : a general call address and ack flag
+* @arg I2C_FLAG_RX_UNDER: Rx Buffer is empty flag
+* @arg I2C_FLAG_RX_OVER : RX Buffer Overrun flag
+* @arg I2C_FLAG_RX_FULL : Rx buffer full flag
+* @arg I2C_FLAG_TX_OVER : TX Buffer Overrun flag
+* @arg I2C_FLAG_TX_EMPTY: TX_FIFO empty flag
+* @arg I2C_FLAG_RD_REQ : I2C work as slave or master flag
+* @arg I2C_FLAG_TX_ABRT : TX error flag(Master mode)
+* @arg I2C_FLAG_RX_DONE : Master not ack flag(slave mode)
+* @arg I2C_FLAG_ACTIVITY: I2C activity flag
+* @arg I2C_FLAG_STOP_DET: stop condition flag
+* @arg I2C_FLAG_START_DET: start condition flag
+* @arg I2C_FLAG_GEN_CALL : a general call address and ack flag
* @retval : The new state of I2C_FLAG (SET or RESET).
*/
FlagStatus I2C_GetFlagStatus(I2C_TypeDef* I2Cx, uint32_t I2C_FLAG)
@@ -646,7 +646,7 @@ FlagStatus I2C_GetFlagStatus(I2C_TypeDef* I2Cx, uint32_t I2C_FLAG)
I2Cx->IC_DATA_CMD = CMD_READ;
I2C_CMD_DIR = 1;
}
-
+
/* Check the status of the specified I2C flag */
if((I2Cx->IC_RAW_INTR_STAT & I2C_FLAG) != (uint32_t)RESET)
{
@@ -658,7 +658,7 @@ FlagStatus I2C_GetFlagStatus(I2C_TypeDef* I2Cx, uint32_t I2C_FLAG)
/* I2C_FLAG is reset */
bitstatus = RESET;
}
-
+
/* Return the I2C_FLAG status */
return bitstatus;
}
@@ -666,20 +666,20 @@ FlagStatus I2C_GetFlagStatus(I2C_TypeDef* I2Cx, uint32_t I2C_FLAG)
/**
* @brief Clears the I2Cx's pending flags.
* @param I2Cx: where x can be 1 or 2 to select the I2C peripheral.
-* @param I2C_FLAG: specifies the flag to clear.
+* @param I2C_FLAG: specifies the flag to clear.
* This parameter can be any combination of the following values:
-* @arg I2C_FLAG_RX_UNDER: Rx Buffer is empty flag
-* @arg I2C_FLAG_RX_OVER : RX Buffer Overrun flag
-* @arg I2C_FLAG_RX_FULL : Rx buffer full flag
-* @arg I2C_FLAG_TX_OVER : TX Buffer Overrun flag
-* @arg I2C_FLAG_TX_EMPTY: TX_FIFO empty flag
-* @arg I2C_FLAG_RD_REQ : I2C work as slave or master flag
-* @arg I2C_FLAG_TX_ABRT : TX error flag(Master mode)
-* @arg I2C_FLAG_RX_DONE : Master not ack flag(slave mode)
-* @arg I2C_FLAG_ACTIVITY: I2C activity flag
-* @arg I2C_FLAG_STOP_DET: stop condition flag
-* @arg I2C_FLAG_START_DET: start condition flag
-* @arg I2C_FLAG_GEN_CALL : a general call address and ack flag
+* @arg I2C_FLAG_RX_UNDER: Rx Buffer is empty flag
+* @arg I2C_FLAG_RX_OVER : RX Buffer Overrun flag
+* @arg I2C_FLAG_RX_FULL : Rx buffer full flag
+* @arg I2C_FLAG_TX_OVER : TX Buffer Overrun flag
+* @arg I2C_FLAG_TX_EMPTY: TX_FIFO empty flag
+* @arg I2C_FLAG_RD_REQ : I2C work as slave or master flag
+* @arg I2C_FLAG_TX_ABRT : TX error flag(Master mode)
+* @arg I2C_FLAG_RX_DONE : Master not ack flag(slave mode)
+* @arg I2C_FLAG_ACTIVITY: I2C activity flag
+* @arg I2C_FLAG_STOP_DET: stop condition flag
+* @arg I2C_FLAG_START_DET: start condition flag
+* @arg I2C_FLAG_GEN_CALL : a general call address and ack flag
* @retval : None
*/
void I2C_ClearFlag(I2C_TypeDef* I2Cx, uint32_t I2C_FLAG)
@@ -690,7 +690,7 @@ void I2C_ClearFlag(I2C_TypeDef* I2Cx, uint32_t I2C_FLAG)
assert_param(IS_I2C_CLEAR_FLAG(I2C_FLAG));
/* Get the I2Cx peripheral base address */
i2cxbase = (*(uint32_t*)&(I2Cx));
-
+
if(I2C_FLAG==I2C_FLAG_RX_UNDER)
{
/* Get the I2Cx SR1 register address */
@@ -766,20 +766,20 @@ void I2C_ClearFlag(I2C_TypeDef* I2Cx, uint32_t I2C_FLAG)
/**
* @brief Checks whether the specified I2C interrupt has occurred or not.
* @param I2Cx: where x can be 1 or 2 to select the I2C peripheral.
-* @param I2C_IT: specifies the interrupt source to check.
+* @param I2C_IT: specifies the interrupt source to check.
* This parameter can be one of the following values:
-* @arg I2C_IT_RX_UNDER: Rx Buffer is empty interrupt
-* @arg I2C_IT_RX_OVER : RX Buffer Overrun interrupt
-* @arg I2C_IT_RX_FULL : Rx buffer full interrupt
-* @arg I2C_IT_TX_OVER : TX Buffer Overrun interrupt
-* @arg I2C_IT_TX_EMPTY : TX_FIFO empty interrupt
-* @arg I2C_IT_RD_REQ : I2C work as slave or master interrupt
-* @arg I2C_IT_TX_ABRT : TX error interrupt (Master mode)
-* @arg I2C_IT_RX_DONE : Master not ack interrupt (slave mode)
-* @arg I2C_IT_ACTIVITY : I2C activity interrupt
-* @arg I2C_IT_STOP_DET : stop condition interrupt
-* @arg I2C_IT_START_DET : start condition interrupt
-* @arg I2C_IT_GEN_CALL : a general call address and ack interrupt
+* @arg I2C_IT_RX_UNDER: Rx Buffer is empty interrupt
+* @arg I2C_IT_RX_OVER : RX Buffer Overrun interrupt
+* @arg I2C_IT_RX_FULL : Rx buffer full interrupt
+* @arg I2C_IT_TX_OVER : TX Buffer Overrun interrupt
+* @arg I2C_IT_TX_EMPTY : TX_FIFO empty interrupt
+* @arg I2C_IT_RD_REQ : I2C work as slave or master interrupt
+* @arg I2C_IT_TX_ABRT : TX error interrupt (Master mode)
+* @arg I2C_IT_RX_DONE : Master not ack interrupt (slave mode)
+* @arg I2C_IT_ACTIVITY : I2C activity interrupt
+* @arg I2C_IT_STOP_DET : stop condition interrupt
+* @arg I2C_IT_START_DET : start condition interrupt
+* @arg I2C_IT_GEN_CALL : a general call address and ack interrupt
* @retval : The new state of I2C_IT (SET or RESET).
*/
ITStatus I2C_GetITStatus(I2C_TypeDef* I2Cx, uint32_t I2C_IT)
@@ -788,7 +788,7 @@ ITStatus I2C_GetITStatus(I2C_TypeDef* I2Cx, uint32_t I2C_IT)
/* Check the parameters */
assert_param(IS_I2C_ALL_PERIPH(I2Cx));
assert_param(IS_I2C_GET_IT(I2C_IT));
-
+
/* Check the status of the specified I2C flag */
if((I2Cx->IC_RAW_INTR_STAT & I2C_IT) != (uint32_t)RESET)
{
@@ -800,7 +800,7 @@ ITStatus I2C_GetITStatus(I2C_TypeDef* I2Cx, uint32_t I2C_IT)
/* I2C_IT is reset */
bitstatus = RESET;
}
-
+
/* Return the I2C_IT status */
return bitstatus;
}
@@ -808,20 +808,20 @@ ITStatus I2C_GetITStatus(I2C_TypeDef* I2Cx, uint32_t I2C_IT)
/**
* @brief Clears the I2Cx interrupt pending bits.
* @param I2Cx: where x can be 1 or 2 to select the I2C peripheral.
-* @param I2C_IT: specifies the interrupt pending bit to clear.
+* @param I2C_IT: specifies the interrupt pending bit to clear.
* This parameter can be any combination of the following values:
-* @arg I2C_IT_RX_UNDER: Rx Buffer is empty interrupt
-* @arg I2C_IT_RX_OVER : RX Buffer Overrun interrupt
-* @arg I2C_IT_RX_FULL : Rx buffer full interrupt
-* @arg I2C_IT_TX_OVER : TX Buffer Overrun interrupt
-* @arg I2C_IT_TX_EMPTY : TX_FIFO empty interrupt
-* @arg I2C_IT_RD_REQ : I2C work as slave or master interrupt
-* @arg I2C_IT_TX_ABRT : TX error interrupt (Master mode)
-* @arg I2C_IT_RX_DONE : Master not ack interrupt (slave mode)
-* @arg I2C_IT_ACTIVITY : I2C activity interrupt
-* @arg I2C_IT_STOP_DET : stop condition interrupt
-* @arg I2C_IT_START_DET : start condition interrupt
-* @arg I2C_IT_GEN_CALL : a general call address and ack interrupt
+* @arg I2C_IT_RX_UNDER: Rx Buffer is empty interrupt
+* @arg I2C_IT_RX_OVER : RX Buffer Overrun interrupt
+* @arg I2C_IT_RX_FULL : Rx buffer full interrupt
+* @arg I2C_IT_TX_OVER : TX Buffer Overrun interrupt
+* @arg I2C_IT_TX_EMPTY : TX_FIFO empty interrupt
+* @arg I2C_IT_RD_REQ : I2C work as slave or master interrupt
+* @arg I2C_IT_TX_ABRT : TX error interrupt (Master mode)
+* @arg I2C_IT_RX_DONE : Master not ack interrupt (slave mode)
+* @arg I2C_IT_ACTIVITY : I2C activity interrupt
+* @arg I2C_IT_STOP_DET : stop condition interrupt
+* @arg I2C_IT_START_DET : start condition interrupt
+* @arg I2C_IT_GEN_CALL : a general call address and ack interrupt
* @retval : None
*/
void I2C_ClearITPendingBit(I2C_TypeDef* I2Cx, uint32_t I2C_IT)
@@ -829,20 +829,20 @@ void I2C_ClearITPendingBit(I2C_TypeDef* I2Cx, uint32_t I2C_IT)
/* Check the parameters */
assert_param(IS_I2C_ALL_PERIPH(I2Cx));
assert_param(IS_I2C_CLEAR_IT(I2C_IT));
-
+
/* Clear the selected I2C flag */
I2Cx->IC_INTR_MASK &= (uint16_t)~I2C_IT;
}
/**
* @}
-*/
+*/
/**
* @}
-*/
+*/
/**
* @}
-*/
+*/
/*-------------------------(C) COPYRIGHT 2016 HOLOCENE ----------------------*/
diff --git a/bsp/tkm32F499/Libraries/Hal_lib/src/HAL_rcc.c b/bsp/tkm32F499/Libraries/Hal_lib/src/HAL_rcc.c
index 1e9b7f8947..ae53d5156f 100644
--- a/bsp/tkm32F499/Libraries/Hal_lib/src/HAL_rcc.c
+++ b/bsp/tkm32F499/Libraries/Hal_lib/src/HAL_rcc.c
@@ -16,7 +16,7 @@
* CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*
* © COPYRIGHT 2016 HOLOCENE
-*/
+*/
/* Includes ------------------------------------------------------------------*/
#include "HAL_rcc.h"
@@ -27,10 +27,10 @@ u32 TK499_PLL_FACTOR = 0x00004;
* @{
*/
-/** @defgroup RCC
+/** @defgroup RCC
* @brief RCC driver modules
* @{
-*/
+*/
/** @defgroup RCC_Private_TypesDefinitions
* @{
@@ -140,19 +140,19 @@ u32 TK499_PLL_FACTOR = 0x00004;
/**
* @}
-*/
+*/
/** @defgroup RCC_Private_Macros
* @{
-*/
+*/
/**
* @}
-*/
+*/
/** @defgroup RCC_Private_Variables
* @{
-*/
+*/
static __I uint8_t APBAHBPrescTable[16] = {0, 0, 0, 0, 1, 2, 3, 4, 1, 2, 3, 4, 6, 7, 8, 9};
static __I uint8_t ADCPrescTable[4] = {2, 4, 6, 8};
@@ -173,12 +173,12 @@ static __I uint8_t ADCPrescTable[4] = {2, 4, 6, 8};
* @{
*/
void SystemClk_HSEInit(uint32_t PLL_DN)
-{
+{
RCC_DeInit();
//HSE on
- //CR寄存器BIT16位(HSEON位)置1,作用是连接外部时钟HSE作为系统时钟
+ //CR瀵勫瓨鍣˙IT16浣嶏紙HSEON浣嶏級缃1锛屼綔鐢ㄦ槸杩炴帴澶栭儴鏃堕挓HSE浣滀负绯荤粺鏃堕挓
RCC_HSEConfig(RCC_HSE_ON);
-
+
while(1)
{
if(RCC_WaitForHSEStartUp()!=0)
@@ -189,7 +189,7 @@ void SystemClk_HSEInit(uint32_t PLL_DN)
RCC_PLLCmd(DISABLE);
RCC_PLLConfig(RCC_PLLSource_HSE_Div1,PLL_DN);
RCC_PLLCmd(ENABLE);
- RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);//选择外部时钟作为系统时钟
+ RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);//閫夋嫨澶栭儴鏃堕挓浣滀负绯荤粺鏃堕挓
}
/**
* @brief Resets the RCC clock configuration to the default reset state.
@@ -202,7 +202,7 @@ void RCC_DeInit(void)
RCC->CR |= (uint32_t)0x00000001;
/* Reset SW[1:0], HPRE[3:0], PPRE1[2:0], PPRE2[2:0], ADCPRE[1:0] and MCO[2:0] bits */
RCC->CFGR &= (uint32_t)0xF8FF0000;
-
+
/* Reset HSEON, CSSON and PLLON bits */
RCC->CR &= (uint32_t)0xFEF6FFFF;
/* Reset HSEBYP bit */
@@ -215,7 +215,7 @@ void RCC_DeInit(void)
/**
* @brief Configures the External High Speed oscillator (HSE).
-* HSE can not be stopped if it is used directly or through the
+* HSE can not be stopped if it is used directly or through the
* PLL as system clock.
* @param RCC_HSE: specifies the new state of the HSE.
* This parameter can be one of the following values:
@@ -241,12 +241,12 @@ void RCC_HSEConfig(uint32_t RCC_HSE)
/* Set HSEON bit */
RCC->CR |= CR_HSEON_Set;
break;
-
+
case RCC_HSE_Bypass:
/* Set HSEBYP and HSEON bits */
RCC->CR |= CR_HSEBYP_Set | CR_HSEON_Set;
break;
-
+
default:
break;
}
@@ -264,12 +264,12 @@ ErrorStatus RCC_WaitForHSEStartUp(void)
__IO uint32_t StartUpCounter = 0;
ErrorStatus status = ERROR;
FlagStatus HSEStatus = RESET;
-
+
/* Wait till HSE is ready and if Time out is reached exit */
do
{
HSEStatus = RCC_GetFlagStatus(RCC_FLAG_HSERDY);
- StartUpCounter++;
+ StartUpCounter++;
} while((HSEStatus == RESET) && (StartUpCounter != HSEStartUp_TimeOut));
if (RCC_GetFlagStatus(RCC_FLAG_HSERDY) != RESET)
{
@@ -278,7 +278,7 @@ ErrorStatus RCC_WaitForHSEStartUp(void)
else
{
status = ERROR;
- }
+ }
return (status);
}
@@ -305,7 +305,7 @@ void RCC_AdjustHSICalibrationValue(uint8_t HSICalibrationValue)
/**
* @brief Enables or disables the Internal High Speed oscillator (HSI).
-* HSI can not be stopped if it is used directly or through the
+* HSI can not be stopped if it is used directly or through the
* PLL as system clock.
* @param NewState: new state of the HSI.
* This parameter can be: ENABLE or DISABLE.
@@ -315,7 +315,7 @@ void RCC_HSICmd(FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_FUNCTIONAL_STATE(NewState));
-
+
if(NewState==ENABLE)
{
RCC->CR |= 0x01;
@@ -345,11 +345,11 @@ void RCC_HSICmd(FunctionalState NewState)
void RCC_PLLDMDNConfig(uint32_t RCC_PLLSource, uint32_t RCC_PLLDN,uint32_t RCC_PLLDP, uint32_t RCC_PLLDM)
{
uint32_t tmpreg0 = 0;
-
+
/* Check the parameters */
assert_param(IS_RCC_PLL_SOURCE(RCC_PLLSource));
assert_param(IS_RCC_PLL_MUL(RCC_PLLMul));
-
+
if(RCC_PLLSource == 0)
{
tmpreg0 &= ~(1<<22);
@@ -359,13 +359,13 @@ void RCC_PLLDMDNConfig(uint32_t RCC_PLLSource, uint32_t RCC_PLLDN,uint32_t RCC_P
TK499_PLL_FACTOR |= 0x10000;
tmpreg0 |= (1<<22);
}
-
+
RCC_PLLDN &= 0x7f;
RCC_PLLDP &= 0x3;
RCC_PLLDM &= 0xf;
/* Set the PLL configuration bits */
tmpreg0 |= (u32)((u32)(RCC_PLLDN<<6))|((u32)(RCC_PLLDP<<4))|((u32)RCC_PLLDM);
-
+
RCC->PLLCFGR = tmpreg0;
// RCC->PLLCFGR = 0x4004d1;
}
@@ -399,7 +399,7 @@ void RCC_PLLConfig(uint32_t RCC_PLLSource, uint32_t RCC_PLLMul)
tmpreg |= RCC_PLLSource;
/* Store the new value */
RCC->CFGR = tmpreg;
-
+
if(RCC_PLLMul==RCC_PLLMul_2)
{
TK499_PLL_FACTOR = 2;
@@ -504,7 +504,7 @@ void RCC_PLLConfig(uint32_t RCC_PLLSource, uint32_t RCC_PLLMul)
{
TK499_PLL_FACTOR = 22;
RCC_PLLDMDNConfig(RCC_PLLSource, 0x00000015, 0x00000000,0x00000000);//Frclk*32/2
- }
+ }
if(RCC_PLLMul==RCC_PLLMul_23)
{
TK499_PLL_FACTOR = 23;
@@ -549,7 +549,7 @@ void RCC_PLLCmd(FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_FUNCTIONAL_STATE(NewState));
-
+
if (NewState != DISABLE)
{
RCC->CR |= 0x01000000;
@@ -618,7 +618,7 @@ uint8_t RCC_GetSYSCLKSource(void)
/**
* @brief Configures the AHB clock (HCLK).
-* @param RCC_SYSCLK: defines the AHB clock divider. This clock is derived from
+* @param RCC_SYSCLK: defines the AHB clock divider. This clock is derived from
* the system clock (SYSCLK).
* This parameter can be one of the following values:
* @arg RCC_SYSCLK_Div1: AHB clock = SYSCLK
@@ -648,7 +648,7 @@ void RCC_HCLKConfig(uint32_t RCC_SYSCLK)
/**
* @brief Configures the Low Speed APB clock (PCLK1).
-* @param RCC_HCLK: defines the APB1 clock divider. This clock is derived from
+* @param RCC_HCLK: defines the APB1 clock divider. This clock is derived from
* the AHB clock (HCLK).
* This parameter can be one of the following values:
* @arg RCC_HCLK_Div1: APB1 clock = HCLK
@@ -674,7 +674,7 @@ void RCC_PCLK1Config(uint32_t RCC_HCLK)
/**
* @brief Configures the High Speed APB clock (PCLK2).
-* @param RCC_HCLK: defines the APB2 clock divider. This clock is derived from
+* @param RCC_HCLK: defines the APB2 clock divider. This clock is derived from
* the AHB clock (HCLK).
* This parameter can be one of the following values:
* @arg RCC_HCLK_Div1: APB2 clock = HCLK
@@ -719,23 +719,23 @@ void RCC_ITConfig(uint8_t RCC_IT, FunctionalState NewState)
if (NewState != DISABLE)
{
/* Perform Byte access to RCC_CIR[12:8] bits to enable the selected interrupts */
-
+
RCC->CIR |= ((uint32_t)RCC_IT)<<8;
}
else
{
/* Perform Byte access to RCC_CIR[12:8] bits to disable the selected interrupts */
-
+
RCC->CIR &= ~((uint32_t)RCC_IT<<8);
}
}
/**
* @brief Configures the USB clock (USBCLK).
-* @param RCC_USBCLKSource: specifies the USB clock source. This clock is
+* @param RCC_USBCLKSource: specifies the USB clock source. This clock is
* derived from the PLL output.
* This parameter can be one of the following values:
-* @arg RCC_USBCLKSource_PLLCLK_1Div5: PLL clock divided by 1,5 selected as USB
+* @arg RCC_USBCLKSource_PLLCLK_1Div5: PLL clock divided by 1,5 selected as USB
* clock source
* @arg RCC_USBCLKSource_PLLCLK_Div1: PLL clock selected as USB clock source
* @retval : None
@@ -749,7 +749,7 @@ void RCC_USBCLKConfig(uint32_t RCC_USBCLKSource)
/**
* @brief Configures the ADC clock (ADCCLK).
-* @param RCC_PCLK2: defines the ADC clock divider. This clock is derived from
+* @param RCC_PCLK2: defines the ADC clock divider. This clock is derived from
* the APB2 clock (PCLK2).
* This parameter can be one of the following values:
* @arg RCC_PCLK2_Div2: ADC clock = PCLK2/2
@@ -798,14 +798,14 @@ void RCC_LSEConfig(uint8_t RCC_LSE)
/* Set LSEON bit */
RCC->BDCR |= RCC_LSE_ON;
break;
-
+
case RCC_LSE_Bypass:
/* Set LSEBYP and LSEON bits */
RCC->BDCR |= RCC_LSE_Bypass | RCC_LSE_ON;
- break;
-
+ break;
+
default:
- break;
+ break;
}
}
@@ -820,7 +820,7 @@ void RCC_LSICmd(FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_FUNCTIONAL_STATE(NewState));
-
+
if (NewState != DISABLE)
{
RCC->CSR |= 0x00000001;
@@ -833,7 +833,7 @@ void RCC_LSICmd(FunctionalState NewState)
/**
* @brief Configures the RTC clock (RTCCLK).
-* Once the RTC clock is selected it can抰 be changed unless the
+* Once the RTC clock is selected it can鎶 be changed unless the
* Backup domain is reset.
* @param RCC_RTCCLKSource: specifies the RTC clock source.
* This parameter can be one of the following values:
@@ -863,7 +863,7 @@ void RCC_RTCCLKCmd(FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_FUNCTIONAL_STATE(NewState));
-
+
if (NewState != DISABLE)
{
RCC->BDCR |= 0x00008000;
@@ -875,7 +875,7 @@ void RCC_RTCCLKCmd(FunctionalState NewState)
}
void getSystemClock(u32 *sysclk)
{
- u32 tempreg0 = RCC->CFGR;
+ u32 tempreg0 = RCC->CFGR;
u32 tempreg1;
u8 dn,dp,dm;
if((tempreg0 & 0xC) == 0x00)
@@ -1011,7 +1011,7 @@ void RCC_AHBPeriphClockCmd(uint32_t RCC_AHBPeriph, FunctionalState NewState)
* @arg RCC_APB2Periph_SYSCFG, RCC_AHBPeriph_GPIOA, RCC_AHBPeriph_GPIOB,
* RCC_AHBPeriph_GPIOC, RCC_AHBPeriph_GPIOD, RCC_APB2Periph_ADC1,
* RCC_APB2Periph_ADC2, RCC_APB2Periph_TIM1, RCC_APB2Periph_SPI1,
-* RCC_APB2Periph_TIM8, RCC_APB2Periph_UART1,
+* RCC_APB2Periph_TIM8, RCC_APB2Periph_UART1,
* RCC_APB2Periph_ALL
* @param NewState: new state of the specified peripheral clock.
* This parameter can be: ENABLE or DISABLE.
@@ -1048,7 +1048,7 @@ void RCC_BackupResetCmd(FunctionalState NewState)
* @arg RCC_APB1Periph_TIM2, RCC_APB1Periph_TIM3, RCC_APB1Periph_TIM4,
* RCC_APB1Periph_TIM5, RCC_APB1Periph_TIM6, RCC_APB1Periph_TIM7,
* RCC_APB1Periph_WWDG, RCC_APB1Periph_SPI2, RCC_APB1Periph_SPI3,
-* RCC_APB1Periph_UART2, RCC_APB1Periph_UART3, RCC_APB1Periph_UART4,
+* RCC_APB1Periph_UART2, RCC_APB1Periph_UART3, RCC_APB1Periph_UART4,
* RCC_APB1Periph_UART5, RCC_APB1Periph_I2C1, RCC_APB1Periph_I2C2,
* RCC_APB1Periph_USB, RCC_APB1Periph_CAN1, RCC_APB1Periph_BKP,
* RCC_APB1Periph_PWR, RCC_APB1Periph_DAC, RCC_APB1Periph_ALL
@@ -1106,7 +1106,7 @@ void RCC_APB2PeriphResetCmd(uint32_t RCC_APB2Periph, FunctionalState NewState)
* @arg RCC_APB1Periph_TIM2, RCC_APB1Periph_TIM3, RCC_APB1Periph_TIM4,
* RCC_APB1Periph_TIM5, RCC_APB1Periph_TIM6, RCC_APB1Periph_TIM7,
* RCC_APB1Periph_WWDG, RCC_APB1Periph_SPI2, RCC_APB1Periph_SPI3,
-* RCC_APB1Periph_UART2, RCC_APB1Periph_UART3, RCC_APB1Periph_UART4,
+* RCC_APB1Periph_UART2, RCC_APB1Periph_UART3, RCC_APB1Periph_UART4,
* RCC_APB1Periph_UART5, RCC_APB1Periph_I2C1, RCC_APB1Periph_I2C2,
* RCC_APB1Periph_USB, RCC_APB1Periph_CAN1, RCC_APB1Periph_BKP,
* RCC_APB1Periph_PWR, RCC_APB1Periph_DAC, RCC_APB1Periph_ALL
@@ -1168,7 +1168,7 @@ void RCC_MCOConfig(uint8_t RCC_MCO)
/* Check the parameters */
assert_param(IS_RCC_MCO(RCC_MCO));
/* Perform Byte access to MCO[2:0] bits to select the MCO source */
-
+
RCC->CFGR |= (RCC_MCO<<24);
}
@@ -1269,7 +1269,7 @@ ITStatus RCC_GetITStatus(uint8_t RCC_IT)
}
/**
-* @brief Clears the RCC抯 interrupt pending bits.
+* @brief Clears the RCC鎶 interrupt pending bits.
* @param RCC_IT: specifies the interrupt pending bit to clear.
* This parameter can be any combination of the following values:
* @arg RCC_IT_LSIRDY: LSI ready interrupt
@@ -1286,7 +1286,7 @@ void RCC_ClearITPendingBit(uint8_t RCC_IT)
assert_param(IS_RCC_CLEAR_IT(RCC_IT));
/* Perform Byte access to RCC_CIR[23:16] bits to clear the selected interrupt
pending bits */
-
+
RCC->CIR |= (uint32_t)RCC_IT<<16;
}
diff --git a/bsp/tkm32F499/Libraries/Hal_lib/src/HAL_uart.c b/bsp/tkm32F499/Libraries/Hal_lib/src/HAL_uart.c
index 224dd38f49..c0d63e13c8 100644
--- a/bsp/tkm32F499/Libraries/Hal_lib/src/HAL_uart.c
+++ b/bsp/tkm32F499/Libraries/Hal_lib/src/HAL_uart.c
@@ -16,7 +16,7 @@
* CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*
* © COPYRIGHT 2016 HOLOCENE
-*/
+*/
/* Includes ------------------------------------------------------------------*/
#include "HAL_uart.h"
@@ -26,7 +26,7 @@
* @{
*/
-/** @defgroup UART
+/** @defgroup UART
* @brief UART driver modules
* @{
*/
@@ -86,7 +86,7 @@
/**
* @brief Deinitializes the UARTx peripheral registers to their
* default reset values.
-* @param UARTx: Select the UART or the UART peripheral.
+* @param UARTx: Select the UART or the UART peripheral.
* This parameter can be one of the following values:
* UART1, UART2, UART3.
* @retval : None
@@ -109,7 +109,7 @@ void UART_DeInit(UART_TypeDef* UARTx)
/**
* @brief Initializes the UARTx peripheral according to the specified
* parameters in the UART_InitStruct .
-* @param UARTx: Select the UART or the UART peripheral.
+* @param UARTx: Select the UART or the UART peripheral.
* This parameter can be one of the following values:
* UART1, UART2, UART3.
* @param UART_InitStruct: pointer to a UART_InitTypeDef structure
@@ -123,7 +123,7 @@ void UART_Init(UART_TypeDef* UARTx, UART_InitTypeDef* UART_InitStruct)
RCC_ClocksTypeDef RCC_ClocksStatus;
/* Check the parameters */
assert_param(IS_UART_ALL_PERIPH(UARTx));
- assert_param(IS_UART_BAUDRATE(UART_InitStruct->UART_BaudRate));
+ assert_param(IS_UART_BAUDRATE(UART_InitStruct->UART_BaudRate));
assert_param(IS_UART_WORD_LENGTH(UART_InitStruct->UART_WordLength));
assert_param(IS_UART_STOPBITS(UART_InitStruct->UART_StopBits));
assert_param(IS_UART_PARITY(UART_InitStruct->UART_Parity));
@@ -139,12 +139,12 @@ void UART_Init(UART_TypeDef* UARTx, UART_InitTypeDef* UART_InitStruct)
/* Set spb bit according to UART_StopBits value */
/* Set PEN bit according to UART_Parity value */
tmpreg |= (uint32_t)UART_InitStruct->UART_WordLength |(uint32_t)UART_InitStruct->UART_StopBits |UART_InitStruct->UART_Parity;
-
+
/* Write to UART CCR */
UARTx->CCR = tmpreg;
-
+
/*---------------------------- UART GCR Configuration -----------------------*/
- /* get UART GCR values */
+ /* get UART GCR values */
tmpreg = UARTx->GCR;
/* Clear TXEN and RXEN ,autoflowen, mode ,uarten bits */
tmpreg &= GCR_CLEAR_Mask;
@@ -160,7 +160,7 @@ void UART_Init(UART_TypeDef* UARTx, UART_InitTypeDef* UART_InitStruct)
/* Determine the UART_baud*/
tmpreg = ((RCC_ClocksStatus.PCLK1_Frequency)/(UART_InitStruct->UART_BaudRate)/16) ;
/* Write to UART BRR */
- UARTx->BRR = tmpreg;
+ UARTx->BRR = tmpreg;
}
/**
@@ -177,13 +177,13 @@ void UART_StructInit(UART_InitTypeDef* UART_InitStruct)
UART_InitStruct->UART_StopBits = UART_StopBits_1;
UART_InitStruct->UART_Parity = UART_Parity_No ;
UART_InitStruct->UART_Mode = UART_Mode_Rx | UART_Mode_Tx;
- UART_InitStruct->UART_HardwareFlowControl = UART_HardwareFlowControl_None;
+ UART_InitStruct->UART_HardwareFlowControl = UART_HardwareFlowControl_None;
}
/**
* @brief Enables or disables the specified UART peripheral.
-* @param UARTx: Select the UART or the UART peripheral.
+* @param UARTx: Select the UART or the UART peripheral.
* This parameter can be one of the following values:
* UART1, UART2, UART3.
* @param NewState: new state of the UARTx peripheral.
@@ -195,7 +195,7 @@ void UART_Cmd(UART_TypeDef* UARTx, FunctionalState NewState)
/* Check the parameters */
assert_param(IS_UART_ALL_PERIPH(UARTx));
assert_param(IS_FUNCTIONAL_STATE(NewState));
-
+
if (NewState != DISABLE)
{
/* Enable the selected UART by setting the uarten bit in the GCR register */
@@ -210,18 +210,18 @@ void UART_Cmd(UART_TypeDef* UARTx, FunctionalState NewState)
/**
* @brief Enables or disables the specified UART interrupts.
-* @param UARTx: Select the UART or the UART peripheral.
+* @param UARTx: Select the UART or the UART peripheral.
* This parameter can be one of the following values:
* UART1, UART2, UART3.
* @param UART_IT: specifies the UART interrupt sources to be
* enabled or disabled.
* This parameter can be one of the following values:
-*
+*
* @arg UART_IT_ERR: Error interrupt(Frame error,)
* @arg UART_IT_PE: Parity Error interrupt
* @arg UART_OVER_ERR: overrun Error interrupt
* @arg UART_TIMEOUT_ERR: timeout Error interrupt
-* @arg UART_IT_RXIEN: Receive Data register interrupt
+* @arg UART_IT_RXIEN: Receive Data register interrupt
* @arg UART_IT_TXIEN: Tansmit Data Register empty interrupt
* @param NewState: new state of the specified UARTx interrupts.
* This parameter can be: ENABLE or DISABLE.
@@ -233,7 +233,7 @@ void UART_ITConfig(UART_TypeDef* UARTx, uint16_t UART_IT, FunctionalState NewSta
assert_param(IS_UART_ALL_PERIPH(UARTx));
assert_param(IS_UART_CONFIG_IT(UART_IT));
assert_param(IS_FUNCTIONAL_STATE(NewState));
-
+
if (NewState != DISABLE)
{
/* Enable the UART_IT interrupt */
@@ -247,25 +247,25 @@ void UART_ITConfig(UART_TypeDef* UARTx, uint16_t UART_IT, FunctionalState NewSta
}
/**
-* @brief Enables or disables the UART抯 DMA interface.
-* @param UARTx: Select the UART or the UART peripheral.
+* @brief Enables or disables the UART鈥檚 DMA interface.
+* @param UARTx: Select the UART or the UART peripheral.
* This parameter can be one of the following values:
-* UART1, UART2, UART3 .
+* UART1, UART2, UART3 .
* @param UART_DMAReq: specifies the DMA request.
* This parameter can be any combination of the following values:
* @arg UART_DMAReq_EN: UART DMA transmit request
-*
+*
* @param NewState: new state of the DMA Request sources.
* This parameter can be: ENABLE or DISABLE.
-* @note The DMA mode is not available for UART5.
+* @note The DMA mode is not available for UART5.
* @retval : None
*/
void UART_DMACmd(UART_TypeDef* UARTx, uint16_t UART_DMAReq, FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_UART_1234_PERIPH(UARTx));
- assert_param(IS_UART_DMAREQ(UART_DMAReq));
- assert_param(IS_FUNCTIONAL_STATE(NewState));
+ assert_param(IS_UART_DMAREQ(UART_DMAReq));
+ assert_param(IS_FUNCTIONAL_STATE(NewState));
if (NewState != DISABLE)
{
/* Enable the DMA transfer */
@@ -281,7 +281,7 @@ void UART_DMACmd(UART_TypeDef* UARTx, uint16_t UART_DMAReq, FunctionalState NewS
/**
* @brief Transmits single data through the UARTx peripheral.
-* @param UARTx: Select the UART or the UART peripheral.
+* @param UARTx: Select the UART or the UART peripheral.
* This parameter can be one of the following values:
* UART1, UART2, UART3.
* @param Data: the data to transmit.
@@ -291,15 +291,15 @@ void UART_SendData(UART_TypeDef* UARTx, uint16_t Data)
{
/* Check the parameters */
assert_param(IS_UART_ALL_PERIPH(UARTx));
- assert_param(IS_UART_DATA(Data));
-
+ assert_param(IS_UART_DATA(Data));
+
/* Transmit Data */
UARTx->TDR = (Data & (uint16_t)0x00FF);
}
/**
* @brief Returns the most recent received data by the UARTx peripheral.
-* @param UARTx: Select the UART or the UART peripheral.
+* @param UARTx: Select the UART or the UART peripheral.
* This parameter can be one of the following values:
* UART1, UART2, UART3.
* @retval : The received data.
@@ -308,7 +308,7 @@ uint16_t UART_ReceiveData(UART_TypeDef* UARTx)
{
/* Check the parameters */
assert_param(IS_UART_ALL_PERIPH(UARTx));
-
+
/* Receive Data */
return (uint16_t)(UARTx->RDR & (uint16_t)0x00FF);
}
@@ -316,15 +316,15 @@ uint16_t UART_ReceiveData(UART_TypeDef* UARTx)
/**
* @brief Checks whether the specified UART flag is set or not.
-* @param UARTx: Select the UART or the UART peripheral.
+* @param UARTx: Select the UART or the UART peripheral.
* This parameter can be one of the following values:
* UART1, UART2, UART3.
* @param UART_FLAG: specifies the flag to check.
* This parameter can be one of the following values:
-* @arg UART_FLAG_TXEMPTY:Transmit data register empty flag
-* @arg UART_FLAG_TXFULL:Transmit data buffer full
+* @arg UART_FLAG_TXEMPTY:Transmit data register empty flag
+* @arg UART_FLAG_TXFULL:Transmit data buffer full
* @arg UART_FLAG_RXAVL:RX Buffer has a byte flag
-* @arg UART_FLAG_OVER:OverRun Error flag
+* @arg UART_FLAG_OVER:OverRun Error flag
* @arg UART_FLAG_TXEPT: tx and shifter are emptys flag
* @retval : The new state of UART_FLAG (SET or RESET).
*/
@@ -347,26 +347,26 @@ FlagStatus UART_GetFlagStatus(UART_TypeDef* UARTx, uint16_t UART_FLAG)
/**
* @brief Clears the UARTx's pending flags.
-* @param UARTx: Select the UART or the UART peripheral.
+* @param UARTx: Select the UART or the UART peripheral.
* This parameter can be one of the following values:
* UART1, UART2, UART3, UART4 or UART5.
* @param UART_FLAG: specifies the flag to clear.
* This parameter can be any combination of the following values:
-* @arg UART_FLAG_TXEMPTY:Transmit data register empty flag
-* @arg UART_FLAG_TXFULL:Transmit data buffer full
+* @arg UART_FLAG_TXEMPTY:Transmit data register empty flag
+* @arg UART_FLAG_TXFULL:Transmit data buffer full
* @arg UART_FLAG_RXAVL:RX Buffer has a byte flag
-* @arg UART_FLAG_OVER:OverRun Error flag
+* @arg UART_FLAG_OVER:OverRun Error flag
* @arg UART_FLAG_TXEPT: tx and shifter are emptys flag
* @retval : None
*/
void UART_ClearFlag(UART_TypeDef* UARTx, uint16_t UART_FLAG)
{
-
+
}
/**
* @brief Checks whether the specified UART interrupt has occurred or not.
-* @param UARTx: Select the UART or the UART peripheral.
+* @param UARTx: Select the UART or the UART peripheral.
* This parameter can be one of the following values:
* UART1, UART2, UART3.
* @param UART_IT: specifies the UART interrupt source to check.
@@ -375,7 +375,7 @@ void UART_ClearFlag(UART_TypeDef* UARTx, uint16_t UART_FLAG)
* @arg UART_IT_PE: Parity Error interrupt
* @arg UART_OVER_ERR: overrun Error interrupt
* @arg UART_TIMEOUT_ERR: timeout Error interrupt
-* @arg UART_IT_RXIEN: Receive Data register interrupt
+* @arg UART_IT_RXIEN: Receive Data register interrupt
* @arg UART_IT_TXIEN: Tansmit Data Register empty interrupt
* @retval : The new state of UART_IT (SET or RESET).
*/
@@ -385,7 +385,7 @@ ITStatus UART_GetITStatus(UART_TypeDef* UARTx, uint16_t UART_IT)
/* Check the parameters */
assert_param(IS_UART_ALL_PERIPH(UARTx));
assert_param(IS_UART_FLAG(UART_FLAG));
- assert_param(IS_UART_PERIPH_FLAG(UARTx, UART_FLAG)); /* The CTS flag is not available for UART4 and UART5 */
+ assert_param(IS_UART_PERIPH_FLAG(UARTx, UART_FLAG)); /* The CTS flag is not available for UART4 and UART5 */
if ((UARTx->ISR & UART_IT) != (uint16_t)RESET)
{
bitstatus = SET;
@@ -398,8 +398,8 @@ ITStatus UART_GetITStatus(UART_TypeDef* UARTx, uint16_t UART_IT)
}
/**
-* @brief Clears the UARTx抯 interrupt pending bits.
-* @param UARTx: Select the UART or the UART peripheral.
+* @brief Clears the UARTx鈥檚 interrupt pending bits.
+* @param UARTx: Select the UART or the UART peripheral.
* This parameter can be one of the following values:
* UART1, UART2, UART3, UART4 or UART5.
* @param UART_IT: specifies the interrupt pending bit to clear.
@@ -408,14 +408,14 @@ ITStatus UART_GetITStatus(UART_TypeDef* UARTx, uint16_t UART_IT)
* @arg UART_IT_PE: Parity Error interrupt
* @arg UART_OVER_ERR: overrun Error interrupt
* @arg UART_TIMEOUT_ERR: timeout Error interrupt
-* @arg UART_IT_RXIEN: Receive Data register interrupt
+* @arg UART_IT_RXIEN: Receive Data register interrupt
* @arg UART_IT_TXIEN: Tansmit Data Register empty interrupt
* @retval : None
*/
void UART_ClearITPendingBit(UART_TypeDef* UARTx, uint16_t UART_IT)
{
-
+
/* Check the parameters */
assert_param(IS_UART_ALL_PERIPH(UARTx));
assert_param(IS_UART_CLEAR_IT(UART_IT));