未验证 提交 c8ee4cc6 编写于 作者: G guo 提交者: GitHub

Merge pull request #5182 from NU-LL/tkm32f499

......@@ -47,6 +47,7 @@ jobs:
- {RTT_BSP: "lm3s9b9x", RTT_TOOL_CHAIN: "sourcery-arm"}
- {RTT_BSP: "lm4f232", RTT_TOOL_CHAIN: "sourcery-arm"}
- {RTT_BSP: "tm4c123bsp", RTT_TOOL_CHAIN: "sourcery-arm"}
- {RTT_BSP: "tkm32F499", RTT_TOOL_CHAIN: "sourcery-arm"}
- {RTT_BSP: "tm4c129x", RTT_TOOL_CHAIN: "sourcery-arm"}
- {RTT_BSP: "lpc43xx/M4", RTT_TOOL_CHAIN: "sourcery-arm"}
- {RTT_BSP: "lpc176x", RTT_TOOL_CHAIN: "sourcery-arm"}
......
......@@ -38,5 +38,7 @@ ncscope.*
tags
.idea
.vscode
.history
CMakeLists.txt
cmake-build-debug
mainmenu "RT-Thread Configuration"
config BSP_DIR
string
option env="BSP_ROOT"
default "."
config RTT_DIR
string
option env="RTT_ROOT"
default "rt-thread"
config PKGS_DIR
string
option env="PKGS_ROOT"
default "packages"
source "$RTT_DIR/Kconfig"
source "$PKGS_DIR/Kconfig"
source "drivers/Kconfig"
/**************************************************************************//**
* @file core_cmFunc.h
* @brief CMSIS Cortex-M Core Function Access Header File
* @version V4.30
* @date 20. October 2015
******************************************************************************/
/* Copyright (c) 2009 - 2015 ARM LIMITED
All rights reserved.
Redistribution and use in source and binary forms, with or without
modification, are permitted provided that the following conditions are met:
- Redistributions of source code must retain the above copyright
notice, this list of conditions and the following disclaimer.
- Redistributions in binary form must reproduce the above copyright
notice, this list of conditions and the following disclaimer in the
documentation and/or other materials provided with the distribution.
- Neither the name of ARM nor the names of its contributors may be used
to endorse or promote products derived from this software without
specific prior written permission.
*
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE
LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
POSSIBILITY OF SUCH DAMAGE.
---------------------------------------------------------------------------*/
#if defined ( __ICCARM__ )
#pragma system_include /* treat file as system include file for MISRA check */
#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
#pragma clang system_header /* treat file as system include file */
#endif
#ifndef __CORE_CMFUNC_H
#define __CORE_CMFUNC_H
/* ########################### Core Function Access ########################### */
/** \ingroup CMSIS_Core_FunctionInterface
\defgroup CMSIS_Core_RegAccFunctions CMSIS Core Register Access Functions
@{
*/
/*------------------ RealView Compiler -----------------*/
#if defined ( __CC_ARM )
#include "cmsis_armcc.h"
/*------------------ ARM Compiler V6 -------------------*/
#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
#include "cmsis_armcc_V6.h"
/*------------------ GNU Compiler ----------------------*/
#elif defined ( __GNUC__ )
#include "cmsis_gcc.h"
/*------------------ ICC Compiler ----------------------*/
#elif defined ( __ICCARM__ )
#include <cmsis_iar.h>
/*------------------ TI CCS Compiler -------------------*/
#elif defined ( __TMS470__ )
#include <cmsis_ccs.h>
/*------------------ TASKING Compiler ------------------*/
#elif defined ( __TASKING__ )
/*
* The CMSIS functions have been implemented as intrinsics in the compiler.
* Please use "carm -?i" to get an up to date list of all intrinsics,
* Including the CMSIS ones.
*/
/*------------------ COSMIC Compiler -------------------*/
#elif defined ( __CSMC__ )
#include <cmsis_csm.h>
#endif
/*@} end of CMSIS_Core_RegAccFunctions */
#endif /* __CORE_CMFUNC_H */
/**************************************************************************//**
* @file core_cmInstr.h
* @brief CMSIS Cortex-M Core Instruction Access Header File
* @version V4.30
* @date 20. October 2015
******************************************************************************/
/* Copyright (c) 2009 - 2015 ARM LIMITED
All rights reserved.
Redistribution and use in source and binary forms, with or without
modification, are permitted provided that the following conditions are met:
- Redistributions of source code must retain the above copyright
notice, this list of conditions and the following disclaimer.
- Redistributions in binary form must reproduce the above copyright
notice, this list of conditions and the following disclaimer in the
documentation and/or other materials provided with the distribution.
- Neither the name of ARM nor the names of its contributors may be used
to endorse or promote products derived from this software without
specific prior written permission.
*
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE
LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
POSSIBILITY OF SUCH DAMAGE.
---------------------------------------------------------------------------*/
#if defined ( __ICCARM__ )
#pragma system_include /* treat file as system include file for MISRA check */
#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
#pragma clang system_header /* treat file as system include file */
#endif
#ifndef __CORE_CMINSTR_H
#define __CORE_CMINSTR_H
/* ########################## Core Instruction Access ######################### */
/** \defgroup CMSIS_Core_InstructionInterface CMSIS Core Instruction Interface
Access to dedicated instructions
@{
*/
/*------------------ RealView Compiler -----------------*/
#if defined ( __CC_ARM )
#include "cmsis_armcc.h"
/*------------------ ARM Compiler V6 -------------------*/
#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
#include "cmsis_armcc_V6.h"
/*------------------ GNU Compiler ----------------------*/
#elif defined ( __GNUC__ )
#include "cmsis_gcc.h"
/*------------------ ICC Compiler ----------------------*/
#elif defined ( __ICCARM__ )
#include <cmsis_iar.h>
/*------------------ TI CCS Compiler -------------------*/
#elif defined ( __TMS470__ )
#include <cmsis_ccs.h>
/*------------------ TASKING Compiler ------------------*/
#elif defined ( __TASKING__ )
/*
* The CMSIS functions have been implemented as intrinsics in the compiler.
* Please use "carm -?i" to get an up to date list of all intrinsics,
* Including the CMSIS ones.
*/
/*------------------ COSMIC Compiler -------------------*/
#elif defined ( __CSMC__ )
#include <cmsis_csm.h>
#endif
/*@}*/ /* end of group CMSIS_Core_InstructionInterface */
#endif /* __CORE_CMINSTR_H */
/**************************************************************************//**
* @file core_cmSimd.h
* @brief CMSIS Cortex-M SIMD Header File
* @version V4.30
* @date 20. October 2015
******************************************************************************/
/* Copyright (c) 2009 - 2015 ARM LIMITED
All rights reserved.
Redistribution and use in source and binary forms, with or without
modification, are permitted provided that the following conditions are met:
- Redistributions of source code must retain the above copyright
notice, this list of conditions and the following disclaimer.
- Redistributions in binary form must reproduce the above copyright
notice, this list of conditions and the following disclaimer in the
documentation and/or other materials provided with the distribution.
- Neither the name of ARM nor the names of its contributors may be used
to endorse or promote products derived from this software without
specific prior written permission.
*
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE
LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
POSSIBILITY OF SUCH DAMAGE.
---------------------------------------------------------------------------*/
#if defined ( __ICCARM__ )
#pragma system_include /* treat file as system include file for MISRA check */
#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
#pragma clang system_header /* treat file as system include file */
#endif
#ifndef __CORE_CMSIMD_H
#define __CORE_CMSIMD_H
#ifdef __cplusplus
extern "C" {
#endif
/* ################### Compiler specific Intrinsics ########################### */
/** \defgroup CMSIS_SIMD_intrinsics CMSIS SIMD Intrinsics
Access to dedicated SIMD instructions
@{
*/
/*------------------ RealView Compiler -----------------*/
#if defined ( __CC_ARM )
#include "cmsis_armcc.h"
/*------------------ ARM Compiler V6 -------------------*/
#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
#include "cmsis_armcc_V6.h"
/*------------------ GNU Compiler ----------------------*/
#elif defined ( __GNUC__ )
#include "cmsis_gcc.h"
/*------------------ ICC Compiler ----------------------*/
#elif defined ( __ICCARM__ )
#include <cmsis_iar.h>
/*------------------ TI CCS Compiler -------------------*/
#elif defined ( __TMS470__ )
#include <cmsis_ccs.h>
/*------------------ TASKING Compiler ------------------*/
#elif defined ( __TASKING__ )
/*
* The CMSIS functions have been implemented as intrinsics in the compiler.
* Please use "carm -?i" to get an up to date list of all intrinsics,
* Including the CMSIS ones.
*/
/*------------------ COSMIC Compiler -------------------*/
#elif defined ( __CSMC__ )
#include <cmsis_csm.h>
#endif
/*@} end of group CMSIS_SIMD_intrinsics */
#ifdef __cplusplus
}
#endif
#endif /* __CORE_CMSIMD_H */
;******************** (C) COPYRIGHT 2016 HOLOCENE ********************
; Amount of memory (in bytes) allocated for Stack
; Tailor this value to your application needs
; <h> Stack Configuration
; <o> Stack Size (in Bytes) <0x0-0xFFFFFFFF:8>
; </h>
;//============== 版本 EK V1.0 20190801 ==============//
Stack_Size EQU 0x00002000
AREA STACK, NOINIT, READWRITE, ALIGN=3
Stack_Mem SPACE Stack_Size
__initial_sp
; <h> Heap Configuration
; <o> Heap Size (in Bytes) <0x0-0xFFFFFFFF:8>
; </h>
Heap_Size EQU 0x00000000
AREA HEAP, NOINIT, READWRITE, ALIGN=3
__heap_base
Heap_Mem SPACE Heap_Size
__heap_limit
PRESERVE8
THUMB
; Vector Table Mapped to Address 0 at Reset
AREA RESET, DATA, READONLY
EXPORT __Vectors
EXPORT __Vectors_End
EXPORT __Vectors_Size
__Vectors DCD __initial_sp ; Top of Stack
DCD Reset_Handler ; Reset Handler
DCD NMI_Handler ; NMI Handler
DCD HardFault_Handler ; Hard Fault Handler
DCD MemManage_Handler ; MPU Fault Handler
DCD BusFault_Handler ; Bus Fault Handler
DCD UsageFault_Handler ; Usage Fault Handler
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD SVC_Handler ; SVCall Handler
DCD DebugMon_Handler ; Debug Monitor Handler
DCD 0 ; Reserved
DCD PendSV_Handler ; PendSV Handler
DCD SysTick_Handler ; SysTick Handler
; External Interrupts
DCD WWDG_IRQHandler ;WWDG
DCD 0 ;
DCD TAMPER_IRQHandler ;TAMPER
DCD RTC_IRQHandler ;RTC
DCD 0 ;
DCD RCC_IRQHandler ;RCC
DCD EXTI0_IRQHandler ;EXTI0
DCD EXTI1_IRQHandler ;EXTI1
DCD EXTI2_IRQHandler ;EXTI2
DCD EXTI3_IRQHandler ;EXTI3
DCD EXTI4_IRQHandler ;EXTI4
DCD DMA1_Channel1_IRQHandler ;DMA1 Channel 1
DCD DMA1_Channel2_IRQHandler ;DMA1 Channel 2
DCD DMA1_Channel3_IRQHandler ;DMA1 Channel 3
DCD DMA1_Channel4_IRQHandler ;DMA1 Channel 4
DCD DMA1_Channel5_IRQHandler ;DMA1 Channel 5
DCD DMA1_Channel6_IRQHandler ;DMA1 Channel 6
DCD DMA1_Channel7_IRQHandler ;DMA1 Channel 7
DCD ADC1_IRQHandler ;ADC1
DCD CAN1_IRQHandler ;CAN1
DCD 0 ;
DCD 0 ;
DCD 0 ;
DCD EXTI9_5_IRQHandler ;EXTI9_5
DCD TIM1_BRK_IRQHandler ;TIM1_BRK
DCD TIM1_UP_IRQHandler ;TIM1_UP
DCD TIM1_TRG_COM_IRQHandler ;TIM1_TRG_COM
DCD TIM1_CC_IRQHandler ;TIM1_CC
DCD TIM3_IRQHandler ;TIM3
DCD TIM4_IRQHandler ;TIM4
DCD TIM5_IRQHandler ;TIM5
DCD TIM6_IRQHandler ;TIM6
DCD TIM7_IRQHandler ;TIM7
DCD I2C1_IRQHandler ;I2C1
DCD I2C2_IRQHandler ;I2C2
DCD SPI1_IRQHandler ;SPI1
DCD SPI2_IRQHandler ;SPI2
DCD UART1_IRQHandler ;UART1
DCD UART2_IRQHandler ;UART2
DCD UART3_IRQHandler ;UART3
DCD EXTI15_10_IRQHandler ;EXTI15_10
DCD RTCAlarm_IRQHandler ;RTC_ALARM
DCD USBAwake_IRQHandler ;USBAwake
DCD TIM2_BRK_IRQHandler ;TIM2_BRK
DCD TIM2_UP_IRQHandler ;TIM2_UP
DCD TIM2_TRG_COM_IRQHandler ;TIM2_TRG_COM
DCD TIM2_CC_IRQHandler ;TIM2_CC
DCD DMA1_Channel8_IRQHandler ;DMA1
DCD TK80_IRQHandler ;TK80
DCD SDIO1_IRQHandler ;SDIO1
DCD SDIO2_IRQHandler ;SDIO2
DCD SPI3_IRQHandler ;SPI3
DCD UART4_IRQHandler ;UART4
DCD UART5_IRQHandler ;UART5
DCD 0 ;
DCD TIM8_IRQHandler ;TIM8
DCD DMA2_Channel1_IRQHandler ;DMA2 Channel 1
DCD DMA2_Channel2_IRQHandler ;DMA2 Channel 2
DCD DMA2_Channel3_IRQHandler ;DMA2 Channel 3
DCD DMA2_Channel4_IRQHandler ;DMA2 Channel 4
DCD DMA2_Channel5_IRQHandler ;DMA2 Channel 5
DCD TIM9_IRQHandler ;TIM9
DCD TIM10_IRQHandler ;TIM10
DCD CAN2_IRQHandler ;CAN2
DCD 0 ;
DCD 0 ;
DCD 0 ;
DCD USB_IRQHandler ;USB
DCD DMA2_Channel6_IRQHandler ;DMA2 Channel 6
DCD DMA2_Channel7_IRQHandler ;DMA2 Channel 7
DCD DMA2_Channel8_IRQHandler ;DMA2 Channel 8
DCD 0 ;
DCD I2C3_IRQHandler ;I2C3
DCD I2C4_IRQHandler ;I2C4
DCD 0 ;
DCD 0 ;
DCD 0 ;
DCD 0 ;
DCD 0 ;
DCD 0 ;
DCD 0 ;
DCD FPU_IRQHandler ;FPU
DCD 0 ;
DCD 0 ;
DCD SPI4_IRQHandler ;SPI4
DCD 0 ;
DCD TOUCHPAD_IRQHandler ;TCHPAD
DCD QSPI_IRQHandler ;QSPI
DCD LTDC_IRQHandler ;LCD-TFT
DCD 0 ;
DCD I2S1_IRQHandler ;I2S1
__Vectors_End
__Vectors_Size EQU __Vectors_End - __Vectors
AREA |.text|, CODE, READONLY
; Reset handler
Reset_Handler PROC
EXPORT Reset_Handler [WEAK]
IMPORT __main
LDR R0, =0xE000ED88 ; 使能浮点运算 CP10,CP11
LDR R1,[R0]
ORR R1,R1,#(0xF << 20)
STR R1,[R0]
;IMPORT SystemInit
; LDR R0, =SystemInit
;BLX R0
LDR R0, =__main
BX R0
ENDP
; Dummy Exception Handlers (infinite loops which can be modified)
NMI_Handler PROC
EXPORT NMI_Handler [WEAK]
B .
ENDP
HardFault_Handler\
PROC
EXPORT HardFault_Handler [WEAK]
B .
ENDP
MemManage_Handler\
PROC
EXPORT MemManage_Handler [WEAK]
B .
ENDP
BusFault_Handler\
PROC
EXPORT BusFault_Handler [WEAK]
B .
ENDP
UsageFault_Handler\
PROC
EXPORT UsageFault_Handler [WEAK]
B .
ENDP
SVC_Handler PROC
EXPORT SVC_Handler [WEAK]
B .
ENDP
DebugMon_Handler\
PROC
EXPORT DebugMon_Handler [WEAK]
B .
ENDP
PendSV_Handler PROC
EXPORT PendSV_Handler [WEAK]
B .
ENDP
SysTick_Handler PROC
EXPORT SysTick_Handler [WEAK]
B .
ENDP
Default_Handler PROC
EXPORT WWDG_IRQHandler [WEAK]
EXPORT TAMPER_IRQHandler [WEAK]
EXPORT RTC_IRQHandler [WEAK]
EXPORT RCC_IRQHandler [WEAK]
EXPORT EXTI0_IRQHandler [WEAK]
EXPORT EXTI1_IRQHandler [WEAK]
EXPORT EXTI2_IRQHandler [WEAK]
EXPORT EXTI3_IRQHandler [WEAK]
EXPORT EXTI4_IRQHandler [WEAK]
EXPORT DMA1_Channel1_IRQHandler [WEAK]
EXPORT DMA1_Channel2_IRQHandler [WEAK]
EXPORT DMA1_Channel3_IRQHandler [WEAK]
EXPORT DMA1_Channel4_IRQHandler [WEAK]
EXPORT DMA1_Channel5_IRQHandler [WEAK]
EXPORT DMA1_Channel6_IRQHandler [WEAK]
EXPORT DMA1_Channel7_IRQHandler [WEAK]
EXPORT ADC1_IRQHandler [WEAK]
EXPORT CAN1_IRQHandler [WEAK]
EXPORT EXTI9_5_IRQHandler [WEAK]
EXPORT TIM1_BRK_IRQHandler [WEAK]
EXPORT TIM1_UP_IRQHandler [WEAK]
EXPORT TIM1_TRG_COM_IRQHandler [WEAK]
EXPORT TIM1_CC_IRQHandler [WEAK]
EXPORT TIM3_IRQHandler [WEAK]
EXPORT TIM4_IRQHandler [WEAK]
EXPORT TIM5_IRQHandler [WEAK]
EXPORT TIM6_IRQHandler [WEAK]
EXPORT TIM7_IRQHandler [WEAK]
EXPORT I2C1_IRQHandler [WEAK]
EXPORT I2C2_IRQHandler [WEAK]
EXPORT SPI1_IRQHandler [WEAK]
EXPORT SPI2_IRQHandler [WEAK]
EXPORT UART1_IRQHandler [WEAK]
EXPORT UART2_IRQHandler [WEAK]
EXPORT UART3_IRQHandler [WEAK]
EXPORT EXTI15_10_IRQHandler [WEAK]
EXPORT RTCAlarm_IRQHandler [WEAK]
EXPORT USBAwake_IRQHandler [WEAK]
EXPORT TIM2_BRK_IRQHandler [WEAK]
EXPORT TIM2_UP_IRQHandler [WEAK]
EXPORT TIM2_TRG_COM_IRQHandler [WEAK]
EXPORT TIM2_CC_IRQHandler [WEAK]
EXPORT DMA1_Channel8_IRQHandler [WEAK]
EXPORT TK80_IRQHandler [WEAK]
EXPORT SDIO1_IRQHandler [WEAK]
EXPORT SDIO2_IRQHandler [WEAK]
EXPORT SPI3_IRQHandler [WEAK]
EXPORT UART4_IRQHandler [WEAK]
EXPORT UART5_IRQHandler [WEAK]
EXPORT TIM8_IRQHandler [WEAK]
EXPORT DMA2_Channel1_IRQHandler [WEAK]
EXPORT DMA2_Channel2_IRQHandler [WEAK]
EXPORT DMA2_Channel3_IRQHandler [WEAK]
EXPORT DMA2_Channel4_IRQHandler [WEAK]
EXPORT DMA2_Channel5_IRQHandler [WEAK]
EXPORT TIM9_IRQHandler [WEAK]
EXPORT TIM10_IRQHandler [WEAK]
EXPORT CAN2_IRQHandler [WEAK]
EXPORT USB_IRQHandler [WEAK]
EXPORT DMA2_Channel6_IRQHandler [WEAK]
EXPORT DMA2_Channel7_IRQHandler [WEAK]
EXPORT DMA2_Channel8_IRQHandler [WEAK]
EXPORT I2C3_IRQHandler [WEAK]
EXPORT I2C4_IRQHandler [WEAK]
EXPORT TOUCHPAD_IRQHandler [WEAK]
EXPORT SPI4_IRQHandler [WEAK]
EXPORT QSPI_IRQHandler [WEAK]
EXPORT LTDC_IRQHandler [WEAK]
EXPORT I2S1_IRQHandler [WEAK]
WWDG_IRQHandler
TAMPER_IRQHandler
RTC_IRQHandler
RCC_IRQHandler
EXTI0_IRQHandler
EXTI1_IRQHandler
EXTI2_IRQHandler
EXTI3_IRQHandler
EXTI4_IRQHandler
DMA1_Channel1_IRQHandler
DMA1_Channel2_IRQHandler
DMA1_Channel3_IRQHandler
DMA1_Channel4_IRQHandler
DMA1_Channel5_IRQHandler
DMA1_Channel6_IRQHandler
DMA1_Channel7_IRQHandler
ADC1_IRQHandler
CAN1_IRQHandler
EXTI9_5_IRQHandler
TIM1_BRK_IRQHandler
TIM1_UP_IRQHandler
TIM1_TRG_COM_IRQHandler
TIM1_CC_IRQHandler
TIM3_IRQHandler
TIM4_IRQHandler
TIM5_IRQHandler
TIM6_IRQHandler
TIM7_IRQHandler
I2C1_IRQHandler
I2C2_IRQHandler
SPI1_IRQHandler
SPI2_IRQHandler
UART1_IRQHandler
UART2_IRQHandler
UART3_IRQHandler
EXTI15_10_IRQHandler
RTCAlarm_IRQHandler
USBAwake_IRQHandler
TIM2_BRK_IRQHandler
TIM2_UP_IRQHandler
TIM2_TRG_COM_IRQHandler
TIM2_CC_IRQHandler
DMA1_Channel8_IRQHandler
TK80_IRQHandler
SDIO1_IRQHandler
SDIO2_IRQHandler
SPI3_IRQHandler
UART4_IRQHandler
UART5_IRQHandler
TIM8_IRQHandler
DMA2_Channel1_IRQHandler
DMA2_Channel2_IRQHandler
DMA2_Channel3_IRQHandler
DMA2_Channel4_IRQHandler
DMA2_Channel5_IRQHandler
TIM9_IRQHandler
TIM10_IRQHandler
CAN2_IRQHandler
USB_IRQHandler
DMA2_Channel6_IRQHandler
DMA2_Channel7_IRQHandler
DMA2_Channel8_IRQHandler
I2C3_IRQHandler
I2C4_IRQHandler
FPU_IRQHandler
SPI4_IRQHandler
QSPI_IRQHandler
TOUCHPAD_IRQHandler
LTDC_IRQHandler
I2S1_IRQHandler
B .
ENDP
ALIGN
;*******************************************************************************
; User Stack and Heap initialization
;*******************************************************************************
IF :DEF:__MICROLIB
EXPORT __initial_sp
EXPORT __heap_base
EXPORT __heap_limit
ELSE
IMPORT __use_two_region_memory
EXPORT __user_initial_stackheap
__user_initial_stackheap
LDR R0, = Heap_Mem
LDR R1, =(Stack_Mem + Stack_Size)
LDR R2, = (Heap_Mem + Heap_Size)
LDR R3, = Stack_Mem
BX LR
ALIGN
ENDIF
END
;******************** (C) COPYRIGHT 2016 HOLOCENE ********************
#include "sys.h"
#include "HAL_misc.h"
void RemapVtorTable(void)
{
int i;
RCC->AHB1ENR |= 1<<13;//bkp clk,enable sram
//关ROM区中断
for(i = 0;i<90;i++)
{
NVIC_DisableIRQ((IRQn_Type)i);
}
SCB->VTOR = 0;
SCB->VTOR |= 0x1<<29;
for(i = 0;i < 512;i+=4)
*(u32*)(T_SRAM_BASE + i) = *(u32*)(T_SDRAM_BASE+i);
}
void AI_Responder_enable(void)
{
AI_Responder->ADDR1= 0x70807040;
// AI_Responder->ADDR0 = 0x70027080;
AI_Responder->ADDR1 = 0;
AI_Responder->CCR &= ~(0x3<<3);
AI_Responder->CCR |= 1;
while((AI_Responder->SR & 0x3) != 2);
}
void AI_Responder_disable(void)
{
AI_Responder->CCR &= ~1;
}
//外部中断配置函数
//只针对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<<EXTOFFSET);//清除原来设置!!!
SYSCFG->EXTICR[BITx/4]|=GPIOx<<EXTOFFSET; //EXTI.BITx映射到GPIOx.BITx
//自动设置
EXTI->IMR|=1<<BITx; //开启line BITx上的中断(如果要禁止中断,则反操作即可)
if(TRIM&0x01)EXTI->FTSR|=1<<BITx; //line BITx事件下降沿触发
if(TRIM&0x02)EXTI->RTSR|=1<<BITx; //line BITx事件上升沿触发
}
//THUMB指令不支持汇编内联
//采用如下方法实现执行汇编指令WFI
void WFI_SET(void)
{
__ASM volatile("wfi");
}
//关闭所有中断(但是不包括fault和NMI中断)
void INTX_DISABLE(void)
{
__ASM volatile("cpsid i");
}
//开启所有中断
void INTX_ENABLE(void)
{
__ASM volatile("cpsie i");
}
//设置栈顶地址 __set_MSP(0x70002000);
//进入待机模式
void Sys_Standby(void)
{
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和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);
temp|=NVIC_SubPriority&(0x0f>>NVIC_Group);
temp&=0xf; //取低四位
NVIC->ISER[NVIC_Channel/32]|=1<<NVIC_Channel%32;//使能中断位(要清除的话,设置ICER对应位为1即可)
NVIC->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
//void copyAtoB(u32 srcAdd,u32 dstAdd,u16 len)
//{
// len = (len + 3)/4;
// while(len--)
// {
// *(u32*)dstAdd = *(u32*)srcAdd;
// dstAdd += 4 ;
// srcAdd +=4 ;
// }
//}
#ifndef __SYS_H
#define __SYS_H
#include "tk499.h"
#include "HAL_conf.h"
//位带操作,实现51类似的GPIO控制功能
//具体实现思想,参考<<CM3权威指南>>第五章(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))
void RemapVtorTable(void);
void AI_Responder_enable(void);
void AI_Responder_disable(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 WFI_SET(void); //执行WFI指令
void INTX_DISABLE(void);//关闭所有中断
void INTX_ENABLE(void); //开启所有中断
void TIM3_Config(u16 arr,u16 psc);
#endif
此差异已折叠。
/**
******************************************************************************
* @file HAL_adc.h
* @author IC Applications Department
* @version V0.8
* @date 2019_08_02
* @brief This file contains all the functions prototypes for the ADC firmware
* library.
******************************************************************************
* @copy
*
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
* TIME. AS A RESULT, HOLOCENE SHALL NOT BE HELD LIABLE FOR ANY
* DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
* FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
* CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*
* <h2><center>&copy; COPYRIGHT 2016 HOLOCENE</center></h2>
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __HAL_ADC_H
#define __HAL_ADC_H
/* Includes ------------------------------------------------------------------*/
#include "HAL_device.h"
/** @addtogroup StdPeriph_Driver
* @{
*/
/** @addtogroup ADC
* @{
*/
/** @defgroup ADC_Exported_Types
* @{
*/
/**
* @brief ADC Init structure definition
*/
/*
typedef struct
{
uint32_t ADC_Mode;
FunctionalState ADC_ScanConvMode;
FunctionalState ADC_ContinuousConvMode;
uint32_t ADC_ExternalTrigConv;
uint32_t ADC_DataAlign;
uint8_t ADC_NbrOfChannel;
}ADC_InitTypeDef;
*/
typedef struct
{
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_DataAlign;
}ADC_InitTypeDef;
/**
* @}
*/
/** @defgroup ADC_Exported_Constants
* @{
*/
#define IS_ADC_ALL_PERIPH(PERIPH) (((*(uint32_t*)&(PERIPH)) == ADC1_BASE) || \
((*(uint32_t*)&(PERIPH)) == ADC2_BASE))
#define IS_ADC_DMA_PERIPH(PERIPH) (((*(uint32_t*)&(PERIPH)) == ADC1_BASE) || \
((*(uint32_t*)&(PERIPH)) == ADC2_BASE))
/** @defgroup ADC_Resolution
* @{
*/
#define ADC_Resolution_12b ((uint32_t)0x00000000)
#define ADC_Resolution_11b ((uint32_t)0x00000080)
#define ADC_Resolution_10b ((uint32_t)0x00000100)
#define ADC_Resolution_9b ((uint32_t)0x00000180)
#define ADC_Resolution_8b ((uint32_t)0x00000200)
#define IS_ADC_RESOLUTION(RESOLUTION) (((RESOLUTION) == ADC_Resolution_12b) || \
((RESOLUTION) == ADC_Resolution_10b) || \
((RESOLUTION) == ADC_Resolution_8b) || \
((RESOLUTION) == ADC_Resolution_6b))
/**
* @brief for ADC1, ADC2
*/
#define ADC_PCLK2_PRESCARE_2 ((uint32_t)0x00000000)
#define ADC_PCLK2_PRESCARE_4 ((uint32_t)0x00000010)
#define ADC_PCLK2_PRESCARE_6 ((uint32_t)0x00000020)
#define ADC_PCLK2_PRESCARE_8 ((uint32_t)0x00000030)
#define ADC_PCLK2_PRESCARE_10 ((uint32_t)0x00000040)
#define ADC_PCLK2_PRESCARE_12 ((uint32_t)0x00000050)
#define ADC_PCLK2_PRESCARE_14 ((uint32_t)0x00000060)
#define ADC_PCLK2_PRESCARE_16 ((uint32_t)0x00000070)
/** @defgroup ADC_dual_mode
* @{
*/
#define ADC_Mode_Single ((uint32_t)0x00000000)
#define ADC_Mode_Single_Period ((uint32_t)0x00000200)
#define ADC_Mode_Continuous_Scan ((uint32_t)0x00000400)
#define IS_ADC_MODE(MODE) (((MODE) == ADC_Mode_Single) || \
((MODE) == ADC_Mode_Single_Period) || \
((MODE) == ADC_Mode_Continuous_Scan))
/**
* @}
*/
#define ADC_TRG_Disable ((uint32_t)0xfffffffB)
#define ADC_TRG_Enable ((uint32_t)0x00000004)
/** @defgroup ADC_extrenal_trigger_sources_for_regular_channels_conversion
* @{
*/
/**
* @brief for ADC1
*/
#define ADC_ExternalTrigConv_T1_CC1 ((uint32_t)0x00000000)
#define ADC_ExternalTrigConv_T1_CC2 ((uint32_t)0x00000010)
#define ADC_ExternalTrigConv_T1_CC3 ((uint32_t)0x00000020)
#define ADC_ExternalTrigConv_T2_CC2 ((uint32_t)0x00000030)
#define ADC_ExternalTrigConv_T3_TRGO ((uint32_t)0x00000040)
#define ADC_ExternalTrigConv_T4_CC4 ((uint32_t)0x00000050)
#define ADC_ExternalTrigConv_T3_CC1 ((uint32_t)0x00000060)
#define ADC_ExternalTrigConv_EXTI_11 ((uint32_t)0x00000070)
/**
* @brief for ADC2
*/
#define ADC_ExternalTrigConv_T1_TRGO ((uint32_t)0x00000000)
#define ADC_ExternalTrigConv_T1_CC4 ((uint32_t)0x00000010)
#define ADC_ExternalTrigConv_T2_TRGO ((uint32_t)0x00000020)
#define ADC_ExternalTrigConv_T2_CC1 ((uint32_t)0x00000030)
#define ADC_ExternalTrigConv_T3_CC4 ((uint32_t)0x00000040)
#define ADC_ExternalTrigConv_T4_TRGO ((uint32_t)0x00000050)
#define ADC_ExternalTrigConv_T3_CC1 ((uint32_t)0x00000060)
#define ADC_ExternalTrigConv_EXTI_15 ((uint32_t)0x00000070)
#define IS_ADC_EXT_TRIG(REGTRIG) (((REGTRIG) == ADC_ExternalTrigConv_T1_CC1) || \
((REGTRIG) == ADC_ExternalTrigConv_T1_CC2) || \
((REGTRIG) == ADC_ExternalTrigConv_T1_CC3) || \
((REGTRIG) == ADC_ExternalTrigConv_T2_CC2) || \
((REGTRIG) == ADC_ExternalTrigConv_T3_TRGO) || \
((REGTRIG) == ADC_ExternalTrigConv_T4_CC4) || \
((REGTRIG) == ADC_ExternalTrigConv_T3_CC1) || \
((REGTRIG) == ADC_ExternalTrigConv_EXTI_11) || \
((REGTRIG) == ADC_ExternalTrigConv_T1_TRGO) || \
((REGTRIG) == ADC_ExternalTrigConv_T1_CC4) || \
((REGTRIG) == ADC_ExternalTrigConv_T2_TRGO) || \
((REGTRIG) == ADC_ExternalTrigConv_T2_CC1) || \
((REGTRIG) == ADC_ExternalTrigConv_T3_CC4) || \
((REGTRIG) == ADC_ExternalTrigConv_T4_TRGO) || \
((REGTRIG) == ADC_ExternalTrigConv_T3_CC1) || \
((REGTRIG) == ADC_ExternalTrigConv_EXTI_15))
/**
* @}
*/
/** @defgroup ADC_data_align
* @{
*/
#define ADC_DataAlign_Right ((uint32_t)0x00000000)
#define ADC_DataAlign_Left ((uint32_t)0x00000800)
#define IS_ADC_DATA_ALIGN(ALIGN) (((ALIGN) == ADC_DataAlign_Right) || \
((ALIGN) == ADC_DataAlign_Left))
/**
* @}
*/
/** @defgroup ADC_channels
* @{
*/
#define ADC_Channel_0 ((uint8_t)0x00)
#define ADC_Channel_1 ((uint8_t)0x01)
#define ADC_Channel_2 ((uint8_t)0x02)
#define ADC_Channel_3 ((uint8_t)0x03)
#define ADC_Channel_4 ((uint8_t)0x04)
#define ADC_Channel_5 ((uint8_t)0x05)
#define ADC_Channel_6 ((uint8_t)0x06)
#define ADC_Channel_7 ((uint8_t)0x07)
#define ADC_Channel_8 ((uint8_t)0x08)
#define ADC_Channel_All ((uint8_t)0x0f)
#define IS_ADC_CHANNEL(CHANNEL) (((CHANNEL) == ADC_Channel_0) || ((CHANNEL) == ADC_Channel_1) || \
((CHANNEL) == ADC_Channel_2) || ((CHANNEL) == ADC_Channel_3) || \
((CHANNEL) == ADC_Channel_4) || ((CHANNEL) == ADC_Channel_5) || \
((CHANNEL) == ADC_Channel_6) || ((CHANNEL) == ADC_Channel_7) || \
((CHANNEL) == ADC_Channel_8) || ((CHANNEL) == ADC_Channel_All))
/**
* @}
*/
/**
* @}
*/
#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
* @{
*/
#define ADC_SampleTime_1_5Cycles ((uint32_t)0x00000000)
#define ADC_SampleTime_7_5Cycles ((uint32_t)0x00000001)
#define ADC_SampleTime_13_5Cycles ((uint32_t)0x00000002)
#define ADC_SampleTime_28_5Cycles ((uint32_t)0x00000003)
#define ADC_SampleTime_41_5Cycles ((uint32_t)0x00000004)
#define ADC_SampleTime_55_5Cycles ((uint32_t)0x00000005)
#define ADC_SampleTime_71_5Cycles ((uint32_t)0x00000006)
#define ADC_SampleTime_239_5Cycles ((uint32_t)0x00000007)
#define IS_ADC_SAMPLE_TIME(TIME) (((TIME) == ADC_SampleTime_1_5Cycles) || \
((TIME) == ADC_SampleTime_7_5Cycles) || \
((TIME) == ADC_SampleTime_13_5Cycles) || \
((TIME) == ADC_SampleTime_28_5Cycles) || \
((TIME) == ADC_SampleTime_41_5Cycles) || \
((TIME) == ADC_SampleTime_55_5Cycles) || \
((TIME) == ADC_SampleTime_71_5Cycles) || \
((TIME) == ADC_SampleTime_239_5Cycles))
/** @defgroup ADC_injected_channel_selection
* @{
*/
#define ADC_InjectedChannel_0 ((uint8_t)0x18)
#define ADC_InjectedChannel_1 ((uint8_t)0x1C)
#define ADC_InjectedChannel_2 ((uint8_t)0x20)
#define ADC_InjectedChannel_3 ((uint8_t)0x24)
#define ADC_InjectedChannel_4 ((uint8_t)0x28)
#define ADC_InjectedChannel_5 ((uint8_t)0x2C)
#define ADC_InjectedChannel_6 ((uint8_t)0x30)
#define ADC_InjectedChannel_7 ((uint8_t)0x34)
#define ADC_InjectedChannel_8 ((uint8_t)0x38)
#define IS_ADC_INJECTED_CHANNEL(CHANNEL) (((CHANNEL) == ADC_InjectedChannel_1) || \
((CHANNEL) == ADC_InjectedChannel_2) || \
((CHANNEL) == ADC_InjectedChannel_3) || \
((CHANNEL) == ADC_InjectedChannel_4) || \
((CHANNEL) == ADC_InjectedChannel_5) || \
((CHANNEL) == ADC_InjectedChannel_6) || \
((CHANNEL) == ADC_InjectedChannel_7) || \
((CHANNEL) == ADC_InjectedChannel_8))
/**
* @}
*/
/** @defgroup ADC_analog_watchdog_selection
* @{
*/
#define ADC_AnalogWatchdog_SingleRegEnable ((uint32_t)0x00000002)
#define ADC_AnalogWatchdog_None ((uint32_t)0x00000000)
#define IS_ADC_ANALOG_WATCHDOG(WATCHDOG) (((WATCHDOG) == ADC_AnalogWatchdog_SingleRegEnable) || \
((WATCHDOG) == ADC_AnalogWatchdog_None))
/**
* @}
*/
/** @defgroup ADC_interrupts_definition
* @{
*/
#define ADC_IT_EOC ((uint16_t)0x0001)
#define ADC_IT_AWD ((uint16_t)0x0002)
#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))
/**
* @}
*/
/** @defgroup ADC_flags_definition
* @{
*/
#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))
/**
* @}
*/
/** @defgroup ADC_thresholds
* @{
*/
#define IS_ADC_THRESHOLD(THRESHOLD) ((THRESHOLD) <= 0xFFF)
/**
* @}
*/
/** @defgroup ADC_injected_offset
* @{
*/
#define IS_ADC_OFFSET(OFFSET) ((OFFSET) <= 0xFFF)
/**
* @}
*/
/** @defgroup ADC_injected_length
* @{
*/
#define IS_ADC_INJECTED_LENGTH(LENGTH) (((LENGTH) >= 0x1) && ((LENGTH) <= 0x4))
/**
* @}
*/
/** @defgroup ADC_injected_rank
* @{
*/
#define IS_ADC_INJECTED_RANK(RANK) (((RANK) >= 0x1) && ((RANK) <= 0x4))
/**
* @}
*/
/** @defgroup ADC_regular_length
* @{
*/
#define IS_ADC_REGULAR_LENGTH(LENGTH) (((LENGTH) >= 0x1) && ((LENGTH) <= 0x10))
/**
* @}
*/
/** @defgroup ADC_regular_rank
* @{
*/
#define IS_ADC_REGULAR_RANK(RANK) (((RANK) >= 0x1) && ((RANK) <= 0x10))
/**
* @}
*/
/** @defgroup ADC_regular_discontinuous_mode_number
* @{
*/
#define IS_ADC_REGULAR_DISC_NUMBER(NUMBER) (((NUMBER) >= 0x1) && ((NUMBER) <= 0x8))
/**
* @}
*/
/**
* @}
*/
/** @defgroup ADC_Exported_Macros
* @{
*/
/**
* @}
*/
/** @defgroup ADC_Exported_Functions
* @{
*/
void ADC_DeInit(ADC_TypeDef* ADCx);
void ADC_Init(ADC_TypeDef* ADCx, ADC_InitTypeDef* ADC_InitStruct);
void ADC_StructInit(ADC_InitTypeDef* ADC_InitStruct);
void ADC_Cmd(ADC_TypeDef* ADCx, FunctionalState NewState);
void ADC_DMACmd(ADC_TypeDef* ADCx, FunctionalState NewState);
void ADC_ITConfig(ADC_TypeDef* ADCx, uint16_t ADC_IT, FunctionalState NewState);
void ADC_SoftwareStartConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState);
FlagStatus ADC_GetSoftwareStartConvStatus(ADC_TypeDef* ADCx);
void ADC_RegularChannelConfig(ADC_TypeDef* ADCx, uint8_t ADC_Channel, uint8_t Rank, uint8_t ADC_SampleTime);
void ADC_ExternalTrigConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState);
uint16_t ADC_GetConversionValue(ADC_TypeDef* ADCx);
void ADC_ExternalTrigInjectedConvConfig(ADC_TypeDef* ADCx, uint32_t ADC_ExternalTrigInjecConv);
void ADC_ExternalTrigInjectedConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState);
void ADC_SoftwareStartInjectedConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState);
void ADC_AnalogWatchdogCmd(ADC_TypeDef* ADCx, uint32_t ADC_AnalogWatchdog);
void ADC_AnalogWatchdogThresholdsConfig(ADC_TypeDef* ADCx, uint16_t HighThreshold, uint16_t LowThreshold);
void ADC_AnalogWatchdogSingleChannelConfig(ADC_TypeDef* ADCx, uint8_t ADC_Channel);
void ADC_TempSensorVrefintCmd(FunctionalState NewState);
FlagStatus ADC_GetFlagStatus(ADC_TypeDef* ADCx, uint8_t ADC_FLAG);
void ADC_ClearFlag(ADC_TypeDef* ADCx, uint8_t ADC_FLAG);
ITStatus ADC_GetITStatus(ADC_TypeDef* ADCx, uint16_t ADC_IT);
void ADC_ClearITPendingBit(ADC_TypeDef* ADCx, uint16_t ADC_IT);
#endif /*__HAL_ADC_H */
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/*-------------------------(C) COPYRIGHT 2016 HOLOCENE ----------------------*/
/**
******************************************************************************
* @file HAL_can.h
* @author IC Applications Department
* @version V0.8
* @date 2019_08_02
* @brief This file provides all the CAN firmware functions.
******************************************************************************
* @copy
*
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
* TIME. AS A RESULT, HOLOCENE SHALL NOT BE HELD LIABLE FOR ANY
* DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
* FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
* CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*
* <h2><center>&copy; COPYRIGHT 2016 HOLOCENE</center></h2>
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __HAL_CAN_H
#define __HAL_CAN_H
/* Includes ------------------------------------------------------------------*/
#include "HAL_device.h"
/** @defgroup CAN_sleep_constants
* @{
*/
#define CANINITFAILED ((uint8_t)0x00) /* CAN initialization failed */
#define CANINITOK ((uint8_t)0x01) /* CAN initialization ok */
/**
* @}
*/
/** @defgroup CAN_sleep_constants
* @{
*/
#define CANSLEEPFAILED ((uint8_t)0x00) /* CAN did not enter the sleep mode */
#define CANSLEEPOK ((uint8_t)0x01) /* CAN entered the sleep mode */
/**
* @}
*/
/** @defgroup CAN_wake_up_constants
* @{
*/
#define CANWAKEUPFAILED ((uint8_t)0x00) /* CAN did not leave the sleep mode */
#define CANWAKEUPOK ((uint8_t)0x01) /* CAN leaved the sleep mode */
/**
* @}
*/
/**
* @brief parasmeter of CAN Mode
*/
#define CAN_BASICMode ((uint32_t)0x0)
#define CAN_PELIMode ((uint32_t)0x80)
#define CAN_WorkMode ((uint32_t)0x80)
#define CAN_ResetMode ((uint32_t)0x1)
#define CAN_ListenOnlyMode ((uint32_t)0x2)
#define CAN_SeftTestMode ((uint32_t)0x4)
#define CAN_FilterMode_Singal ((uint32_t)0x8)
#define CAN_FilterMode_Double ((uint32_t)0xf7)
#define CAN_SleepMode ((uint32_t)0x10)
/**
* @}
*/
/**
* @brief parasmeter of BASIC CAN interrupt
*/
#define CAN_IT_RIE ((uint32_t)0x2)
#define CAN_IT_TIE ((uint32_t)0x4)
#define CAN_IT_EIE ((uint32_t)0x8)
#define CAN_IT_OIE ((uint32_t)0x10)
/**
* @}
*/
/**
* @brief parasmeter of PELI CAN interrupt
*/
#define CAN_IT_RI ((uint32_t)0x1)
#define CAN_IT_TI ((uint32_t)0x2)
#define CAN_IT_EI ((uint32_t)0x4)
#define CAN_IT_DOI ((uint32_t)0x8)
#define CAN_IT_WUI ((uint32_t)0x10)
#define CAN_IT_EPI ((uint32_t)0x20)
#define CAN_IT_ALI ((uint32_t)0x40)
#define CAN_IT_BEI ((uint32_t)0x80)
#define CAN_IT_ALL ((uint32_t)0xff)
/**
* @}
*/
/**
* @brief parasmeter of CAN Status
*/
#define CAN_STATUS_RBS ((uint32_t)0x1)
#define CAN_STATUS_DOS ((uint32_t)0x2)
#define CAN_STATUS_TBS ((uint32_t)0x4)
#define CAN_STATUS_TCS ((uint32_t)0x8)
#define CAN_STATUS_RS ((uint32_t)0x10)
#define CAN_STATUS_TS ((uint32_t)0x20)
#define CAN_STATUS_ES ((uint32_t)0x40)
#define CAN_STATUS_BS ((uint32_t)0x80)
/**
* @}
*/
/**
* @brief parasmeter of CAN Command register
*/
#define CAN_TR 0x1
#define CAN_AT 0x2
#define CAN_RRB 0x4
#define CAN_CDO 0x8
/**
* @}
*/
/**
* @brief CAN_Basic init structure definition
*/
typedef struct
{
uint8_t SJW;
uint8_t BRP;
FlagStatus SAM;
uint8_t TESG2;
uint8_t TESG1;
FunctionalState GTS;
uint8_t CDCLK;
uint8_t CLOSE_OPEN_CLK;
uint8_t RXINTEN;
uint8_t CBP;
} CAN_Basic_InitTypeDef;
/**
* @}
*/
/**
* @brief CAN_Peli init structure definition
*/
typedef struct
{
uint8_t SJW;
uint8_t BRP;
FlagStatus SAM;
uint8_t TESG2;
uint8_t TESG1;
FunctionalState LOM;
FunctionalState STM;
FunctionalState SM;
FunctionalState SRR;
uint32_t EWLR;
} CAN_Peli_InitTypeDef;
/**
* @}
*/
/**
* @brief CAN_Basic filter init structure definition
*/
typedef struct
{
uint8_t CAN_FilterId; /*!< Specifies the filter identification number .
This parameter can be a value between 0x00 and 0xFF */
uint8_t CAN_FilterMaskId; /*!< Specifies the filter mask number or identification number,
This parameter can be a value between 0x00 and 0xFF */
} CAN_Basic_FilterInitTypeDef;
/**
* @}
*/
/**
* @brief CAN_Peli filter init structure definition
*/
typedef struct
{
uint8_t AFM;
uint8_t CAN_FilterId0; /*!< Specifies the filter identification number
This parameter can be a value between 0x00 and 0xFF */
uint8_t CAN_FilterId1;
uint8_t CAN_FilterId2;
uint8_t CAN_FilterId3;
uint8_t CAN_FilterMaskId0; /*!< Specifies the filter mask number or identification number,
This parameter can be a value between 0x00 and 0xFF */
uint8_t CAN_FilterMaskId1;
uint8_t CAN_FilterMaskId2;
uint8_t CAN_FilterMaskId3;
} CAN_Peli_FilterInitTypeDef;
/**
* @}
*/
/**
* @brief CAN_Peli transmit frame definition
*/
typedef enum {DataFrame = 0, RemoteFrame = !DataFrame} TransFrame;
/**
* @}
*/
/**
* @brief CAN_Basic Tx message structure definition
*/
typedef struct
{
uint8_t IDH; /*!< Specifies the standard high identifier.
This parameter can be a value between 0 to 0xFF. */
uint8_t IDL; /*!< Specifies the standard low identifier.
This parameter can be a value between 0 to 0x7. */
uint8_t RTR; /*!< Specifies the type of frame for the message that will
be transmitted. This parameter can be @TransFrame */
uint8_t DLC; /*!< Specifies the length of the frame that will be
transmitted. This parameter can be a value between
0 to 8 */
uint8_t Data[8]; /*!< Contains the data to be transmitted. It ranges from 0
to 0xFF. */
} CanBasicTxMsg;
/**
* @}
*/
/**
* @brief CAN_Basic Rx message structure definition
*/
typedef struct
{
uint16_t ID; /*!< Specifies the standard identifier.
This parameter can be a value between 0 to 0x7FF. */
uint8_t RTR; /*!< Specifies the type of frame for the received message.
This parameter can be a value of
@ref TransFrame */
uint8_t DLC; /*!< Specifies the length of the frame that will be received.
This parameter can be a value between 0 to 8 */
uint8_t Data[8]; /*!< Contains the data to be received. It ranges from 0 to
0xFF. */
} CanBasicRxMsg;
/**
* @}
*/
/**
* @brief CAN_Peli_Tx message structure definition
*/
typedef struct
{
uint8_t IDLL; /*!< Specifies the extended identifier.
This parameter can be a value between 0 to 0xFF. */
uint8_t IDLH;
uint8_t IDHL;
uint8_t IDHH;
uint8_t FF; /*!< Specifies the type of identifier for the message that
will be transmitted. This parameter can be a value
of @ref CAN_identifier_type */
uint8_t RTR; /*!< Specifies the type of frame for the message that will
be transmitted. This parameter can be a value of
@ref TransFrame */
uint8_t DLC; /*!< Specifies the length of the frame that will be
transmitted. This parameter can be a value between
0 to 8 */
uint8_t Data[8]; /*!< Contains the data to be transmitted. It ranges from 0
to 0xFF. */
} CanPeliTxMsg;
/**
* @}
*/
/**
* @brief CAN Rx message structure definition
*/
typedef struct
{
uint32_t ID; /*!< Specifies the extended identifier.
This parameter can be a value between 0 to 0x1FFFFFFF. */
uint8_t FF; /*!< Specifies the type of identifier for the message that
will be received. This parameter can be a value of
@ref CAN_identifier_type */
uint8_t RTR; /*!< Specifies the type of frame for the received message.
This parameter can be a value of
@ref TransFrame */
uint8_t DLC; /*!< Specifies the length of the frame that will be received.
This parameter can be a value between 0 to 8 */
uint8_t Data[8]; /*!< Contains the data to be received. It ranges from 0 to
0xFF. */
} CanPeliRxMsg;
#define CANTXFAILED ((uint8_t)0x00) /* CAN transmission failed */
#define CANTXOK ((uint8_t)0x01) /* CAN transmission succeeded */
#define CANTXPENDING ((uint8_t)0x02) /* CAN transmission pending */
#define CAN_NO_MB ((uint8_t)0x04) /* CAN cell did not provide an empty mailbox */
/************************ Basic and Peli Work all need function ********************/
void CAN_Mode_Cmd(CAN_TypeDef* CANx, uint32_t CAN_MODE);
void CAN_ResetMode_Cmd(CAN_TypeDef* CANx, FunctionalState NewState);
void CAN_ClearDataOverflow(CAN_TypeDef* CANx);
void CAN_ClearITPendingBit(CAN_TypeDef* CANx);
/************************ Basic Work function ********************/
void CAN_DeInit(CAN_TypeDef* CANx);
uint8_t CAN_Init(CAN_TypeDef* CANx, CAN_Basic_InitTypeDef* CAN_Basic_InitStruct);
void CAN_FilterInit(CAN_TypeDef* CANx, CAN_Basic_FilterInitTypeDef* CAN_Basic_FilterInitStruct);
void CAN_StructInit(CAN_Basic_InitTypeDef* CAN_Basic_InitStruct);
void CAN_ITConfig(CAN_TypeDef* CANx, uint32_t CAN_IT, FunctionalState Newstate);
uint8_t CAN_Transmit(CAN_TypeDef* CANx, CanBasicTxMsg* BasicTxMessage);
void CAN_CancelTransmit(CAN_TypeDef* CANx);
void CAN_FIFORelease(CAN_TypeDef* CANx);
void CAN_Receive(CAN_TypeDef* CANx, CanBasicRxMsg* BasicRxMessage);
uint8_t CAN_Sleep(CAN_TypeDef* CANx);
uint8_t CAN_WakeUp(CAN_TypeDef* CANx);
FlagStatus CAN_GetFlagStatus(CAN_TypeDef* CANx, uint32_t CAN_FLAG);
ITStatus CAN_GetITStatus(CAN_TypeDef* CANx, uint32_t CAN_IT);
/************************ Peli Work function *********************/
void CAN_Peli_SleepMode_Cmd(CAN_TypeDef* CANx, FunctionalState NewState);
void CAN_Peli_Init(CAN_TypeDef* CANx, CAN_Peli_InitTypeDef* CAN_Peli_InitStruct);
void CAN_Peli_StructInit(CAN_Peli_InitTypeDef* CAN_Peli_InitStruct);
void CAN_Peli_FilterInit(CAN_TypeDef* CANx, CAN_Peli_FilterInitTypeDef* CAN_Peli_FilterInitStruct);
void CAN_Peli_FilterStructInit(CAN_Peli_FilterInitTypeDef* CAN_Peli_FilterInitStruct);
void CAN_Peli_Transmit(CAN_TypeDef* CANx, CanPeliTxMsg* PeliTxMessage);
void CAN_Peli_TransmitRepeat(CAN_TypeDef* CANx, CanPeliTxMsg* PeliTxMessage);
void CAN_Peli_Receive(CAN_TypeDef* CANx, CanPeliRxMsg* PeliRxMessage);
uint32_t CAN_Peli_GetRxFIFOInfo(CAN_TypeDef* CANx);
uint8_t CAN_Peli_GetLastErrorCode(CAN_TypeDef* CANx);
uint8_t CAN_Peli_GetReceiveErrorCounter(CAN_TypeDef* CANx);
uint8_t CAN_Peli_GetLSBTransmitErrorCounter(CAN_TypeDef* CANx);
void CAN_Peli_ITConfig(CAN_TypeDef* CANx, uint32_t CAN_IT, FunctionalState NewState);
ITStatus CAN_Peli_GetITStatus(CAN_TypeDef* CANx, uint32_t CAN_IT);
void CAN_AutoCfg_BaudParam(CAN_Peli_InitTypeDef *CAN_Peli_InitStruct, unsigned int SrcClk, unsigned int baud );
#endif /* __HAL_CAN_H */
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/*-------------------------(C) COPYRIGHT 2016 HOLOCENE ----------------------*/
/**
******************************************************************************
* @file HAL_conf.h
* @author IC Applications Department
* @version V0.8
* @date 2019_08_02
* @brief This file contains Header file for generic microcontroller.
******************************************************************************
* @copy
*
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
* TIME. AS A RESULT, HOLOCENE SHALL NOT BE HELD LIABLE FOR ANY
* DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
* FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
* CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*
* <h2><center>&copy; COPYRIGHT 2016 HOLOCENE</center></h2>
*/
#ifndef __HAL_CONF_H__
#define __HAL_CONF_H__
/*此处可添加或删除外设*/
#include "HAL_device.h"
#include "HAL_adc.h"
#include "HAL_dma.h"
#include "HAL_exti.h"
#include "HAL_flash.h"
#include "HAL_gpio.h"
#include "HAL_i2c.h"
#include "HAL_iwdg.h"
#include "HAL_pwr.h"
#include "HAL_rcc.h"
#include "HAL_spi.h"
#include "HAL_tim.h"
#include "HAL_uart.h"
#include "HAL_wwdg.h"
#include "HAL_misc.h"
#include "HAL_syscfg.h"
#include "HAL_can.h"
#endif
/*-------------------------(C) COPYRIGHT 2016 HOLOCENE ----------------------*/
/**************************************************************************//**
* @file HAL_device.h
* @brief CMSIS Cortex-M Peripheral Access Layer for HOLOCENE
* microcontroller devices
*
* This is a convenience header file for defining the part number on the
* build command line, instead of specifying the part specific header file.
*
* Example: Add "-TKM32F499" to your build options, to define part
* Add "#include "HAL_device.h" to your source files
*
*
* @version 1.5.0
*
*
*****************************************************************************/
#ifndef __HAL_device_H
#define __HAL_device_H
#include "tk499.h"
#endif /* __HAL_device_H */
/*-------------------------(C) COPYRIGHT 2016 HOLOCENE ----------------------*/
/**
******************************************************************************
* @file HAL_dma.h
* @author IC Applications Department
* @version V0.8
* @date 2019_08_02
* @brief This file contains all the functions prototypes for the DMA firmware
* library.
******************************************************************************
* @copy
*
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
* TIME. AS A RESULT, HOLOCENE SHALL NOT BE HELD LIABLE FOR ANY
* DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
* FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
* CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*
* <h2><center>&copy; COPYRIGHT 2016 HOLOCENE</center></h2>
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __HAL_DMA_H
#define __HAL_DMA_H
/* Includes ------------------------------------------------------------------*/
#include "HAL_device.h"
/** @addtogroup StdPeriph_Driver
* @{
*/
/** @addtogroup DMA
* @{
*/
/** @defgroup DMA_Exported_Types
* @{
*/
/**
* @brief DMA Init structure definition
*/
typedef struct
{
uint32_t DMA_PeripheralBaseAddr;
uint32_t DMA_MemoryBaseAddr;
uint32_t DMA_DIR;
uint32_t DMA_BufferSize;
uint32_t DMA_PeripheralInc;
uint32_t DMA_MemoryInc;
uint32_t DMA_PeripheralDataSize;
uint32_t DMA_MemoryDataSize;
uint32_t DMA_Mode;
uint32_t DMA_Priority;
uint32_t DMA_M2M;
}DMA_InitTypeDef;
/**
* @}
*/
/** @defgroup DMA_Exported_Constants
* @{
*/
#define IS_DMA_ALL_PERIPH(PERIPH) (((*(uint32_t*)&(PERIPH)) == DMA1_Channel1_BASE) || \
((*(uint32_t*)&(PERIPH)) == DMA1_Channel2_BASE) || \
((*(uint32_t*)&(PERIPH)) == DMA1_Channel3_BASE) || \
((*(uint32_t*)&(PERIPH)) == DMA1_Channel4_BASE) || \
((*(uint32_t*)&(PERIPH)) == DMA1_Channel5_BASE))
/** @defgroup DMA_data_transfer_direction
* @{
*/
#define DMA_DIR_PeripheralDST ((uint32_t)0x00000010) //mtop
#define DMA_DIR_PeripheralSRC ((uint32_t)0x00000000) //ptom
#define IS_DMA_DIR(DIR) (((DIR) == DMA_DIR_PeripheralDST) || \
((DIR) == DMA_DIR_PeripheralSRC))
/**
* @}
*/
/** @defgroup DMA_peripheral_incremented_mode
* @{
*/
#define DMA_PeripheralInc_Enable ((uint32_t)0x00000040)
#define DMA_PeripheralInc_Disable ((uint32_t)0x00000000)
#define IS_DMA_PERIPHERAL_INC_STATE(STATE) (((STATE) == DMA_PeripheralInc_Enable) || \
((STATE) == DMA_PeripheralInc_Disable))
/**
* @}
*/
/** @defgroup DMA_memory_incremented_mode
* @{
*/
#define DMA_MemoryInc_Enable ((uint32_t)0x00000080)
#define DMA_MemoryInc_Disable ((uint32_t)0x00000000)
#define IS_DMA_MEMORY_INC_STATE(STATE) (((STATE) == DMA_MemoryInc_Enable) || \
((STATE) == DMA_MemoryInc_Disable))
/**
* @}
*/
/** @defgroup DMA_peripheral_data_size
* @{
*/
#define DMA_PeripheralDataSize_Byte ((uint32_t)0x00000000)
#define DMA_PeripheralDataSize_HalfWord ((uint32_t)0x00000100)
#define DMA_PeripheralDataSize_Word ((uint32_t)0x00000200)
#define IS_DMA_PERIPHERAL_DATA_SIZE(SIZE) (((SIZE) == DMA_PeripheralDataSize_Byte) || \
((SIZE) == DMA_PeripheralDataSize_HalfWord) || \
((SIZE) == DMA_PeripheralDataSize_Word))
/**
* @}
*/
/** @defgroup DMA_memory_data_size
* @{
*/
#define DMA_MemoryDataSize_Byte ((uint32_t)0x00000000)
#define DMA_MemoryDataSize_HalfWord ((uint32_t)0x00000400)
#define DMA_MemoryDataSize_Word ((uint32_t)0x00000800)
#define IS_DMA_MEMORY_DATA_SIZE(SIZE) (((SIZE) == DMA_MemoryDataSize_Byte) || \
((SIZE) == DMA_MemoryDataSize_HalfWord) || \
((SIZE) == DMA_MemoryDataSize_Word))
/**
* @}
*/
/** @defgroup DMA_circular_normal_mode
* @{
*/
#define DMA_Mode_Circular ((uint32_t)0x00000020)
#define DMA_Mode_Normal ((uint32_t)0x00000000)
#define IS_DMA_MODE(MODE) (((MODE) == DMA_Mode_Circular) || ((MODE) == DMA_Mode_Normal))
/**
* @}
*/
/** @defgroup DMA_priority_level
* @{
*/
#define DMA_Priority_VeryHigh ((uint32_t)0x00003000)
#define DMA_Priority_High ((uint32_t)0x00002000)
#define DMA_Priority_Medium ((uint32_t)0x00001000)
#define DMA_Priority_Low ((uint32_t)0x00000000)
#define IS_DMA_PRIORITY(PRIORITY) (((PRIORITY) == DMA_Priority_VeryHigh) || \
((PRIORITY) == DMA_Priority_High) || \
((PRIORITY) == DMA_Priority_Medium) || \
((PRIORITY) == DMA_Priority_Low))
/**
* @}
*/
/** @defgroup DMA_memory_to_memory
* @{
*/
#define DMA_M2M_Enable ((uint32_t)0x00004000)
#define DMA_M2M_Disable ((uint32_t)0x00000000)
#define IS_DMA_M2M_STATE(STATE) (((STATE) == DMA_M2M_Enable) || ((STATE) == DMA_M2M_Disable))
/**
* @}
*/
/** @defgroup DMA_interrupts_definition
* @{
*/
#define DMA_IT_TC ((uint32_t)0x00000002)
#define DMA_IT_HT ((uint32_t)0x00000004)
#define DMA_IT_TE ((uint32_t)0x00000008)
#define IS_DMA_CONFIG_IT(IT) ((((IT) & 0xFFFFFFF1) == 0x00) && ((IT) != 0x00))
/**
* @brief For DMA1
*/
#define DMA1_IT_GL1 ((uint32_t)0x00000001)
#define DMA1_IT_TC1 ((uint32_t)0x00000002)
#define DMA1_IT_HT1 ((uint32_t)0x00000004)
#define DMA1_IT_TE1 ((uint32_t)0x00000008)
#define DMA1_IT_GL2 ((uint32_t)0x00000010)
#define DMA1_IT_TC2 ((uint32_t)0x00000020)
#define DMA1_IT_HT2 ((uint32_t)0x00000040)
#define DMA1_IT_TE2 ((uint32_t)0x00000080)
#define DMA1_IT_GL3 ((uint32_t)0x00000100)
#define DMA1_IT_TC3 ((uint32_t)0x00000200)
#define DMA1_IT_HT3 ((uint32_t)0x00000400)
#define DMA1_IT_TE3 ((uint32_t)0x00000800)
#define DMA1_IT_GL4 ((uint32_t)0x00001000)
#define DMA1_IT_TC4 ((uint32_t)0x00002000)
#define DMA1_IT_HT4 ((uint32_t)0x00004000)
#define DMA1_IT_TE4 ((uint32_t)0x00008000)
#define DMA1_IT_GL5 ((uint32_t)0x00010000)
#define DMA1_IT_TC5 ((uint32_t)0x00020000)
#define DMA1_IT_HT5 ((uint32_t)0x00040000)
#define DMA1_IT_TE5 ((uint32_t)0x00080000)
#define DMA2_IT_GL1 ((uint32_t)0x10000001)
#define DMA2_IT_TC1 ((uint32_t)0x10000002)
#define DMA2_IT_HT1 ((uint32_t)0x10000004)
#define DMA2_IT_TE1 ((uint32_t)0x10000008)
#define DMA2_IT_GL2 ((uint32_t)0x10000010)
#define DMA2_IT_TC2 ((uint32_t)0x10000020)
#define DMA2_IT_HT2 ((uint32_t)0x10000040)
#define DMA2_IT_TE2 ((uint32_t)0x10000080)
#define DMA2_IT_GL3 ((uint32_t)0x10000100)
#define DMA2_IT_TC3 ((uint32_t)0x10000200)
#define DMA2_IT_HT3 ((uint32_t)0x10000400)
#define DMA2_IT_TE3 ((uint32_t)0x10000800)
#define DMA2_IT_GL4 ((uint32_t)0x10001000)
#define DMA2_IT_TC4 ((uint32_t)0x10002000)
#define DMA2_IT_HT4 ((uint32_t)0x10004000)
#define DMA2_IT_TE4 ((uint32_t)0x10008000)
#define DMA2_IT_GL5 ((uint32_t)0x10010000)
#define DMA2_IT_TC5 ((uint32_t)0x10020000)
#define DMA2_IT_HT5 ((uint32_t)0x10040000)
#define DMA2_IT_TE5 ((uint32_t)0x10080000)
#define DMA2_IT_GL6 ((uint32_t)0x10100000)
#define DMA2_IT_TC6 ((uint32_t)0x10200000)
#define DMA2_IT_HT6 ((uint32_t)0x10400000)
#define DMA2_IT_TE6 ((uint32_t)0x10800000)
#define DMA2_IT_GL7 ((uint32_t)0x11000000)
#define DMA2_IT_TC7 ((uint32_t)0x12000000)
#define DMA2_IT_HT7 ((uint32_t)0x14000000)
#define DMA2_IT_TE7 ((uint32_t)0x18000000)
#define DMA2_IT_GL8 ((uint32_t)0x10000001)
#define DMA2_IT_TC8 ((uint32_t)0x20000001)
#define DMA2_IT_HT8 ((uint32_t)0x40000001)
#define DMA2_IT_TE8 ((uint32_t)0x80000001)
#define IS_DMA_CLEAR_IT(IT) (((((IT) & 0xF0000000) == 0x00) || (((IT) & 0xEFF00000) == 0x00)) && ((IT) != 0x00))
#define IS_DMA_GET_IT(IT) (((IT) == DMA1_IT_GL1) || ((IT) == DMA1_IT_TC1) || \
((IT) == DMA1_IT_HT1) || ((IT) == DMA1_IT_TE1) || \
((IT) == DMA1_IT_GL2) || ((IT) == DMA1_IT_TC2) || \
((IT) == DMA1_IT_HT2) || ((IT) == DMA1_IT_TE2) || \
((IT) == DMA1_IT_GL3) || ((IT) == DMA1_IT_TC3) || \
((IT) == DMA1_IT_HT3) || ((IT) == DMA1_IT_TE3) || \
((IT) == DMA1_IT_GL4) || ((IT) == DMA1_IT_TC4) || \
((IT) == DMA1_IT_HT4) || ((IT) == DMA1_IT_TE4) || \
((IT) == DMA1_IT_GL5) || ((IT) == DMA1_IT_TC5) || \
((IT) == DMA1_IT_HT5) || ((IT) == DMA1_IT_TE5))
/**
* @}
*/
/** @defgroup DMA_flags_definition
* @{
*/
/**
* @brief For DMA1
*/
#define DMA1_FLAG_GL1 ((uint32_t)0x00000001)
#define DMA1_FLAG_TC1 ((uint32_t)0x00000002)
#define DMA1_FLAG_HT1 ((uint32_t)0x00000004)
#define DMA1_FLAG_TE1 ((uint32_t)0x00000008)
#define DMA1_FLAG_GL2 ((uint32_t)0x00000010)
#define DMA1_FLAG_TC2 ((uint32_t)0x00000020)
#define DMA1_FLAG_HT2 ((uint32_t)0x00000040)
#define DMA1_FLAG_TE2 ((uint32_t)0x00000080)
#define DMA1_FLAG_GL3 ((uint32_t)0x00000100)
#define DMA1_FLAG_TC3 ((uint32_t)0x00000200)
#define DMA1_FLAG_HT3 ((uint32_t)0x00000400)
#define DMA1_FLAG_TE3 ((uint32_t)0x00000800)
#define DMA1_FLAG_GL4 ((uint32_t)0x00001000)
#define DMA1_FLAG_TC4 ((uint32_t)0x00002000)
#define DMA1_FLAG_HT4 ((uint32_t)0x00004000)
#define DMA1_FLAG_TE4 ((uint32_t)0x00008000)
#define DMA1_FLAG_GL5 ((uint32_t)0x00010000)
#define DMA1_FLAG_TC5 ((uint32_t)0x00020000)
#define DMA1_FLAG_HT5 ((uint32_t)0x00040000)
#define DMA1_FLAG_TE5 ((uint32_t)0x00080000)
#define DMA1_FLAG_GL6 ((uint32_t)0x00100000)
#define DMA1_FLAG_TC6 ((uint32_t)0x00200000)
#define DMA1_FLAG_HT6 ((uint32_t)0x00400000)
#define DMA1_FLAG_TE6 ((uint32_t)0x00800000)
#define DMA1_FLAG_GL7 ((uint32_t)0x01000000)
#define DMA1_FLAG_TC7 ((uint32_t)0x02000000)
#define DMA1_FLAG_HT7 ((uint32_t)0x04000000)
#define DMA1_FLAG_TE7 ((uint32_t)0x08000000)
#define DMA1_FLAG_GL8 ((uint32_t)0x10000000)
#define DMA1_FLAG_TC8 ((uint32_t)0x20000000)
#define DMA1_FLAG_HT8 ((uint32_t)0x40000000)
#define DMA1_FLAG_TE8 ((uint32_t)0x80000000)
#define DMA2_FLAG_GL1 ((uint32_t)0x10000001)
#define DMA2_FLAG_TC1 ((uint32_t)0x10000002)
#define DMA2_FLAG_HT1 ((uint32_t)0x10000004)
#define DMA2_FLAG_TE1 ((uint32_t)0x10000008)
#define DMA2_FLAG_GL2 ((uint32_t)0x10000010)
#define DMA2_FLAG_TC2 ((uint32_t)0x10000020)
#define DMA2_FLAG_HT2 ((uint32_t)0x10000040)
#define DMA2_FLAG_TE2 ((uint32_t)0x10000080)
#define DMA2_FLAG_GL3 ((uint32_t)0x10000100)
#define DMA2_FLAG_TC3 ((uint32_t)0x10000200)
#define DMA2_FLAG_HT3 ((uint32_t)0x10000400)
#define DMA2_FLAG_TE3 ((uint32_t)0x10000800)
#define DMA2_FLAG_GL4 ((uint32_t)0x10001000)
#define DMA2_FLAG_TC4 ((uint32_t)0x10002000)
#define DMA2_FLAG_HT4 ((uint32_t)0x10004000)
#define DMA2_FLAG_TE4 ((uint32_t)0x10008000)
#define DMA2_FLAG_GL5 ((uint32_t)0x10010000)
#define DMA2_FLAG_TC5 ((uint32_t)0x10020000)
#define DMA2_FLAG_HT5 ((uint32_t)0x10040000)
#define DMA2_FLAG_TE5 ((uint32_t)0x10080000)
#define DMA2_FLAG_GL6 ((uint32_t)0x10100000)
#define DMA2_FLAG_TC6 ((uint32_t)0x10200000)
#define DMA2_FLAG_HT6 ((uint32_t)0x10400000)
#define DMA2_FLAG_TE6 ((uint32_t)0x10800000)
#define DMA2_FLAG_GL7 ((uint32_t)0x11000000)
#define DMA2_FLAG_TC7 ((uint32_t)0x12000000)
#define DMA2_FLAG_HT7 ((uint32_t)0x14000000)
#define DMA2_FLAG_TE7 ((uint32_t)0x18000000)
#define DMA2_FLAG_GL8 ((uint32_t)0x10000001)
#define DMA2_FLAG_TC8 ((uint32_t)0x20000001)
#define DMA2_FLAG_HT8 ((uint32_t)0x40000001)
#define DMA2_FLAG_TE8 ((uint32_t)0x80000001)
#define IS_DMA_CLEAR_FLAG(FLAG) (((((FLAG) & 0xF0000000) == 0x00) || (((FLAG) & 0xEFF00000) == 0x00)) && ((FLAG) != 0x00))
#define IS_DMA_GET_FLAG(FLAG) (((FLAG) == DMA1_FLAG_GL1) || ((FLAG) == DMA1_FLAG_TC1) || \
((FLAG) == DMA1_FLAG_HT1) || ((FLAG) == DMA1_FLAG_TE1) || \
((FLAG) == DMA1_FLAG_GL2) || ((FLAG) == DMA1_FLAG_TC2) || \
((FLAG) == DMA1_FLAG_HT2) || ((FLAG) == DMA1_FLAG_TE2) || \
((FLAG) == DMA1_FLAG_GL3) || ((FLAG) == DMA1_FLAG_TC3) || \
((FLAG) == DMA1_FLAG_HT3) || ((FLAG) == DMA1_FLAG_TE3) || \
((FLAG) == DMA1_FLAG_GL4) || ((FLAG) == DMA1_FLAG_TC4) || \
((FLAG) == DMA1_FLAG_HT4) || ((FLAG) == DMA1_FLAG_TE4) || \
((FLAG) == DMA1_FLAG_GL5) || ((FLAG) == DMA1_FLAG_TC5) || \
((FLAG) == DMA1_FLAG_HT5) || ((FLAG) == DMA1_FLAG_TE5))
/**
* @}
*/
/** @defgroup DMA_Buffer_Size
* @{
*/
#define IS_DMA_BUFFER_SIZE(SIZE) (((SIZE) >= 0x1) && ((SIZE) < 0x10000))
/**
* @}
*/
/**
* @}
*/
/** @defgroup DMA_Exported_Macros
* @{
*/
/**
* @}
*/
/** @defgroup DMA_Exported_Functions
* @{
*/
void DMA_DeInit(DMA_Channel_TypeDef* DMAy_Channelx);
void DMA_Init(DMA_Channel_TypeDef* DMAy_Channelx, DMA_InitTypeDef* DMA_InitStruct);
void DMA_StructInit(DMA_InitTypeDef* DMA_InitStruct);
void DMA_Cmd(DMA_Channel_TypeDef* DMAy_Channelx, FunctionalState NewState);
void DMA_ITConfig(DMA_Channel_TypeDef* DMAy_Channelx, uint32_t DMA_IT, FunctionalState NewState);
uint16_t DMA_GetCurrDataCounter(DMA_Channel_TypeDef* DMAy_Channelx);
FlagStatus DMA_GetFlagStatus(uint32_t DMA_FLAG);
void DMA_ClearFlag(uint32_t DMA_FLAG);
ITStatus DMA_GetITStatus(uint32_t DMA_IT);
void DMA_ClearITPendingBit(uint32_t DMA_IT);
#endif /*__HAL_DMA_H */
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/*------------------ (C) COPYRIGHT 2016 HOLOCENE ------------------*/
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
/**
******************************************************************************
* @file HAL_wwdg.h
* @author IC Applications Department
* @version V0.8
* @date 2019_08_02
* @brief This file contains all the functions prototypes for the WWDG
* firmware library.
******************************************************************************
* @copy
*
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
* TIME. AS A RESULT, HOLOCENE SHALL NOT BE HELD LIABLE FOR ANY
* DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
* FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
* CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*
* <h2><center>&copy; COPYRIGHT 2016 HOLOCENE</center></h2>
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __HAL_WWDG_H
#define __HAL_WWDG_H
/* Includes ------------------------------------------------------------------*/
#include "HAL_device.h"
/** @addtogroup StdPeriph_Driver
* @{
*/
/** @addtogroup WWDG
* @{
*/
/** @defgroup WWDG_Exported_Types
* @{
*/
/**
* @}
*/
/** @defgroup WWDG_Exported_Constants
* @{
*/
/** @defgroup WWDG_Prescaler
* @{
*/
#define WWDG_Prescaler_1 ((uint32_t)0x00000000)
#define WWDG_Prescaler_2 ((uint32_t)0x00000080)
#define WWDG_Prescaler_4 ((uint32_t)0x00000100)
#define WWDG_Prescaler_8 ((uint32_t)0x00000180)
#define IS_WWDG_PRESCALER(PRESCALER) (((PRESCALER) == WWDG_Prescaler_1) || \
((PRESCALER) == WWDG_Prescaler_2) || \
((PRESCALER) == WWDG_Prescaler_4) || \
((PRESCALER) == WWDG_Prescaler_8))
#define IS_WWDG_WINDOW_VALUE(VALUE) ((VALUE) <= 0x7F)
#define IS_WWDG_COUNTER(COUNTER) (((COUNTER) >= 0x40) && ((COUNTER) <= 0x7F))
/**
* @}
*/
/**
* @}
*/
/** @defgroup WWDG_Exported_Macros
* @{
*/
/**
* @}
*/
/** @defgroup WWDG_Exported_Functions
* @{
*/
void WWDG_DeInit(void);
void WWDG_SetPrescaler(uint32_t WWDG_Prescaler);
void WWDG_SetWindowValue(uint8_t WindowValue);
void WWDG_EnableIT(void);
void WWDG_SetCounter(uint8_t Counter);
void WWDG_Enable(uint8_t Counter);
FlagStatus WWDG_GetFlagStatus(void);
void WWDG_ClearFlag(void);
#endif /* __HAL_WWDG_H */
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/*-------------------------(C) COPYRIGHT 2016 HOLOCENE ----------------------*/
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
# for module compiling
import os
Import('RTT_ROOT')
from building import *
cwd = GetCurrentDir()
objs = []
list = os.listdir(cwd)
for d in list:
path = os.path.join(cwd, d)
if os.path.isfile(os.path.join(path, 'SConscript')):
objs = objs + SConscript(os.path.join(d, 'SConscript'))
Return('objs')
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册