合并重构代码版本

main
UESTCsecurity 2024-01-24 22:08:32 +08:00
parent 5c1551a23e
commit e03c7d92dd
183 changed files with 840 additions and 52459 deletions

View File

@ -14,7 +14,7 @@ from PyQt5.QtCore import QObject,pyqtSignal
import pb
import threading
port = "COM4"
port = "COM8"
pypibot.assistant.enableGlobalExcept()
# log.enableFileLog(log_dir + "ros_$(Date8)_$(filenumber2).log")

View File

@ -10,7 +10,7 @@ float count_ms = 0;
float reload = 0;
void PB_System_Timer_Init(void)
void System_TimerInit(void)
{
SysTick_CLKSourceConfig(SysTick_CLKSource_HCLK_Div8);//clear bit2, and using external clock HCK/8
count_us=SystemCoreClock / 8000000;

View File

@ -11,7 +11,7 @@ extern "C" {
void delay_ms(uint16_t t); // using timer to delay time, max delay time is 1864ms
void delay_us(uint16_t t); // using timer to delay time, max delay time is 1864ms
/**********************************************************************************************************************/
void PB_System_Timer_Init(void); // Initialize the Time measurement system
void System_TimerInit(void); // Initialize the Time measurement system
float getSystemTime(void); // Return the current time(us), max:281474976s--->3257.8 days
float getDeltaTime(void); // Return the time difference(us). max:655s

View File

@ -6,9 +6,10 @@ extern "C"
#include "encoder.h"
#include "nvic.h"
#include "print.h"
#define ENCODER_TIM_PERIOD (u16)(60000) // number of pulses per revolution
void Encoder_Init(TIM_TypeDef *TIMx, unsigned char GPIO_AF) // Initialize encoder mode, input parameter TIM1 TIM2 TIM3
void Encoder_InitGPIO(TIM_TypeDef *TIMx, unsigned char GPIO_AF) // Initialize encoder mode, input parameter TIM1 TIM2 TIM3
{
TIM_ICInitTypeDef TIM_ICInitStructure;
GPIO_InitTypeDef GPIO_InitStructure;
@ -19,7 +20,7 @@ extern "C"
RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2, ENABLE); /* enable clock */
if (GPIO_AF == 0)
{
//---------------------------------------------------------------TIM2 CHI1 CHI2---PA0 PA1;
// TIM2 CHI1 CHI2---PA0 PA1;
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA, ENABLE);
GPIO_StructInit(&GPIO_InitStructure);
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_0 | GPIO_Pin_1;
@ -50,7 +51,7 @@ extern "C"
RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM3 | RCC_APB2Periph_GPIOB | RCC_APB2Periph_GPIOA, ENABLE); /* enable clock */
if (GPIO_AF == 0)
{
//---------------------------------------------------------------TIM3 CHI1 CHI2---PA6 PA7;
// TIM3 CHI1 CHI2---PA6 PA7;
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA, ENABLE);
GPIO_StructInit(&GPIO_InitStructure);
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6 | GPIO_Pin_7;
@ -59,7 +60,7 @@ extern "C"
}
else if (GPIO_AF == 1)
{
//---------------------------------------------------------------TIM3 CHI1 CHI2---PB4 PB5;
// TIM3 CHI1 CHI2---PB4 PB5;
GPIO_PinRemapConfig(GPIO_PartialRemap_TIM3, ENABLE);
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOB, ENABLE);
GPIO_StructInit(&GPIO_InitStructure);
@ -75,7 +76,7 @@ extern "C"
RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM4, ENABLE); /* enable clock */
if (GPIO_AF == 0)
{
//---------------------------------------------------------------TIM4 CHI1 CHI2---PB6 PB7;
// TIM4 CHI1 CHI2---PB6 PB7;
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOB, ENABLE);
GPIO_StructInit(&GPIO_InitStructure);
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6 | GPIO_Pin_7;
@ -84,7 +85,7 @@ extern "C"
}
else if (GPIO_AF == 1)
{
//---------------------------------------------------------------TIM4 CHI1 CHI2---PD12 PD13;
// TIM4 CHI1 CHI2---PD12 PD13;
GPIO_PinRemapConfig(GPIO_Remap_TIM4, ENABLE);
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOD, ENABLE);
GPIO_StructInit(&GPIO_InitStructure);
@ -101,7 +102,7 @@ extern "C"
if (GPIO_AF == 0)
{
//---------------------------------------------------------------TIM5 CHI1 CHI2---PA0 PA1;
// TIM5 CHI1 CHI2---PA0 PA1;
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA, ENABLE);
GPIO_StructInit(&GPIO_InitStructure);
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_0 | GPIO_Pin_1;
@ -127,7 +128,7 @@ extern "C"
TIMx->CNT = 0x7fff;
}
float PB_Get_Encode_TIM2(void)
float Encoder_GetTIM2(void)
{
float cnt;
cnt = (float)((uint16_t)0x7fff) - (float)((uint16_t)(TIM2->CNT)); //! (float) is must
@ -135,7 +136,7 @@ extern "C"
return cnt;
}
float Get_EncoderTIM3(void)
float Encoder_GetTIM3(void)
{
float cnt;
cnt = (float)((uint16_t)30000) - (float)((uint16_t)(TIM3->CNT));
@ -143,7 +144,7 @@ extern "C"
return cnt;
}
float Get_EncoderTIM4(void)
float Encoder_GetTIM4(void)
{
float cnt;
cnt = (float)((uint16_t)30000) - (float)((uint16_t)(TIM4->CNT));
@ -151,7 +152,7 @@ extern "C"
return cnt;
}
float PB_Get_Encode_TIM5(void)
float Encoder_GetTIM5(void)
{
float cnt;
cnt = (float)((uint16_t)0x7fff) - (float)((uint16_t)(TIM5->CNT));

View File

@ -6,12 +6,13 @@ extern "C" {
#endif
#include "stm32f10x.h"
#include "stdint.h"
void Encoder_Init(TIM_TypeDef* TIMx , unsigned char GPIO_AF);
float PB_Get_Encode_TIM5(void);//What you get here is the total angle.
float Get_EncoderTIM4(void);
float Get_EncoderTIM3(void);
float PB_Get_Encode_TIM2(void);
void Encoder_InitGPIO(TIM_TypeDef* TIMx , uint8_t GPIO_AF);
float Encoder_GetTIM5(void);
float Encoder_GetTIM4(void);
float Encoder_GetTIM3(void);
float Encoder_GetTIM2(void);
#ifdef __cplusplus
}

View File

@ -1,12 +1,13 @@
#ifdef __cplusplus
extern "C" {
extern "C"
{
#endif
#include "flash.h"
u16 PB_Flash_ReadHalfWord(u32 faddr){
u16 Flash_ReadHalfWord(u32 faddr)
{
uint16_t val = 0;
faddr = faddr + FLASH_SAVE_ADDR;
val = *(uint16_t *)faddr;
@ -14,15 +15,19 @@ u16 PB_Flash_ReadHalfWord(u32 faddr){
return val;
}
u32 PB_Flash_ReadWord(u32 faddr){
u32 Flash_ReadWord(u32 faddr)
{
uint16_t val = 0;
faddr = faddr + FLASH_SAVE_ADDR;
val = *(uint32_t *)faddr;
return val;
}
#define PageSize 0x400
void PB_Flash_EnableWrite(){
void Flash_EnableWrite()
{
/*FLASH_Unlock();
FLASH_ErasePage(FLASH_SAVE_ADDR);
CLEAR_BIT(FLASH->CR, FLASH_CR_PER);*/
@ -32,24 +37,24 @@ void PB_Flash_EnableWrite(){
// FLASH_ErasePage(FLASH_SAVE_ADDR + PageSize);
}
void PB_Flash_DisableWrite(){
void Flash_DisableWrite()
{
FLASH_Lock();
}
u32 PB_Flash_WriteHalfWord(u32 faddr, u16 data){
u32 Flash_WriteHalfWord(u32 faddr, u16 data)
{
faddr = faddr + FLASH_SAVE_ADDR;
return FLASH_ProgramHalfWord(faddr, data);
}
u32 PB_Flash_WriteWord(u32 faddr, u32 data){
u32 Flash_WriteWord(u32 faddr, u32 data)
{
faddr = faddr + FLASH_SAVE_ADDR;
return FLASH_ProgramWord(faddr, data);
}
#ifdef __cplusplus
}
#endif

View File

@ -1,5 +1,5 @@
#ifndef FLASH_H
#define FLASH_H
#ifndef __FLASH_H__
#define __FLASH_H__
#ifdef __cplusplus
extern "C" {
#endif
@ -8,13 +8,12 @@ extern "C" {
#define FLASH_SAVE_ADDR ((uint32_t)0x800FC00)
u16 PB_Flash_ReadHalfWord(u32 faddr);
u32 PB_Flash_ReadWord(u32 faddr);
void PB_Flash_EnableWrite(void);
void PB_Flash_DisableWrite(void);
u32 PB_Flash_WriteHalfWord(u32 faddr, u16 data);
u32 PB_Flash_WriteWord(u32 faddr, u32 data);
u16 Flash_ReadHalfWord(u32 faddr);
u32 Flash_ReadWord(u32 faddr);
void Flash_EnableWrite(void);
void Flash_DisableWrite(void);
u32 Flash_WriteHalfWord(u32 faddr, u16 data);
u32 Flash_WriteWord(u32 faddr, u32 data);
#ifdef __cplusplus
}

View File

@ -99,7 +99,7 @@ static void I2C_SendByte(uint8_t b)
SCL_L;
}
static uint8_t I2C_ReadByte()
static uint8_t I2C_ReadByteData()
{
uint8_t i = 8;
uint8_t byte = 0;
@ -119,7 +119,7 @@ static uint8_t I2C_ReadByte()
return byte;
}
void PB_I2C_Init(void)
void I2C_InitGPIO(void)
{
GPIO_InitTypeDef GPIO_InitStructure;
//已更改
@ -130,7 +130,7 @@ void PB_I2C_Init(void)
GPIO_Init(GPIOB, &GPIO_InitStructure);
}
int PB_I2C_Write_Byte(uint8_t addr, uint8_t reg, uint8_t data)
int I2C_WriteByte(uint8_t addr, uint8_t reg, uint8_t data)
{
if (!I2C_Start())
return 0;
@ -150,7 +150,7 @@ int PB_I2C_Write_Byte(uint8_t addr, uint8_t reg, uint8_t data)
return 1;
}
int PB_I2C_Write_Buf(uint8_t addr, uint8_t reg, uint8_t *data , uint8_t size)
int I2C_WriteBuf(uint8_t addr, uint8_t reg, uint8_t *data , uint8_t size)
{
int i;
if (!I2C_Start())
@ -173,7 +173,7 @@ int PB_I2C_Write_Buf(uint8_t addr, uint8_t reg, uint8_t *data , uint8_t size)
return 1;
}
int PB_I2C_Read_Byte(uint8_t addr, uint8_t reg, uint8_t* data)
int I2C_ReadByte(uint8_t addr, uint8_t reg, uint8_t* data)
{
if (!I2C_Start())
return 0;
@ -187,13 +187,13 @@ int PB_I2C_Read_Byte(uint8_t addr, uint8_t reg, uint8_t* data)
I2C_Start();
I2C_SendByte(addr << 1 | I2C_Direction_Receiver);
I2C_WaitAck();
*data = I2C_ReadByte();
*data = I2C_ReadByteData();
I2C_NoAck();
I2C_Stop();
return 1;
}
int PB_I2C_Read_Buf(uint8_t addr,uint8_t reg, uint8_t* data , uint8_t size)
int I2C_ReadBuf(uint8_t addr,uint8_t reg, uint8_t* data , uint8_t size)
{
if (!I2C_Start())
return 0;
@ -208,7 +208,7 @@ int PB_I2C_Read_Buf(uint8_t addr,uint8_t reg, uint8_t* data , uint8_t size)
I2C_SendByte(addr << 1 | I2C_Direction_Receiver);
I2C_WaitAck();
while (size) {
*data = I2C_ReadByte();
*data = I2C_ReadByteData();
if (size == 1)
I2C_NoAck();
else

View File

@ -1,5 +1,5 @@
#ifndef __i2c_H__
#define __i2c_H__
#ifndef __I2C_H__
#define __I2C_H__
#ifdef __cplusplus
extern "C" {
@ -18,18 +18,17 @@ extern "C" {
/*********************************************************************************************************************/
void PB_I2C_Init(void);
int PB_I2C_Write_Byte(uint8_t addr, uint8_t reg, uint8_t data);
int PB_I2C_Write_Buf(uint8_t addr, uint8_t reg, uint8_t *data, uint8_t size);
int PB_I2C_Read_Byte(uint8_t addr, uint8_t reg, uint8_t* data);
int PB_I2C_Read_Buf(uint8_t addr,uint8_t reg, uint8_t* data, uint8_t size);
void I2C_InitGPIO(void);
int I2C_WriteByte(uint8_t addr, uint8_t reg, uint8_t data);
int I2C_WriteBuf(uint8_t addr, uint8_t reg, uint8_t *data, uint8_t size);
int I2C_ReadByte(uint8_t addr, uint8_t reg, uint8_t* data);
int I2C_ReadBuf(uint8_t addr,uint8_t reg, uint8_t* data, uint8_t size);
#ifdef __cplusplus
}
#endif
#endif //__i2c_H__
#endif // __I2C_H__

View File

@ -5,7 +5,7 @@ extern "C" {
#include "timer.h"
#include "nvic.h"
void PB_Timer_Init(TIM_TypeDef* TIMx, uint32_t Time_us)
void Timer_InitBase(TIM_TypeDef *TIMx, uint32_t Time_us)
{
TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
@ -34,8 +34,8 @@ void PB_Timer_Init(TIM_TypeDef* TIMx, uint32_t Time_us)
TIM7_NVIC_Configuration(); //enable interruptation
}
TIM_DeInit(TIMx);
TIM_TimeBaseStructure.TIM_Period= Time_us-1; /* the value of auto reload register */
TIM_TimeBaseStructure.TIM_Prescaler= (72 - 1); /* prescler : 72M/72 */
TIM_TimeBaseStructure.TIM_Period= Time_us-1; /* The value of auto reload register */
TIM_TimeBaseStructure.TIM_Prescaler= (72 - 1); /* Prescler : 72M/72 */
if(TIMx == TIM3 || TIMx == TIM4){ /* ClockDivision*/
TIM_TimeBaseStructure.TIM_ClockDivision=TIM_CKD_DIV4;
@ -43,9 +43,9 @@ void PB_Timer_Init(TIM_TypeDef* TIMx, uint32_t Time_us)
TIM_TimeBaseStructure.TIM_ClockDivision=TIM_CKD_DIV1;
}
TIM_TimeBaseStructure.TIM_CounterMode=TIM_CounterMode_Up; /* count upwards */
TIM_TimeBaseStructure.TIM_CounterMode=TIM_CounterMode_Up; /* Count upwards */
TIM_TimeBaseInit(TIMx , &TIM_TimeBaseStructure);
TIM_ClearFlag(TIMx , TIM_FLAG_Update); /* clear interrupt flags */
TIM_ClearFlag(TIMx , TIM_FLAG_Update); /* Clear interrupt flags */
TIM_ITConfig(TIMx ,TIM_IT_Update,ENABLE);
TIM_Cmd(TIMx , ENABLE);
}

View File

@ -1,13 +1,13 @@
#ifndef TIMER_H
#define TIMER_H
#ifndef __TIMER_H__
#define __TIMER_H__
#ifdef __cplusplus
extern "C" {
#endif
#include "stm32f10x.h"
void PB_Timer_Init(TIM_TypeDef* TIMx, uint32_t Time_us); //Input parameter :TIMx and delay time(us), *timer2--7 1ms
//Input parameter :TIMx and delay time(us), *timer2--7 1ms
void Timer_InitBase(TIM_TypeDef* TIMx, uint32_t Time_us);
#ifdef __cplusplus
}

View File

@ -6,8 +6,7 @@ extern "C" {
#include "usart.h"
#include "nvic.h"
void PB_USART_Init(uint8_t USART_Channel ,unsigned int BaudRate,unsigned char GPIO_AF)
void USART_InitGPIO(uint8_t USART_Channel, uint32_t BaudRate, uint8_t GPIO_AF)
{
// GPIO config
USART_TypeDef *USARTx;
@ -28,8 +27,7 @@ void PB_USART_Init(uint8_t USART_Channel ,unsigned int BaudRate,unsigned char GP
}
else if (USART_Channel == 5){
USARTx = UART5;
}
else{
}else{
return;
}
@ -60,7 +58,8 @@ void PB_USART_Init(uint8_t USART_Channel ,unsigned int BaudRate,unsigned char GP
}
USART1_NVIC_Configuration();
}
else if(USARTx==USART2){
else if (USARTx == USART2)
{
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA | RCC_APB2Periph_AFIO | RCC_APB2Periph_GPIOD, ENABLE);
RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART2, ENABLE);
@ -91,7 +90,8 @@ void PB_USART_Init(uint8_t USART_Channel ,unsigned int BaudRate,unsigned char GP
USART2_NVIC_Configuration();
}
else if(USARTx==USART3){
else if (USARTx == USART3)
{
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOB | RCC_APB2Periph_AFIO | RCC_APB2Periph_GPIOC | RCC_APB2Periph_GPIOD, ENABLE);
RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART3, ENABLE);
if (GPIO_AF == 0)
@ -105,7 +105,8 @@ void PB_USART_Init(uint8_t USART_Channel ,unsigned int BaudRate,unsigned char GP
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
GPIO_Init(GPIOB, &GPIO_InitStructure);
}
else if(GPIO_AF == 1){
else if (GPIO_AF == 1)
{
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_10; // USART3_TX PC.10
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
@ -116,7 +117,8 @@ void PB_USART_Init(uint8_t USART_Channel ,unsigned int BaudRate,unsigned char GP
GPIO_Init(GPIOC, &GPIO_InitStructure);
GPIO_PinRemapConfig(GPIO_FullRemap_USART3, ENABLE); // use Remapping
}
else if(GPIO_AF == 2){
else if (GPIO_AF == 2)
{
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_8; // USART3_TX PD8
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
@ -129,7 +131,8 @@ void PB_USART_Init(uint8_t USART_Channel ,unsigned int BaudRate,unsigned char GP
}
USART3_NVIC_Configuration();
}
else if(USARTx==UART4){
else if (USARTx == UART4)
{
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOC | RCC_APB2Periph_AFIO, ENABLE);
RCC_APB1PeriphClockCmd(RCC_APB1Periph_UART4, ENABLE);
if (GPIO_AF == 0)
@ -145,7 +148,8 @@ void PB_USART_Init(uint8_t USART_Channel ,unsigned int BaudRate,unsigned char GP
}
UART4_NVIC_Configuration();
}
else if(USARTx==UART5){
else if (USARTx == UART5)
{
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOC | RCC_APB2Periph_GPIOD | RCC_APB2Periph_AFIO, ENABLE);
RCC_APB1PeriphClockCmd(RCC_APB1Periph_UART5, ENABLE);
if (GPIO_AF == 0)
@ -162,7 +166,7 @@ void PB_USART_Init(uint8_t USART_Channel ,unsigned int BaudRate,unsigned char GP
UART5_NVIC_Configuration();
}
USART_InitStructure.USART_BaudRate = BaudRate ; //usually set 9600;
USART_InitStructure.USART_BaudRate = BaudRate;
USART_InitStructure.USART_WordLength = USART_WordLength_8b;
USART_InitStructure.USART_StopBits = USART_StopBits_1;
USART_InitStructure.USART_Parity = USART_Parity_No;
@ -170,37 +174,45 @@ void PB_USART_Init(uint8_t USART_Channel ,unsigned int BaudRate,unsigned char GP
USART_InitStructure.USART_Mode = USART_Mode_Rx | USART_Mode_Tx;
USART_Init(USARTx, &USART_InitStructure);
USART_ITConfig(USARTx, USART_IT_RXNE, ENABLE); //enable interrupt
// enable interrupt
USART_ITConfig(USARTx, USART_IT_RXNE, ENABLE);
USART_ClearITPendingBit(USARTx, USART_IT_RXNE);
USART_Cmd(USARTx, ENABLE); //enable usart
// enable usart
USART_Cmd(USARTx, ENABLE);
}
void PB_USART_Put_Char(uint8_t USART_Channel , unsigned char Tx_Byte)
void USART_PutChar(uint8_t USART_Channel, unsigned char Tx_Byte)
{
USART_TypeDef *USARTx;
if(USART_Channel == 1){
if (USART_Channel == 1)
{
USARTx = USART1;
}
else if(USART_Channel == 2){
else if (USART_Channel == 2)
{
USARTx = USART2;
}
else if(USART_Channel == 3){
else if (USART_Channel == 3)
{
USARTx = USART3;
}
else if(USART_Channel == 4){
else if (USART_Channel == 4)
{
USARTx = UART4;
}
else if(USART_Channel == 5){
else if (USART_Channel == 5)
{
USARTx = UART5;
}
else{
else
{
return;
}
USART_SendData(USARTx, Tx_Byte);
while(USART_GetFlagStatus(USARTx, USART_FLAG_TXE) == RESET);
while (USART_GetFlagStatus(USARTx, USART_FLAG_TXE) == RESET)
;
}
static char *itoa(int value, char *string, int radix)
@ -318,4 +330,3 @@ void USART_printf(USART_TypeDef* USARTx, uint8_t *Data,...)
#ifdef __cplusplus
}
#endif

View File

@ -1,5 +1,5 @@
#ifndef USART_H
#define USART_H
#ifndef __USART_H__
#define __USART_H__
#ifdef __cplusplus
extern "C"{
@ -9,10 +9,13 @@ extern "C" {
#include "stdarg.h"
#include "stdio.h"
//Initilaize the serial, First Parameter:USART1,USART2,USART3; 2nd Para:bits rate; 3rd: IO reuse
void PB_USART_Init(uint8_t USART_Channel ,unsigned int BaudRate,unsigned char GPIO_AF);
void PB_USART_Put_Char(uint8_t USART_Channel , unsigned char Tx_Byte); //USARTx to print 1 byte
void USART_printf(USART_TypeDef* USARTx, uint8_t *Data, ...); //format output as printf in C standard library
// Initilaize the serial, First Parameter:USART1,USART2,USART3;
// 2nd Para:bits rate; 3rd: IO reuse
void USART_InitGPIO(uint8_t USART_Channel, uint32_t BaudRate, uint8_t GPIO_AF);
// USARTx to print 1 byte
void USART_PutChar(uint8_t USART_Channel, uint8_t Tx_Byte);
// format output as printf in C standard library
void USART_printf(USART_TypeDef *USARTx, uint8_t *Data, ...);
// int fputc(int ch, FILE *f);
@ -20,6 +23,6 @@ void USART_printf(USART_TypeDef* USARTx, uint8_t *Data, ...); //format output a
}
#endif
#endif // #ifndef USART_H
#endif // #ifndef __USART_H__

View File

@ -40,7 +40,7 @@ public:
virtual void init()=0;
virtual void enable_irq()=0;
virtual void disable_irq()=0;
virtual void usart_debug_init()=0;
virtual void Usart_DebugInit()=0;
virtual void usart_init(unsigned char num, unsigned long buad)=0;
virtual Queue* usart_getDataQueue(unsigned char num)=0;
@ -59,7 +59,7 @@ public:
virtual void motor_pwm(unsigned char num, long pwm_value)=0;
virtual void encoder_init(unsigned char motor_id) = 0;
virtual long getEncoderCount(unsigned char motor_id) = 0;
virtual long GetEncoderCount(unsigned char motor_id) = 0;
virtual void i2c_init() = 0;
virtual unsigned char i2c_write_byte(unsigned char equipment_address, unsigned char reg_address , unsigned char pt_char)=0;
@ -99,7 +99,6 @@ public:
return count;
}
static Board* get();
};

View File

@ -24,7 +24,7 @@ Board_STM32::~Board_STM32()
void Board_STM32::init()
{
PB_System_Timer_Init();
System_TimerInit();
DOInit();
DIInit();
}
@ -37,17 +37,18 @@ void Board_STM32::disable_irq()
{
}
void Board_STM32::usart_debug_init()
void Board_STM32::Usart_DebugInit()
{
PB_USART_Init(1, 115200, 0);
USART_InitGPIO(1, 115200, 0);
}
#ifdef __cplusplus
extern "C" {
extern "C"
{
#endif
int fputc(int ch, FILE *f)
{
PB_USART_Put_Char(1, ch);
USART_PutChar(1, ch);
return (ch);
}
#ifdef __cplusplus
@ -56,17 +57,23 @@ int fputc(int ch, FILE *f)
void Board_STM32::usart_init(unsigned char num, unsigned long buad)
{
if (num == (unsigned char)USART_1) {
PB_USART_Init(1, 115200, 0);
} else if (num == (unsigned char)USART_3) {
PB_USART_Init(3, 115200, 0);
if (num == (unsigned char)USART_1)
{
USART_InitGPIO(1, 115200, 0);
}
else if (num == (unsigned char)USART_3)
{
USART_InitGPIO(3, 115200, 0);
}
}
Queue *Board_STM32::usart_getDataQueue(unsigned char num)
{
if (num == (unsigned char)USART_1) {
} else if (num == (unsigned char)USART_3) {
if (num == (unsigned char)USART_1)
{
}
else if (num == (unsigned char)USART_3)
{
return &usart3_queue;
}
@ -75,35 +82,43 @@ Queue* Board_STM32::usart_getDataQueue(unsigned char num)
void Board_STM32::usart_write(unsigned char num, unsigned char ch)
{
if (num == (unsigned char)USART_1) {
PB_USART_Put_Char(1, ch);
} else if (num == (unsigned char)USART_3) {
PB_USART_Put_Char(3, ch);
if (num == (unsigned char)USART_1)
{
USART_PutChar(1, ch);
}
else if (num == (unsigned char)USART_3)
{
USART_PutChar(3, ch);
}
}
void Board_STM32::usart_write(unsigned char num, unsigned char *data, unsigned char len)
{
if (num == (unsigned char)USART_1) {
if (num == (unsigned char)USART_1)
{
while (len--)
PB_USART_Put_Char(1, *data++);
} else if (num == (unsigned char)USART_3) {
USART_PutChar(1, *data++);
}
else if (num == (unsigned char)USART_3)
{
while (len--)
PB_USART_Put_Char(3, *data++);
USART_PutChar(3, *data++);
}
}
void Board_STM32::set_config(unsigned char *data, unsigned short len)
{
if (len%2==0) {
PB_Flash_EnableWrite();
for(int i=0;i<len/2;i++) {
if (len % 2 == 0)
{
Flash_EnableWrite();
for (int i = 0; i < len / 2; i++)
{
uint16_t a = 0;
memcpy(&a, data + i * 2, 2);
PB_Flash_WriteHalfWord(i*2, a);
Flash_WriteHalfWord(i * 2, a);
delay_us(10);
}
PB_Flash_DisableWrite();
Flash_DisableWrite();
}
}
@ -111,7 +126,7 @@ void Board_STM32::get_config(unsigned char* data, unsigned short len)
{
if (len % 2 == 0){
for (int i = 0; i < len / 2; i++){
uint16_t a = PB_Flash_ReadHalfWord(i*2);
uint16_t a = Flash_ReadHalfWord(i * 2);
memcpy(data + i * 2, &a, 2);
}
}
@ -191,7 +206,6 @@ bool Board_STM32::getDIState(unsigned char _id)
if ( _id == _JS_DAT) {
return GPIO_ReadInputDataBit(GPIOA, GPIO_Pin_4);
}
return false;
}
@ -317,43 +331,43 @@ unsigned long Board_STM32::getTickCount()
void Board_STM32::encoder_init(unsigned char motor_id)
{
if (motor_id == MOTOR_1){
Encoder_Init(TIM3, 0);
Encoder_InitGPIO(TIM3, 0);
}else if (motor_id == MOTOR_2){
Encoder_Init(TIM4, 0);
Encoder_InitGPIO(TIM4, 0);
}
}
long Board_STM32::getEncoderCount(unsigned char motorId)
long Board_STM32::GetEncoderCount(unsigned char motorId)
{
if (motorId == MOTOR_1){
return Get_EncoderTIM3();
return Encoder_GetTIM3();
}else if (motorId == MOTOR_2){
return Get_EncoderTIM4();
return Encoder_GetTIM4();
}
return 0;
}
void Board_STM32::i2c_init()
{
PB_I2C_Init();
I2C_InitGPIO();
}
unsigned char Board_STM32::i2c_write_byte(unsigned char equipment_address, unsigned char reg_address, unsigned char pt_char)
{
return PB_I2C_Write_Byte(equipment_address, reg_address, pt_char);
return I2C_WriteByte(equipment_address, reg_address, pt_char);
}
unsigned char Board_STM32::i2c_write_buf(unsigned char equipment_address, unsigned char reg_address, unsigned char *pt_char, unsigned char size)
{
return PB_I2C_Write_Buf(equipment_address, reg_address, pt_char, size);
return I2C_WriteBuf(equipment_address, reg_address, pt_char, size);
}
unsigned char Board_STM32::i2c_read_byte(unsigned char equipment_address, unsigned char reg_address, unsigned char *pt_char)
{
return PB_I2C_Read_Byte(equipment_address, reg_address, pt_char);
return I2C_ReadByte(equipment_address, reg_address, pt_char);
}
unsigned char Board_STM32::i2c_read_buf(unsigned char equipment_address, unsigned char reg_address, unsigned char *pt_char, unsigned char size)
{
return PB_I2C_Read_Buf(equipment_address, reg_address, pt_char, size);
return I2C_ReadBuf(equipment_address, reg_address, pt_char, size);
}

View File

@ -13,7 +13,7 @@ public:
virtual void init();
virtual void enable_irq();
virtual void disable_irq();
virtual void usart_debug_init();
virtual void Usart_DebugInit();
virtual void usart_write(unsigned char num, unsigned char ch);
virtual void usart_init(unsigned char num, unsigned long buad);
virtual Queue* usart_getDataQueue(unsigned char num);
@ -32,7 +32,7 @@ public:
virtual void motor_pwm(unsigned char num, long pwm_value);
virtual void encoder_init(unsigned char motor_id) ;
virtual long getEncoderCount(unsigned char motor_id);
virtual long GetEncoderCount(unsigned char motor_id);
virtual void i2c_init();
virtual unsigned char i2c_write_byte(unsigned char equipment_address, unsigned char reg_address , unsigned char pt_char);

View File

@ -5,8 +5,10 @@
#if DEBUG_ENABLE
#define log(format,...) printf("" __FILE__ ":%d - " format "\r\n", __LINE__, ##__VA_ARGS__)
#define logi(format,...) printf("[INFO]" __FILE__ ":%d - " format "\r\n", __LINE__, ##__VA_ARGS__)
#else
#define log(format,...)
#define logi(format,...)
#endif
#endif

View File

@ -1,5 +1,5 @@
#ifndef DataHolder_H_
#define DataHolder_H_
#ifndef __DataHolder_H__
#define __DataHolder_H__
#include <string.h>
@ -71,8 +71,7 @@ struct Robot_odom
short yaw; // 里程计航角 0.01rad 100 means 1 rad
};
struct Robot_pid_data
{
struct Robot_pid_data{
long input[4]; // 各轮子驱动输入值
long output[4]; // 个轮子输出值
};
@ -102,10 +101,10 @@ public:
struct Robot_velocity velocity; // 速度
struct Robot_odom odom; // 里程
struct Robot_pid_data pid_data; // pid输入输出
struct Robot_pwm_value pwm; // 控制的pwm
float imu_data[9]; // imu的值 9axis
float encoder_count[4]; // 编码器计数
struct Robot_pwm_value pwm; // 控制的pwm
};
#endif

View File

@ -21,9 +21,9 @@ void EncoderImp::clear()
long EncoderImp::get_total_count()
{
if (reverse)
total_count += Board::get()->getEncoderCount(num);
total_count += Board::get()->GetEncoderCount(num);
else
total_count -= Board::get()->getEncoderCount(num);
total_count -= Board::get()->GetEncoderCount(num);
return total_count;
}
@ -31,9 +31,9 @@ long EncoderImp::get_total_count()
long EncoderImp::get_increment_count_for_dopid()
{
if (reverse)
total_count += Board::get()->getEncoderCount(num);
total_count += Board::get()->GetEncoderCount(num);
else
total_count -= Board::get()->getEncoderCount(num);
total_count -= Board::get()->GetEncoderCount(num);
long l = total_count-pid_pos;
pid_pos = total_count;
return l;
@ -42,9 +42,9 @@ long EncoderImp::get_increment_count_for_dopid()
long EncoderImp::get_increment_count_for_odom()
{
if (reverse)
total_count += Board::get()->getEncoderCount(num);
total_count += Board::get()->GetEncoderCount(num);
else
total_count -= Board::get()->getEncoderCount(num);
total_count -= Board::get()->GetEncoderCount(num);
long l = total_count-odom_pos;
odom_pos = total_count;

View File

@ -8,7 +8,7 @@
#define WRITE_INTERVAL 20
bool GY65::init()
bool GY65::Init()
{
delay_ms(500);
Board::get()->i2c_init();
@ -38,7 +38,7 @@ bool GY65::init()
return true;
}
void GY65::get_data(float* imu_data)
void GY65::GetData(float* imu_data)
{
mpu6050.getMotion6(&ax, &ay, &az, &gx, &gy, &gz);

View File

@ -7,8 +7,8 @@
class GY65 : public IMU
{
public:
virtual bool init();
virtual void get_data(float* imu_data);
virtual bool Init();
virtual void GetData(float* imu_data);
private:
MPU6050 mpu6050;

View File

@ -8,7 +8,7 @@
#define HMC5883L_SCALE 0.92 // mG/LSb
#define WRITE_INTERVAL 20
bool GY85::init()
bool GY85::Init()
{
delay_ms(500);
Board::get()->i2c_init();
@ -103,7 +103,7 @@ bool GY85::init()
#define CYCLE_COUNT 3
void GY85::get_data(float* imu_data)
void GY85::GetData(float* imu_data)
{
static int i=0;

View File

@ -9,8 +9,8 @@
class GY85 : public IMU
{
public:
virtual bool init();
virtual void get_data(float imu_data[9]);
virtual bool Init();
virtual void GetData(float imu_data[9]);
private:
ADXL345 accel;
ITG3200 gyro;

View File

@ -9,7 +9,7 @@
#define WRITE_INTERVAL 20
bool GY87::init()
bool GY87::Init()
{
delay_ms(500);
#if IMU_DEBUG_ENABLE
@ -70,7 +70,7 @@ bool GY87::init()
}
#define CYCLE_COUNT 2
void GY87::get_data(float* imu_data)
void GY87::GetData(float* imu_data)
{
static int i=0;

View File

@ -8,8 +8,8 @@
class GY87 : public IMU
{
public:
virtual bool init();
virtual void get_data(float* imu_data);
virtual bool Init();
virtual void GetData(float* imu_data);
private:
MPU6050 mpu6050;
HMC5883L mag;

View File

@ -1,11 +1,11 @@
#ifndef PIBOT_IMU_H_
#define PIBOT_IMU_H_
#ifndef _GEBOT_IMU_H_
#define _GEBOT_IMU_H_
class IMU
{
public:
virtual bool init() = 0;
virtual void get_data(float* imu_data) = 0;
virtual bool Init() = 0;
virtual void GetData(float* imu_data) = 0;
};
#endif

View File

@ -1,5 +1,5 @@
#ifndef PIBOT_DIFFERENTIAL_H_
#define PIBOT_DIFFERENTIAL_H_
#ifndef __GEBOT_DIFFERENTIAL_H__
#define __GEBOT_DIFFERENTIAL_H__
// 2轮差分模型
#include "model.h"
@ -16,17 +16,16 @@ public:
Differential(float _wheel_radius, float _body_radius) : Model(_wheel_radius, _body_radius) {}
// 运动解算 把给到机器人的速度分解为各个轮子速度
virtual void motionSolver(float* robot_speed, float* motor_speed) {
virtual void motionSolver(float* robotSpeed, float* motorSpeed) {
// robot_speed[0] x robot_speed[1] y robot_speed[2] z
motor_speed[0] = (-robot_speed[0] + robot_speed[2] * body_radius)/ wheel_radius;
motor_speed[1] = ( robot_speed[0] + robot_speed[2] * body_radius) / wheel_radius;
motorSpeed[0] = (-robotSpeed[0] + robotSpeed[2] * bodyRadius) / wheelRadius;
motorSpeed[1] = ( robotSpeed[0] + robotSpeed[2] * bodyRadius) / wheelRadius;
}
//反解算, 把各个轮子的速度转为机器人的速度 ,这里通过固定时间间隔转为里程
virtual void get_odom(struct Odom* odom, float* motor_dis, unsigned long interval) {
float dxy_ave = (-motor_dis[0] + motor_dis[1]) / 2.0;
float dth = ( motor_dis[0] + motor_dis[1]) / (2* body_radius);
float dth = ( motor_dis[0] + motor_dis[1]) / (2* bodyRadius);
float vxy = 1000 * dxy_ave / interval;
float vth = 1000 * dth / interval;

View File

@ -17,27 +17,28 @@ struct Model
{
// 构造函数
Model(){}
Model(float _wheel_radius, float _body_radius): wheel_radius(_wheel_radius), body_radius(_body_radius){}
Model(float _wheel_radius, float _body_radius): wheelRadius(_wheel_radius), bodyRadius(_body_radius){}
// 参数更新接口
void set(float _wheel_radius, float _body_radius) {
wheel_radius = _wheel_radius;
body_radius = _body_radius;
wheelRadius = _wheel_radius;
bodyRadius = _body_radius;
}
// 析构函数
~Model(){}
//robot speed ------------> motor speed 运动解算 把给到机器人的速度分解为各个轮子速度
// robot speed -> motor speed 运动解算 把给到机器人的速度分解为各个轮子速度
virtual void motionSolver(float* robot_speed, float* motor_speed) = 0;
//motor speed-------------> robot speed 反解算, 把各个轮子的速度转为机器人的速度 ,这里通过固定时间间隔转为里程
// motor speed -> robot speed 反解算, 把各个轮子的速度转为机器人的速度,
// 这里通过固定时间间隔转为里程
//interval ms
virtual void get_odom(struct Odom* odom, float* motor_dis, unsigned long interval) = 0;
protected:
float wheel_radius; // 轮子半径
float body_radius; // 机器人半径(泛指)
float wheelRadius; // 轮子半径
float bodyRadius; // 机器人半径(泛指), 对于差分机器人模型bodyRadius就是轮距
};
#endif

View File

@ -6,7 +6,6 @@
// 定义Motor数目
#define MOTOR_COUNT 3
#define sqrt_of_3 1.732f
// 3轮全向模型接口实现
@ -17,24 +16,20 @@ public:
Omni3(float _wheel_radius, float _body_radius) : Model(_wheel_radius, _body_radius) {}
// 运动解算 把给到机器人的速度分解为各个轮子速度
void motionSolver(float *robot_speed, float *motor_speed)
{
void motionSolver(float* robot_speed, float* motor_speed) {
// robot_speed[0] x robot_speed[1] y robot_speed[2] z
motor_speed[0] = (robot_speed[1] + robot_speed[2] * body_radius) / wheel_radius;
motor_speed[1] = (-robot_speed[0] * sqrt_of_3 * 0.5 - robot_speed[1] * 0.5 + robot_speed[2] * body_radius) / wheel_radius;
motor_speed[2] = (robot_speed[0] * sqrt_of_3 * 0.5 - robot_speed[1] * 0.5 + robot_speed[2] * body_radius) / wheel_radius;
motor_speed[0] = ( robot_speed[1] + robot_speed[2] * bodyRadius)/ wheelRadius;
motor_speed[1] = (-robot_speed[0]*sqrt_of_3*0.5 - robot_speed[1]*0.5 + robot_speed[2] * bodyRadius) / wheelRadius;
motor_speed[2] = ( robot_speed[0]*sqrt_of_3*0.5 - robot_speed[1]*0.5 + robot_speed[2] * bodyRadius) / wheelRadius;
}
// 反解算, 把各个轮子的速度转为机器人的速度 ,这里通过固定时间间隔转为里程
void get_odom(struct Odom *odom, float *motor_dis, unsigned long interval)
{
if (motor_dis[0] != 0 || motor_dis[1] != 0 || motor_dis[2] != 0)
{
void get_odom(struct Odom* odom, float* motor_dis, unsigned long interval) {
if (motor_dis[0]!=0 || motor_dis[1]!=0 || motor_dis[2]!=0){
//speed
float dvx = (-motor_dis[1]+motor_dis[2])*sqrt_of_3/3.0f;
float dvy = (motor_dis[0]*2-motor_dis[1]-motor_dis[2])/3.0f;
float dvth = ( motor_dis[0] + motor_dis[1] + motor_dis[2]) / (3 * body_radius);
float dvth = (motor_dis[0]+motor_dis[1]+motor_dis[2])/ (3 * bodyRadius);
odom->vel_x = dvx / interval;
odom->vel_y = dvy / interval;
odom->vel_z = dvth / interval;
@ -44,7 +39,7 @@ public:
//odometry
float dx = (-sin(th)*motor_dis[0]*2+(-sqrt_of_3*cos(th)+sin(th))*motor_dis[1]+(sqrt_of_3*cos(th)+sin(th))*motor_dis[2])/3.0f;
float dy = (cos(th)*motor_dis[0]*2+(-sqrt_of_3*sin(th)-cos(th))*motor_dis[1]+(sqrt_of_3*sin(th)-cos(th))*motor_dis[2])/3.0f;
float dth = (motor_dis[0] + motor_dis[1] + motor_dis[2]) / (3 * body_radius);
float dth = (motor_dis[0]+motor_dis[1]+motor_dis[2])/ (3 * bodyRadius);
odom->x += dx;
odom->y += dy;

View File

@ -1,48 +1,51 @@
#include "pid.h"
#include "board.h"
#include "print.h"
PID::PID(float *_input, float *_feedback, float _kp, float _ki, float _kd, unsigned short _max_output)
: kp(_kp), ki(_ki), kd(_kd), max_output(_max_output * 1.0), input(_input), feedback(_feedback)
{
clear();
Clear();
}
void PID::clear()
void PID::Clear()
{
error = integra = derivative = previous_error =0;
err = integra = derivative = preErr = 0;
}
void PID::update(float _kp, float _ki, float _kd, unsigned short _max_output)
void PID::Update(float _kp, float _ki, float _kd, unsigned short _maxOutput)
{
kp = _kp;
ki = _ki;
kd = _kd;
max_output = _max_output;
max_output = _maxOutput;
}
short PID::compute(float interval)
short PID::Compute(float interval)
{
error = *input - *feedback;
// 计算输入值和反馈值的差值
err = *input - *feedback;
// 计算积分误差
integra = integra + err * interval;
// 计算微分参数
derivative = (err - preErr) / interval;
// 更新误差
preErr = err;
integra = integra + error*interval;
derivative = (error - previous_error) / interval;
previous_error = error;
if (ki != 0) {
if (ki != 0)
{
#if PID_DEBUG_OUTPUT
log("integra=%ld max_output=%ld %ld", long(integra * 1000), long(-(max_output / ki * 1000)), long(max_output / ki * 1000));
#endif
if (integra < -(max_output/ki)) {
if (integra < -(max_output / ki))
{
#if PID_DEBUG_OUTPUT
log("integra clear-");
#endif
integra = -(max_output / ki);
}
if (integra > max_output/ki) {
if (integra > max_output / ki)
{
#if PID_DEBUG_OUTPUT
log("integra clear+");
#endif
@ -50,8 +53,10 @@ short PID::compute(float interval)
}
}
float val = error*kp + integra*ki + derivative*kd;
// 计算PID值
float val = err * kp + integra * ki + derivative * kd;
// 输出范围约束
if (val < -max_output)
val = -max_output + 1;
else if (val > max_output)

View File

@ -1,5 +1,5 @@
#ifndef PIBOT_PID_H_
#define PIBOT_PID_H_
#ifndef __GEBOT_PID_H__
#define __GEBOT_PID_H__
//pid接口
class PID
@ -8,19 +8,19 @@ public:
/* pid构造函数
* @param input pid
* @param output pid
* @param kp ki kd pid
* @param kp,ki,kd pid
* @param max_output
*/
PID(float* input, float* feedback, float kp, float ki, float kd, unsigned short max_output);
// pid计算
short compute(float interval);
short Compute(float interval);
// 重置pid的值
void clear();
void Clear();
// 更新pid参数
void update(float kp, float ki, float kd, unsigned short max_output);
void Update(float kp, float ki, float kd, unsigned short _maxOutput);
private:
float kp;
float ki;
@ -28,12 +28,10 @@ private:
float max_output;
float* input;
float* feedback;
float error; //比例值
float err; // 比例值
float integra; // 积分值
float derivative; // 微分值
float previous_error; //上一次的输入反馈差值
float preErr; // 上一次的输入反馈差值
};
#endif

View File

@ -34,7 +34,7 @@ public:
virtual bool init()=0;
// 注册notify 对需要关注的id添加关注
virtual void register_notify(const MESSAGE_ID id, Notify* _nf)=0;
virtual void RegisterNotify(const MESSAGE_ID id, Notify* _nf)=0;
// 数据接收接口
virtual bool dataRecv(unsigned char c)=0;

View File

@ -3,17 +3,15 @@
#include "print.h"
#include "transport.h"
Simple_dataframe::Simple_dataframe(Transport* _trans): trans(_trans)
{
SimpleDataFrame::SimpleDataFrame(Transport* _trans): trans(_trans){
recv_state = STATE_RECV_FIX;
}
bool Simple_dataframe::init()
{
bool SimpleDataFrame::init(){
return true;
}
bool Simple_dataframe::dataRecv(unsigned char c)
bool SimpleDataFrame::dataRecv(unsigned char c)
{
switch (recv_state) {// 根据当前接收的状态解析数据存储到active_rx_msg
case STATE_RECV_FIX:
@ -64,7 +62,7 @@ bool Simple_dataframe::dataRecv(unsigned char c)
}
//接收到一帧正确的数据后被调用
bool Simple_dataframe::dataParse()
bool SimpleDataFrame::dataParse()
{
MESSAGE_ID id = (MESSAGE_ID)active_rx_msg.head.msg_id;
@ -122,7 +120,7 @@ bool Simple_dataframe::dataParse()
return true;
}
bool Simple_dataframe::send_message(const MESSAGE_ID id)
bool SimpleDataFrame::send_message(const MESSAGE_ID id)
{
Message msg(id);
@ -131,7 +129,7 @@ bool Simple_dataframe::send_message(const MESSAGE_ID id)
return true;
}
bool Simple_dataframe::send_message(const MESSAGE_ID id, unsigned char* data, unsigned char len)
bool SimpleDataFrame::send_message(const MESSAGE_ID id, unsigned char* data, unsigned char len)
{
Message msg(id, data, len);
@ -140,7 +138,7 @@ bool Simple_dataframe::send_message(const MESSAGE_ID id, unsigned char* data, un
return true;
}
bool Simple_dataframe::send_message(Message* msg)
bool SimpleDataFrame::send_message(Message* msg)
{
if (trans == 0)
return true;

View File

@ -1,21 +1,21 @@
#ifndef PIBOT_SIMPLE_DATAFRAME_SLAVE_H_
#define PIBOT_SIMPLE_DATAFRAME_SLAVE_H_
#ifndef __GEBOT_SIMPLE_DATAFRAME_SLAVE_H__
#define __GEBOT_SIMPLE_DATAFRAME_SLAVE_H__
#include "simple_dataframe.h"
class Transport;
// 一个简单的协议实现 详见https://www.jianshu.com/p/1dc5f9e2f90f
class Simple_dataframe : public Dataframe
class SimpleDataFrame : public Dataframe
{
public:
/* 构造函数
* @param trans
*/
Simple_dataframe(Transport* trans=0);
SimpleDataFrame(Transport* trans=0);
// 注册通知接口实现, 保存notify到数组以作映射
virtual void register_notify(const MESSAGE_ID id, Notify* _nf) {
virtual void RegisterNotify(const MESSAGE_ID id, Notify* _nf) {
if (id >= ID_MESSGAE_MAX)
return;
nf[id] = _nf;

View File

@ -1,5 +1,18 @@
/******************** (C) COPYRIGHT 2024 GeBot *********************************
* File Name : main.c
* Current Version : V1.0 & ST 3.5.0
* Author : zhanli 719901725@qq.com
* Date of Issued : 2024.01.23 zhanli: Create.
* Comments : Gebot
********************************************************************************/
#include "robot.h"
/**----------------------------------------------------------------------
* Function : main
* Description : Gebot
* Author : zhanli&719901725@qq.com
* Date : 2023/04/22 zhanli
*---------------------------------------------------------------------**/
int main(void)
{
//初始化

View File

@ -6,7 +6,6 @@
#include "data_holder.h"
#include "usart.h"
#if MOTOR_CONTROLLER == COMMON_CONTROLLER
#include "common_motor_controller.h"
#define MAX_PWM_VALUE 5000
@ -68,13 +67,13 @@ void Robot::Init()
#if DEBUG_ENABLE
// 调试串口初始化
Board::get()->usart_debug_init();
Board::get()->Usart_DebugInit();
#endif
// 加载参数, 该参数一般存储在flash或者eeprom
DataHolder::get()->loadParameter();
log("RobotParameters: %d %d %d %d %d %d %d %d %d %d %d %d %d",
logi("RobotParameters: %d %d %d %d %d %d %d %d %d %d %d %d %d",
DataHolder::get()->parameter.params.wheel_diameter, DataHolder::get()->parameter.params.wheel_track, DataHolder::get()->parameter.params.encoder_resolution, DataHolder::get()->parameter.params.motor_ratio,
DataHolder::get()->parameter.params.do_pid_interval, DataHolder::get()->parameter.params.kp, DataHolder::get()->parameter.params.ki, DataHolder::get()->parameter.params.kd, DataHolder::get()->parameter.params.ko,
DataHolder::get()->parameter.params.cmd_last_time, DataHolder::get()->parameter.params.max_v_liner_x, DataHolder::get()->parameter.params.max_v_liner_y, DataHolder::get()->parameter.params.max_v_angular_z);
@ -119,7 +118,7 @@ void Robot::init_imu()
}
if (imu != NULL){
imu->init();
imu->Init();
}
#endif
}
@ -233,7 +232,7 @@ void Robot::InitTrans()
static USART_transport _trans(MASTER_USART, 115200);
// 定义一个通讯协议处理对象, 同上, 我们需要更换协议只需要继承实现Dataframe的接口就可以实现
static Simple_dataframe _frame(&_trans);
static SimpleDataFrame _frame(&_trans);
// 保存对象指针
trans = &_trans;
@ -245,11 +244,11 @@ void Robot::InitTrans()
// 注册消息处理对象 这里把各个消息id的处理注册了一个观察者 即再收到相应的消息后会回调update函数
// Robot(this)继承实现了notify
frame->register_notify(ID_SET_ROBOT_PARAMTER, this);
frame->register_notify(ID_CLEAR_ODOM, this);
frame->register_notify(ID_SET_VELOCITY, this);
frame->register_notify(ID_GET_ENCODER_COUNT, this);
frame->register_notify(ID_SET_MOTOR_PWM, this);
frame->RegisterNotify(ID_SET_ROBOT_PARAMTER, this);
frame->RegisterNotify(ID_CLEAR_ODOM, this);
frame->RegisterNotify(ID_SET_VELOCITY, this);
frame->RegisterNotify(ID_GET_ENCODER_COUNT, this);
frame->RegisterNotify(ID_SET_MOTOR_PWM, this);
}
void Robot::CheckCommand()
@ -257,7 +256,6 @@ void Robot::CheckCommand()
static unsigned long lastMillis = 0;
if (Board::get()->getTickCount() - lastMillis >= 50){
lastMillis = Board::get()->getTickCount();
Board::get()->setDOState(_RUN_LED, 2);
}
@ -275,16 +273,29 @@ void Robot::CheckCommand()
// 实现Notify接口 上面注册的命令id接收到时候会回调执行响应的动作
void Robot::update(const MESSAGE_ID id, void *data)
{
switch (id) {
switch (id)
{
case ID_SET_ROBOT_PARAMTER: // 设置参数的回调, 这里会更新pid的参数 model的参数 最终保存到flash
log("RobotParameters: %d %d %d %d %d %d %d %d %d %d %d %d %d",
DataHolder::get()->parameter.params.wheel_diameter, DataHolder::get()->parameter.params.wheel_track, DataHolder::get()->parameter.params.encoder_resolution, DataHolder::get()->parameter.params.motor_ratio,
DataHolder::get()->parameter.params.do_pid_interval, DataHolder::get()->parameter.params.kp, DataHolder::get()->parameter.params.ki, DataHolder::get()->parameter.params.kd, DataHolder::get()->parameter.params.ko,
DataHolder::get()->parameter.params.cmd_last_time, DataHolder::get()->parameter.params.max_v_liner_x, DataHolder::get()->parameter.params.max_v_liner_y, DataHolder::get()->parameter.params.max_v_angular_z);
DataHolder::get()->parameter.params.wheel_diameter,
DataHolder::get()->parameter.params.wheel_track,
DataHolder::get()->parameter.params.encoder_resolution,
DataHolder::get()->parameter.params.motor_ratio,
DataHolder::get()->parameter.params.do_pid_interval,
DataHolder::get()->parameter.params.kp,
DataHolder::get()->parameter.params.ki,
DataHolder::get()->parameter.params.kd,
DataHolder::get()->parameter.params.ko,
DataHolder::get()->parameter.params.cmd_last_time,
DataHolder::get()->parameter.params.max_v_liner_x,
DataHolder::get()->parameter.params.max_v_liner_y,
DataHolder::get()->parameter.params.max_v_angular_z);
// 更新pid参数 这样可以保证设置参数实时生效
for (int i=0;i<MOTOR_COUNT;i++) {
pid[i]->update(float(DataHolder::get()->parameter.params.kp)/DataHolder::get()->parameter.params.ko,
for (int i = 0; i < MOTOR_COUNT; i++)
{
pid[i]->Update(float(DataHolder::get()->parameter.params.kp) / DataHolder::get()->parameter.params.ko,
float(DataHolder::get()->parameter.params.ki) / DataHolder::get()->parameter.params.ko,
float(DataHolder::get()->parameter.params.kd) / DataHolder::get()->parameter.params.ko, MAX_PWM_VALUE);
}
@ -295,17 +306,21 @@ void Robot::update(const MESSAGE_ID id, void* data)
// 保存参数到flash
DataHolder::get()->save_parameter();
break;
case ID_CLEAR_ODOM: // 清除里程计信息
case ID_CLEAR_ODOM:
// 清除里程计信息
clear_odom();
break;
case ID_SET_VELOCITY: // 设置机器人的速度
updateVelocity(); //更新机器人的期望速度
case ID_SET_VELOCITY:
// 更新机器人的期望速度
updateVelocity();
break;
case ID_GET_ENCODER_COUNT:
update_encoder_count(); // 更新encoder count
// 更新encoder count
update_encoder_count();
break;
case ID_SET_MOTOR_PWM:
update_pwm_value(); // 设置pwm值
// 设置pwm值
update_pwm_value();
break;
default:
break;
@ -357,7 +372,8 @@ void Robot::updateVelocity()
void Robot::update_encoder_count()
{
for (int i = 0; i < MOTOR_COUNT; i++){
DataHolder::get()->encoder_count[i] = encoder[i]->get_total_count();//输出累计编码器值 用于调试
// 输出累计编码器值 用于调试
DataHolder::get()->encoder_count[i] = encoder[i]->get_total_count();
}
}
@ -371,27 +387,32 @@ void Robot::DoKinmatics()
{
if (do_set_pwm_flag){
do_set_pwm_flag = false;
for (int i = 0; i < MOTOR_COUNT; i++){
motor[i]->control(DataHolder::get()->pwm.value[i]);
}
}
if (!do_kinmatics_flag) { // 停止后
for(int i=0;i<MOTOR_COUNT;i++) {
pid[i]->clear(); // 清除pid
encoder[i]->get_increment_count_for_dopid();// 实时更新用于pid的encoder值
if (!do_kinmatics_flag)
{ // 停止后
for (int i = 0; i < MOTOR_COUNT; i++)
{
// 清除pid
pid[i]->Clear();
// 实时更新用于pid的encoder值
encoder[i]->get_increment_count_for_dopid();
}
return; // do_kinmatics_flag false表示电机停止 不需要做pid 故返回
}
static unsigned long last_millis = 0;
// 判断时间间隔做pid运算
if (Board::get()->getTickCount()-last_millis>=DataHolder::get()->parameter.params.do_pid_interval) {
if (Board::get()->getTickCount() - last_millis >= DataHolder::get()->parameter.params.do_pid_interval)
{
last_millis = Board::get()->getTickCount();
// 得到编码器的反馈差值, 即在do_pid_interval这段间隔时间内编码器的差值 该值作为pid的反馈
for (int i=0;i<MOTOR_COUNT;i++) {
for (int i = 0; i < MOTOR_COUNT; i++)
{
feedback[i] = encoder[i]->get_increment_count_for_dopid();
}
#if PID_DEBUG_OUTPUT
@ -410,8 +431,10 @@ void Robot::DoKinmatics()
#endif
bool stoped = true;
// 当期望和反馈都为0 置位stoped标志
for (int i=0;i<MOTOR_COUNT;i++) {
if (input[i] != 0 || feedback[i] != 0) {
for (int i = 0; i < MOTOR_COUNT; i++)
{
if (input[i] != 0 || feedback[i] != 0)
{
stoped = false;
break;
}
@ -423,7 +446,7 @@ void Robot::DoKinmatics()
}else{
// 没有需要停止则做pid运算得到out值该值作为电机模块控制器输入
for (int i = 0; i < MOTOR_COUNT; i++){
output[i] = pid[i]->compute(DataHolder::get()->parameter.params.do_pid_interval*0.001);
output[i] = pid[i]->Compute(DataHolder::get()->parameter.params.do_pid_interval * 0.001);
}
}
@ -432,7 +455,7 @@ void Robot::DoKinmatics()
DataHolder::get()->pid_data.input[i] = int(input[i]);
DataHolder::get()->pid_data.output[i] = int(feedback[i]);
}
log("output=%ld %ld", output[0], output[1]);
#if PID_DEBUG_OUTPUT
#if MOTOR_COUNT == 2
log("output=%ld %ld", output[0], output[1]);
@ -466,7 +489,8 @@ void Robot::CalcOdom()
{
static unsigned long last_millis = 0;
// 根据实际间隔计算轮子里程
if (Board::get()->getTickCount()-last_millis>=CALC_ODOM_INTERVAL) {
if (Board::get()->getTickCount() - last_millis >= CALC_ODOM_INTERVAL)
{
last_millis = Board::get()->getTickCount();
#if ODOM_DEBUG_OUTPUT
long total_count[MOTOR_COUNT] = {0};
@ -485,9 +509,9 @@ void Robot::CalcOdom()
#endif
#endif
float dis[MOTOR_COUNT] = {0};
for (int i=0;i<MOTOR_COUNT;i++) {
for (int i = 0; i < MOTOR_COUNT; i++)
{
// 根据CALC_ODOM_INTERVAL的间隔内的各个电机的编码器变化值转换各个电机实际的里程
// 距离 = 编码器增量 * PI * 轮子直径(mm) * 0.001 / 编码器分辨率 / 电机的减速比
dis[i] = encoder[i]->get_increment_count_for_odom() * __PI * DataHolder::get()->parameter.params.wheel_diameter * 0.001 / DataHolder::get()->parameter.params.encoder_resolution / DataHolder::get()->parameter.params.motor_ratio;
#if ODOM_DEBUG_OUTPUT
log(" %ld ", long(dis[i] * 1000000));
@ -501,10 +525,13 @@ void Robot::CalcOdom()
log(" x=%ld y=%ld yaw=%ld", long(odom.x * 1000), long(odom.y * 1000), long(odom.z * 1000)); // mm
log("");
#endif
log("x=%ld cm/s y=%ld cm/s yaw=%ld", long(odom.vel_x * 100), long(odom.vel_y * 100), long(odom.z * 1000)); // mm
// 转换单位保存到DataHolder
DataHolder::get()->odom.v_liner_x = odom.vel_x * 100; // 转为cm/s
DataHolder::get()->odom.v_liner_y = odom.vel_y*100;
DataHolder::get()->odom.v_liner_y = odom.vel_y * 100; // 转为cm/s
DataHolder::get()->odom.v_angular_z = odom.vel_z * 100;
DataHolder::get()->odom.x = odom.x * 100; // 转为cm
DataHolder::get()->odom.y = odom.y * 100;
@ -524,7 +551,7 @@ void Robot::GetImuData()
// 按照设置的时间间隔获取imu数据
if (Board::get()->getTickCount() - last_millis >= CALC_IMU_INTERVAL){
last_millis = Board::get()->getTickCount();
imu->get_data(DataHolder::get()->imu_data);
imu->GetData(DataHolder::get()->imu_data);
}
#endif
}

View File

@ -1,9 +0,0 @@
.vscode
STM32/Output/*
Output
DebugConfig
JLinkLog.txt
pibot check.map
pibot.uvguix.*
startup_stm32f10x_md.lst
MDK-ARM

View File

@ -1,273 +0,0 @@
#ifdef __cplusplus
extern "C" {
#endif
#include "adc_dac.h"
#define ADC1_DR_Address ((u32)0x40012400+0x4c)
volatile unsigned int ADC_Sample_Value[32];
float Reference_Voltage;
float cpu_temperature;
uint8_t ADC_EN_NUM;
void PB_ADC_Init(uint16_t adc_channel , uint8_t adc_num , float Reference_Voltage_ )
{
/**********************************************************************************************************************/
DMA_InitTypeDef DMA_InitStructure;
ADC_InitTypeDef ADC_InitStructure;
uint8_t ADC_Channel_Num;
GPIO_InitTypeDef GPIO_InitStructure;
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA | RCC_APB2Periph_GPIOB |RCC_APB2Periph_GPIOC, ENABLE);
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AIN;
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA1, ENABLE);
RCC_APB2PeriphClockCmd(RCC_APB2Periph_ADC1,ENABLE);
/**********************************************************************************************************************/
ADC_EN_NUM = adc_num;
Reference_Voltage = Reference_Voltage_;
DMA_DeInit(DMA1_Channel1);
DMA_InitStructure.DMA_PeripheralBaseAddr = ADC1_DR_Address; //ADC address
DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)ADC_Sample_Value;//RAM address
DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralSRC;
DMA_InitStructure.DMA_BufferSize = adc_num+1;//plus 1 is for the temperature adc.
DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;//Peripherals fixed address
DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable; //RAM fixed address
DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Word;
DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Word;
DMA_InitStructure.DMA_Mode = DMA_Mode_Circular; //cycle transmission
DMA_InitStructure.DMA_Priority = DMA_Priority_High;
DMA_InitStructure.DMA_M2M = DMA_M2M_Disable;
DMA_Init(DMA1_Channel1, &DMA_InitStructure);
DMA_Cmd(DMA1_Channel1, ENABLE);
/* ADC1 configuration */
ADC_InitStructure.ADC_Mode = ADC_Mode_RegSimult; //indepedent ADC mode
ADC_InitStructure.ADC_ScanConvMode = ENABLE ; //enable scan mode, scan mode used by multi-channel collect
ADC_InitStructure.ADC_ContinuousConvMode = ENABLE; //enable continuous convert mode
ADC_InitStructure.ADC_ExternalTrigConv = ADC_ExternalTrigConv_None; //not use external interrupt to start convert
ADC_InitStructure.ADC_DataAlign = ADC_DataAlign_Right; //collect data Align Right
ADC_InitStructure.ADC_NbrOfChannel = adc_num+1; //number of channel need be convert
ADC_Init(ADC1, &ADC_InitStructure);
/*configure ADC clock, the frequency must below 14MHz*/
RCC_ADCCLKConfig(RCC_PCLK2_Div6);
ADC_DMACmd(ADC1, ENABLE);
ADC_Cmd(ADC1, ENABLE);
ADC_Channel_Num=0;
//if ADC0 enable
if( ( (adc_channel >> 0) & 0x0001) == 1) {
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_0;
GPIO_Init(GPIOA, &GPIO_InitStructure);
ADC_RegularChannelConfig(ADC1, ADC_Channel_0, ++ADC_Channel_Num , ADC_SampleTime_55Cycles5);
}
//if ADC1 enable
if( ( (adc_channel >> 1) & 0x0001) == 1) {
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_1;
GPIO_Init(GPIOA, &GPIO_InitStructure);
ADC_RegularChannelConfig(ADC1, ADC_Channel_1, ++ADC_Channel_Num , ADC_SampleTime_55Cycles5);
}
//if ADC2 enable
if( ( (adc_channel >> 2) & 0x0001) == 1) {
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_2;
GPIO_Init(GPIOA, &GPIO_InitStructure);
ADC_RegularChannelConfig(ADC1, ADC_Channel_2, ++ADC_Channel_Num , ADC_SampleTime_55Cycles5);
}
//if ADC3 enable
if( ( (adc_channel >> 3) & 0x0001) == 1) {
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_3;
GPIO_Init(GPIOA, &GPIO_InitStructure);
ADC_RegularChannelConfig(ADC1, ADC_Channel_3, ++ADC_Channel_Num , ADC_SampleTime_55Cycles5);
}
//if ADC4 enable
if( ( (adc_channel >> 4) & 0x0001) == 1) {
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_4;
GPIO_Init(GPIOA, &GPIO_InitStructure);
ADC_RegularChannelConfig(ADC1, ADC_Channel_4, ++ADC_Channel_Num , ADC_SampleTime_55Cycles5);
}
//if ADC5 enable
if( ( (adc_channel >> 5) & 0x0001) == 1) {
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_5;
GPIO_Init(GPIOA, &GPIO_InitStructure);
ADC_RegularChannelConfig(ADC1, ADC_Channel_5, ++ADC_Channel_Num , ADC_SampleTime_55Cycles5);
}
//if ADC6 enable
if( ( (adc_channel >> 6) & 0x0001) == 1) {
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6;
GPIO_Init(GPIOA, &GPIO_InitStructure);
ADC_RegularChannelConfig(ADC1, ADC_Channel_6, ++ADC_Channel_Num , ADC_SampleTime_55Cycles5);
}
//if ADC7 enable
if( ( (adc_channel >> 7) & 0x0001) == 1) {
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_7;
GPIO_Init(GPIOA, &GPIO_InitStructure);
ADC_RegularChannelConfig(ADC1, ADC_Channel_7, ++ADC_Channel_Num , ADC_SampleTime_55Cycles5);
}
//if ADC8 enable
if( ( (adc_channel >> 8) & 0x0001) == 1) {
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_0;
GPIO_Init(GPIOB, &GPIO_InitStructure);
ADC_RegularChannelConfig(ADC1, ADC_Channel_8, ++ADC_Channel_Num , ADC_SampleTime_55Cycles5);
}
//if ADC9 enable
if( ( (adc_channel >> 9) & 0x0001) == 1) {
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_1;
GPIO_Init(GPIOB, &GPIO_InitStructure);
ADC_RegularChannelConfig(ADC1, ADC_Channel_9, ++ADC_Channel_Num , ADC_SampleTime_55Cycles5);
}
//if ADC10 enable
if( ( (adc_channel >> 10) & 0x0001) == 1) {
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_0;
GPIO_Init(GPIOC, &GPIO_InitStructure);
ADC_RegularChannelConfig(ADC1, ADC_Channel_10, ++ADC_Channel_Num , ADC_SampleTime_55Cycles5);
}
//if ADC11 enable
if( ( (adc_channel >> 11) & 0x0001) == 1) {
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_1;
GPIO_Init(GPIOC, &GPIO_InitStructure);
ADC_RegularChannelConfig(ADC1, ADC_Channel_11, ++ADC_Channel_Num , ADC_SampleTime_55Cycles5);
}
//if ADC12 enable
if( ( (adc_channel >> 12) & 0x0001) == 1) {
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_2;
GPIO_Init(GPIOC, &GPIO_InitStructure);
ADC_RegularChannelConfig(ADC1, ADC_Channel_12, ++ADC_Channel_Num , ADC_SampleTime_55Cycles5);
}
//if ADC13 enable
if( ( (adc_channel >> 13) & 0x0001) == 1) {
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_3;
GPIO_Init(GPIOC, &GPIO_InitStructure);
ADC_RegularChannelConfig(ADC1, ADC_Channel_13, ++ADC_Channel_Num , ADC_SampleTime_55Cycles5);
}
//if ADC14 enable
if( ( (adc_channel >> 14) & 0x0001) == 1) {
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_4;
GPIO_Init(GPIOC, &GPIO_InitStructure);
ADC_RegularChannelConfig(ADC1, ADC_Channel_14, ++ADC_Channel_Num , ADC_SampleTime_55Cycles5);
}
//if ADC15 enable
if( ( (adc_channel >> 15) & 0x0001) == 1) {
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_5;
GPIO_Init(GPIOC, &GPIO_InitStructure);
ADC_RegularChannelConfig(ADC1, ADC_Channel_15, ++ADC_Channel_Num , ADC_SampleTime_55Cycles5);
}
//the channel16 is always enable
//set collect channel IN16,set collect time
ADC_RegularChannelConfig(ADC1, ADC_Channel_16, ++ADC_Channel_Num , ADC_SampleTime_239Cycles5); //set collect channel IN16,set collect time
ADC_TempSensorVrefintCmd(ENABLE); //enable inner standard voltage and temperture sensor
ADC_DMACmd(ADC1, ENABLE);
ADC_Cmd(ADC1, ENABLE);
ADC_ResetCalibration(ADC1);
while(ADC_GetResetCalibrationStatus(ADC1));
ADC_StartCalibration(ADC1);
while(ADC_GetCalibrationStatus(ADC1));
ADC_SoftwareStartConvCmd(ADC1, ENABLE); /* because not using external interrupt to start collect, using software to start */
}
float PB_Get_ADC_Output(uint8_t n)
{
float ADC_Standard_Value = 0;
if(n <= ADC_EN_NUM + 1)
{
ADC_Standard_Value = ( (float)ADC_Sample_Value[n-1]/4096 ) * (float)Reference_Voltage;
}
return ADC_Standard_Value;
}
#define ADC1_DR_Address ((u32)0x40012400+0x4c)
#define V25 0x6EE
#define AVG_SLOPE 0x05
float PB_Get_CPU_Temperature(void)
{
cpu_temperature = 0.8f*cpu_temperature + 0.2f*(((float)V25- PB_Get_ADC_Output(ADC_EN_NUM + 1)) / (float)AVG_SLOPE+25) ;
return cpu_temperature;
}
void PB_DAC_Init(uint8_t channel_x)
{
GPIO_InitTypeDef GPIO_InitStructure;
DAC_InitTypeDef DAC_InitType;
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA, ENABLE ); //enable PORTA clock
RCC_APB1PeriphClockCmd(RCC_APB1Periph_DAC, ENABLE ); //enable DAC clock
DAC_InitType.DAC_Trigger=DAC_Trigger_None; //disable trigger, TEN1=0
DAC_InitType.DAC_WaveGeneration=DAC_WaveGeneration_None;//disable wave generate
DAC_InitType.DAC_LFSRUnmask_TriangleAmplitude=DAC_LFSRUnmask_Bit0;//mask amplitude set
DAC_InitType.DAC_OutputBuffer=DAC_OutputBuffer_Disable ; //disable DAC1 output cache, BOFF1=1
if(channel_x == DAC_Channel_1)
{
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_4; // GPIO configuration
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AIN; //Analog Input
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_Init(GPIOA, &GPIO_InitStructure);
GPIO_SetBits(GPIOA,GPIO_Pin_4) ; //PA.4 High output
DAC_Init(DAC_Channel_1,&DAC_InitType); //initialize DAC output channel1
DAC_Cmd(DAC_Channel_1, ENABLE);
DAC_SetChannel1Data(DAC_Align_12b_R, 0); //12 Bits align right mode to set value of DAC
}
else if(channel_x == DAC_Channel_2)
{
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_5; // GPIO Configuration
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AIN; //Analog Input
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_Init(GPIOA, &GPIO_InitStructure);
GPIO_SetBits(GPIOA,GPIO_Pin_5) ; //PA.4 High output
DAC_Init(DAC_Channel_2,&DAC_InitType); //initialize DAC output channel1
DAC_Cmd(DAC_Channel_2, ENABLE);
DAC_SetChannel2Data(DAC_Align_12b_R, 0); //12 Bits align right mode to set value of DAC
}
}
void PB_DAC_Set_Vol(uint8_t channel_x , uint16_t vol)
{
float temp=vol;
temp/=1000;
temp=temp*4096/(float)3.3;
if( channel_x == DAC_Channel_1){
DAC_SetChannel1Data(DAC_Align_12b_R,temp);//12 Bits align right mode to set value of DAC
}
else if(channel_x == DAC_Channel_2){
DAC_SetChannel2Data(DAC_Align_12b_R,temp);//12 Bits align right mode to set value of DAC
}
}
#ifdef __cplusplus
}
#endif

View File

@ -1,23 +0,0 @@
#ifndef ADC_DAC_H
#define ADC_DAC_H
#ifdef __cplusplus
extern "C" {
#endif
#include "stm32f10x.h"
void PB_ADC_Init(uint16_t adc_channel , uint8_t adc_num , float Reference_Voltage_);
float PB_Get_ADC_Output(uint8_t n);
float PB_Get_CPU_Temperature(void); //°C
void PB_DAC_Init(uint8_t channel_x);
void PB_DAC_Set_Vol(uint8_t channel_x , uint16_t vol);
#ifdef __cplusplus
}
#endif
#endif // #ifndef ADC_DAC_H

View File

@ -1,22 +0,0 @@
#ifndef BSPLIB_H
#define BSPLIB_H
#include "nvic.h"
#include "delay.h"
#include "rtc.h"
#include "wdg_wkup.h"
#include "flash.h"
#include "usart.h"
#include "adc_dac.h"
#include "timer.h"
#include "pwm_in.h"
#include "pwm_out.h"
#include "encoder.h"
#include "i2c.h"
#include "spi.h"
#endif //#ifndef BSPLIB_H

View File

@ -1,80 +0,0 @@
#ifdef __cplusplus
extern "C" {
#endif
#include "delay.h"
float count_time = 0;
float count_us = 0;
float count_ms = 0;
float reload = 0;
void System_TimerInit(void)
{
SysTick_CLKSourceConfig(SysTick_CLKSource_HCLK_Div8);//clear bit2, and using external clock HCK/8
count_us=SystemCoreClock / 8000000;
count_ms=(uint16_t)count_us * 1000;
reload = 16777215;
SysTick->CTRL|=SysTick_CTRL_TICKINT_Msk; //enable SYSTICK interrupt
SysTick->LOAD=reload; //enter interrupt every 1/delay_ostickspersec second
SysTick->VAL = reload;
SysTick->CTRL|=SysTick_CTRL_ENABLE_Msk; //enable SYSTICK
}
void SysTick_Handler(void)
{
count_time++;
if(count_time >= 0xffffffff)
{
count_time=0;
}
}
float getSystemTime(void)
{
float count , time;
count = (float)( (reload + 1 - SysTick->VAL) + (float)(reload + 1) * count_time);
time = count/count_us;
return time;
}
float getDeltaTime(void)
{
static float lasttime;
float temp1,temp2;
temp1 = getSystemTime();
temp2 = temp1 - lasttime;
if(temp2 < 0)
{
temp2 = ( ( (float)(reload + 1) * (float)0xffffffff) / count_us) - lasttime + temp1;
}
lasttime = temp1;
return temp2;
}
void delay_us(unsigned short int t)
{
int i;
for( i=0;i<t;i++)
{
int a=9;
while(a--) ;
}
}
void delay_ms(unsigned short int t)
{
int i;
for( i=0;i<t;i++)
{
int a=10300;
while(a--) ;
}
}
#ifdef __cplusplus
}
#endif

View File

@ -1,22 +0,0 @@
#ifndef DELAY_H
#define DELAY_H
#ifdef __cplusplus
extern "C" {
#endif
#include "stm32f10x.h"
/**********************************************************************************************************************/
void delay_ms(uint16_t t); // using timer to delay time, max delay time is 1864ms
void delay_us(uint16_t t); // using timer to delay time, max delay time is 1864ms
/**********************************************************************************************************************/
void System_TimerInit(void); // Initialize the Time measurement system
float getSystemTime(void); // Return the current time(us), max:281474976s--->3257.8 days
float getDeltaTime(void); // Return the time difference(us). max:655s
#ifdef __cplusplus
}
#endif
#endif // #ifndef DELAY_H

View File

@ -1,164 +0,0 @@
#ifdef __cplusplus
extern "C"
{
#endif
#include "encoder.h"
#include "nvic.h"
#include "print.h"
#define ENCODER_TIM_PERIOD (u16)(60000) // number of pulses per revolution
void Encoder_InitGPIO(TIM_TypeDef *TIMx, unsigned char GPIO_AF) // Initialize encoder mode, input parameter TIM1 TIM2 TIM3
{
TIM_ICInitTypeDef TIM_ICInitStructure;
GPIO_InitTypeDef GPIO_InitStructure;
TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
if (TIMx == TIM2)
{
RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2, ENABLE); /* enable clock */
if (GPIO_AF == 0)
{
// TIM2 CHI1 CHI2---PA0 PA1;
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA, ENABLE);
GPIO_StructInit(&GPIO_InitStructure);
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_0 | GPIO_Pin_1;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
GPIO_Init(GPIOA, &GPIO_InitStructure);
}
else if (GPIO_AF == 1)
{
//---------------------------------------------------------------TIM2 CHI1 CHI2---PA15 PB3;
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA | RCC_APB2Periph_GPIOB | RCC_APB2Periph_AFIO, ENABLE);
GPIO_PinRemapConfig(GPIO_FullRemap_TIM2, ENABLE);
GPIO_PinRemapConfig(GPIO_Remap_SWJ_JTAGDisable, ENABLE); // This is very important!
GPIO_StructInit(&GPIO_InitStructure);
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_15;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
GPIO_Init(GPIOA, &GPIO_InitStructure);
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_3;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
GPIO_Init(GPIOB, &GPIO_InitStructure);
}
TIM2_NVIC_Configuration(); // enable interrupt
}
else if (TIMx == TIM3)
{
RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM3 | RCC_APB2Periph_GPIOB | RCC_APB2Periph_GPIOA, ENABLE); /* enable clock */
if (GPIO_AF == 0)
{
// TIM3 CHI1 CHI2---PA6 PA7;
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA, ENABLE);
GPIO_StructInit(&GPIO_InitStructure);
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6 | GPIO_Pin_7;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
GPIO_Init(GPIOA, &GPIO_InitStructure);
}
else if (GPIO_AF == 1)
{
// TIM3 CHI1 CHI2---PB4 PB5;
GPIO_PinRemapConfig(GPIO_PartialRemap_TIM3, ENABLE);
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOB, ENABLE);
GPIO_StructInit(&GPIO_InitStructure);
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_4 | GPIO_Pin_5;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
GPIO_Init(GPIOB, &GPIO_InitStructure);
}
TIM3_NVIC_Configuration(); // enable interrupt
}
else if (TIMx == TIM4)
{
RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM4, ENABLE); /* enable clock */
if (GPIO_AF == 0)
{
// TIM4 CHI1 CHI2---PB6 PB7;
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOB, ENABLE);
GPIO_StructInit(&GPIO_InitStructure);
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6 | GPIO_Pin_7;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
GPIO_Init(GPIOB, &GPIO_InitStructure);
}
else if (GPIO_AF == 1)
{
// TIM4 CHI1 CHI2---PD12 PD13;
GPIO_PinRemapConfig(GPIO_Remap_TIM4, ENABLE);
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOD, ENABLE);
GPIO_StructInit(&GPIO_InitStructure);
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_12 | GPIO_Pin_13;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
GPIO_Init(GPIOD, &GPIO_InitStructure);
}
TIM4_NVIC_Configuration();
}
else if (TIMx == TIM5)
{
RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM5, ENABLE);
if (GPIO_AF == 0)
{
// TIM5 CHI1 CHI2---PA0 PA1;
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA, ENABLE);
GPIO_StructInit(&GPIO_InitStructure);
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_0 | GPIO_Pin_1;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
GPIO_Init(GPIOA, &GPIO_InitStructure);
}
TIM5_NVIC_Configuration();
}
TIM_TimeBaseStructInit(&TIM_TimeBaseStructure);
TIM_TimeBaseStructure.TIM_Prescaler = 0x0; /* prescler : 72M/72 */
TIM_TimeBaseStructure.TIM_Period = ENCODER_TIM_PERIOD;
TIM_TimeBaseStructure.TIM_ClockDivision = TIM_CKD_DIV1;
TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up; /* count upwards */
TIM_TimeBaseInit(TIMx, &TIM_TimeBaseStructure);
TIM_EncoderInterfaceConfig(TIMx, TIM_EncoderMode_TI12, TIM_ICPolarity_Rising, TIM_ICPolarity_Rising);
TIM_ICStructInit(&TIM_ICInitStructure);
TIM_ICInitStructure.TIM_ICFilter = 10;
TIM_ICInit(TIMx, &TIM_ICInitStructure);
TIM_Cmd(TIMx, ENABLE);
TIMx->CNT = 0x7fff;
}
float Encoder_GetTIM2(void)
{
float cnt;
cnt = (float)((uint16_t)0x7fff) - (float)((uint16_t)(TIM2->CNT)); //! (float) is must
TIM2->CNT = 0x7fff;
return cnt;
}
float Encoder_GetTIM3(void)
{
float cnt;
cnt = (float)((uint16_t)30000) - (float)((uint16_t)(TIM3->CNT));
TIM3->CNT = 30000;
return cnt;
}
float Encoder_GetTIM4(void)
{
float cnt;
cnt = (float)((uint16_t)30000) - (float)((uint16_t)(TIM4->CNT));
TIM4->CNT = 30000;
return cnt;
}
float Encoder_GetTIM5(void)
{
float cnt;
cnt = (float)((uint16_t)0x7fff) - (float)((uint16_t)(TIM5->CNT));
TIM5->CNT = 0x7fff;
return cnt;
}
#ifdef __cplusplus
}
#endif

View File

@ -1,23 +0,0 @@
#ifndef ENCODER_H
#define ENCODER_H
#ifdef __cplusplus
extern "C" {
#endif
#include "stm32f10x.h"
#include "stdint.h"
void Encoder_InitGPIO(TIM_TypeDef* TIMx , uint8_t GPIO_AF);
float Encoder_GetTIM5(void);
float Encoder_GetTIM4(void);
float Encoder_GetTIM3(void);
float Encoder_GetTIM2(void);
#ifdef __cplusplus
}
#endif
#endif // #ifndef ENCODER_H

View File

@ -1,60 +0,0 @@
#ifdef __cplusplus
extern "C"
{
#endif
#include "flash.h"
u16 Flash_ReadHalfWord(u32 faddr)
{
uint16_t val = 0;
faddr = faddr + FLASH_SAVE_ADDR;
val = *(uint16_t *)faddr;
return val;
}
u32 Flash_ReadWord(u32 faddr)
{
uint16_t val = 0;
faddr = faddr + FLASH_SAVE_ADDR;
val = *(uint32_t *)faddr;
return val;
}
#define PageSize 0x400
void Flash_EnableWrite()
{
/*FLASH_Unlock();
FLASH_ErasePage(FLASH_SAVE_ADDR);
CLEAR_BIT(FLASH->CR, FLASH_CR_PER);*/
FLASH_Unlock();
FLASH_ClearFlag(FLASH_FLAG_BSY | FLASH_FLAG_EOP | FLASH_FLAG_PGERR | FLASH_FLAG_WRPRTERR);
FLASH_ErasePage(FLASH_SAVE_ADDR);
// FLASH_ErasePage(FLASH_SAVE_ADDR + PageSize);
}
void Flash_DisableWrite()
{
FLASH_Lock();
}
u32 Flash_WriteHalfWord(u32 faddr, u16 data)
{
faddr = faddr + FLASH_SAVE_ADDR;
return FLASH_ProgramHalfWord(faddr, data);
}
u32 Flash_WriteWord(u32 faddr, u32 data)
{
faddr = faddr + FLASH_SAVE_ADDR;
return FLASH_ProgramWord(faddr, data);
}
#ifdef __cplusplus
}
#endif

View File

@ -1,25 +0,0 @@
#ifndef FLASH_H
#define FLASH_H
#ifdef __cplusplus
extern "C" {
#endif
#include "stm32f10x.h"
#define FLASH_SAVE_ADDR ((uint32_t)0x800FC00)
u16 Flash_ReadHalfWord(u32 faddr);
u32 Flash_ReadWord(u32 faddr);
void Flash_EnableWrite(void);
void Flash_DisableWrite(void);
u32 Flash_WriteHalfWord(u32 faddr, u16 data);
u32 Flash_WriteWord(u32 faddr, u32 data);
#ifdef __cplusplus
}
#endif
#endif // #ifndef FLASH_H

View File

@ -1,226 +0,0 @@
#ifdef __cplusplus
extern "C" {
#endif
#include "i2c.h"
#include "nvic.h"
static void I2C_delay()
{
volatile int i = 7;
while (i)
i--;
}
static int I2C_Start()
{
SDA_H;
SCL_H;
I2C_delay();
if (!SDA_read)
return 0;
SDA_L;
I2C_delay();
if (SDA_read)
return 0;
SDA_L;
I2C_delay();
return 1;
}
static void I2C_Stop()
{
SCL_L;
I2C_delay();
SDA_L;
I2C_delay();
SCL_H;
I2C_delay();
SDA_H;
I2C_delay();
}
static void I2C_Ack()
{
SCL_L;
I2C_delay();
SDA_L;
I2C_delay();
SCL_H;
I2C_delay();
SCL_L;
I2C_delay();
}
static void I2C_NoAck()
{
SCL_L;
I2C_delay();
SDA_H;
I2C_delay();
SCL_H;
I2C_delay();
SCL_L;
I2C_delay();
}
static int I2C_WaitAck()
{
SCL_L;
I2C_delay();
SDA_H;
I2C_delay();
SCL_H;
I2C_delay();
if (SDA_read) {
SCL_L;
return 0;
}
SCL_L;
return 1;
}
static void I2C_SendByte(uint8_t b)
{
uint8_t i = 8;
while (i--) {
SCL_L;
I2C_delay();
if (b & 0x80)
SDA_H;
else
SDA_L;
b <<= 1;
I2C_delay();
SCL_H;
I2C_delay();
}
SCL_L;
}
static uint8_t I2C_ReadByteData()
{
uint8_t i = 8;
uint8_t byte = 0;
SDA_H;
while (i--) {
byte <<= 1;
SCL_L;
I2C_delay();
SCL_H;
I2C_delay();
if (SDA_read) {
byte |= 0x01;
}
}
SCL_L;
return byte;
}
void I2C_InitGPIO(void)
{
GPIO_InitTypeDef GPIO_InitStructure;
//已更改
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOB , ENABLE);
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_8 | GPIO_Pin_9;
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_2MHz;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_OD;
GPIO_Init(GPIOB, &GPIO_InitStructure);
}
int I2C_WriteByte(uint8_t addr, uint8_t reg, uint8_t data)
{
if (!I2C_Start())
return 0;
I2C_SendByte(addr << 1 | I2C_Direction_Transmitter);
if (!I2C_WaitAck()) {
I2C_Stop();
return 0;
}
I2C_SendByte(reg);
I2C_WaitAck();
I2C_SendByte(data);
if (!I2C_WaitAck()) {
I2C_Stop();
return 0;
}
I2C_Stop();
return 1;
}
int I2C_WriteBuf(uint8_t addr, uint8_t reg, uint8_t *data , uint8_t size)
{
int i;
if (!I2C_Start())
return 0;
I2C_SendByte(addr << 1 | I2C_Direction_Transmitter);
if (!I2C_WaitAck()) {
I2C_Stop();
return 0;
}
I2C_SendByte(reg);
I2C_WaitAck();
for (i = 0; i < size; i++) {
I2C_SendByte(data[i]);
if (!I2C_WaitAck()) {
I2C_Stop();
return 0;
}
}
I2C_Stop();
return 1;
}
int I2C_ReadByte(uint8_t addr, uint8_t reg, uint8_t* data)
{
if (!I2C_Start())
return 0;
I2C_SendByte(addr << 1 | I2C_Direction_Transmitter);
if (!I2C_WaitAck()) {
I2C_Stop();
return 0;
}
I2C_SendByte(reg);
I2C_WaitAck();
I2C_Start();
I2C_SendByte(addr << 1 | I2C_Direction_Receiver);
I2C_WaitAck();
*data = I2C_ReadByteData();
I2C_NoAck();
I2C_Stop();
return 1;
}
int I2C_ReadBuf(uint8_t addr,uint8_t reg, uint8_t* data , uint8_t size)
{
if (!I2C_Start())
return 0;
I2C_SendByte(addr << 1 | I2C_Direction_Transmitter);
if (!I2C_WaitAck()) {
I2C_Stop();
return 0;
}
I2C_SendByte(reg);
I2C_WaitAck();
I2C_Start();
I2C_SendByte(addr << 1 | I2C_Direction_Receiver);
I2C_WaitAck();
while (size) {
*data = I2C_ReadByteData();
if (size == 1)
I2C_NoAck();
else
I2C_Ack();
data++;
size--;
}
I2C_Stop();
return 1;
}
#ifdef __cplusplus
}
#endif

View File

@ -1,35 +0,0 @@
#ifndef __i2c_H__
#define __i2c_H__
#ifdef __cplusplus
extern "C" {
#endif
#include "stm32f10x.h"
#define SCL_H GPIOB->BSRR = GPIO_Pin_8
#define SCL_L GPIOB->BRR = GPIO_Pin_8
#define SDA_H GPIOB->BSRR = GPIO_Pin_9
#define SDA_L GPIOB->BRR = GPIO_Pin_9
#define SCL_read GPIOB->IDR & GPIO_Pin_8
#define SDA_read GPIOB->IDR & GPIO_Pin_9
/*********************************************************************************************************************/
void I2C_InitGPIO(void);
int I2C_WriteByte(uint8_t addr, uint8_t reg, uint8_t data);
int I2C_WriteBuf(uint8_t addr, uint8_t reg, uint8_t *data, uint8_t size);
int I2C_ReadByte(uint8_t addr, uint8_t reg, uint8_t* data);
int I2C_ReadBuf(uint8_t addr,uint8_t reg, uint8_t* data, uint8_t size);
#ifdef __cplusplus
}
#endif
#endif //__i2c_H__

View File

@ -1,217 +0,0 @@
#ifdef __cplusplus
extern "C" {
#endif
#include "nvic.h"
void CAN1_NVIC_Configuration(void)
{
NVIC_InitTypeDef NVIC_InitStructure;
NVIC_PriorityGroupConfig(NVIC_PriorityGroup_2);
NVIC_InitStructure.NVIC_IRQChannel = USB_LP_CAN1_RX0_IRQn;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 1; //PreemptionPriority 0--4 Lower value, Higher Priority.
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0; //SubPriority 0--4 Lower value, Higher Priority.
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; //ENABLE Interrupt
NVIC_Init(&NVIC_InitStructure);
}
void CAN2_NVIC_Configuration(void)
{
// NVIC_InitTypeDef NVIC_InitStructure;
// NVIC_PriorityGroupConfig(NVIC_PriorityGroup_2);
// NVIC_InitStructure.NVIC_IRQChannel = USB_LP_CAN1_RX0_IRQn;
// NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 1; //PreemptionPriority 0--4 Lower value, Higher Priority.
// NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0; //SubPriority 0--4 Lower value, Higher Priority.
// NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; //ENABLE Interrupt
// NVIC_Init(&NVIC_InitStructure);
}
void USART1_NVIC_Configuration(void)
{
NVIC_InitTypeDef NVIC_InitStructure;
NVIC_PriorityGroupConfig(NVIC_PriorityGroup_2);
NVIC_InitStructure.NVIC_IRQChannel = USART1_IRQn;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 1; //PreemptionPriority 0--4 Lower value, Higher Priority.
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 1; //SubPriority 0--4 Lower value, Higher Priority.
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; //ENABLE Interrupt
NVIC_Init(&NVIC_InitStructure);
}
void USART2_NVIC_Configuration(void)
{
NVIC_InitTypeDef NVIC_InitStructure;
NVIC_PriorityGroupConfig(NVIC_PriorityGroup_2);
NVIC_InitStructure.NVIC_IRQChannel = USART2_IRQn;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 1; //PreemptionPriority 0--4 Lower value, Higher Priority.
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 1; //SubPriority 0--4 Lower value, Higher Priority.
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; //ENABLE Interrupt
NVIC_Init(&NVIC_InitStructure);
}
void USART3_NVIC_Configuration(void)
{
NVIC_InitTypeDef NVIC_InitStructure;
NVIC_PriorityGroupConfig(NVIC_PriorityGroup_2);
NVIC_InitStructure.NVIC_IRQChannel = USART3_IRQn;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 1; //PreemptionPriority 0--4 Lower value, Higher Priority.
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 1; //SubPriority 0--4 Lower value, Higher Priority.
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; //ENABLE Interrupt
NVIC_Init(&NVIC_InitStructure);
}
void UART4_NVIC_Configuration(void)
{
}
void UART5_NVIC_Configuration(void)
{
}
void TIM1_NVIC_Configuration(void)
{
NVIC_InitTypeDef NVIC_InitStructure;
NVIC_PriorityGroupConfig(NVIC_PriorityGroup_2);
NVIC_InitStructure.NVIC_IRQChannel = TIM1_UP_IRQn;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 2; //PreemptionPriority 0--4 Lower value, Higher Priority.
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0; //SubPriority 0--4 Lower value, Higher Priority.
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; //ENABLE Interrupt
NVIC_Init(&NVIC_InitStructure);
}
void TIM2_NVIC_Configuration(void)
{
NVIC_InitTypeDef NVIC_InitStructure;
NVIC_PriorityGroupConfig(NVIC_PriorityGroup_2);
NVIC_InitStructure.NVIC_IRQChannel = TIM2_IRQn;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 2; //PreemptionPriority 0--4 Lower value, Higher Priority.
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0; //SubPriority 0--4 Lower value, Higher Priority.
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; //ENABLE Interrupt
NVIC_Init(&NVIC_InitStructure);
}
void TIM3_NVIC_Configuration(void)
{
NVIC_InitTypeDef NVIC_InitStructure;
NVIC_PriorityGroupConfig(NVIC_PriorityGroup_2);
NVIC_InitStructure.NVIC_IRQChannel = TIM3_IRQn;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 2; //PreemptionPriority 0--4 Lower value, Higher Priority.
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0; //SubPriority 0--4 Lower value, Higher Priority.
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; //ENABLE Interrupt
NVIC_Init(&NVIC_InitStructure);
}
void TIM4_NVIC_Configuration(void)
{
NVIC_InitTypeDef NVIC_InitStructure;
NVIC_PriorityGroupConfig(NVIC_PriorityGroup_2);
NVIC_InitStructure.NVIC_IRQChannel = TIM4_IRQn;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 2; //PreemptionPriority 0--4 Lower value, Higher Priority.
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0; //SubPriority 0--4 Lower value, Higher Priority.
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; //ENABLE Interrupt
NVIC_Init(&NVIC_InitStructure);
}
void TIM5_NVIC_Configuration(void)
{
}
void TIM6_NVIC_Configuration(void)
{
}
void TIM7_NVIC_Configuration(void)
{
}
void TIM8_NVIC_Configuration(void)
{
}
void EXTI0_NVIC_Configuration(void)
{
NVIC_InitTypeDef NVIC_InitStructure;
NVIC_PriorityGroupConfig(NVIC_PriorityGroup_2);
NVIC_InitStructure.NVIC_IRQChannel = EXTI0_IRQn;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 2;
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 2;
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&NVIC_InitStructure);
}
void EXTI1_NVIC_Configuration(void)
{
NVIC_InitTypeDef NVIC_InitStructure;
NVIC_PriorityGroupConfig(NVIC_PriorityGroup_2);
NVIC_InitStructure.NVIC_IRQChannel = EXTI1_IRQn;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 2;
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 2;
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&NVIC_InitStructure);
}
void EXTI2_NVIC_Configuration(void)
{
NVIC_InitTypeDef NVIC_InitStructure;
NVIC_PriorityGroupConfig(NVIC_PriorityGroup_2);
NVIC_InitStructure.NVIC_IRQChannel = EXTI2_IRQn;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 2;
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 2;
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&NVIC_InitStructure);
}
void EXTI3_NVIC_Configuration(void)
{
NVIC_InitTypeDef NVIC_InitStructure;
NVIC_PriorityGroupConfig(NVIC_PriorityGroup_2);
NVIC_InitStructure.NVIC_IRQChannel = EXTI3_IRQn;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 2;
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 2;
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&NVIC_InitStructure);
}
void EXTI4_NVIC_Configuration(void)
{
NVIC_InitTypeDef NVIC_InitStructure;
NVIC_PriorityGroupConfig(NVIC_PriorityGroup_2);
NVIC_InitStructure.NVIC_IRQChannel = EXTI4_IRQn;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 2;
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 2;
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&NVIC_InitStructure);
}
void EXTI9_5_NVIC_Configuration(void)
{
NVIC_InitTypeDef NVIC_InitStructure;
NVIC_PriorityGroupConfig(NVIC_PriorityGroup_2);
NVIC_InitStructure.NVIC_IRQChannel = EXTI9_5_IRQn;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 2;
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 2;
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&NVIC_InitStructure);
}
void EXTI15_10_NVIC_Configuration(void)
{
NVIC_InitTypeDef NVIC_InitStructure;
NVIC_InitStructure.NVIC_IRQChannel = EXTI15_10_IRQn;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority= 2;
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 2;
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&NVIC_InitStructure);
}
#ifdef __cplusplus
}
#endif

View File

@ -1,37 +0,0 @@
#ifndef NVIC_H
#define NVIC_H
#ifdef __cplusplus
extern "C" {
#endif
#include "stm32f10x.h"
void CAN1_NVIC_Configuration(void);
void CAN2_NVIC_Configuration(void);
void USART1_NVIC_Configuration(void);
void USART2_NVIC_Configuration(void);
void USART3_NVIC_Configuration(void);
void UART4_NVIC_Configuration(void);
void UART5_NVIC_Configuration(void);
void TIM1_NVIC_Configuration(void);
void TIM2_NVIC_Configuration(void);
void TIM3_NVIC_Configuration(void);
void TIM4_NVIC_Configuration(void);
void TIM5_NVIC_Configuration(void);
void TIM6_NVIC_Configuration(void);
void TIM7_NVIC_Configuration(void);
void TIM8_NVIC_Configuration(void);
void EXTI0_NVIC_Configuration(void);
void EXTI1_NVIC_Configuration(void);
void EXTI2_NVIC_Configuration(void);
void EXTI3_NVIC_Configuration(void);
void EXTI4_NVIC_Configuration(void);
void EXTI9_5_NVIC_Configuration(void);
void EXTI15_10_NVIC_Configuration(void);
#ifdef __cplusplus
}
#endif
#endif // #ifndef NVIC_H

View File

@ -1,193 +0,0 @@
#ifdef __cplusplus
extern "C" {
#endif
#include "pwm_in.h"
#include "nvic.h"
#include "delay.h"
static float PWM_Input_CH[5]; //current input value of PWM (Unit:us)
void PB_PwmIn_Init(uint8_t pwmin_channel)
{
GPIO_InitTypeDef GPIO_InitStructure;
EXTI_InitTypeDef EXTI_InitStructure;
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOC | RCC_APB2Periph_AFIO,ENABLE);
//RCC_APB2PeriphClockCmd(RCC_APB2Periph_SYSCFG, ENABLE);
//if enable this channel
if( pwmin_channel == 0) {
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_0 ;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IPD; // input pull down
GPIO_Init(GPIOC, &GPIO_InitStructure);
GPIO_EXTILineConfig(GPIO_PortSourceGPIOC, GPIO_PinSource0); /* EXTI line(PC0) mode config */
EXTI_InitStructure.EXTI_Line = EXTI_Line0;
EXTI_InitStructure.EXTI_Mode = EXTI_Mode_Interrupt; //interrupt mode
EXTI_InitStructure.EXTI_Trigger = EXTI_Trigger_Rising_Falling; //enable interrupt of posedge and negedge
EXTI_InitStructure.EXTI_LineCmd = ENABLE; //enable interrupt
EXTI_Init(&EXTI_InitStructure);
EXTI0_NVIC_Configuration() ;
}
//if enable this channel
if( pwmin_channel == 1) {
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_1 ;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IPD; //input pull down
GPIO_Init(GPIOC, &GPIO_InitStructure);
GPIO_EXTILineConfig(GPIO_PortSourceGPIOC, GPIO_PinSource1); /* EXTI line(PC0) mode config */
EXTI_InitStructure.EXTI_Line = EXTI_Line1;
EXTI_InitStructure.EXTI_Mode = EXTI_Mode_Interrupt; //interrupt mode
EXTI_InitStructure.EXTI_Trigger = EXTI_Trigger_Rising_Falling; //enable interrupt of posedge and negedge
EXTI_InitStructure.EXTI_LineCmd = ENABLE; //enable interrupt
EXTI_Init(&EXTI_InitStructure);
EXTI1_NVIC_Configuration() ;
}
//if enable this channel
if( pwmin_channel == 2) {
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_2 ;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IPD; // input pull down
GPIO_Init(GPIOC, &GPIO_InitStructure);
GPIO_EXTILineConfig(GPIO_PortSourceGPIOC, GPIO_PinSource2); /* EXTI line(PC0) mode config */
EXTI_InitStructure.EXTI_Line = EXTI_Line2;
EXTI_InitStructure.EXTI_Mode = EXTI_Mode_Interrupt; //interrupt mode
EXTI_InitStructure.EXTI_Trigger = EXTI_Trigger_Rising_Falling; //enable interrupt of posedge and negedge
EXTI_InitStructure.EXTI_LineCmd = ENABLE; //enable interrupt
EXTI_Init(&EXTI_InitStructure);
EXTI2_NVIC_Configuration() ;
}
//if enable this channel
if( pwmin_channel == 3) {
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_3 ;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IPD; // input pull down
GPIO_Init(GPIOC, &GPIO_InitStructure);
GPIO_EXTILineConfig(GPIO_PortSourceGPIOC, GPIO_PinSource3); /* EXTI line(PC0) mode config */
EXTI_InitStructure.EXTI_Line = EXTI_Line3;
EXTI_InitStructure.EXTI_Mode = EXTI_Mode_Interrupt; //interrupt mode
EXTI_InitStructure.EXTI_Trigger = EXTI_Trigger_Rising_Falling; //enable interrupt of posedge and negedge
EXTI_InitStructure.EXTI_LineCmd = ENABLE; //enable interrupt
EXTI_Init(&EXTI_InitStructure);
EXTI3_NVIC_Configuration() ;
}
//if enable this channel
if( pwmin_channel == 4) {
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_4 ;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IPD; // input pull down
GPIO_Init(GPIOC, &GPIO_InitStructure);
GPIO_EXTILineConfig(GPIO_PortSourceGPIOC, GPIO_PinSource4); /* EXTI line(PC0) mode config */
EXTI_InitStructure.EXTI_Line = EXTI_Line4;
EXTI_InitStructure.EXTI_Mode = EXTI_Mode_Interrupt; //interrupt mode
EXTI_InitStructure.EXTI_Trigger = EXTI_Trigger_Rising_Falling; //enable interrupt of posedge and negedge
EXTI_InitStructure.EXTI_LineCmd = ENABLE; //enable interrupt
EXTI_Init(&EXTI_InitStructure);
EXTI4_NVIC_Configuration() ;
}
}
float PB_Get_PWM_Value(uint8_t channel_x)
{
return PWM_Input_CH[channel_x];
}
void EXTI1_IRQHandler(void)
{
static float FallingTime=0 , RisingTime =0;
if( GPIOC->IDR & 0x0002)
{
RisingTime = PB_Get_System_Time();
}
else
{
FallingTime = PB_Get_System_Time();
if(FallingTime < RisingTime){ return ;}
else
{
PWM_Input_CH[0] = FallingTime - RisingTime;
}
}
EXTI->PR=1<<1; //clear interrupt flag
}
//interrupt program of interrupt line2
void EXTI2_IRQHandler(void)
{
static float FallingTime=0 , RisingTime =0;
if( GPIOC->IDR & 0x0004)
{
RisingTime = PB_Get_System_Time();
}
else
{
FallingTime = PB_Get_System_Time();
if(FallingTime < RisingTime){return ;}
else
{
PWM_Input_CH[1] = FallingTime - RisingTime;
}
}
EXTI->PR=1<<2; //clear interrupt flag
}
//interrupt program of interrupt line3
void EXTI3_IRQHandler(void)
{
static float FallingTime=0 , RisingTime =0;
if( GPIOC->IDR & 0x0008)
{
RisingTime = PB_Get_System_Time();
}
else
{
FallingTime = PB_Get_System_Time();
if(FallingTime < RisingTime){ return ;}
else
{
PWM_Input_CH[3] = FallingTime - RisingTime;
}
}
EXTI->PR=1<<3; //clear interrupt flag
}
//interrupt program of interrupt line4
void EXTI4_IRQHandler(void)
{
static float FallingTime=0 , RisingTime =0;
if( GPIOC->IDR & 0x0010)
{
RisingTime = PB_Get_System_Time();
}
else
{
FallingTime = PB_Get_System_Time();
if(FallingTime < RisingTime){ return ;}
else
{
PWM_Input_CH[4] = FallingTime - RisingTime;
}
}
EXTI->PR=1<<4; //clear interrupt flag
}
#ifdef __cplusplus
}
#endif

View File

@ -1,26 +0,0 @@
#ifndef __pwm_in_H__
#define __pwm_in_H__
#ifdef __cplusplus
extern "C" {
#endif
#include "stm32f10x.h"
#define PWM_Input_CH0_ENABLE 1 // if use this channel to capture PWM PC0
#define PWM_Input_CH1_ENABLE 0 // if use this channel to capture PWM PC1
#define PWM_Input_CH2_ENABLE 0 // if use this channel to capture PWM PC2
#define PWM_Input_CH3_ENABLE 0 // if use this channel to capture PWM PC3
#define PWM_Input_CH4_ENABLE 0 // if use this channel to capture PWM PC4
//void PWM_Input_Init(void);
void PB_PwmIn_Init(uint8_t pwmin_channel);
float PB_Get_PWM_Value(uint8_t channel_x); //current input value of PWM (Unit:us)
#ifdef __cplusplus
}
#endif
#endif //__pwm_in_H__

View File

@ -1,152 +0,0 @@
#ifdef __cplusplus
extern "C" {
#endif
#include "pwm_out.h"
void PB_PWMChannel_Init(TIM_TypeDef* TIMx, uint8_t Channel, uint16_t Prescaler,uint16_t Period, uint8_t GPIO_AF)
{
GPIO_InitTypeDef GPIO_InitStructure;
TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
TIM_OCInitTypeDef TIM_OCInitStructure;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
RCC_APB2PeriphClockCmd(RCC_APB2Periph_AFIO, ENABLE); //使能GPIO外设和AFIO复用功能模块时钟
if (TIMx == TIM1) {
RCC_APB2PeriphClockCmd(RCC_APB2Periph_TIM1, ENABLE);
if (GPIO_AF == 0) {
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA, ENABLE);
/******************************TIM1 Multiplexing Push-pull output*********************************************/
if (Channel == 1)
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_8;
else if(Channel == 2)
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_9;
else if(Channel == 3)
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_10;
else if(Channel == 4)
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_11;
else return;
GPIO_Init(GPIOA, &GPIO_InitStructure);
} else if (GPIO_AF == 1 ) {
}
} else if (TIMx == TIM2) {
RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2, ENABLE);
if (GPIO_AF == 0 ) {
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA, ENABLE);
/******************************TIM1 Multiplexing Push-pull output*********************************************/
if (Channel == 1)
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_0;
else if (Channel == 2)
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_1;
else if (Channel == 3)
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_2;
else if (Channel == 4)
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_3;
else return;
GPIO_Init(GPIOA, &GPIO_InitStructure);
} else if (GPIO_AF == 1) {
}
} else if (TIMx == TIM3) {
RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM3,ENABLE);
if (GPIO_AF == 0) {
/******************************TIM1 Multiplexing Push-pull output*********************************************/
if (Channel == 1) {
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA, ENABLE);
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6;
GPIO_Init(GPIOA, &GPIO_InitStructure);
} else if (Channel == 2) {
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA, ENABLE);
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_7;
GPIO_Init(GPIOA, &GPIO_InitStructure);
} else if (Channel == 3) {
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOB, ENABLE);
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_0;
GPIO_Init(GPIOB, &GPIO_InitStructure);
} else if (Channel == 4) {
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOB, ENABLE);
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_1;
GPIO_Init(GPIOB, &GPIO_InitStructure);
} else
return;
} else if (GPIO_AF == 1) {
GPIO_Init(GPIOC, &GPIO_InitStructure);
}
} else if (TIMx == TIM4) {
RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM4,ENABLE);
if (GPIO_AF == 0) {
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOB, ENABLE);
/******************************TIM1 Multiplexing Push-pull output*********************************************/
if (Channel == 1)
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6;
else if (Channel == 2)
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_7;
else if (Channel == 3)
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_8;
else if (Channel == 4)
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_9;
else
return;
GPIO_Init(GPIOB, &GPIO_InitStructure);
} else if (GPIO_AF == 1) {
}
}
TIM_TimeBaseStructure.TIM_Prescaler = Prescaler;
TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
TIM_TimeBaseStructure.TIM_Period = Period;
TIM_TimeBaseStructure.TIM_ClockDivision = 0;
TIM_TimeBaseStructure.TIM_RepetitionCounter = 0;
TIM_TimeBaseInit(TIMx, &TIM_TimeBaseStructure);
TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM2;
TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
TIM_OCInitStructure.TIM_OutputNState = TIM_OutputNState_Disable;
TIM_OCInitStructure.TIM_Pulse =0;
TIM_OCInitStructure.TIM_OCPolarity = TIM_OCPolarity_Low;
TIM_OCInitStructure.TIM_OCNPolarity = TIM_OCNPolarity_High;
TIM_OCInitStructure.TIM_OCIdleState = TIM_OCIdleState_Set;
TIM_OCInitStructure.TIM_OCNIdleState = TIM_OCIdleState_Reset;
TIM_OCInitStructure.TIM_Pulse = 0;
if (Channel == 1) {
TIM_OC1Init(TIMx, &TIM_OCInitStructure);
} else if (Channel == 2) {
TIM_OC2Init(TIMx, &TIM_OCInitStructure);
} else if (Channel == 3) {
TIM_OC3Init(TIMx, &TIM_OCInitStructure);
} else if (Channel == 4) {
TIM_OC4Init(TIMx, &TIM_OCInitStructure);
} else
return;
TIM_Cmd(TIMx, ENABLE);
TIM_CtrlPWMOutputs(TIMx, ENABLE);
}
//Set Pulse Width
void PB_Set_PWM(TIM_TypeDef* TIMx, uint8_t Channel, uint16_t Pwm_Value)
{
uint16_t TIM_PWM_Period;
TIM_PWM_Period = TIMx->ARR;
if (Pwm_Value <= 0) Pwm_Value = 0;
if (Pwm_Value >= TIM_PWM_Period)
Pwm_Value = TIM_PWM_Period;
if (Channel == 1) {
TIM_SetCompare1(TIMx, Pwm_Value);
} else if (Channel == 2){
TIM_SetCompare2(TIMx, Pwm_Value);
} else if (Channel == 3) {
TIM_SetCompare3(TIMx, Pwm_Value);
} else if (Channel ==4 ) {
TIM_SetCompare4(TIMx, Pwm_Value);
} else
return;
}
#ifdef __cplusplus
}
#endif

View File

@ -1,21 +0,0 @@
#ifndef PWM_OUT_H
#define PWM_OUT_H
#ifdef __cplusplus
extern "C" {
#endif
#include "stm32f10x.h"
void PB_PWMChannel_Init(TIM_TypeDef* TIMx , uint8_t Channel , uint16_t Prescaler,
uint16_t Period, uint8_t GPIO_AF);
void PB_Set_PWM(TIM_TypeDef* TIMx , uint8_t Channel , uint16_t Pwm_Value);
#ifdef __cplusplus
}
#endif
#endif // #ifndef PWM_OUT_H

View File

@ -1,376 +0,0 @@
#ifdef __cplusplus
extern "C" {
#endif
#include "rtc.h"
#include "delay.h"
#include "usart.h"
//time structure
typedef struct
{
volatile unsigned char hour;
volatile unsigned char min;
volatile unsigned char sec;
//Gregorian calendar
volatile unsigned short int w_year;
volatile unsigned char w_month;
volatile unsigned char w_date;
volatile unsigned char week;
}CALENDAR;
CALENDAR calendar_r;//clock structure
//month data table
unsigned char const table_week[12]={0,3,3,6,1,4,6,2,5,0,3,5}; //month correct data
//month data table of normal year
const unsigned char mon_table[12]={31,28,31,30,31,30,31,31,30,31,30,31};
/***********************************************************************************************************************
* Function: static unsigned char Is_Leap_Year(unsigned short int year)
*
* Scope:
*
* Description: judge whether is leap year
* month 1 2 3 4 5 6 7 8 9 10 11 12
* leap year 31 29 31 30 31 30 31 31 30 31 30 31
* not leap year 31 28 31 30 31 30 31 31 30 31 30 31
* Input : Year
* Arguments:
*
* Return: 1,is leap year
* 0,not is leap year
* Cpu_Time:
*
* History:
************************************************************************************************************************/
static unsigned char Is_Leap_Year(unsigned short int year)
{
if(year%4==0) //must be divisible by 4
{
if(year%100==0)
{
if(year%400==0)return 1;//If end is 00, must be divisible by 400
else return 0;
}else return 1;
}else return 0;
}
/************************************************************************************************************************
* Function: unsigned char RTC_Get_Week(unsigned short int year,unsigned char month,unsigned char day)
*
* Scope:
*
* Description: Input date data to get week data
* legal input is 1901-2099
* year,month,dayGregorian calendar date
*
* Arguments:
*
* Return: week data
*
* Cpu_Time:
*
* History:
*************************************************************************************************************************/
unsigned char RTC_Get_Week(unsigned short int year,unsigned char month,unsigned char day)
{
unsigned short int temp2;
unsigned char yearH,yearL;
yearH=year/100; yearL=year%100;
//if 21th century, year need add 100
if (yearH>19)yearL+=100;
//leap year only calculate after 1900
temp2=yearL+yearL/4;
temp2=temp2%7;
temp2=temp2+day+table_week[month-1];
if (yearL%4==0&&month<3)temp2--;
temp2%=7;
if(temp2==0)temp2=7;
return temp2;
}
/*************************************************************************************************************************
* Function: static unsigned char RTC_Get(void)
*
* Scope:
*
* Description: get current time
*
* Arguments:
*
* Return: 0-->succeeded others-->failed
*
* Cpu_Time:
*
* History:
**************************************************************************************************************************/
static unsigned char RTC_Get(void)
{
static unsigned short int daycnt=0;
unsigned int timecount=0;
unsigned int temp=0;
unsigned short int temp1=0;
timecount=RTC_GetCounter();
temp=timecount/86400; //get days(correspond the second)
if(daycnt!=temp)//over one day
{
daycnt=temp;
temp1=1970; //start at 1970
while(temp>=365)
{
if(Is_Leap_Year(temp1))//is leap year
{
if(temp>=366)temp-=366;//the seconds of leap year
else {temp1++;break;}
}
else temp-=365; //normal year
temp1++;
}
calendar_r.w_year=temp1;//get year
temp1=0;
while(temp>=28)//over one month
{
if(Is_Leap_Year(calendar_r.w_year)&&temp1==1)//judge if is leap month (February)
{
if(temp>=29)temp-=29;//the seconds of leap year
else break;
}
else
{
if(temp>=mon_table[temp1])temp-=mon_table[temp1];//normal year
else break;
}
temp1++;
}
calendar_r.w_month=temp1+1; //get month
calendar_r.w_date=temp+1; //get date
}
temp=timecount%86400; //get second
calendar_r.hour=temp/3600; //hour
calendar_r.min=(temp%3600)/60; //minute
calendar_r.sec=(temp%3600)%60; //second
calendar_r.week=RTC_Get_Week(calendar_r.w_year,calendar_r.w_month,calendar_r.w_date);//get week
return 0;
}
/*************************************************************************************************************************
* Function: RTC_NVIC_Config(void)
*
* Scope: private
*
* Description: RTC Configuration of Interruption
*
* Arguments:
*
* Return:
*
* Cpu_Time:
*
* History:
**************************************************************************************************************************/
static void RTC_NVIC_Config(void)
{
NVIC_InitTypeDef NVIC_InitStructure;
NVIC_InitStructure.NVIC_IRQChannel = RTC_IRQn; //RTC Global Interrupt
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0; //PreemptionPriority
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0; //SubPriority
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; //ENABLE the interrupt
NVIC_Init(&NVIC_InitStructure); //Initialize the NVIC register
}
/*************************************************************************************************************************
* Function: RTC_IRQHandler(void)
*
* Scope: private
*
* Description: RTC Interruptation update every second
*
* Arguments:
*
* Return:
*
* Cpu_Time:
*
* History:
**************************************************************************************************************************/
void RTC_IRQHandler(void)
{
if (RTC_GetITStatus(RTC_IT_SEC) != RESET)//RTC Interruptation
{
RTC_Get();//更新时间
}
if(RTC_GetITStatus(RTC_IT_ALR)!= RESET)//alarm clock interrupt
{
RTC_ClearITPendingBit(RTC_IT_ALR); //clear clock interrupt
RTC_Get(); //update time
// printf("Alarm Time:%d-%d-%d %d:%d:%d\n",calendar_r.w_year,calendar_r.w_month,calendar_r.w_date,calendar_r.hour,calendar_r.min,calendar_r.sec);//输出闹铃时间
}
RTC_ClearITPendingBit(RTC_IT_SEC|RTC_IT_OW); //clear alarm clock interrupt
RTC_WaitForLastTask();
}
unsigned char PB_RTC_Init(void)
{
//check if is first configuration of RTC
unsigned char temp=0;
RCC_APB1PeriphClockCmd(RCC_APB1Periph_PWR | RCC_APB1Periph_BKP, ENABLE); //ENABLE clock of PWR and BKP
PWR_BackupAccessCmd(ENABLE); //enable access of backup register
if (BKP_ReadBackupRegister(BKP_DR1) != 0x5050) //read data from backup register
{
BKP_DeInit(); //RESET backuo area
RCC_LSEConfig(RCC_LSE_ON); //set external LSE, and use LSE
while (RCC_GetFlagStatus(RCC_FLAG_LSERDY) == RESET&&temp<250) //check if set flag of RCC, and wait LSE is ready
{
temp++;
delay_ms(10);
}
if(temp>=250) return 1;//Initialize clock failed, the Crystal has error
RCC_RTCCLKConfig(RCC_RTCCLKSource_LSE); //set LSE to be the clock of RTC
RCC_RTCCLKCmd(ENABLE); //enable RTC
RTC_WaitForLastTask(); //wait finish writing RTC register
RTC_WaitForSynchro(); //wait RTC sync
RTC_ITConfig(RTC_IT_SEC, ENABLE); //ENABLE RTC Interrupt
RTC_WaitForLastTask(); //wait finish writing RTC register
RTC_EnterConfigMode();/// allow to configure
RTC_SetPrescaler(32767); //set Prescaler
RTC_WaitForLastTask(); //wait finish writing RTC register
RTC_Set(2015,1,14,17,42,55); //set time
RTC_ExitConfigMode(); //quit configuration mode
BKP_WriteBackupRegister(BKP_DR1, 0X5050); //write user program data to assign backup register
}
else//system continue counting time
{
RTC_WaitForSynchro(); //wait finish writing RTC register
RTC_ITConfig(RTC_IT_SEC, ENABLE); //enable RTC interrupt
RTC_WaitForLastTask(); //wait finish writing RTC register
}
RTC_NVIC_Config();//RTC interrupt NVIC configure
RTC_Get();//update time
return 0; //ok
}
/*************************************************************************************************************************
* Function: unsigned char RTC_Set(unsigned short int syear,unsigned char smon,unsigned char sday,unsigned char hour,unsigned char min,unsigned char sec)
*
* Scope: public
*
* Description: set clock
* transform the time data to seconds
* time base is 1,1,1970
* legal input is 1970~2099
*
* Arguments:
*
* Return: 0-->succeeded others-->failed
*
* Cpu_Time:
*
* History:
**************************************************************************************************************************/
unsigned char RTC_Set(unsigned short int syear,unsigned char smon,unsigned char sday,unsigned char hour,unsigned char min,unsigned char sec)
{
unsigned short int t;
unsigned int seccount=0;
if(syear<1970||syear>2099)return 1;
for(t=1970;t<syear;t++) //add all second data of year
{
if(Is_Leap_Year(t))seccount+=31622400;//seconds of leap year
else seccount+=31536000; //seconds of noramal year
}
smon-=1;
for(t=0;t<smon;t++) //add all second data of month
{
seccount+=(unsigned int)mon_table[t]*86400;//add second of every month
if(Is_Leap_Year(syear)&&t==1)seccount+=86400;//if is leap year, add one more day time
}
seccount+=(unsigned int)(sday-1)*86400;//add all second before
seccount+=(unsigned int)hour*3600;//second of hour
seccount+=(unsigned int)min*60; //second of minute
seccount+=sec;//add second
RCC_APB1PeriphClockCmd(RCC_APB1Periph_PWR | RCC_APB1Periph_BKP, ENABLE); //enable clock of PWR and BKP
PWR_BackupAccessCmd(ENABLE); // enable access to backup register
RTC_SetCounter(seccount); //set value of RTC counter
RTC_WaitForLastTask(); //wait finish writing RTC register
return 0;
}
/*************************************************************************************************************************
* Function: void RTC_Alarm_Set(unsigned short int syear,unsigned char smon,unsigned char sday,unsigned char hour,unsigned char min,unsigned char sec)
*
* Scope: public
*
* Description: Initialize clock
* transform the time data to seconds
* time base is 1,1,1970
* legal input is 1970~2099
*
* Arguments:
*
* Return: 0-->succeeded others-->failed
*
* Cpu_Time:
*
* History:
**************************************************************************************************************************/
void RTC_Alarm_Set(unsigned short int syear,unsigned char smon,unsigned char sday,unsigned char hour,unsigned char min,unsigned char sec)
{
unsigned short int t;
unsigned int seccount=0;
if(syear<1970||syear>2099)return ;
for(t=1970;t<syear;t++) //add all second data of year
{
if(Is_Leap_Year(t))seccount+=31622400;//seconds of leap year
else seccount+=31536000; //seconds of noramal year
}
smon-=1;
for(t=0;t<smon;t++) //add all second data of month
{
seccount+=(unsigned int)mon_table[t]*86400;//add second of every month
if(Is_Leap_Year(syear)&&t==1)seccount+=86400;//if is leap year, add one more day time
}
seccount+=(unsigned int)(sday-1)*86400;//add all second before
seccount+=(unsigned int)hour*3600;//second of hour
seccount+=(unsigned int)min*60; //second of minute
seccount+=sec;//add second
//set clock
RCC_APB1PeriphClockCmd(RCC_APB1Periph_PWR | RCC_APB1Periph_BKP, ENABLE); //enable clock of PWR and BKP
PWR_BackupAccessCmd(ENABLE); //enable access to backup register
//3 upside steps are necessary
RTC_SetAlarm(seccount);
RTC_WaitForLastTask(); //wait finish writing RTC register
return ;
}
void PB_Get_RTC_Time(uint8_t* year , uint8_t* month , uint8_t* date , uint8_t* week
,uint8_t* hour , uint8_t* min , uint8_t* sec , uint8_t* ampm)
{
RTC_Get();
*year = calendar_r.w_year;
*month = calendar_r.w_month;
*date = calendar_r.w_date;
*week = calendar_r.week;
*hour = calendar_r.hour;
*min = calendar_r.min;
*sec = calendar_r.sec;
*ampm = 0;
}
#ifdef __cplusplus
}
#endif

View File

@ -1,27 +0,0 @@
#ifndef RTC_H
#define RTC_H
#ifdef __cplusplus
extern "C" {
#endif
#include "stm32f10x.h"
unsigned char PB_RTC_Init(void); //RTC initialization
void PB_Get_RTC_Time(uint8_t* year , uint8_t* month , uint8_t* date , uint8_t* week,
uint8_t* hour , uint8_t* min , uint8_t* sec , uint8_t* ampm);
unsigned char RTC_Get_Week(unsigned short int year, unsigned char month, unsigned char day);
void RTC_Alarm_Set(unsigned short int syear, unsigned char smon, unsigned char sday,
unsigned char hour, unsigned char min, unsigned char sec);
unsigned char RTC_Set(unsigned short int syear, unsigned char smon, unsigned char sday,
unsigned char hour, unsigned char min, unsigned char sec);//set time
#ifdef __cplusplus
}
#endif
#endif // RTC_H

View File

@ -1,132 +0,0 @@
#ifdef __cplusplus
extern "C"
{
#endif
#include "spi.h"
#include "nvic.h"
#define GPIO_SPI1 GPIOA
#define RCC_SPI1 RCC_APB2Periph_GPIOA
#define SPI1_NSS GPIO_Pin_4
#define SPI1_SCK GPIO_Pin_5
#define SPI1_MISO GPIO_Pin_6
#define SPI1_MOSI GPIO_Pin_7
#define GPIO_SPI2 GPIOB
#define RCC_SPI2 RCC_APB2Periph_GPIOB
#define SPI2_NSS GPIO_Pin_12
#define SPI2_SCK GPIO_Pin_13
#define SPI2_MISO GPIO_Pin_14
#define SPI2_MOSI GPIO_Pin_15
void PB_SPI_Init(uint8_t SPI_Channel, unsigned char GPIO_AF) // SPI interface initialization, input parameter SPI1 SPI2
{
SPI_TypeDef *SPIx;
SPI_InitTypeDef SPI_InitStructure;
GPIO_InitTypeDef GPIO_InitStructure; // initialize SPI structure
SPI_InitStructure.SPI_Direction = SPI_Direction_2Lines_FullDuplex; // SPI设置为两线全双工
SPI_InitStructure.SPI_Mode = SPI_Mode_Master; // config SPI working on master mode
SPI_InitStructure.SPI_DataSize = SPI_DataSize_8b; // SPI发送接收为8位数据帧结构
SPI_InitStructure.SPI_CPOL = SPI_CPOL_Low; // 串行时钟在不操作时,时钟为低电平
SPI_InitStructure.SPI_CPHA = SPI_CPHA_1Edge; // 第一个时钟沿开始采集数据
SPI_InitStructure.SPI_NSS = SPI_NSS_Soft; // NSS有软件(使用SSI为)管理
SPI_InitStructure.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_8; // SPI波特率预分频值为8
SPI_InitStructure.SPI_FirstBit = SPI_FirstBit_MSB; // data start transmiss at MSB
SPI_InitStructure.SPI_CRCPolynomial = 7; // CRC值计算的多项式
if (SPI_Channel == 1)
{
SPIx = SPI1;
}
else if (SPI_Channel == 2)
{
SPIx = SPI2;
}
else if (SPI_Channel == 3)
{
SPIx = SPI3;
}
else
{
return;
}
if (SPIx == SPI1)
{
RCC_APB2PeriphClockCmd(RCC_APB2Periph_SPI1, ENABLE);
if (GPIO_AF == 0)
{
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA | RCC_APB2Periph_AFIO, ENABLE);
GPIO_InitStructure.GPIO_Pin = SPI1_MISO | SPI1_MOSI | SPI1_SCK;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP; // Multiplexing push-pull output
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_Init(GPIO_SPI1, &GPIO_InitStructure);
GPIO_SetBits(GPIO_SPI1, SPI1_MISO | SPI1_MOSI | SPI1_SCK);
}
else if (GPIO_AF == 1)
{
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA | RCC_APB2Periph_AFIO | RCC_APB2Periph_GPIOB, ENABLE);
GPIO_PinRemapConfig(GPIO_Remap_SPI1, ENABLE); // Pin Multiplexing to spi1
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_3 | GPIO_Pin_4 | GPIO_Pin_5;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP; // Multiplexing push-pull output
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_Init(GPIO_SPI1, &GPIO_InitStructure);
GPIO_SetBits(GPIO_SPI1, GPIO_Pin_3 | GPIO_Pin_4 | GPIO_Pin_5);
}
}
else if (SPIx == SPI2)
{
RCC_APB1PeriphClockCmd(RCC_APB1Periph_SPI2, ENABLE);
if (GPIO_AF == 0)
{
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOB | RCC_APB2Periph_AFIO, ENABLE);
GPIO_InitStructure.GPIO_Pin = SPI2_MISO | SPI2_MOSI | SPI2_SCK;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP; // Multiplexing push-pull output
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_Init(GPIO_SPI2, &GPIO_InitStructure);
GPIO_SetBits(GPIO_SPI2, SPI2_MISO | SPI2_MOSI | SPI2_SCK);
}
else if (GPIO_AF == 1)
{
}
}
SPI_Init(SPIx, &SPI_InitStructure);
SPI_Cmd(SPIx, ENABLE);
PB_SPI_ReadWriteByte(SPI_Channel, 0xff); // start transmission
}
uint8_t PB_SPI_ReadWriteByte(uint8_t SPI_Channel, uint8_t TxData)
{
SPI_TypeDef *SPIx;
if (SPI_Channel == 1)
{
SPIx = SPI1;
}
else if (SPI_Channel == 2)
{
SPIx = SPI2;
}
else if (SPI_Channel == 3)
{
SPIx = SPI3;
}
else
{
return 0;
}
while (SPI_I2S_GetFlagStatus(SPIx, SPI_I2S_FLAG_TXE) == RESET)
; // flag of send cache is not reset
SPI_I2S_SendData(SPIx, TxData); // send data
while (SPI_I2S_GetFlagStatus(SPIx, SPI_I2S_FLAG_RXNE) == RESET)
; // flag of receivecache is not reset
return SPI_I2S_ReceiveData(SPIx); // receive data
}
#ifdef __cplusplus
}
#endif

View File

@ -1,20 +0,0 @@
#ifndef SPI_H
#define SPI_H
#ifdef __cplusplus
extern "C" {
#endif
#include "stm32f10x.h"
//Initialize serial external interface of SPI, config SPI working on master mode
void PB_SPI_Init(uint8_t SPI_Channel , unsigned char GPIO_AF); //SPI interface initialization, input parameter SPI1 SPI2
uint8_t PB_SPI_ReadWriteByte(uint8_t SPI_Channel , uint8_t TxData); //SPI w/r data function
#ifdef __cplusplus
}
#endif
#endif // #ifndef SPI_H

View File

@ -1,66 +0,0 @@
#ifdef __cplusplus
extern "C"
{
#endif
#include "timer.h"
#include "nvic.h"
void Timer_InitBase(TIM_TypeDef *TIMx, uint32_t Time_us)
{
TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
if (TIMx == TIM2)
{
RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2, ENABLE); /* enable clock */
TIM2_NVIC_Configuration(); // enable interruptation
}
else if (TIMx == TIM3)
{
RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM3, ENABLE); /* enable clock */
TIM3_NVIC_Configuration(); // enable interruptation
}
else if (TIMx == TIM4)
{
RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM4, ENABLE); /* enable clock */
TIM4_NVIC_Configuration(); // enable interruptation
}
else if (TIMx == TIM5)
{
RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM5, ENABLE); /* enable clock */
TIM5_NVIC_Configuration(); // enable interruptation
}
else if (TIMx == TIM6)
{
RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM6, ENABLE); /* enable clock */
TIM6_NVIC_Configuration(); // enable interruptation
}
else if (TIMx == TIM7)
{
RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM7, ENABLE); /* enable clock */
TIM7_NVIC_Configuration(); // enable interruptation
}
TIM_DeInit(TIMx);
TIM_TimeBaseStructure.TIM_Period = Time_us - 1; /* the value of auto reload register */
TIM_TimeBaseStructure.TIM_Prescaler = (72 - 1); /* prescler : 72M/72 */
/* ClockDivision*/
if (TIMx == TIM3 || TIMx == TIM4)
{
TIM_TimeBaseStructure.TIM_ClockDivision = TIM_CKD_DIV4;
}
else
{
TIM_TimeBaseStructure.TIM_ClockDivision = TIM_CKD_DIV1;
}
TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up; /* count upwards */
TIM_TimeBaseInit(TIMx, &TIM_TimeBaseStructure);
TIM_ClearFlag(TIMx, TIM_FLAG_Update); /* clear interrupt flags */
TIM_ITConfig(TIMx, TIM_IT_Update, ENABLE);
TIM_Cmd(TIMx, ENABLE);
}
#ifdef __cplusplus
}
#endif

View File

@ -1,18 +0,0 @@
#ifndef TIMER_H
#define TIMER_H
#ifdef __cplusplus
extern "C" {
#endif
#include "stm32f10x.h"
void Timer_InitBase(TIM_TypeDef* TIMx, uint32_t Time_us); //Input parameter :TIMx and delay time(us), *timer2--7 1ms
#ifdef __cplusplus
}
#endif
#endif //#ifndef TIMER_H

View File

@ -1,343 +0,0 @@
#ifdef __cplusplus
extern "C"
{
#endif
#include "usart.h"
#include "nvic.h"
void USART_InitGPIO(uint8_t USART_Channel, uint32_t BaudRate, uint8_t GPIO_AF)
{
// GPIO config
USART_TypeDef *USARTx;
GPIO_InitTypeDef GPIO_InitStructure;
USART_InitTypeDef USART_InitStructure;
if (USART_Channel == 1)
{
USARTx = USART1;
}
else if (USART_Channel == 2)
{
USARTx = USART2;
}
else if (USART_Channel == 3)
{
USARTx = USART3;
}
else if (USART_Channel == 4)
{
USARTx = UART4;
}
else if (USART_Channel == 5)
{
USARTx = UART5;
}
else
{
return;
}
if (USARTx == USART1)
{
RCC_APB2PeriphClockCmd(RCC_APB2Periph_USART1 | RCC_APB2Periph_GPIOA | RCC_APB2Periph_AFIO | RCC_APB2Periph_GPIOB, ENABLE);
if (GPIO_AF == 0)
{
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_9; // USART1_TX PA.9
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
GPIO_Init(GPIOA, &GPIO_InitStructure);
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_10; // USART1_RX PA.10
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
GPIO_Init(GPIOA, &GPIO_InitStructure);
}
else if (GPIO_AF == 1)
{
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6; // USART1_TX PB6
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
GPIO_Init(GPIOB, &GPIO_InitStructure);
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_7; // USART1_RX PB7
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
GPIO_Init(GPIOB, &GPIO_InitStructure);
GPIO_PinRemapConfig(GPIO_Remap_USART1, ENABLE); // use Remapping
}
USART1_NVIC_Configuration();
}
else if (USARTx == USART2)
{
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA | RCC_APB2Periph_AFIO | RCC_APB2Periph_GPIOD, ENABLE);
RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART2, ENABLE);
if (GPIO_AF == 0)
{
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_2; // USART2_TX PA.2
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
GPIO_Init(GPIOA, &GPIO_InitStructure);
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_3;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING; // USART2_RX PA.3
GPIO_Init(GPIOA, &GPIO_InitStructure);
}
else if (GPIO_AF == 1)
{
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_5; // USART2_TX PD5
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
GPIO_Init(GPIOD, &GPIO_InitStructure);
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING; // USART2_RX PD6
GPIO_Init(GPIOD, &GPIO_InitStructure);
GPIO_PinRemapConfig(GPIO_Remap_USART2, ENABLE); // use Remapping
}
USART2_NVIC_Configuration();
}
else if (USARTx == USART3)
{
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOB | RCC_APB2Periph_AFIO | RCC_APB2Periph_GPIOC | RCC_APB2Periph_GPIOD, ENABLE);
RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART3, ENABLE);
if (GPIO_AF == 0)
{
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_10; // USART3_TX PB.10
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
GPIO_Init(GPIOB, &GPIO_InitStructure);
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_11; // USART3_RX PB.11
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
GPIO_Init(GPIOB, &GPIO_InitStructure);
}
else if (GPIO_AF == 1)
{
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_10; // USART3_TX PC.10
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
GPIO_Init(GPIOC, &GPIO_InitStructure);
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_11; // USART3_RX PC.11
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
GPIO_Init(GPIOC, &GPIO_InitStructure);
GPIO_PinRemapConfig(GPIO_FullRemap_USART3, ENABLE); // use Remapping
}
else if (GPIO_AF == 2)
{
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_8; // USART3_TX PD8
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
GPIO_Init(GPIOD, &GPIO_InitStructure);
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_9; // USART3_RX PD9
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
GPIO_Init(GPIOD, &GPIO_InitStructure);
GPIO_PinRemapConfig(GPIO_FullRemap_USART3, ENABLE); // use Remapping
}
USART3_NVIC_Configuration();
}
else if (USARTx == UART4)
{
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOC | RCC_APB2Periph_AFIO, ENABLE);
RCC_APB1PeriphClockCmd(RCC_APB1Periph_UART4, ENABLE);
if (GPIO_AF == 0)
{
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_10; // USART4_TX PC.10
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
GPIO_Init(GPIOC, &GPIO_InitStructure);
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_11; // USART4_RX PC.11
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
GPIO_Init(GPIOC, &GPIO_InitStructure);
}
UART4_NVIC_Configuration();
}
else if (USARTx == UART5)
{
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOC | RCC_APB2Periph_GPIOD | RCC_APB2Periph_AFIO, ENABLE);
RCC_APB1PeriphClockCmd(RCC_APB1Periph_UART5, ENABLE);
if (GPIO_AF == 0)
{
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_12; // USART4_TX PC.12
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
GPIO_Init(GPIOC, &GPIO_InitStructure);
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_2; // USART4_RX PD.2
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
GPIO_Init(GPIOD, &GPIO_InitStructure);
}
UART5_NVIC_Configuration();
}
USART_InitStructure.USART_BaudRate = BaudRate;
USART_InitStructure.USART_WordLength = USART_WordLength_8b;
USART_InitStructure.USART_StopBits = USART_StopBits_1;
USART_InitStructure.USART_Parity = USART_Parity_No;
USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None;
USART_InitStructure.USART_Mode = USART_Mode_Rx | USART_Mode_Tx;
USART_Init(USARTx, &USART_InitStructure);
// enable interrupt
USART_ITConfig(USARTx, USART_IT_RXNE, ENABLE);
USART_ClearITPendingBit(USARTx, USART_IT_RXNE);
// enable usart
USART_Cmd(USARTx, ENABLE);
}
void USART_PutChar(uint8_t USART_Channel, unsigned char Tx_Byte)
{
USART_TypeDef *USARTx;
if (USART_Channel == 1)
{
USARTx = USART1;
}
else if (USART_Channel == 2)
{
USARTx = USART2;
}
else if (USART_Channel == 3)
{
USARTx = USART3;
}
else if (USART_Channel == 4)
{
USARTx = UART4;
}
else if (USART_Channel == 5)
{
USARTx = UART5;
}
else
{
return;
}
USART_SendData(USARTx, Tx_Byte);
while (USART_GetFlagStatus(USARTx, USART_FLAG_TXE) == RESET)
;
}
static char *itoa(int value, char *string, int radix)
{
int i, d;
int flag = 0;
char *ptr = string;
/* This implementation only works for decimal numbers. */
if (radix != 10)
{
*ptr = 0;
return string;
}
if (!value)
{
*ptr++ = 0x30;
*ptr = 0;
return string;
}
/* if this is a negative value insert the minus sign. */
if (value < 0)
{
*ptr++ = '-';
/* Make the value positive. */
value *= -1;
}
for (i = 10000; i > 0; i /= 10)
{
d = value / i;
if (d || flag)
{
*ptr++ = (char)(d + 0x30);
value -= (d * i);
flag = 1;
}
}
/* Null terminate the string. */
*ptr = 0;
return string;
} /* NCL_Itoa */
void USART_printf(USART_TypeDef *USARTx, uint8_t *Data, ...)
{
const char *s;
int d;
char buf[16];
va_list ap;
va_start(ap, Data);
while (*Data != 0) // 判断是否到达字符串结束符
{
if (*Data == 0x5c) //'\'
{
switch (*++Data)
{
case 'r': // 回车符
USART_SendData(USARTx, 0x0d);
Data++;
break;
case 'n': // 换行符
USART_SendData(USARTx, 0x0a);
Data++;
break;
default:
Data++;
break;
}
}
else if (*Data == '%')
{
switch (*++Data)
{
case 's': // 字符串
s = va_arg(ap, const char *);
for (; *s; s++)
{
USART_SendData(USARTx, *s);
while (USART_GetFlagStatus(USARTx, USART_FLAG_TC) == RESET)
;
}
Data++;
break;
case 'd': // 十进制
d = va_arg(ap, int);
itoa(d, buf, 10);
for (s = buf; *s; s++)
{
USART_SendData(USARTx, *s);
while (USART_GetFlagStatus(USARTx, USART_FLAG_TC) == RESET);
}
Data++;
break;
default:
Data++;
break;
}
} /* end of else if */
else
USART_SendData(USARTx, *Data++);
while (USART_GetFlagStatus(USARTx, USART_FLAG_TC) == RESET);
}
}
#ifdef __cplusplus
}
#endif

View File

@ -1,24 +0,0 @@
#ifndef USART_H
#define USART_H
#ifdef __cplusplus
extern "C"
{
#endif
#include "stm32f10x.h"
#include "stdarg.h"
#include "stdio.h"
// Initilaize the serial, First Parameter:USART1,USART2,USART3; 2nd Para:bits rate; 3rd: IO reuse
void USART_InitGPIO(uint8_t USART_Channel, uint32_t BaudRate, uint8_t GPIO_AF);
void USART_PutChar(uint8_t USART_Channel, uint8_t Tx_Byte); // USARTx to print 1 byte
void USART_printf(USART_TypeDef *USARTx, uint8_t *Data, ...); // format output as printf in C standard library
// int fputc(int ch, FILE *f);
#ifdef __cplusplus
}
#endif
#endif // #ifndef USART_H

View File

@ -1,130 +0,0 @@
#ifdef __cplusplus
extern "C" {
#endif
#include "wdg_wkup.h"
#include "delay.h"
void PB_IWDG_Init(void)
{
IWDG_WriteAccessCmd(IWDG_WriteAccess_Enable); //Enable access to write register
IWDG_SetPrescaler(IWDG_Prescaler_64); //Frequency: 40K / 64 = 0.625K, and one cycle is 1.6ms
IWDG_SetReload(800); //800*1.6ms = 1.28S
IWDG_ReloadCounter(); //the program to feed dog, if not write 0xAAAA every while, WDG will reset
IWDG_Enable(); //enable
}
void PB_IWDG_Feed(void)
{
IWDG_ReloadCounter();
}
static void WWDG_NVIC_Init()
{
NVIC_InitTypeDef NVIC_InitStructure;
NVIC_InitStructure.NVIC_IRQChannel = WWDG_IRQn; //WWDG interrupt
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 2; //PreemptionPriority
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 3; //SubPriority
NVIC_Init(&NVIC_InitStructure);//NVIC initialization
}
u8 WWDG_CNT=0x7f;
void PB_WWDG_Init(u8 tr,u8 wr,u32 fprer)
{
RCC_APB1PeriphClockCmd(RCC_APB1Periph_WWDG, ENABLE); // enable WWDG clock
WWDG_SetPrescaler(fprer); //set IWDG Prescaler
WWDG_SetWindowValue(wr); //set window value
WWDG_Enable(tr); //enable WWDG, and set counter
WWDG_ClearFlag();
WWDG_NVIC_Init(); //initialize WWDG NVIC
WWDG_EnableIT(); //enable interrupt of WWDG
}
void PB_WWDG_Set_Counter(u8 cnt)
{
WWDG_Enable(cnt);
}
void PB_WWDG_IRQHandler(void)
{
WWDG_SetCounter(0x7F); //if annotate this words, WWDG will reset
WWDG_ClearFlag(); //clear flag of advance wake up
}
static void Sys_Standby(void)
{
RCC_APB1PeriphClockCmd(RCC_APB1Periph_PWR, ENABLE); //ENABLE PWR clock
PWR_WakeUpPinCmd(ENABLE); //enable the wake-up Pin
PWR_EnterSTANDBYMode(); //enter standby mode
}
static void Sys_Enter_Standby(void)
{
RCC_APB2PeriphResetCmd(0X01FC,DISABLE); //RESET all IO
Sys_Standby();
}
static u8 Check_WKUP(void)
{
u8 t=0; //recording the time when pressing
// LED0=0;
while(1)
{
if(WKUP_KD)
{
t++; //have pressed
delay_ms(30);
if(t>=100) //having been pressed over 3s
{
// LED0=0; //light DS0
return 1; //having been pressed over 3s
}
}else
{
// LED0=1;
return 0; //having been pressed short 3s
}
}
}
void PB_WKUP_Init(void)
{
GPIO_InitTypeDef GPIO_InitStructure;
NVIC_InitTypeDef NVIC_InitStructure;
EXTI_InitTypeDef EXTI_InitStructure;
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA | RCC_APB2Periph_AFIO, ENABLE);
GPIO_InitStructure.GPIO_Pin =GPIO_Pin_0; //PA.0
GPIO_InitStructure.GPIO_Mode =GPIO_Mode_IPD;//pull up input
GPIO_Init(GPIOA, &GPIO_InitStructure); //Initialize IO
//use external interrupt
GPIO_EXTILineConfig(GPIO_PortSourceGPIOA, GPIO_PinSource0); //connect Interrupt Line 0 with GPIOA
EXTI_InitStructure.EXTI_Line = EXTI_Line0; //set all line of key
EXTI_InitStructure.EXTI_Mode = EXTI_Mode_Interrupt; //use external interrupt mode
EXTI_InitStructure.EXTI_Trigger = EXTI_Trigger_Rising; //response at posedge
EXTI_InitStructure.EXTI_LineCmd = ENABLE;
EXTI_Init(&EXTI_InitStructure); // initialize external interruption
NVIC_InitStructure.NVIC_IRQChannel = EXTI0_IRQn; //enable external interrupt line of key
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 2;
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 2;
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; //enable external interrupt channel
NVIC_Init(&NVIC_InitStructure);
if(Check_WKUP()==0) Sys_Standby(); //enter standby mode
}
#ifdef __cplusplus
}
#endif

View File

@ -1,23 +0,0 @@
#ifndef WDG_WKUP_H
#define WDG_WKUP_H
#ifdef __cplusplus
extern "C" {
#endif
#include "stm32f10x.h"
void PB_IWDG_Init(void);
void PB_IWDG_Feed(void);
void PB_WWDG_Init(u8 tr, u8 wr, u32 fprer);//Initialize WDG
void PB_WWDG_Set_Counter(u8 cnt); //Set the counter of WDG
#define WKUP_KD GPIOA->IDR & GPIO_Pin_0 //PA0 check if have WK_UP KEY pressed
void PB_WKUP_Init(void); //PA0 WKUP Initialization
#ifdef __cplusplus
}
#endif
#endif // #ifndef WDG_WKUP_H

View File

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

View File

@ -1,368 +0,0 @@
;******************** (C) COPYRIGHT 2011 STMicroelectronics ********************
;* File Name : startup_stm32f10x_cl.s
;* Author : MCD Application Team
;* Version : V3.5.0
;* Date : 11-March-2011
;* Description : STM32F10x Connectivity line devices vector table for MDK-ARM
;* toolchain.
;* This module performs:
;* - Set the initial SP
;* - Set the initial PC == Reset_Handler
;* - Set the vector table entries with the exceptions ISR address
;* - Configure the clock system
;* - Branches to __main in the C library (which eventually
;* calls main()).
;* After Reset the CortexM3 processor is in Thread mode,
;* priority is Privileged, and the Stack is set to Main.
;* <<< Use Configuration Wizard in Context Menu >>>
;*******************************************************************************
; 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, STMICROELECTRONICS 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.
;*******************************************************************************
; 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>
Stack_Size EQU 0x00000400
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 0x00000200
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 ; Window Watchdog
DCD PVD_IRQHandler ; PVD through EXTI Line detect
DCD TAMPER_IRQHandler ; Tamper
DCD RTC_IRQHandler ; RTC
DCD FLASH_IRQHandler ; Flash
DCD RCC_IRQHandler ; RCC
DCD EXTI0_IRQHandler ; EXTI Line 0
DCD EXTI1_IRQHandler ; EXTI Line 1
DCD EXTI2_IRQHandler ; EXTI Line 2
DCD EXTI3_IRQHandler ; EXTI Line 3
DCD EXTI4_IRQHandler ; EXTI Line 4
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_2_IRQHandler ; ADC1 and ADC2
DCD CAN1_TX_IRQHandler ; CAN1 TX
DCD CAN1_RX0_IRQHandler ; CAN1 RX0
DCD CAN1_RX1_IRQHandler ; CAN1 RX1
DCD CAN1_SCE_IRQHandler ; CAN1 SCE
DCD EXTI9_5_IRQHandler ; EXTI Line 9..5
DCD TIM1_BRK_IRQHandler ; TIM1 Break
DCD TIM1_UP_IRQHandler ; TIM1 Update
DCD TIM1_TRG_COM_IRQHandler ; TIM1 Trigger and Commutation
DCD TIM1_CC_IRQHandler ; TIM1 Capture Compare
DCD TIM2_IRQHandler ; TIM2
DCD TIM3_IRQHandler ; TIM3
DCD TIM4_IRQHandler ; TIM4
DCD I2C1_EV_IRQHandler ; I2C1 Event
DCD I2C1_ER_IRQHandler ; I2C1 Error
DCD I2C2_EV_IRQHandler ; I2C2 Event
DCD I2C2_ER_IRQHandler ; I2C1 Error
DCD SPI1_IRQHandler ; SPI1
DCD SPI2_IRQHandler ; SPI2
DCD USART1_IRQHandler ; USART1
DCD USART2_IRQHandler ; USART2
DCD USART3_IRQHandler ; USART3
DCD EXTI15_10_IRQHandler ; EXTI Line 15..10
DCD RTCAlarm_IRQHandler ; RTC alarm through EXTI line
DCD OTG_FS_WKUP_IRQHandler ; USB OTG FS Wakeup through EXTI line
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD TIM5_IRQHandler ; TIM5
DCD SPI3_IRQHandler ; SPI3
DCD UART4_IRQHandler ; UART4
DCD UART5_IRQHandler ; UART5
DCD TIM6_IRQHandler ; TIM6
DCD TIM7_IRQHandler ; TIM7
DCD DMA2_Channel1_IRQHandler ; DMA2 Channel1
DCD DMA2_Channel2_IRQHandler ; DMA2 Channel2
DCD DMA2_Channel3_IRQHandler ; DMA2 Channel3
DCD DMA2_Channel4_IRQHandler ; DMA2 Channel4
DCD DMA2_Channel5_IRQHandler ; DMA2 Channel5
DCD ETH_IRQHandler ; Ethernet
DCD ETH_WKUP_IRQHandler ; Ethernet Wakeup through EXTI line
DCD CAN2_TX_IRQHandler ; CAN2 TX
DCD CAN2_RX0_IRQHandler ; CAN2 RX0
DCD CAN2_RX1_IRQHandler ; CAN2 RX1
DCD CAN2_SCE_IRQHandler ; CAN2 SCE
DCD OTG_FS_IRQHandler ; USB OTG FS
__Vectors_End
__Vectors_Size EQU __Vectors_End - __Vectors
AREA |.text|, CODE, READONLY
; Reset handler
Reset_Handler PROC
EXPORT Reset_Handler [WEAK]
IMPORT SystemInit
IMPORT __main
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 PVD_IRQHandler [WEAK]
EXPORT TAMPER_IRQHandler [WEAK]
EXPORT RTC_IRQHandler [WEAK]
EXPORT FLASH_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_2_IRQHandler [WEAK]
EXPORT CAN1_TX_IRQHandler [WEAK]
EXPORT CAN1_RX0_IRQHandler [WEAK]
EXPORT CAN1_RX1_IRQHandler [WEAK]
EXPORT CAN1_SCE_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 TIM2_IRQHandler [WEAK]
EXPORT TIM3_IRQHandler [WEAK]
EXPORT TIM4_IRQHandler [WEAK]
EXPORT I2C1_EV_IRQHandler [WEAK]
EXPORT I2C1_ER_IRQHandler [WEAK]
EXPORT I2C2_EV_IRQHandler [WEAK]
EXPORT I2C2_ER_IRQHandler [WEAK]
EXPORT SPI1_IRQHandler [WEAK]
EXPORT SPI2_IRQHandler [WEAK]
EXPORT USART1_IRQHandler [WEAK]
EXPORT USART2_IRQHandler [WEAK]
EXPORT USART3_IRQHandler [WEAK]
EXPORT EXTI15_10_IRQHandler [WEAK]
EXPORT RTCAlarm_IRQHandler [WEAK]
EXPORT OTG_FS_WKUP_IRQHandler [WEAK]
EXPORT TIM5_IRQHandler [WEAK]
EXPORT SPI3_IRQHandler [WEAK]
EXPORT UART4_IRQHandler [WEAK]
EXPORT UART5_IRQHandler [WEAK]
EXPORT TIM6_IRQHandler [WEAK]
EXPORT TIM7_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 ETH_IRQHandler [WEAK]
EXPORT ETH_WKUP_IRQHandler [WEAK]
EXPORT CAN2_TX_IRQHandler [WEAK]
EXPORT CAN2_RX0_IRQHandler [WEAK]
EXPORT CAN2_RX1_IRQHandler [WEAK]
EXPORT CAN2_SCE_IRQHandler [WEAK]
EXPORT OTG_FS_IRQHandler [WEAK]
WWDG_IRQHandler
PVD_IRQHandler
TAMPER_IRQHandler
RTC_IRQHandler
FLASH_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_2_IRQHandler
CAN1_TX_IRQHandler
CAN1_RX0_IRQHandler
CAN1_RX1_IRQHandler
CAN1_SCE_IRQHandler
EXTI9_5_IRQHandler
TIM1_BRK_IRQHandler
TIM1_UP_IRQHandler
TIM1_TRG_COM_IRQHandler
TIM1_CC_IRQHandler
TIM2_IRQHandler
TIM3_IRQHandler
TIM4_IRQHandler
I2C1_EV_IRQHandler
I2C1_ER_IRQHandler
I2C2_EV_IRQHandler
I2C2_ER_IRQHandler
SPI1_IRQHandler
SPI2_IRQHandler
USART1_IRQHandler
USART2_IRQHandler
USART3_IRQHandler
EXTI15_10_IRQHandler
RTCAlarm_IRQHandler
OTG_FS_WKUP_IRQHandler
TIM5_IRQHandler
SPI3_IRQHandler
UART4_IRQHandler
UART5_IRQHandler
TIM6_IRQHandler
TIM7_IRQHandler
DMA2_Channel1_IRQHandler
DMA2_Channel2_IRQHandler
DMA2_Channel3_IRQHandler
DMA2_Channel4_IRQHandler
DMA2_Channel5_IRQHandler
ETH_IRQHandler
ETH_WKUP_IRQHandler
CAN2_TX_IRQHandler
CAN2_RX0_IRQHandler
CAN2_RX1_IRQHandler
CAN2_SCE_IRQHandler
OTG_FS_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 2011 STMicroelectronics *****END OF FILE*****

View File

@ -1,358 +0,0 @@
;******************** (C) COPYRIGHT 2011 STMicroelectronics ********************
;* File Name : startup_stm32f10x_hd.s
;* Author : MCD Application Team
;* Version : V3.5.0
;* Date : 11-March-2011
;* Description : STM32F10x High Density Devices vector table for MDK-ARM
;* toolchain.
;* This module performs:
;* - Set the initial SP
;* - Set the initial PC == Reset_Handler
;* - Set the vector table entries with the exceptions ISR address
;* - Configure the clock system and also configure the external
;* SRAM mounted on STM3210E-EVAL board to be used as data
;* memory (optional, to be enabled by user)
;* - Branches to __main in the C library (which eventually
;* calls main()).
;* After Reset the CortexM3 processor is in Thread mode,
;* priority is Privileged, and the Stack is set to Main.
;* <<< Use Configuration Wizard in Context Menu >>>
;*******************************************************************************
; 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, STMICROELECTRONICS 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.
;*******************************************************************************
; 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>
Stack_Size EQU 0x00000400
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 0x00000200
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 ; Window Watchdog
DCD PVD_IRQHandler ; PVD through EXTI Line detect
DCD TAMPER_IRQHandler ; Tamper
DCD RTC_IRQHandler ; RTC
DCD FLASH_IRQHandler ; Flash
DCD RCC_IRQHandler ; RCC
DCD EXTI0_IRQHandler ; EXTI Line 0
DCD EXTI1_IRQHandler ; EXTI Line 1
DCD EXTI2_IRQHandler ; EXTI Line 2
DCD EXTI3_IRQHandler ; EXTI Line 3
DCD EXTI4_IRQHandler ; EXTI Line 4
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_2_IRQHandler ; ADC1 & ADC2
DCD USB_HP_CAN1_TX_IRQHandler ; USB High Priority or CAN1 TX
DCD USB_LP_CAN1_RX0_IRQHandler ; USB Low Priority or CAN1 RX0
DCD CAN1_RX1_IRQHandler ; CAN1 RX1
DCD CAN1_SCE_IRQHandler ; CAN1 SCE
DCD EXTI9_5_IRQHandler ; EXTI Line 9..5
DCD TIM1_BRK_IRQHandler ; TIM1 Break
DCD TIM1_UP_IRQHandler ; TIM1 Update
DCD TIM1_TRG_COM_IRQHandler ; TIM1 Trigger and Commutation
DCD TIM1_CC_IRQHandler ; TIM1 Capture Compare
DCD TIM2_IRQHandler ; TIM2
DCD TIM3_IRQHandler ; TIM3
DCD TIM4_IRQHandler ; TIM4
DCD I2C1_EV_IRQHandler ; I2C1 Event
DCD I2C1_ER_IRQHandler ; I2C1 Error
DCD I2C2_EV_IRQHandler ; I2C2 Event
DCD I2C2_ER_IRQHandler ; I2C2 Error
DCD SPI1_IRQHandler ; SPI1
DCD SPI2_IRQHandler ; SPI2
DCD USART1_IRQHandler ; USART1
DCD USART2_IRQHandler ; USART2
DCD USART3_IRQHandler ; USART3
DCD EXTI15_10_IRQHandler ; EXTI Line 15..10
DCD RTCAlarm_IRQHandler ; RTC Alarm through EXTI Line
DCD USBWakeUp_IRQHandler ; USB Wakeup from suspend
DCD TIM8_BRK_IRQHandler ; TIM8 Break
DCD TIM8_UP_IRQHandler ; TIM8 Update
DCD TIM8_TRG_COM_IRQHandler ; TIM8 Trigger and Commutation
DCD TIM8_CC_IRQHandler ; TIM8 Capture Compare
DCD ADC3_IRQHandler ; ADC3
DCD FSMC_IRQHandler ; FSMC
DCD SDIO_IRQHandler ; SDIO
DCD TIM5_IRQHandler ; TIM5
DCD SPI3_IRQHandler ; SPI3
DCD UART4_IRQHandler ; UART4
DCD UART5_IRQHandler ; UART5
DCD TIM6_IRQHandler ; TIM6
DCD TIM7_IRQHandler ; TIM7
DCD DMA2_Channel1_IRQHandler ; DMA2 Channel1
DCD DMA2_Channel2_IRQHandler ; DMA2 Channel2
DCD DMA2_Channel3_IRQHandler ; DMA2 Channel3
DCD DMA2_Channel4_5_IRQHandler ; DMA2 Channel4 & Channel5
__Vectors_End
__Vectors_Size EQU __Vectors_End - __Vectors
AREA |.text|, CODE, READONLY
; Reset handler
Reset_Handler PROC
EXPORT Reset_Handler [WEAK]
IMPORT __main
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 PVD_IRQHandler [WEAK]
EXPORT TAMPER_IRQHandler [WEAK]
EXPORT RTC_IRQHandler [WEAK]
EXPORT FLASH_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_2_IRQHandler [WEAK]
EXPORT USB_HP_CAN1_TX_IRQHandler [WEAK]
EXPORT USB_LP_CAN1_RX0_IRQHandler [WEAK]
EXPORT CAN1_RX1_IRQHandler [WEAK]
EXPORT CAN1_SCE_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 TIM2_IRQHandler [WEAK]
EXPORT TIM3_IRQHandler [WEAK]
EXPORT TIM4_IRQHandler [WEAK]
EXPORT I2C1_EV_IRQHandler [WEAK]
EXPORT I2C1_ER_IRQHandler [WEAK]
EXPORT I2C2_EV_IRQHandler [WEAK]
EXPORT I2C2_ER_IRQHandler [WEAK]
EXPORT SPI1_IRQHandler [WEAK]
EXPORT SPI2_IRQHandler [WEAK]
EXPORT USART1_IRQHandler [WEAK]
EXPORT USART2_IRQHandler [WEAK]
EXPORT USART3_IRQHandler [WEAK]
EXPORT EXTI15_10_IRQHandler [WEAK]
EXPORT RTCAlarm_IRQHandler [WEAK]
EXPORT USBWakeUp_IRQHandler [WEAK]
EXPORT TIM8_BRK_IRQHandler [WEAK]
EXPORT TIM8_UP_IRQHandler [WEAK]
EXPORT TIM8_TRG_COM_IRQHandler [WEAK]
EXPORT TIM8_CC_IRQHandler [WEAK]
EXPORT ADC3_IRQHandler [WEAK]
EXPORT FSMC_IRQHandler [WEAK]
EXPORT SDIO_IRQHandler [WEAK]
EXPORT TIM5_IRQHandler [WEAK]
EXPORT SPI3_IRQHandler [WEAK]
EXPORT UART4_IRQHandler [WEAK]
EXPORT UART5_IRQHandler [WEAK]
EXPORT TIM6_IRQHandler [WEAK]
EXPORT TIM7_IRQHandler [WEAK]
EXPORT DMA2_Channel1_IRQHandler [WEAK]
EXPORT DMA2_Channel2_IRQHandler [WEAK]
EXPORT DMA2_Channel3_IRQHandler [WEAK]
EXPORT DMA2_Channel4_5_IRQHandler [WEAK]
WWDG_IRQHandler
PVD_IRQHandler
TAMPER_IRQHandler
RTC_IRQHandler
FLASH_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_2_IRQHandler
USB_HP_CAN1_TX_IRQHandler
USB_LP_CAN1_RX0_IRQHandler
CAN1_RX1_IRQHandler
CAN1_SCE_IRQHandler
EXTI9_5_IRQHandler
TIM1_BRK_IRQHandler
TIM1_UP_IRQHandler
TIM1_TRG_COM_IRQHandler
TIM1_CC_IRQHandler
TIM2_IRQHandler
TIM3_IRQHandler
TIM4_IRQHandler
I2C1_EV_IRQHandler
I2C1_ER_IRQHandler
I2C2_EV_IRQHandler
I2C2_ER_IRQHandler
SPI1_IRQHandler
SPI2_IRQHandler
USART1_IRQHandler
USART2_IRQHandler
USART3_IRQHandler
EXTI15_10_IRQHandler
RTCAlarm_IRQHandler
USBWakeUp_IRQHandler
TIM8_BRK_IRQHandler
TIM8_UP_IRQHandler
TIM8_TRG_COM_IRQHandler
TIM8_CC_IRQHandler
ADC3_IRQHandler
FSMC_IRQHandler
SDIO_IRQHandler
TIM5_IRQHandler
SPI3_IRQHandler
UART4_IRQHandler
UART5_IRQHandler
TIM6_IRQHandler
TIM7_IRQHandler
DMA2_Channel1_IRQHandler
DMA2_Channel2_IRQHandler
DMA2_Channel3_IRQHandler
DMA2_Channel4_5_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 2011 STMicroelectronics *****END OF FILE*****

View File

@ -1,346 +0,0 @@
;******************** (C) COPYRIGHT 2011 STMicroelectronics ********************
;* File Name : startup_stm32f10x_hd_vl.s
;* Author : MCD Application Team
;* Version : V3.5.0
;* Date : 11-March-2011
;* Description : STM32F10x High Density Value Line Devices vector table
;* for MDK-ARM toolchain.
;* This module performs:
;* - Set the initial SP
;* - Set the initial PC == Reset_Handler
;* - Set the vector table entries with the exceptions ISR address
;* - Configure the clock system and also configure the external
;* SRAM mounted on STM32100E-EVAL board to be used as data
;* memory (optional, to be enabled by user)
;* - Branches to __main in the C library (which eventually
;* calls main()).
;* After Reset the CortexM3 processor is in Thread mode,
;* priority is Privileged, and the Stack is set to Main.
;* <<< Use Configuration Wizard in Context Menu >>>
;*******************************************************************************
; 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, STMICROELECTRONICS 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.
;*******************************************************************************
; 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>
Stack_Size EQU 0x00000400
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 0x00000200
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 ; Window Watchdog
DCD PVD_IRQHandler ; PVD through EXTI Line detect
DCD TAMPER_IRQHandler ; Tamper
DCD RTC_IRQHandler ; RTC
DCD FLASH_IRQHandler ; Flash
DCD RCC_IRQHandler ; RCC
DCD EXTI0_IRQHandler ; EXTI Line 0
DCD EXTI1_IRQHandler ; EXTI Line 1
DCD EXTI2_IRQHandler ; EXTI Line 2
DCD EXTI3_IRQHandler ; EXTI Line 3
DCD EXTI4_IRQHandler ; EXTI Line 4
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 0 ; Reserved
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD EXTI9_5_IRQHandler ; EXTI Line 9..5
DCD TIM1_BRK_TIM15_IRQHandler ; TIM1 Break and TIM15
DCD TIM1_UP_TIM16_IRQHandler ; TIM1 Update and TIM16
DCD TIM1_TRG_COM_TIM17_IRQHandler ; TIM1 Trigger and Commutation and TIM17
DCD TIM1_CC_IRQHandler ; TIM1 Capture Compare
DCD TIM2_IRQHandler ; TIM2
DCD TIM3_IRQHandler ; TIM3
DCD TIM4_IRQHandler ; TIM4
DCD I2C1_EV_IRQHandler ; I2C1 Event
DCD I2C1_ER_IRQHandler ; I2C1 Error
DCD I2C2_EV_IRQHandler ; I2C2 Event
DCD I2C2_ER_IRQHandler ; I2C2 Error
DCD SPI1_IRQHandler ; SPI1
DCD SPI2_IRQHandler ; SPI2
DCD USART1_IRQHandler ; USART1
DCD USART2_IRQHandler ; USART2
DCD USART3_IRQHandler ; USART3
DCD EXTI15_10_IRQHandler ; EXTI Line 15..10
DCD RTCAlarm_IRQHandler ; RTC Alarm through EXTI Line
DCD CEC_IRQHandler ; HDMI-CEC
DCD TIM12_IRQHandler ; TIM12
DCD TIM13_IRQHandler ; TIM13
DCD TIM14_IRQHandler ; TIM14
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD TIM5_IRQHandler ; TIM5
DCD SPI3_IRQHandler ; SPI3
DCD UART4_IRQHandler ; UART4
DCD UART5_IRQHandler ; UART5
DCD TIM6_DAC_IRQHandler ; TIM6 and DAC underrun
DCD TIM7_IRQHandler ; TIM7
DCD DMA2_Channel1_IRQHandler ; DMA2 Channel1
DCD DMA2_Channel2_IRQHandler ; DMA2 Channel2
DCD DMA2_Channel3_IRQHandler ; DMA2 Channel3
DCD DMA2_Channel4_5_IRQHandler ; DMA2 Channel4 & Channel5
DCD DMA2_Channel5_IRQHandler ; DMA2 Channel5
__Vectors_End
__Vectors_Size EQU __Vectors_End - __Vectors
AREA |.text|, CODE, READONLY
; Reset handler
Reset_Handler PROC
EXPORT Reset_Handler [WEAK]
IMPORT __main
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 PVD_IRQHandler [WEAK]
EXPORT TAMPER_IRQHandler [WEAK]
EXPORT RTC_IRQHandler [WEAK]
EXPORT FLASH_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 EXTI9_5_IRQHandler [WEAK]
EXPORT TIM1_BRK_TIM15_IRQHandler [WEAK]
EXPORT TIM1_UP_TIM16_IRQHandler [WEAK]
EXPORT TIM1_TRG_COM_TIM17_IRQHandler [WEAK]
EXPORT TIM1_CC_IRQHandler [WEAK]
EXPORT TIM2_IRQHandler [WEAK]
EXPORT TIM3_IRQHandler [WEAK]
EXPORT TIM4_IRQHandler [WEAK]
EXPORT I2C1_EV_IRQHandler [WEAK]
EXPORT I2C1_ER_IRQHandler [WEAK]
EXPORT I2C2_EV_IRQHandler [WEAK]
EXPORT I2C2_ER_IRQHandler [WEAK]
EXPORT SPI1_IRQHandler [WEAK]
EXPORT SPI2_IRQHandler [WEAK]
EXPORT USART1_IRQHandler [WEAK]
EXPORT USART2_IRQHandler [WEAK]
EXPORT USART3_IRQHandler [WEAK]
EXPORT EXTI15_10_IRQHandler [WEAK]
EXPORT RTCAlarm_IRQHandler [WEAK]
EXPORT CEC_IRQHandler [WEAK]
EXPORT TIM12_IRQHandler [WEAK]
EXPORT TIM13_IRQHandler [WEAK]
EXPORT TIM14_IRQHandler [WEAK]
EXPORT TIM5_IRQHandler [WEAK]
EXPORT SPI3_IRQHandler [WEAK]
EXPORT UART4_IRQHandler [WEAK]
EXPORT UART5_IRQHandler [WEAK]
EXPORT TIM6_DAC_IRQHandler [WEAK]
EXPORT TIM7_IRQHandler [WEAK]
EXPORT DMA2_Channel1_IRQHandler [WEAK]
EXPORT DMA2_Channel2_IRQHandler [WEAK]
EXPORT DMA2_Channel3_IRQHandler [WEAK]
EXPORT DMA2_Channel4_5_IRQHandler [WEAK]
EXPORT DMA2_Channel5_IRQHandler [WEAK]
WWDG_IRQHandler
PVD_IRQHandler
TAMPER_IRQHandler
RTC_IRQHandler
FLASH_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
EXTI9_5_IRQHandler
TIM1_BRK_TIM15_IRQHandler
TIM1_UP_TIM16_IRQHandler
TIM1_TRG_COM_TIM17_IRQHandler
TIM1_CC_IRQHandler
TIM2_IRQHandler
TIM3_IRQHandler
TIM4_IRQHandler
I2C1_EV_IRQHandler
I2C1_ER_IRQHandler
I2C2_EV_IRQHandler
I2C2_ER_IRQHandler
SPI1_IRQHandler
SPI2_IRQHandler
USART1_IRQHandler
USART2_IRQHandler
USART3_IRQHandler
EXTI15_10_IRQHandler
RTCAlarm_IRQHandler
CEC_IRQHandler
TIM12_IRQHandler
TIM13_IRQHandler
TIM14_IRQHandler
TIM5_IRQHandler
SPI3_IRQHandler
UART4_IRQHandler
UART5_IRQHandler
TIM6_DAC_IRQHandler
TIM7_IRQHandler
DMA2_Channel1_IRQHandler
DMA2_Channel2_IRQHandler
DMA2_Channel3_IRQHandler
DMA2_Channel4_5_IRQHandler
DMA2_Channel5_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 2011 STMicroelectronics *****END OF FILE*****

View File

@ -1,297 +0,0 @@
;******************** (C) COPYRIGHT 2011 STMicroelectronics ********************
;* File Name : startup_stm32f10x_ld.s
;* Author : MCD Application Team
;* Version : V3.5.0
;* Date : 11-March-2011
;* Description : STM32F10x Low Density Devices vector table for MDK-ARM
;* toolchain.
;* This module performs:
;* - Set the initial SP
;* - Set the initial PC == Reset_Handler
;* - Set the vector table entries with the exceptions ISR address
;* - Configure the clock system
;* - Branches to __main in the C library (which eventually
;* calls main()).
;* After Reset the CortexM3 processor is in Thread mode,
;* priority is Privileged, and the Stack is set to Main.
;* <<< Use Configuration Wizard in Context Menu >>>
;*******************************************************************************
; 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, STMICROELECTRONICS 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.
;*******************************************************************************
; 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>
Stack_Size EQU 0x00000400
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 0x00000200
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 ; Window Watchdog
DCD PVD_IRQHandler ; PVD through EXTI Line detect
DCD TAMPER_IRQHandler ; Tamper
DCD RTC_IRQHandler ; RTC
DCD FLASH_IRQHandler ; Flash
DCD RCC_IRQHandler ; RCC
DCD EXTI0_IRQHandler ; EXTI Line 0
DCD EXTI1_IRQHandler ; EXTI Line 1
DCD EXTI2_IRQHandler ; EXTI Line 2
DCD EXTI3_IRQHandler ; EXTI Line 3
DCD EXTI4_IRQHandler ; EXTI Line 4
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_2_IRQHandler ; ADC1_2
DCD USB_HP_CAN1_TX_IRQHandler ; USB High Priority or CAN1 TX
DCD USB_LP_CAN1_RX0_IRQHandler ; USB Low Priority or CAN1 RX0
DCD CAN1_RX1_IRQHandler ; CAN1 RX1
DCD CAN1_SCE_IRQHandler ; CAN1 SCE
DCD EXTI9_5_IRQHandler ; EXTI Line 9..5
DCD TIM1_BRK_IRQHandler ; TIM1 Break
DCD TIM1_UP_IRQHandler ; TIM1 Update
DCD TIM1_TRG_COM_IRQHandler ; TIM1 Trigger and Commutation
DCD TIM1_CC_IRQHandler ; TIM1 Capture Compare
DCD TIM2_IRQHandler ; TIM2
DCD TIM3_IRQHandler ; TIM3
DCD 0 ; Reserved
DCD I2C1_EV_IRQHandler ; I2C1 Event
DCD I2C1_ER_IRQHandler ; I2C1 Error
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD SPI1_IRQHandler ; SPI1
DCD 0 ; Reserved
DCD USART1_IRQHandler ; USART1
DCD USART2_IRQHandler ; USART2
DCD 0 ; Reserved
DCD EXTI15_10_IRQHandler ; EXTI Line 15..10
DCD RTCAlarm_IRQHandler ; RTC Alarm through EXTI Line
DCD USBWakeUp_IRQHandler ; USB Wakeup from suspend
__Vectors_End
__Vectors_Size EQU __Vectors_End - __Vectors
AREA |.text|, CODE, READONLY
; Reset handler routine
Reset_Handler PROC
EXPORT Reset_Handler [WEAK]
IMPORT __main
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 PVD_IRQHandler [WEAK]
EXPORT TAMPER_IRQHandler [WEAK]
EXPORT RTC_IRQHandler [WEAK]
EXPORT FLASH_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_2_IRQHandler [WEAK]
EXPORT USB_HP_CAN1_TX_IRQHandler [WEAK]
EXPORT USB_LP_CAN1_RX0_IRQHandler [WEAK]
EXPORT CAN1_RX1_IRQHandler [WEAK]
EXPORT CAN1_SCE_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 TIM2_IRQHandler [WEAK]
EXPORT TIM3_IRQHandler [WEAK]
EXPORT I2C1_EV_IRQHandler [WEAK]
EXPORT I2C1_ER_IRQHandler [WEAK]
EXPORT SPI1_IRQHandler [WEAK]
EXPORT USART1_IRQHandler [WEAK]
EXPORT USART2_IRQHandler [WEAK]
EXPORT EXTI15_10_IRQHandler [WEAK]
EXPORT RTCAlarm_IRQHandler [WEAK]
EXPORT USBWakeUp_IRQHandler [WEAK]
WWDG_IRQHandler
PVD_IRQHandler
TAMPER_IRQHandler
RTC_IRQHandler
FLASH_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_2_IRQHandler
USB_HP_CAN1_TX_IRQHandler
USB_LP_CAN1_RX0_IRQHandler
CAN1_RX1_IRQHandler
CAN1_SCE_IRQHandler
EXTI9_5_IRQHandler
TIM1_BRK_IRQHandler
TIM1_UP_IRQHandler
TIM1_TRG_COM_IRQHandler
TIM1_CC_IRQHandler
TIM2_IRQHandler
TIM3_IRQHandler
I2C1_EV_IRQHandler
I2C1_ER_IRQHandler
SPI1_IRQHandler
USART1_IRQHandler
USART2_IRQHandler
EXTI15_10_IRQHandler
RTCAlarm_IRQHandler
USBWakeUp_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 2011 STMicroelectronics *****END OF FILE*****

View File

@ -1,304 +0,0 @@
;******************** (C) COPYRIGHT 2011 STMicroelectronics ********************
;* File Name : startup_stm32f10x_ld_vl.s
;* Author : MCD Application Team
;* Version : V3.5.0
;* Date : 11-March-2011
;* Description : STM32F10x Low Density Value Line Devices vector table
;* for MDK-ARM toolchain.
;* This module performs:
;* - Set the initial SP
;* - Set the initial PC == Reset_Handler
;* - Set the vector table entries with the exceptions ISR address
;* - Configure the clock system
;* - Branches to __main in the C library (which eventually
;* calls main()).
;* After Reset the CortexM3 processor is in Thread mode,
;* priority is Privileged, and the Stack is set to Main.
;* <<< Use Configuration Wizard in Context Menu >>>
;*******************************************************************************
; 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, STMICROELECTRONICS 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.
;*******************************************************************************
; 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>
Stack_Size EQU 0x00000400
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 0x00000200
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 ; Window Watchdog
DCD PVD_IRQHandler ; PVD through EXTI Line detect
DCD TAMPER_IRQHandler ; Tamper
DCD RTC_IRQHandler ; RTC
DCD FLASH_IRQHandler ; Flash
DCD RCC_IRQHandler ; RCC
DCD EXTI0_IRQHandler ; EXTI Line 0
DCD EXTI1_IRQHandler ; EXTI Line 1
DCD EXTI2_IRQHandler ; EXTI Line 2
DCD EXTI3_IRQHandler ; EXTI Line 3
DCD EXTI4_IRQHandler ; EXTI Line 4
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 0 ; Reserved
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD EXTI9_5_IRQHandler ; EXTI Line 9..5
DCD TIM1_BRK_TIM15_IRQHandler ; TIM1 Break and TIM15
DCD TIM1_UP_TIM16_IRQHandler ; TIM1 Update and TIM16
DCD TIM1_TRG_COM_TIM17_IRQHandler ; TIM1 Trigger and Commutation and TIM17
DCD TIM1_CC_IRQHandler ; TIM1 Capture Compare
DCD TIM2_IRQHandler ; TIM2
DCD TIM3_IRQHandler ; TIM3
DCD 0 ; Reserved
DCD I2C1_EV_IRQHandler ; I2C1 Event
DCD I2C1_ER_IRQHandler ; I2C1 Error
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD SPI1_IRQHandler ; SPI1
DCD 0 ; Reserved
DCD USART1_IRQHandler ; USART1
DCD USART2_IRQHandler ; USART2
DCD 0 ; Reserved
DCD EXTI15_10_IRQHandler ; EXTI Line 15..10
DCD RTCAlarm_IRQHandler ; RTC Alarm through EXTI Line
DCD CEC_IRQHandler ; HDMI-CEC
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD TIM6_DAC_IRQHandler ; TIM6 and DAC underrun
DCD TIM7_IRQHandler ; TIM7
__Vectors_End
__Vectors_Size EQU __Vectors_End - __Vectors
AREA |.text|, CODE, READONLY
; Reset handler
Reset_Handler PROC
EXPORT Reset_Handler [WEAK]
IMPORT __main
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 PVD_IRQHandler [WEAK]
EXPORT TAMPER_IRQHandler [WEAK]
EXPORT RTC_IRQHandler [WEAK]
EXPORT FLASH_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 EXTI9_5_IRQHandler [WEAK]
EXPORT TIM1_BRK_TIM15_IRQHandler [WEAK]
EXPORT TIM1_UP_TIM16_IRQHandler [WEAK]
EXPORT TIM1_TRG_COM_TIM17_IRQHandler [WEAK]
EXPORT TIM1_CC_IRQHandler [WEAK]
EXPORT TIM2_IRQHandler [WEAK]
EXPORT TIM3_IRQHandler [WEAK]
EXPORT I2C1_EV_IRQHandler [WEAK]
EXPORT I2C1_ER_IRQHandler [WEAK]
EXPORT SPI1_IRQHandler [WEAK]
EXPORT USART1_IRQHandler [WEAK]
EXPORT USART2_IRQHandler [WEAK]
EXPORT EXTI15_10_IRQHandler [WEAK]
EXPORT RTCAlarm_IRQHandler [WEAK]
EXPORT CEC_IRQHandler [WEAK]
EXPORT TIM6_DAC_IRQHandler [WEAK]
EXPORT TIM7_IRQHandler [WEAK]
WWDG_IRQHandler
PVD_IRQHandler
TAMPER_IRQHandler
RTC_IRQHandler
FLASH_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
EXTI9_5_IRQHandler
TIM1_BRK_TIM15_IRQHandler
TIM1_UP_TIM16_IRQHandler
TIM1_TRG_COM_TIM17_IRQHandler
TIM1_CC_IRQHandler
TIM2_IRQHandler
TIM3_IRQHandler
I2C1_EV_IRQHandler
I2C1_ER_IRQHandler
SPI1_IRQHandler
USART1_IRQHandler
USART2_IRQHandler
EXTI15_10_IRQHandler
RTCAlarm_IRQHandler
CEC_IRQHandler
TIM6_DAC_IRQHandler
TIM7_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 2011 STMicroelectronics *****END OF FILE*****

View File

@ -1,307 +0,0 @@
;******************** (C) COPYRIGHT 2011 STMicroelectronics ********************
;* File Name : startup_stm32f10x_md.s
;* Author : MCD Application Team
;* Version : V3.5.0
;* Date : 11-March-2011
;* Description : STM32F10x Medium Density Devices vector table for MDK-ARM
;* toolchain.
;* This module performs:
;* - Set the initial SP
;* - Set the initial PC == Reset_Handler
;* - Set the vector table entries with the exceptions ISR address
;* - Configure the clock system
;* - Branches to __main in the C library (which eventually
;* calls main()).
;* After Reset the CortexM3 processor is in Thread mode,
;* priority is Privileged, and the Stack is set to Main.
;* <<< Use Configuration Wizard in Context Menu >>>
;*******************************************************************************
; 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, STMICROELECTRONICS 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.
;*******************************************************************************
; 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>
Stack_Size EQU 0x00000400
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 0x00000200
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 ; Window Watchdog
DCD PVD_IRQHandler ; PVD through EXTI Line detect
DCD TAMPER_IRQHandler ; Tamper
DCD RTC_IRQHandler ; RTC
DCD FLASH_IRQHandler ; Flash
DCD RCC_IRQHandler ; RCC
DCD EXTI0_IRQHandler ; EXTI Line 0
DCD EXTI1_IRQHandler ; EXTI Line 1
DCD EXTI2_IRQHandler ; EXTI Line 2
DCD EXTI3_IRQHandler ; EXTI Line 3
DCD EXTI4_IRQHandler ; EXTI Line 4
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_2_IRQHandler ; ADC1_2
DCD USB_HP_CAN1_TX_IRQHandler ; USB High Priority or CAN1 TX
DCD USB_LP_CAN1_RX0_IRQHandler ; USB Low Priority or CAN1 RX0
DCD CAN1_RX1_IRQHandler ; CAN1 RX1
DCD CAN1_SCE_IRQHandler ; CAN1 SCE
DCD EXTI9_5_IRQHandler ; EXTI Line 9..5
DCD TIM1_BRK_IRQHandler ; TIM1 Break
DCD TIM1_UP_IRQHandler ; TIM1 Update
DCD TIM1_TRG_COM_IRQHandler ; TIM1 Trigger and Commutation
DCD TIM1_CC_IRQHandler ; TIM1 Capture Compare
DCD TIM2_IRQHandler ; TIM2
DCD TIM3_IRQHandler ; TIM3
DCD TIM4_IRQHandler ; TIM4
DCD I2C1_EV_IRQHandler ; I2C1 Event
DCD I2C1_ER_IRQHandler ; I2C1 Error
DCD I2C2_EV_IRQHandler ; I2C2 Event
DCD I2C2_ER_IRQHandler ; I2C2 Error
DCD SPI1_IRQHandler ; SPI1
DCD SPI2_IRQHandler ; SPI2
DCD USART1_IRQHandler ; USART1
DCD USART2_IRQHandler ; USART2
DCD USART3_IRQHandler ; USART3
DCD EXTI15_10_IRQHandler ; EXTI Line 15..10
DCD RTCAlarm_IRQHandler ; RTC Alarm through EXTI Line
DCD USBWakeUp_IRQHandler ; USB Wakeup from suspend
__Vectors_End
__Vectors_Size EQU __Vectors_End - __Vectors
AREA |.text|, CODE, READONLY
; Reset handler
Reset_Handler PROC
EXPORT Reset_Handler [WEAK]
IMPORT __main
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 PVD_IRQHandler [WEAK]
EXPORT TAMPER_IRQHandler [WEAK]
EXPORT RTC_IRQHandler [WEAK]
EXPORT FLASH_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_2_IRQHandler [WEAK]
EXPORT USB_HP_CAN1_TX_IRQHandler [WEAK]
EXPORT USB_LP_CAN1_RX0_IRQHandler [WEAK]
EXPORT CAN1_RX1_IRQHandler [WEAK]
EXPORT CAN1_SCE_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 TIM2_IRQHandler [WEAK]
EXPORT TIM3_IRQHandler [WEAK]
EXPORT TIM4_IRQHandler [WEAK]
EXPORT I2C1_EV_IRQHandler [WEAK]
EXPORT I2C1_ER_IRQHandler [WEAK]
EXPORT I2C2_EV_IRQHandler [WEAK]
EXPORT I2C2_ER_IRQHandler [WEAK]
EXPORT SPI1_IRQHandler [WEAK]
EXPORT SPI2_IRQHandler [WEAK]
EXPORT USART1_IRQHandler [WEAK]
EXPORT USART2_IRQHandler [WEAK]
EXPORT USART3_IRQHandler [WEAK]
EXPORT EXTI15_10_IRQHandler [WEAK]
EXPORT RTCAlarm_IRQHandler [WEAK]
EXPORT USBWakeUp_IRQHandler [WEAK]
WWDG_IRQHandler
PVD_IRQHandler
TAMPER_IRQHandler
RTC_IRQHandler
FLASH_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_2_IRQHandler
USB_HP_CAN1_TX_IRQHandler
USB_LP_CAN1_RX0_IRQHandler
CAN1_RX1_IRQHandler
CAN1_SCE_IRQHandler
EXTI9_5_IRQHandler
TIM1_BRK_IRQHandler
TIM1_UP_IRQHandler
TIM1_TRG_COM_IRQHandler
TIM1_CC_IRQHandler
TIM2_IRQHandler
TIM3_IRQHandler
TIM4_IRQHandler
I2C1_EV_IRQHandler
I2C1_ER_IRQHandler
I2C2_EV_IRQHandler
I2C2_ER_IRQHandler
SPI1_IRQHandler
SPI2_IRQHandler
USART1_IRQHandler
USART2_IRQHandler
USART3_IRQHandler
EXTI15_10_IRQHandler
RTCAlarm_IRQHandler
USBWakeUp_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 2011 STMicroelectronics *****END OF FILE*****

View File

@ -1,315 +0,0 @@
;******************** (C) COPYRIGHT 2011 STMicroelectronics ********************
;* File Name : startup_stm32f10x_md_vl.s
;* Author : MCD Application Team
;* Version : V3.5.0
;* Date : 11-March-2011
;* Description : STM32F10x Medium Density Value Line Devices vector table
;* for MDK-ARM toolchain.
;* This module performs:
;* - Set the initial SP
;* - Set the initial PC == Reset_Handler
;* - Set the vector table entries with the exceptions ISR address
;* - Configure the clock system
;* - Branches to __main in the C library (which eventually
;* calls main()).
;* After Reset the CortexM3 processor is in Thread mode,
;* priority is Privileged, and the Stack is set to Main.
;* <<< Use Configuration Wizard in Context Menu >>>
;*******************************************************************************
; 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, STMICROELECTRONICS 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.
;*******************************************************************************
; 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>
Stack_Size EQU 0x00000400
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 0x00000200
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 ; Window Watchdog
DCD PVD_IRQHandler ; PVD through EXTI Line detect
DCD TAMPER_IRQHandler ; Tamper
DCD RTC_IRQHandler ; RTC
DCD FLASH_IRQHandler ; Flash
DCD RCC_IRQHandler ; RCC
DCD EXTI0_IRQHandler ; EXTI Line 0
DCD EXTI1_IRQHandler ; EXTI Line 1
DCD EXTI2_IRQHandler ; EXTI Line 2
DCD EXTI3_IRQHandler ; EXTI Line 3
DCD EXTI4_IRQHandler ; EXTI Line 4
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 0 ; Reserved
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD EXTI9_5_IRQHandler ; EXTI Line 9..5
DCD TIM1_BRK_TIM15_IRQHandler ; TIM1 Break and TIM15
DCD TIM1_UP_TIM16_IRQHandler ; TIM1 Update and TIM16
DCD TIM1_TRG_COM_TIM17_IRQHandler ; TIM1 Trigger and Commutation and TIM17
DCD TIM1_CC_IRQHandler ; TIM1 Capture Compare
DCD TIM2_IRQHandler ; TIM2
DCD TIM3_IRQHandler ; TIM3
DCD TIM4_IRQHandler ; TIM4
DCD I2C1_EV_IRQHandler ; I2C1 Event
DCD I2C1_ER_IRQHandler ; I2C1 Error
DCD I2C2_EV_IRQHandler ; I2C2 Event
DCD I2C2_ER_IRQHandler ; I2C2 Error
DCD SPI1_IRQHandler ; SPI1
DCD SPI2_IRQHandler ; SPI2
DCD USART1_IRQHandler ; USART1
DCD USART2_IRQHandler ; USART2
DCD USART3_IRQHandler ; USART3
DCD EXTI15_10_IRQHandler ; EXTI Line 15..10
DCD RTCAlarm_IRQHandler ; RTC Alarm through EXTI Line
DCD CEC_IRQHandler ; HDMI-CEC
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD TIM6_DAC_IRQHandler ; TIM6 and DAC underrun
DCD TIM7_IRQHandler ; TIM7
__Vectors_End
__Vectors_Size EQU __Vectors_End - __Vectors
AREA |.text|, CODE, READONLY
; Reset handler
Reset_Handler PROC
EXPORT Reset_Handler [WEAK]
IMPORT __main
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 PVD_IRQHandler [WEAK]
EXPORT TAMPER_IRQHandler [WEAK]
EXPORT RTC_IRQHandler [WEAK]
EXPORT FLASH_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 EXTI9_5_IRQHandler [WEAK]
EXPORT TIM1_BRK_TIM15_IRQHandler [WEAK]
EXPORT TIM1_UP_TIM16_IRQHandler [WEAK]
EXPORT TIM1_TRG_COM_TIM17_IRQHandler [WEAK]
EXPORT TIM1_CC_IRQHandler [WEAK]
EXPORT TIM2_IRQHandler [WEAK]
EXPORT TIM3_IRQHandler [WEAK]
EXPORT TIM4_IRQHandler [WEAK]
EXPORT I2C1_EV_IRQHandler [WEAK]
EXPORT I2C1_ER_IRQHandler [WEAK]
EXPORT I2C2_EV_IRQHandler [WEAK]
EXPORT I2C2_ER_IRQHandler [WEAK]
EXPORT SPI1_IRQHandler [WEAK]
EXPORT SPI2_IRQHandler [WEAK]
EXPORT USART1_IRQHandler [WEAK]
EXPORT USART2_IRQHandler [WEAK]
EXPORT USART3_IRQHandler [WEAK]
EXPORT EXTI15_10_IRQHandler [WEAK]
EXPORT RTCAlarm_IRQHandler [WEAK]
EXPORT CEC_IRQHandler [WEAK]
EXPORT TIM6_DAC_IRQHandler [WEAK]
EXPORT TIM7_IRQHandler [WEAK]
WWDG_IRQHandler
PVD_IRQHandler
TAMPER_IRQHandler
RTC_IRQHandler
FLASH_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
EXTI9_5_IRQHandler
TIM1_BRK_TIM15_IRQHandler
TIM1_UP_TIM16_IRQHandler
TIM1_TRG_COM_TIM17_IRQHandler
TIM1_CC_IRQHandler
TIM2_IRQHandler
TIM3_IRQHandler
TIM4_IRQHandler
I2C1_EV_IRQHandler
I2C1_ER_IRQHandler
I2C2_EV_IRQHandler
I2C2_ER_IRQHandler
SPI1_IRQHandler
SPI2_IRQHandler
USART1_IRQHandler
USART2_IRQHandler
USART3_IRQHandler
EXTI15_10_IRQHandler
RTCAlarm_IRQHandler
CEC_IRQHandler
TIM6_DAC_IRQHandler
TIM7_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 2011 STMicroelectronics *****END OF FILE*****

View File

@ -1,358 +0,0 @@
;******************** (C) COPYRIGHT 2011 STMicroelectronics ********************
;* File Name : startup_stm32f10x_xl.s
;* Author : MCD Application Team
;* Version : V3.5.0
;* Date : 11-March-2011
;* Description : STM32F10x XL-Density Devices vector table for MDK-ARM
;* toolchain.
;* This module performs:
;* - Set the initial SP
;* - Set the initial PC == Reset_Handler
;* - Set the vector table entries with the exceptions ISR address
;* - Configure the clock system and also configure the external
;* SRAM mounted on STM3210E-EVAL board to be used as data
;* memory (optional, to be enabled by user)
;* - Branches to __main in the C library (which eventually
;* calls main()).
;* After Reset the CortexM3 processor is in Thread mode,
;* priority is Privileged, and the Stack is set to Main.
;* <<< Use Configuration Wizard in Context Menu >>>
;*******************************************************************************
; 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, STMICROELECTRONICS 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.
;*******************************************************************************
; 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>
Stack_Size EQU 0x00000400
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 0x00000200
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 ; Window Watchdog
DCD PVD_IRQHandler ; PVD through EXTI Line detect
DCD TAMPER_IRQHandler ; Tamper
DCD RTC_IRQHandler ; RTC
DCD FLASH_IRQHandler ; Flash
DCD RCC_IRQHandler ; RCC
DCD EXTI0_IRQHandler ; EXTI Line 0
DCD EXTI1_IRQHandler ; EXTI Line 1
DCD EXTI2_IRQHandler ; EXTI Line 2
DCD EXTI3_IRQHandler ; EXTI Line 3
DCD EXTI4_IRQHandler ; EXTI Line 4
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_2_IRQHandler ; ADC1 & ADC2
DCD USB_HP_CAN1_TX_IRQHandler ; USB High Priority or CAN1 TX
DCD USB_LP_CAN1_RX0_IRQHandler ; USB Low Priority or CAN1 RX0
DCD CAN1_RX1_IRQHandler ; CAN1 RX1
DCD CAN1_SCE_IRQHandler ; CAN1 SCE
DCD EXTI9_5_IRQHandler ; EXTI Line 9..5
DCD TIM1_BRK_TIM9_IRQHandler ; TIM1 Break and TIM9
DCD TIM1_UP_TIM10_IRQHandler ; TIM1 Update and TIM10
DCD TIM1_TRG_COM_TIM11_IRQHandler ; TIM1 Trigger and Commutation and TIM11
DCD TIM1_CC_IRQHandler ; TIM1 Capture Compare
DCD TIM2_IRQHandler ; TIM2
DCD TIM3_IRQHandler ; TIM3
DCD TIM4_IRQHandler ; TIM4
DCD I2C1_EV_IRQHandler ; I2C1 Event
DCD I2C1_ER_IRQHandler ; I2C1 Error
DCD I2C2_EV_IRQHandler ; I2C2 Event
DCD I2C2_ER_IRQHandler ; I2C2 Error
DCD SPI1_IRQHandler ; SPI1
DCD SPI2_IRQHandler ; SPI2
DCD USART1_IRQHandler ; USART1
DCD USART2_IRQHandler ; USART2
DCD USART3_IRQHandler ; USART3
DCD EXTI15_10_IRQHandler ; EXTI Line 15..10
DCD RTCAlarm_IRQHandler ; RTC Alarm through EXTI Line
DCD USBWakeUp_IRQHandler ; USB Wakeup from suspend
DCD TIM8_BRK_TIM12_IRQHandler ; TIM8 Break and TIM12
DCD TIM8_UP_TIM13_IRQHandler ; TIM8 Update and TIM13
DCD TIM8_TRG_COM_TIM14_IRQHandler ; TIM8 Trigger and Commutation and TIM14
DCD TIM8_CC_IRQHandler ; TIM8 Capture Compare
DCD ADC3_IRQHandler ; ADC3
DCD FSMC_IRQHandler ; FSMC
DCD SDIO_IRQHandler ; SDIO
DCD TIM5_IRQHandler ; TIM5
DCD SPI3_IRQHandler ; SPI3
DCD UART4_IRQHandler ; UART4
DCD UART5_IRQHandler ; UART5
DCD TIM6_IRQHandler ; TIM6
DCD TIM7_IRQHandler ; TIM7
DCD DMA2_Channel1_IRQHandler ; DMA2 Channel1
DCD DMA2_Channel2_IRQHandler ; DMA2 Channel2
DCD DMA2_Channel3_IRQHandler ; DMA2 Channel3
DCD DMA2_Channel4_5_IRQHandler ; DMA2 Channel4 & Channel5
__Vectors_End
__Vectors_Size EQU __Vectors_End - __Vectors
AREA |.text|, CODE, READONLY
; Reset handler
Reset_Handler PROC
EXPORT Reset_Handler [WEAK]
IMPORT __main
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 PVD_IRQHandler [WEAK]
EXPORT TAMPER_IRQHandler [WEAK]
EXPORT RTC_IRQHandler [WEAK]
EXPORT FLASH_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_2_IRQHandler [WEAK]
EXPORT USB_HP_CAN1_TX_IRQHandler [WEAK]
EXPORT USB_LP_CAN1_RX0_IRQHandler [WEAK]
EXPORT CAN1_RX1_IRQHandler [WEAK]
EXPORT CAN1_SCE_IRQHandler [WEAK]
EXPORT EXTI9_5_IRQHandler [WEAK]
EXPORT TIM1_BRK_TIM9_IRQHandler [WEAK]
EXPORT TIM1_UP_TIM10_IRQHandler [WEAK]
EXPORT TIM1_TRG_COM_TIM11_IRQHandler [WEAK]
EXPORT TIM1_CC_IRQHandler [WEAK]
EXPORT TIM2_IRQHandler [WEAK]
EXPORT TIM3_IRQHandler [WEAK]
EXPORT TIM4_IRQHandler [WEAK]
EXPORT I2C1_EV_IRQHandler [WEAK]
EXPORT I2C1_ER_IRQHandler [WEAK]
EXPORT I2C2_EV_IRQHandler [WEAK]
EXPORT I2C2_ER_IRQHandler [WEAK]
EXPORT SPI1_IRQHandler [WEAK]
EXPORT SPI2_IRQHandler [WEAK]
EXPORT USART1_IRQHandler [WEAK]
EXPORT USART2_IRQHandler [WEAK]
EXPORT USART3_IRQHandler [WEAK]
EXPORT EXTI15_10_IRQHandler [WEAK]
EXPORT RTCAlarm_IRQHandler [WEAK]
EXPORT USBWakeUp_IRQHandler [WEAK]
EXPORT TIM8_BRK_TIM12_IRQHandler [WEAK]
EXPORT TIM8_UP_TIM13_IRQHandler [WEAK]
EXPORT TIM8_TRG_COM_TIM14_IRQHandler [WEAK]
EXPORT TIM8_CC_IRQHandler [WEAK]
EXPORT ADC3_IRQHandler [WEAK]
EXPORT FSMC_IRQHandler [WEAK]
EXPORT SDIO_IRQHandler [WEAK]
EXPORT TIM5_IRQHandler [WEAK]
EXPORT SPI3_IRQHandler [WEAK]
EXPORT UART4_IRQHandler [WEAK]
EXPORT UART5_IRQHandler [WEAK]
EXPORT TIM6_IRQHandler [WEAK]
EXPORT TIM7_IRQHandler [WEAK]
EXPORT DMA2_Channel1_IRQHandler [WEAK]
EXPORT DMA2_Channel2_IRQHandler [WEAK]
EXPORT DMA2_Channel3_IRQHandler [WEAK]
EXPORT DMA2_Channel4_5_IRQHandler [WEAK]
WWDG_IRQHandler
PVD_IRQHandler
TAMPER_IRQHandler
RTC_IRQHandler
FLASH_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_2_IRQHandler
USB_HP_CAN1_TX_IRQHandler
USB_LP_CAN1_RX0_IRQHandler
CAN1_RX1_IRQHandler
CAN1_SCE_IRQHandler
EXTI9_5_IRQHandler
TIM1_BRK_TIM9_IRQHandler
TIM1_UP_TIM10_IRQHandler
TIM1_TRG_COM_TIM11_IRQHandler
TIM1_CC_IRQHandler
TIM2_IRQHandler
TIM3_IRQHandler
TIM4_IRQHandler
I2C1_EV_IRQHandler
I2C1_ER_IRQHandler
I2C2_EV_IRQHandler
I2C2_ER_IRQHandler
SPI1_IRQHandler
SPI2_IRQHandler
USART1_IRQHandler
USART2_IRQHandler
USART3_IRQHandler
EXTI15_10_IRQHandler
RTCAlarm_IRQHandler
USBWakeUp_IRQHandler
TIM8_BRK_TIM12_IRQHandler
TIM8_UP_TIM13_IRQHandler
TIM8_TRG_COM_TIM14_IRQHandler
TIM8_CC_IRQHandler
ADC3_IRQHandler
FSMC_IRQHandler
SDIO_IRQHandler
TIM5_IRQHandler
SPI3_IRQHandler
UART4_IRQHandler
UART5_IRQHandler
TIM6_IRQHandler
TIM7_IRQHandler
DMA2_Channel1_IRQHandler
DMA2_Channel2_IRQHandler
DMA2_Channel3_IRQHandler
DMA2_Channel4_5_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 2011 STMicroelectronics *****END OF FILE*****

View File

@ -1,98 +0,0 @@
/**
******************************************************************************
* @file system_stm32f10x.h
* @author MCD Application Team
* @version V3.5.0
* @date 11-March-2011
* @brief CMSIS Cortex-M3 Device Peripheral Access Layer System Header File.
******************************************************************************
* @attention
*
* 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, STMICROELECTRONICS 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 2011 STMicroelectronics</center></h2>
******************************************************************************
*/
/** @addtogroup CMSIS
* @{
*/
/** @addtogroup stm32f10x_system
* @{
*/
/**
* @brief Define to prevent recursive inclusion
*/
#ifndef __SYSTEM_STM32F10X_H
#define __SYSTEM_STM32F10X_H
#ifdef __cplusplus
extern "C" {
#endif
/** @addtogroup STM32F10x_System_Includes
* @{
*/
/**
* @}
*/
/** @addtogroup STM32F10x_System_Exported_types
* @{
*/
extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */
/**
* @}
*/
/** @addtogroup STM32F10x_System_Exported_Constants
* @{
*/
/**
* @}
*/
/** @addtogroup STM32F10x_System_Exported_Macros
* @{
*/
/**
* @}
*/
/** @addtogroup STM32F10x_System_Exported_Functions
* @{
*/
extern void SystemInit(void);
extern void SystemCoreClockUpdate(void);
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif /*__SYSTEM_STM32F10X_H */
/**
* @}
*/
/**
* @}
*/
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/

View File

@ -1,220 +0,0 @@
/**
******************************************************************************
* @file misc.h
* @author MCD Application Team
* @version V3.5.0
* @date 11-March-2011
* @brief This file contains all the functions prototypes for the miscellaneous
* firmware library functions (add-on to CMSIS functions).
******************************************************************************
* @attention
*
* 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, STMICROELECTRONICS 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 2011 STMicroelectronics</center></h2>
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __MISC_H
#define __MISC_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32f10x.h"
/** @addtogroup STM32F10x_StdPeriph_Driver
* @{
*/
/** @addtogroup MISC
* @{
*/
/** @defgroup MISC_Exported_Types
* @{
*/
/**
* @brief NVIC Init Structure definition
*/
typedef struct
{
uint8_t NVIC_IRQChannel; /*!< Specifies the IRQ channel to be enabled or disabled.
This parameter can be a value of @ref IRQn_Type
(For the complete STM32 Devices IRQ Channels list, please
refer to stm32f10x.h file) */
uint8_t NVIC_IRQChannelPreemptionPriority; /*!< Specifies the pre-emption priority for the IRQ channel
specified in NVIC_IRQChannel. This parameter can be a value
between 0 and 15 as described in the table @ref NVIC_Priority_Table */
uint8_t NVIC_IRQChannelSubPriority; /*!< Specifies the subpriority level for the IRQ channel specified
in NVIC_IRQChannel. This parameter can be a value
between 0 and 15 as described in the table @ref NVIC_Priority_Table */
FunctionalState NVIC_IRQChannelCmd; /*!< Specifies whether the IRQ channel defined in NVIC_IRQChannel
will be enabled or disabled.
This parameter can be set either to ENABLE or DISABLE */
} NVIC_InitTypeDef;
/**
* @}
*/
/** @defgroup NVIC_Priority_Table
* @{
*/
/**
@code
The table below gives the allowed values of the pre-emption priority and subpriority according
to the Priority Grouping configuration performed by NVIC_PriorityGroupConfig function
============================================================================================================================
NVIC_PriorityGroup | NVIC_IRQChannelPreemptionPriority | NVIC_IRQChannelSubPriority | Description
============================================================================================================================
NVIC_PriorityGroup_0 | 0 | 0-15 | 0 bits for pre-emption priority
| | | 4 bits for subpriority
----------------------------------------------------------------------------------------------------------------------------
NVIC_PriorityGroup_1 | 0-1 | 0-7 | 1 bits for pre-emption priority
| | | 3 bits for subpriority
----------------------------------------------------------------------------------------------------------------------------
NVIC_PriorityGroup_2 | 0-3 | 0-3 | 2 bits for pre-emption priority
| | | 2 bits for subpriority
----------------------------------------------------------------------------------------------------------------------------
NVIC_PriorityGroup_3 | 0-7 | 0-1 | 3 bits for pre-emption priority
| | | 1 bits for subpriority
----------------------------------------------------------------------------------------------------------------------------
NVIC_PriorityGroup_4 | 0-15 | 0 | 4 bits for pre-emption priority
| | | 0 bits for subpriority
============================================================================================================================
@endcode
*/
/**
* @}
*/
/** @defgroup MISC_Exported_Constants
* @{
*/
/** @defgroup Vector_Table_Base
* @{
*/
#define NVIC_VectTab_RAM ((uint32_t)0x20000000)
#define NVIC_VectTab_FLASH ((uint32_t)0x08000000)
#define IS_NVIC_VECTTAB(VECTTAB) (((VECTTAB) == NVIC_VectTab_RAM) || \
((VECTTAB) == NVIC_VectTab_FLASH))
/**
* @}
*/
/** @defgroup System_Low_Power
* @{
*/
#define NVIC_LP_SEVONPEND ((uint8_t)0x10)
#define NVIC_LP_SLEEPDEEP ((uint8_t)0x04)
#define NVIC_LP_SLEEPONEXIT ((uint8_t)0x02)
#define IS_NVIC_LP(LP) (((LP) == NVIC_LP_SEVONPEND) || \
((LP) == NVIC_LP_SLEEPDEEP) || \
((LP) == NVIC_LP_SLEEPONEXIT))
/**
* @}
*/
/** @defgroup Preemption_Priority_Group
* @{
*/
#define NVIC_PriorityGroup_0 ((uint32_t)0x700) /*!< 0 bits for pre-emption priority
4 bits for subpriority */
#define NVIC_PriorityGroup_1 ((uint32_t)0x600) /*!< 1 bits for pre-emption priority
3 bits for subpriority */
#define NVIC_PriorityGroup_2 ((uint32_t)0x500) /*!< 2 bits for pre-emption priority
2 bits for subpriority */
#define NVIC_PriorityGroup_3 ((uint32_t)0x400) /*!< 3 bits for pre-emption priority
1 bits for subpriority */
#define NVIC_PriorityGroup_4 ((uint32_t)0x300) /*!< 4 bits for pre-emption priority
0 bits for subpriority */
#define IS_NVIC_PRIORITY_GROUP(GROUP) (((GROUP) == NVIC_PriorityGroup_0) || \
((GROUP) == NVIC_PriorityGroup_1) || \
((GROUP) == NVIC_PriorityGroup_2) || \
((GROUP) == NVIC_PriorityGroup_3) || \
((GROUP) == NVIC_PriorityGroup_4))
#define IS_NVIC_PREEMPTION_PRIORITY(PRIORITY) ((PRIORITY) < 0x10)
#define IS_NVIC_SUB_PRIORITY(PRIORITY) ((PRIORITY) < 0x10)
#define IS_NVIC_OFFSET(OFFSET) ((OFFSET) < 0x000FFFFF)
/**
* @}
*/
/** @defgroup SysTick_clock_source
* @{
*/
#define SysTick_CLKSource_HCLK_Div8 ((uint32_t)0xFFFFFFFB)
#define SysTick_CLKSource_HCLK ((uint32_t)0x00000004)
#define IS_SYSTICK_CLK_SOURCE(SOURCE) (((SOURCE) == SysTick_CLKSource_HCLK) || \
((SOURCE) == SysTick_CLKSource_HCLK_Div8))
/**
* @}
*/
/**
* @}
*/
/** @defgroup MISC_Exported_Macros
* @{
*/
/**
* @}
*/
/** @defgroup MISC_Exported_Functions
* @{
*/
void NVIC_PriorityGroupConfig(uint32_t NVIC_PriorityGroup);
void NVIC_Init(NVIC_InitTypeDef* NVIC_InitStruct);
void NVIC_SetVectorTable(uint32_t NVIC_VectTab, uint32_t Offset);
void NVIC_SystemLPConfig(uint8_t LowPowerMode, FunctionalState NewState);
void SysTick_CLKSourceConfig(uint32_t SysTick_CLKSource);
#ifdef __cplusplus
}
#endif
#endif /* __MISC_H */
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/

View File

@ -1,483 +0,0 @@
/**
******************************************************************************
* @file stm32f10x_adc.h
* @author MCD Application Team
* @version V3.5.0
* @date 11-March-2011
* @brief This file contains all the functions prototypes for the ADC firmware
* library.
******************************************************************************
* @attention
*
* 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, STMICROELECTRONICS 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 2011 STMicroelectronics</center></h2>
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32F10x_ADC_H
#define __STM32F10x_ADC_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32f10x.h"
/** @addtogroup STM32F10x_StdPeriph_Driver
* @{
*/
/** @addtogroup ADC
* @{
*/
/** @defgroup ADC_Exported_Types
* @{
*/
/**
* @brief ADC Init structure definition
*/
typedef struct
{
uint32_t ADC_Mode; /*!< Configures the ADC to operate in independent or
dual mode.
This parameter can be a value of @ref ADC_mode */
FunctionalState ADC_ScanConvMode; /*!< Specifies whether the conversion is performed in
Scan (multichannels) or Single (one channel) mode.
This parameter can be set to ENABLE or DISABLE */
FunctionalState ADC_ContinuousConvMode; /*!< Specifies whether the conversion is performed in
Continuous or Single mode.
This parameter can be set to ENABLE or DISABLE. */
uint32_t ADC_ExternalTrigConv; /*!< Defines the external trigger used to start the analog
to digital conversion of regular channels. This parameter
can be a value of @ref ADC_external_trigger_sources_for_regular_channels_conversion */
uint32_t ADC_DataAlign; /*!< Specifies whether the ADC data alignment is left or right.
This parameter can be a value of @ref ADC_data_align */
uint8_t ADC_NbrOfChannel; /*!< Specifies the number of ADC channels that will be converted
using the sequencer for regular channel group.
This parameter must range from 1 to 16. */
}ADC_InitTypeDef;
/**
* @}
*/
/** @defgroup ADC_Exported_Constants
* @{
*/
#define IS_ADC_ALL_PERIPH(PERIPH) (((PERIPH) == ADC1) || \
((PERIPH) == ADC2) || \
((PERIPH) == ADC3))
#define IS_ADC_DMA_PERIPH(PERIPH) (((PERIPH) == ADC1) || \
((PERIPH) == ADC3))
/** @defgroup ADC_mode
* @{
*/
#define ADC_Mode_Independent ((uint32_t)0x00000000)
#define ADC_Mode_RegInjecSimult ((uint32_t)0x00010000)
#define ADC_Mode_RegSimult_AlterTrig ((uint32_t)0x00020000)
#define ADC_Mode_InjecSimult_FastInterl ((uint32_t)0x00030000)
#define ADC_Mode_InjecSimult_SlowInterl ((uint32_t)0x00040000)
#define ADC_Mode_InjecSimult ((uint32_t)0x00050000)
#define ADC_Mode_RegSimult ((uint32_t)0x00060000)
#define ADC_Mode_FastInterl ((uint32_t)0x00070000)
#define ADC_Mode_SlowInterl ((uint32_t)0x00080000)
#define ADC_Mode_AlterTrig ((uint32_t)0x00090000)
#define IS_ADC_MODE(MODE) (((MODE) == ADC_Mode_Independent) || \
((MODE) == ADC_Mode_RegInjecSimult) || \
((MODE) == ADC_Mode_RegSimult_AlterTrig) || \
((MODE) == ADC_Mode_InjecSimult_FastInterl) || \
((MODE) == ADC_Mode_InjecSimult_SlowInterl) || \
((MODE) == ADC_Mode_InjecSimult) || \
((MODE) == ADC_Mode_RegSimult) || \
((MODE) == ADC_Mode_FastInterl) || \
((MODE) == ADC_Mode_SlowInterl) || \
((MODE) == ADC_Mode_AlterTrig))
/**
* @}
*/
/** @defgroup ADC_external_trigger_sources_for_regular_channels_conversion
* @{
*/
#define ADC_ExternalTrigConv_T1_CC1 ((uint32_t)0x00000000) /*!< For ADC1 and ADC2 */
#define ADC_ExternalTrigConv_T1_CC2 ((uint32_t)0x00020000) /*!< For ADC1 and ADC2 */
#define ADC_ExternalTrigConv_T2_CC2 ((uint32_t)0x00060000) /*!< For ADC1 and ADC2 */
#define ADC_ExternalTrigConv_T3_TRGO ((uint32_t)0x00080000) /*!< For ADC1 and ADC2 */
#define ADC_ExternalTrigConv_T4_CC4 ((uint32_t)0x000A0000) /*!< For ADC1 and ADC2 */
#define ADC_ExternalTrigConv_Ext_IT11_TIM8_TRGO ((uint32_t)0x000C0000) /*!< For ADC1 and ADC2 */
#define ADC_ExternalTrigConv_T1_CC3 ((uint32_t)0x00040000) /*!< For ADC1, ADC2 and ADC3 */
#define ADC_ExternalTrigConv_None ((uint32_t)0x000E0000) /*!< For ADC1, ADC2 and ADC3 */
#define ADC_ExternalTrigConv_T3_CC1 ((uint32_t)0x00000000) /*!< For ADC3 only */
#define ADC_ExternalTrigConv_T2_CC3 ((uint32_t)0x00020000) /*!< For ADC3 only */
#define ADC_ExternalTrigConv_T8_CC1 ((uint32_t)0x00060000) /*!< For ADC3 only */
#define ADC_ExternalTrigConv_T8_TRGO ((uint32_t)0x00080000) /*!< For ADC3 only */
#define ADC_ExternalTrigConv_T5_CC1 ((uint32_t)0x000A0000) /*!< For ADC3 only */
#define ADC_ExternalTrigConv_T5_CC3 ((uint32_t)0x000C0000) /*!< For ADC3 only */
#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_Ext_IT11_TIM8_TRGO) || \
((REGTRIG) == ADC_ExternalTrigConv_None) || \
((REGTRIG) == ADC_ExternalTrigConv_T3_CC1) || \
((REGTRIG) == ADC_ExternalTrigConv_T2_CC3) || \
((REGTRIG) == ADC_ExternalTrigConv_T8_CC1) || \
((REGTRIG) == ADC_ExternalTrigConv_T8_TRGO) || \
((REGTRIG) == ADC_ExternalTrigConv_T5_CC1) || \
((REGTRIG) == ADC_ExternalTrigConv_T5_CC3))
/**
* @}
*/
/** @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_9 ((uint8_t)0x09)
#define ADC_Channel_10 ((uint8_t)0x0A)
#define ADC_Channel_11 ((uint8_t)0x0B)
#define ADC_Channel_12 ((uint8_t)0x0C)
#define ADC_Channel_13 ((uint8_t)0x0D)
#define ADC_Channel_14 ((uint8_t)0x0E)
#define ADC_Channel_15 ((uint8_t)0x0F)
#define ADC_Channel_16 ((uint8_t)0x10)
#define ADC_Channel_17 ((uint8_t)0x11)
#define ADC_Channel_TempSensor ((uint8_t)ADC_Channel_16)
#define ADC_Channel_Vrefint ((uint8_t)ADC_Channel_17)
#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_9) || \
((CHANNEL) == ADC_Channel_10) || ((CHANNEL) == ADC_Channel_11) || \
((CHANNEL) == ADC_Channel_12) || ((CHANNEL) == ADC_Channel_13) || \
((CHANNEL) == ADC_Channel_14) || ((CHANNEL) == ADC_Channel_15) || \
((CHANNEL) == ADC_Channel_16) || ((CHANNEL) == ADC_Channel_17))
/**
* @}
*/
/** @defgroup ADC_sampling_time
* @{
*/
#define ADC_SampleTime_1Cycles5 ((uint8_t)0x00)
#define ADC_SampleTime_7Cycles5 ((uint8_t)0x01)
#define ADC_SampleTime_13Cycles5 ((uint8_t)0x02)
#define ADC_SampleTime_28Cycles5 ((uint8_t)0x03)
#define ADC_SampleTime_41Cycles5 ((uint8_t)0x04)
#define ADC_SampleTime_55Cycles5 ((uint8_t)0x05)
#define ADC_SampleTime_71Cycles5 ((uint8_t)0x06)
#define ADC_SampleTime_239Cycles5 ((uint8_t)0x07)
#define IS_ADC_SAMPLE_TIME(TIME) (((TIME) == ADC_SampleTime_1Cycles5) || \
((TIME) == ADC_SampleTime_7Cycles5) || \
((TIME) == ADC_SampleTime_13Cycles5) || \
((TIME) == ADC_SampleTime_28Cycles5) || \
((TIME) == ADC_SampleTime_41Cycles5) || \
((TIME) == ADC_SampleTime_55Cycles5) || \
((TIME) == ADC_SampleTime_71Cycles5) || \
((TIME) == ADC_SampleTime_239Cycles5))
/**
* @}
*/
/** @defgroup ADC_external_trigger_sources_for_injected_channels_conversion
* @{
*/
#define ADC_ExternalTrigInjecConv_T2_TRGO ((uint32_t)0x00002000) /*!< For ADC1 and ADC2 */
#define ADC_ExternalTrigInjecConv_T2_CC1 ((uint32_t)0x00003000) /*!< For ADC1 and ADC2 */
#define ADC_ExternalTrigInjecConv_T3_CC4 ((uint32_t)0x00004000) /*!< For ADC1 and ADC2 */
#define ADC_ExternalTrigInjecConv_T4_TRGO ((uint32_t)0x00005000) /*!< For ADC1 and ADC2 */
#define ADC_ExternalTrigInjecConv_Ext_IT15_TIM8_CC4 ((uint32_t)0x00006000) /*!< For ADC1 and ADC2 */
#define ADC_ExternalTrigInjecConv_T1_TRGO ((uint32_t)0x00000000) /*!< For ADC1, ADC2 and ADC3 */
#define ADC_ExternalTrigInjecConv_T1_CC4 ((uint32_t)0x00001000) /*!< For ADC1, ADC2 and ADC3 */
#define ADC_ExternalTrigInjecConv_None ((uint32_t)0x00007000) /*!< For ADC1, ADC2 and ADC3 */
#define ADC_ExternalTrigInjecConv_T4_CC3 ((uint32_t)0x00002000) /*!< For ADC3 only */
#define ADC_ExternalTrigInjecConv_T8_CC2 ((uint32_t)0x00003000) /*!< For ADC3 only */
#define ADC_ExternalTrigInjecConv_T8_CC4 ((uint32_t)0x00004000) /*!< For ADC3 only */
#define ADC_ExternalTrigInjecConv_T5_TRGO ((uint32_t)0x00005000) /*!< For ADC3 only */
#define ADC_ExternalTrigInjecConv_T5_CC4 ((uint32_t)0x00006000) /*!< For ADC3 only */
#define IS_ADC_EXT_INJEC_TRIG(INJTRIG) (((INJTRIG) == ADC_ExternalTrigInjecConv_T1_TRGO) || \
((INJTRIG) == ADC_ExternalTrigInjecConv_T1_CC4) || \
((INJTRIG) == ADC_ExternalTrigInjecConv_T2_TRGO) || \
((INJTRIG) == ADC_ExternalTrigInjecConv_T2_CC1) || \
((INJTRIG) == ADC_ExternalTrigInjecConv_T3_CC4) || \
((INJTRIG) == ADC_ExternalTrigInjecConv_T4_TRGO) || \
((INJTRIG) == ADC_ExternalTrigInjecConv_Ext_IT15_TIM8_CC4) || \
((INJTRIG) == ADC_ExternalTrigInjecConv_None) || \
((INJTRIG) == ADC_ExternalTrigInjecConv_T4_CC3) || \
((INJTRIG) == ADC_ExternalTrigInjecConv_T8_CC2) || \
((INJTRIG) == ADC_ExternalTrigInjecConv_T8_CC4) || \
((INJTRIG) == ADC_ExternalTrigInjecConv_T5_TRGO) || \
((INJTRIG) == ADC_ExternalTrigInjecConv_T5_CC4))
/**
* @}
*/
/** @defgroup ADC_injected_channel_selection
* @{
*/
#define ADC_InjectedChannel_1 ((uint8_t)0x14)
#define ADC_InjectedChannel_2 ((uint8_t)0x18)
#define ADC_InjectedChannel_3 ((uint8_t)0x1C)
#define ADC_InjectedChannel_4 ((uint8_t)0x20)
#define IS_ADC_INJECTED_CHANNEL(CHANNEL) (((CHANNEL) == ADC_InjectedChannel_1) || \
((CHANNEL) == ADC_InjectedChannel_2) || \
((CHANNEL) == ADC_InjectedChannel_3) || \
((CHANNEL) == ADC_InjectedChannel_4))
/**
* @}
*/
/** @defgroup ADC_analog_watchdog_selection
* @{
*/
#define ADC_AnalogWatchdog_SingleRegEnable ((uint32_t)0x00800200)
#define ADC_AnalogWatchdog_SingleInjecEnable ((uint32_t)0x00400200)
#define ADC_AnalogWatchdog_SingleRegOrInjecEnable ((uint32_t)0x00C00200)
#define ADC_AnalogWatchdog_AllRegEnable ((uint32_t)0x00800000)
#define ADC_AnalogWatchdog_AllInjecEnable ((uint32_t)0x00400000)
#define ADC_AnalogWatchdog_AllRegAllInjecEnable ((uint32_t)0x00C00000)
#define ADC_AnalogWatchdog_None ((uint32_t)0x00000000)
#define IS_ADC_ANALOG_WATCHDOG(WATCHDOG) (((WATCHDOG) == ADC_AnalogWatchdog_SingleRegEnable) || \
((WATCHDOG) == ADC_AnalogWatchdog_SingleInjecEnable) || \
((WATCHDOG) == ADC_AnalogWatchdog_SingleRegOrInjecEnable) || \
((WATCHDOG) == ADC_AnalogWatchdog_AllRegEnable) || \
((WATCHDOG) == ADC_AnalogWatchdog_AllInjecEnable) || \
((WATCHDOG) == ADC_AnalogWatchdog_AllRegAllInjecEnable) || \
((WATCHDOG) == ADC_AnalogWatchdog_None))
/**
* @}
*/
/** @defgroup ADC_interrupts_definition
* @{
*/
#define ADC_IT_EOC ((uint16_t)0x0220)
#define ADC_IT_AWD ((uint16_t)0x0140)
#define ADC_IT_JEOC ((uint16_t)0x0480)
#define IS_ADC_IT(IT) ((((IT) & (uint16_t)0xF81F) == 0x00) && ((IT) != 0x00))
#define IS_ADC_GET_IT(IT) (((IT) == ADC_IT_EOC) || ((IT) == ADC_IT_AWD) || \
((IT) == ADC_IT_JEOC))
/**
* @}
*/
/** @defgroup ADC_flags_definition
* @{
*/
#define ADC_FLAG_AWD ((uint8_t)0x01)
#define ADC_FLAG_EOC ((uint8_t)0x02)
#define ADC_FLAG_JEOC ((uint8_t)0x04)
#define ADC_FLAG_JSTRT ((uint8_t)0x08)
#define ADC_FLAG_STRT ((uint8_t)0x10)
#define IS_ADC_CLEAR_FLAG(FLAG) ((((FLAG) & (uint8_t)0xE0) == 0x00) && ((FLAG) != 0x00))
#define IS_ADC_GET_FLAG(FLAG) (((FLAG) == ADC_FLAG_AWD) || ((FLAG) == ADC_FLAG_EOC) || \
((FLAG) == ADC_FLAG_JEOC) || ((FLAG)== ADC_FLAG_JSTRT) || \
((FLAG) == ADC_FLAG_STRT))
/**
* @}
*/
/** @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_ResetCalibration(ADC_TypeDef* ADCx);
FlagStatus ADC_GetResetCalibrationStatus(ADC_TypeDef* ADCx);
void ADC_StartCalibration(ADC_TypeDef* ADCx);
FlagStatus ADC_GetCalibrationStatus(ADC_TypeDef* ADCx);
void ADC_SoftwareStartConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState);
FlagStatus ADC_GetSoftwareStartConvStatus(ADC_TypeDef* ADCx);
void ADC_DiscModeChannelCountConfig(ADC_TypeDef* ADCx, uint8_t Number);
void ADC_DiscModeCmd(ADC_TypeDef* ADCx, FunctionalState NewState);
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);
uint32_t ADC_GetDualModeConversionValue(void);
void ADC_AutoInjectedConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState);
void ADC_InjectedDiscModeCmd(ADC_TypeDef* ADCx, FunctionalState NewState);
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);
FlagStatus ADC_GetSoftwareStartInjectedConvCmdStatus(ADC_TypeDef* ADCx);
void ADC_InjectedChannelConfig(ADC_TypeDef* ADCx, uint8_t ADC_Channel, uint8_t Rank, uint8_t ADC_SampleTime);
void ADC_InjectedSequencerLengthConfig(ADC_TypeDef* ADCx, uint8_t Length);
void ADC_SetInjectedOffset(ADC_TypeDef* ADCx, uint8_t ADC_InjectedChannel, uint16_t Offset);
uint16_t ADC_GetInjectedConversionValue(ADC_TypeDef* ADCx, uint8_t ADC_InjectedChannel);
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);
#ifdef __cplusplus
}
#endif
#endif /*__STM32F10x_ADC_H */
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/

View File

@ -1,195 +0,0 @@
/**
******************************************************************************
* @file stm32f10x_bkp.h
* @author MCD Application Team
* @version V3.5.0
* @date 11-March-2011
* @brief This file contains all the functions prototypes for the BKP firmware
* library.
******************************************************************************
* @attention
*
* 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, STMICROELECTRONICS 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 2011 STMicroelectronics</center></h2>
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32F10x_BKP_H
#define __STM32F10x_BKP_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32f10x.h"
/** @addtogroup STM32F10x_StdPeriph_Driver
* @{
*/
/** @addtogroup BKP
* @{
*/
/** @defgroup BKP_Exported_Types
* @{
*/
/**
* @}
*/
/** @defgroup BKP_Exported_Constants
* @{
*/
/** @defgroup Tamper_Pin_active_level
* @{
*/
#define BKP_TamperPinLevel_High ((uint16_t)0x0000)
#define BKP_TamperPinLevel_Low ((uint16_t)0x0001)
#define IS_BKP_TAMPER_PIN_LEVEL(LEVEL) (((LEVEL) == BKP_TamperPinLevel_High) || \
((LEVEL) == BKP_TamperPinLevel_Low))
/**
* @}
*/
/** @defgroup RTC_output_source_to_output_on_the_Tamper_pin
* @{
*/
#define BKP_RTCOutputSource_None ((uint16_t)0x0000)
#define BKP_RTCOutputSource_CalibClock ((uint16_t)0x0080)
#define BKP_RTCOutputSource_Alarm ((uint16_t)0x0100)
#define BKP_RTCOutputSource_Second ((uint16_t)0x0300)
#define IS_BKP_RTC_OUTPUT_SOURCE(SOURCE) (((SOURCE) == BKP_RTCOutputSource_None) || \
((SOURCE) == BKP_RTCOutputSource_CalibClock) || \
((SOURCE) == BKP_RTCOutputSource_Alarm) || \
((SOURCE) == BKP_RTCOutputSource_Second))
/**
* @}
*/
/** @defgroup Data_Backup_Register
* @{
*/
#define BKP_DR1 ((uint16_t)0x0004)
#define BKP_DR2 ((uint16_t)0x0008)
#define BKP_DR3 ((uint16_t)0x000C)
#define BKP_DR4 ((uint16_t)0x0010)
#define BKP_DR5 ((uint16_t)0x0014)
#define BKP_DR6 ((uint16_t)0x0018)
#define BKP_DR7 ((uint16_t)0x001C)
#define BKP_DR8 ((uint16_t)0x0020)
#define BKP_DR9 ((uint16_t)0x0024)
#define BKP_DR10 ((uint16_t)0x0028)
#define BKP_DR11 ((uint16_t)0x0040)
#define BKP_DR12 ((uint16_t)0x0044)
#define BKP_DR13 ((uint16_t)0x0048)
#define BKP_DR14 ((uint16_t)0x004C)
#define BKP_DR15 ((uint16_t)0x0050)
#define BKP_DR16 ((uint16_t)0x0054)
#define BKP_DR17 ((uint16_t)0x0058)
#define BKP_DR18 ((uint16_t)0x005C)
#define BKP_DR19 ((uint16_t)0x0060)
#define BKP_DR20 ((uint16_t)0x0064)
#define BKP_DR21 ((uint16_t)0x0068)
#define BKP_DR22 ((uint16_t)0x006C)
#define BKP_DR23 ((uint16_t)0x0070)
#define BKP_DR24 ((uint16_t)0x0074)
#define BKP_DR25 ((uint16_t)0x0078)
#define BKP_DR26 ((uint16_t)0x007C)
#define BKP_DR27 ((uint16_t)0x0080)
#define BKP_DR28 ((uint16_t)0x0084)
#define BKP_DR29 ((uint16_t)0x0088)
#define BKP_DR30 ((uint16_t)0x008C)
#define BKP_DR31 ((uint16_t)0x0090)
#define BKP_DR32 ((uint16_t)0x0094)
#define BKP_DR33 ((uint16_t)0x0098)
#define BKP_DR34 ((uint16_t)0x009C)
#define BKP_DR35 ((uint16_t)0x00A0)
#define BKP_DR36 ((uint16_t)0x00A4)
#define BKP_DR37 ((uint16_t)0x00A8)
#define BKP_DR38 ((uint16_t)0x00AC)
#define BKP_DR39 ((uint16_t)0x00B0)
#define BKP_DR40 ((uint16_t)0x00B4)
#define BKP_DR41 ((uint16_t)0x00B8)
#define BKP_DR42 ((uint16_t)0x00BC)
#define IS_BKP_DR(DR) (((DR) == BKP_DR1) || ((DR) == BKP_DR2) || ((DR) == BKP_DR3) || \
((DR) == BKP_DR4) || ((DR) == BKP_DR5) || ((DR) == BKP_DR6) || \
((DR) == BKP_DR7) || ((DR) == BKP_DR8) || ((DR) == BKP_DR9) || \
((DR) == BKP_DR10) || ((DR) == BKP_DR11) || ((DR) == BKP_DR12) || \
((DR) == BKP_DR13) || ((DR) == BKP_DR14) || ((DR) == BKP_DR15) || \
((DR) == BKP_DR16) || ((DR) == BKP_DR17) || ((DR) == BKP_DR18) || \
((DR) == BKP_DR19) || ((DR) == BKP_DR20) || ((DR) == BKP_DR21) || \
((DR) == BKP_DR22) || ((DR) == BKP_DR23) || ((DR) == BKP_DR24) || \
((DR) == BKP_DR25) || ((DR) == BKP_DR26) || ((DR) == BKP_DR27) || \
((DR) == BKP_DR28) || ((DR) == BKP_DR29) || ((DR) == BKP_DR30) || \
((DR) == BKP_DR31) || ((DR) == BKP_DR32) || ((DR) == BKP_DR33) || \
((DR) == BKP_DR34) || ((DR) == BKP_DR35) || ((DR) == BKP_DR36) || \
((DR) == BKP_DR37) || ((DR) == BKP_DR38) || ((DR) == BKP_DR39) || \
((DR) == BKP_DR40) || ((DR) == BKP_DR41) || ((DR) == BKP_DR42))
#define IS_BKP_CALIBRATION_VALUE(VALUE) ((VALUE) <= 0x7F)
/**
* @}
*/
/**
* @}
*/
/** @defgroup BKP_Exported_Macros
* @{
*/
/**
* @}
*/
/** @defgroup BKP_Exported_Functions
* @{
*/
void BKP_DeInit(void);
void BKP_TamperPinLevelConfig(uint16_t BKP_TamperPinLevel);
void BKP_TamperPinCmd(FunctionalState NewState);
void BKP_ITConfig(FunctionalState NewState);
void BKP_RTCOutputConfig(uint16_t BKP_RTCOutputSource);
void BKP_SetRTCCalibrationValue(uint8_t CalibrationValue);
void BKP_WriteBackupRegister(uint16_t BKP_DR, uint16_t Data);
uint16_t BKP_ReadBackupRegister(uint16_t BKP_DR);
FlagStatus BKP_GetFlagStatus(void);
void BKP_ClearFlag(void);
ITStatus BKP_GetITStatus(void);
void BKP_ClearITPendingBit(void);
#ifdef __cplusplus
}
#endif
#endif /* __STM32F10x_BKP_H */
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/

View File

@ -1,697 +0,0 @@
/**
******************************************************************************
* @file stm32f10x_can.h
* @author MCD Application Team
* @version V3.5.0
* @date 11-March-2011
* @brief This file contains all the functions prototypes for the CAN firmware
* library.
******************************************************************************
* @attention
*
* 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, STMICROELECTRONICS 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 2011 STMicroelectronics</center></h2>
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32F10x_CAN_H
#define __STM32F10x_CAN_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32f10x.h"
/** @addtogroup STM32F10x_StdPeriph_Driver
* @{
*/
/** @addtogroup CAN
* @{
*/
/** @defgroup CAN_Exported_Types
* @{
*/
#define IS_CAN_ALL_PERIPH(PERIPH) (((PERIPH) == CAN1) || \
((PERIPH) == CAN2))
/**
* @brief CAN init structure definition
*/
typedef struct
{
uint16_t CAN_Prescaler; /*!< Specifies the length of a time quantum.
It ranges from 1 to 1024. */
uint8_t CAN_Mode; /*!< Specifies the CAN operating mode.
This parameter can be a value of
@ref CAN_operating_mode */
uint8_t CAN_SJW; /*!< Specifies the maximum number of time quanta
the CAN hardware is allowed to lengthen or
shorten a bit to perform resynchronization.
This parameter can be a value of
@ref CAN_synchronisation_jump_width */
uint8_t CAN_BS1; /*!< Specifies the number of time quanta in Bit
Segment 1. This parameter can be a value of
@ref CAN_time_quantum_in_bit_segment_1 */
uint8_t CAN_BS2; /*!< Specifies the number of time quanta in Bit
Segment 2.
This parameter can be a value of
@ref CAN_time_quantum_in_bit_segment_2 */
FunctionalState CAN_TTCM; /*!< Enable or disable the time triggered
communication mode. This parameter can be set
either to ENABLE or DISABLE. */
FunctionalState CAN_ABOM; /*!< Enable or disable the automatic bus-off
management. This parameter can be set either
to ENABLE or DISABLE. */
FunctionalState CAN_AWUM; /*!< Enable or disable the automatic wake-up mode.
This parameter can be set either to ENABLE or
DISABLE. */
FunctionalState CAN_NART; /*!< Enable or disable the no-automatic
retransmission mode. This parameter can be
set either to ENABLE or DISABLE. */
FunctionalState CAN_RFLM; /*!< Enable or disable the Receive FIFO Locked mode.
This parameter can be set either to ENABLE
or DISABLE. */
FunctionalState CAN_TXFP; /*!< Enable or disable the transmit FIFO priority.
This parameter can be set either to ENABLE
or DISABLE. */
} CAN_InitTypeDef;
/**
* @brief CAN filter init structure definition
*/
typedef struct
{
uint16_t CAN_FilterIdHigh; /*!< Specifies the filter identification number (MSBs for a 32-bit
configuration, first one for a 16-bit configuration).
This parameter can be a value between 0x0000 and 0xFFFF */
uint16_t CAN_FilterIdLow; /*!< Specifies the filter identification number (LSBs for a 32-bit
configuration, second one for a 16-bit configuration).
This parameter can be a value between 0x0000 and 0xFFFF */
uint16_t CAN_FilterMaskIdHigh; /*!< Specifies the filter mask number or identification number,
according to the mode (MSBs for a 32-bit configuration,
first one for a 16-bit configuration).
This parameter can be a value between 0x0000 and 0xFFFF */
uint16_t CAN_FilterMaskIdLow; /*!< Specifies the filter mask number or identification number,
according to the mode (LSBs for a 32-bit configuration,
second one for a 16-bit configuration).
This parameter can be a value between 0x0000 and 0xFFFF */
uint16_t CAN_FilterFIFOAssignment; /*!< Specifies the FIFO (0 or 1) which will be assigned to the filter.
This parameter can be a value of @ref CAN_filter_FIFO */
uint8_t CAN_FilterNumber; /*!< Specifies the filter which will be initialized. It ranges from 0 to 13. */
uint8_t CAN_FilterMode; /*!< Specifies the filter mode to be initialized.
This parameter can be a value of @ref CAN_filter_mode */
uint8_t CAN_FilterScale; /*!< Specifies the filter scale.
This parameter can be a value of @ref CAN_filter_scale */
FunctionalState CAN_FilterActivation; /*!< Enable or disable the filter.
This parameter can be set either to ENABLE or DISABLE. */
} CAN_FilterInitTypeDef;
/**
* @brief CAN Tx message structure definition
*/
typedef struct
{
uint32_t StdId; /*!< Specifies the standard identifier.
This parameter can be a value between 0 to 0x7FF. */
uint32_t ExtId; /*!< Specifies the extended identifier.
This parameter can be a value between 0 to 0x1FFFFFFF. */
uint8_t IDE; /*!< 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 CAN_remote_transmission_request */
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. */
} CanTxMsg;
/**
* @brief CAN Rx message structure definition
*/
typedef struct
{
uint32_t StdId; /*!< Specifies the standard identifier.
This parameter can be a value between 0 to 0x7FF. */
uint32_t ExtId; /*!< Specifies the extended identifier.
This parameter can be a value between 0 to 0x1FFFFFFF. */
uint8_t IDE; /*!< 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 CAN_remote_transmission_request */
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. */
uint8_t FMI; /*!< Specifies the index of the filter the message stored in
the mailbox passes through. This parameter can be a
value between 0 to 0xFF */
} CanRxMsg;
/**
* @}
*/
/** @defgroup CAN_Exported_Constants
* @{
*/
/** @defgroup CAN_sleep_constants
* @{
*/
#define CAN_InitStatus_Failed ((uint8_t)0x00) /*!< CAN initialization failed */
#define CAN_InitStatus_Success ((uint8_t)0x01) /*!< CAN initialization OK */
/**
* @}
*/
/** @defgroup CAN_Mode
* @{
*/
#define CAN_Mode_Normal ((uint8_t)0x00) /*!< normal mode */
#define CAN_Mode_LoopBack ((uint8_t)0x01) /*!< loopback mode */
#define CAN_Mode_Silent ((uint8_t)0x02) /*!< silent mode */
#define CAN_Mode_Silent_LoopBack ((uint8_t)0x03) /*!< loopback combined with silent mode */
#define IS_CAN_MODE(MODE) (((MODE) == CAN_Mode_Normal) || \
((MODE) == CAN_Mode_LoopBack)|| \
((MODE) == CAN_Mode_Silent) || \
((MODE) == CAN_Mode_Silent_LoopBack))
/**
* @}
*/
/**
* @defgroup CAN_Operating_Mode
* @{
*/
#define CAN_OperatingMode_Initialization ((uint8_t)0x00) /*!< Initialization mode */
#define CAN_OperatingMode_Normal ((uint8_t)0x01) /*!< Normal mode */
#define CAN_OperatingMode_Sleep ((uint8_t)0x02) /*!< sleep mode */
#define IS_CAN_OPERATING_MODE(MODE) (((MODE) == CAN_OperatingMode_Initialization) ||\
((MODE) == CAN_OperatingMode_Normal)|| \
((MODE) == CAN_OperatingMode_Sleep))
/**
* @}
*/
/**
* @defgroup CAN_Mode_Status
* @{
*/
#define CAN_ModeStatus_Failed ((uint8_t)0x00) /*!< CAN entering the specific mode failed */
#define CAN_ModeStatus_Success ((uint8_t)!CAN_ModeStatus_Failed) /*!< CAN entering the specific mode Succeed */
/**
* @}
*/
/** @defgroup CAN_synchronisation_jump_width
* @{
*/
#define CAN_SJW_1tq ((uint8_t)0x00) /*!< 1 time quantum */
#define CAN_SJW_2tq ((uint8_t)0x01) /*!< 2 time quantum */
#define CAN_SJW_3tq ((uint8_t)0x02) /*!< 3 time quantum */
#define CAN_SJW_4tq ((uint8_t)0x03) /*!< 4 time quantum */
#define IS_CAN_SJW(SJW) (((SJW) == CAN_SJW_1tq) || ((SJW) == CAN_SJW_2tq)|| \
((SJW) == CAN_SJW_3tq) || ((SJW) == CAN_SJW_4tq))
/**
* @}
*/
/** @defgroup CAN_time_quantum_in_bit_segment_1
* @{
*/
#define CAN_BS1_1tq ((uint8_t)0x00) /*!< 1 time quantum */
#define CAN_BS1_2tq ((uint8_t)0x01) /*!< 2 time quantum */
#define CAN_BS1_3tq ((uint8_t)0x02) /*!< 3 time quantum */
#define CAN_BS1_4tq ((uint8_t)0x03) /*!< 4 time quantum */
#define CAN_BS1_5tq ((uint8_t)0x04) /*!< 5 time quantum */
#define CAN_BS1_6tq ((uint8_t)0x05) /*!< 6 time quantum */
#define CAN_BS1_7tq ((uint8_t)0x06) /*!< 7 time quantum */
#define CAN_BS1_8tq ((uint8_t)0x07) /*!< 8 time quantum */
#define CAN_BS1_9tq ((uint8_t)0x08) /*!< 9 time quantum */
#define CAN_BS1_10tq ((uint8_t)0x09) /*!< 10 time quantum */
#define CAN_BS1_11tq ((uint8_t)0x0A) /*!< 11 time quantum */
#define CAN_BS1_12tq ((uint8_t)0x0B) /*!< 12 time quantum */
#define CAN_BS1_13tq ((uint8_t)0x0C) /*!< 13 time quantum */
#define CAN_BS1_14tq ((uint8_t)0x0D) /*!< 14 time quantum */
#define CAN_BS1_15tq ((uint8_t)0x0E) /*!< 15 time quantum */
#define CAN_BS1_16tq ((uint8_t)0x0F) /*!< 16 time quantum */
#define IS_CAN_BS1(BS1) ((BS1) <= CAN_BS1_16tq)
/**
* @}
*/
/** @defgroup CAN_time_quantum_in_bit_segment_2
* @{
*/
#define CAN_BS2_1tq ((uint8_t)0x00) /*!< 1 time quantum */
#define CAN_BS2_2tq ((uint8_t)0x01) /*!< 2 time quantum */
#define CAN_BS2_3tq ((uint8_t)0x02) /*!< 3 time quantum */
#define CAN_BS2_4tq ((uint8_t)0x03) /*!< 4 time quantum */
#define CAN_BS2_5tq ((uint8_t)0x04) /*!< 5 time quantum */
#define CAN_BS2_6tq ((uint8_t)0x05) /*!< 6 time quantum */
#define CAN_BS2_7tq ((uint8_t)0x06) /*!< 7 time quantum */
#define CAN_BS2_8tq ((uint8_t)0x07) /*!< 8 time quantum */
#define IS_CAN_BS2(BS2) ((BS2) <= CAN_BS2_8tq)
/**
* @}
*/
/** @defgroup CAN_clock_prescaler
* @{
*/
#define IS_CAN_PRESCALER(PRESCALER) (((PRESCALER) >= 1) && ((PRESCALER) <= 1024))
/**
* @}
*/
/** @defgroup CAN_filter_number
* @{
*/
#ifndef STM32F10X_CL
#define IS_CAN_FILTER_NUMBER(NUMBER) ((NUMBER) <= 13)
#else
#define IS_CAN_FILTER_NUMBER(NUMBER) ((NUMBER) <= 27)
#endif /* STM32F10X_CL */
/**
* @}
*/
/** @defgroup CAN_filter_mode
* @{
*/
#define CAN_FilterMode_IdMask ((uint8_t)0x00) /*!< identifier/mask mode */
#define CAN_FilterMode_IdList ((uint8_t)0x01) /*!< identifier list mode */
#define IS_CAN_FILTER_MODE(MODE) (((MODE) == CAN_FilterMode_IdMask) || \
((MODE) == CAN_FilterMode_IdList))
/**
* @}
*/
/** @defgroup CAN_filter_scale
* @{
*/
#define CAN_FilterScale_16bit ((uint8_t)0x00) /*!< Two 16-bit filters */
#define CAN_FilterScale_32bit ((uint8_t)0x01) /*!< One 32-bit filter */
#define IS_CAN_FILTER_SCALE(SCALE) (((SCALE) == CAN_FilterScale_16bit) || \
((SCALE) == CAN_FilterScale_32bit))
/**
* @}
*/
/** @defgroup CAN_filter_FIFO
* @{
*/
#define CAN_Filter_FIFO0 ((uint8_t)0x00) /*!< Filter FIFO 0 assignment for filter x */
#define CAN_Filter_FIFO1 ((uint8_t)0x01) /*!< Filter FIFO 1 assignment for filter x */
#define IS_CAN_FILTER_FIFO(FIFO) (((FIFO) == CAN_FilterFIFO0) || \
((FIFO) == CAN_FilterFIFO1))
/**
* @}
*/
/** @defgroup Start_bank_filter_for_slave_CAN
* @{
*/
#define IS_CAN_BANKNUMBER(BANKNUMBER) (((BANKNUMBER) >= 1) && ((BANKNUMBER) <= 27))
/**
* @}
*/
/** @defgroup CAN_Tx
* @{
*/
#define IS_CAN_TRANSMITMAILBOX(TRANSMITMAILBOX) ((TRANSMITMAILBOX) <= ((uint8_t)0x02))
#define IS_CAN_STDID(STDID) ((STDID) <= ((uint32_t)0x7FF))
#define IS_CAN_EXTID(EXTID) ((EXTID) <= ((uint32_t)0x1FFFFFFF))
#define IS_CAN_DLC(DLC) ((DLC) <= ((uint8_t)0x08))
/**
* @}
*/
/** @defgroup CAN_identifier_type
* @{
*/
#define CAN_Id_Standard ((uint32_t)0x00000000) /*!< Standard Id */
#define CAN_Id_Extended ((uint32_t)0x00000004) /*!< Extended Id */
#define IS_CAN_IDTYPE(IDTYPE) (((IDTYPE) == CAN_Id_Standard) || \
((IDTYPE) == CAN_Id_Extended))
/**
* @}
*/
/** @defgroup CAN_remote_transmission_request
* @{
*/
#define CAN_RTR_Data ((uint32_t)0x00000000) /*!< Data frame */
#define CAN_RTR_Remote ((uint32_t)0x00000002) /*!< Remote frame */
#define IS_CAN_RTR(RTR) (((RTR) == CAN_RTR_Data) || ((RTR) == CAN_RTR_Remote))
/**
* @}
*/
/** @defgroup CAN_transmit_constants
* @{
*/
#define CAN_TxStatus_Failed ((uint8_t)0x00)/*!< CAN transmission failed */
#define CAN_TxStatus_Ok ((uint8_t)0x01) /*!< CAN transmission succeeded */
#define CAN_TxStatus_Pending ((uint8_t)0x02) /*!< CAN transmission pending */
#define CAN_TxStatus_NoMailBox ((uint8_t)0x04) /*!< CAN cell did not provide an empty mailbox */
/**
* @}
*/
/** @defgroup CAN_receive_FIFO_number_constants
* @{
*/
#define CAN_FIFO0 ((uint8_t)0x00) /*!< CAN FIFO 0 used to receive */
#define CAN_FIFO1 ((uint8_t)0x01) /*!< CAN FIFO 1 used to receive */
#define IS_CAN_FIFO(FIFO) (((FIFO) == CAN_FIFO0) || ((FIFO) == CAN_FIFO1))
/**
* @}
*/
/** @defgroup CAN_sleep_constants
* @{
*/
#define CAN_Sleep_Failed ((uint8_t)0x00) /*!< CAN did not enter the sleep mode */
#define CAN_Sleep_Ok ((uint8_t)0x01) /*!< CAN entered the sleep mode */
/**
* @}
*/
/** @defgroup CAN_wake_up_constants
* @{
*/
#define CAN_WakeUp_Failed ((uint8_t)0x00) /*!< CAN did not leave the sleep mode */
#define CAN_WakeUp_Ok ((uint8_t)0x01) /*!< CAN leaved the sleep mode */
/**
* @}
*/
/**
* @defgroup CAN_Error_Code_constants
* @{
*/
#define CAN_ErrorCode_NoErr ((uint8_t)0x00) /*!< No Error */
#define CAN_ErrorCode_StuffErr ((uint8_t)0x10) /*!< Stuff Error */
#define CAN_ErrorCode_FormErr ((uint8_t)0x20) /*!< Form Error */
#define CAN_ErrorCode_ACKErr ((uint8_t)0x30) /*!< Acknowledgment Error */
#define CAN_ErrorCode_BitRecessiveErr ((uint8_t)0x40) /*!< Bit Recessive Error */
#define CAN_ErrorCode_BitDominantErr ((uint8_t)0x50) /*!< Bit Dominant Error */
#define CAN_ErrorCode_CRCErr ((uint8_t)0x60) /*!< CRC Error */
#define CAN_ErrorCode_SoftwareSetErr ((uint8_t)0x70) /*!< Software Set Error */
/**
* @}
*/
/** @defgroup CAN_flags
* @{
*/
/* If the flag is 0x3XXXXXXX, it means that it can be used with CAN_GetFlagStatus()
and CAN_ClearFlag() functions. */
/* If the flag is 0x1XXXXXXX, it means that it can only be used with CAN_GetFlagStatus() function. */
/* Transmit Flags */
#define CAN_FLAG_RQCP0 ((uint32_t)0x38000001) /*!< Request MailBox0 Flag */
#define CAN_FLAG_RQCP1 ((uint32_t)0x38000100) /*!< Request MailBox1 Flag */
#define CAN_FLAG_RQCP2 ((uint32_t)0x38010000) /*!< Request MailBox2 Flag */
/* Receive Flags */
#define CAN_FLAG_FMP0 ((uint32_t)0x12000003) /*!< FIFO 0 Message Pending Flag */
#define CAN_FLAG_FF0 ((uint32_t)0x32000008) /*!< FIFO 0 Full Flag */
#define CAN_FLAG_FOV0 ((uint32_t)0x32000010) /*!< FIFO 0 Overrun Flag */
#define CAN_FLAG_FMP1 ((uint32_t)0x14000003) /*!< FIFO 1 Message Pending Flag */
#define CAN_FLAG_FF1 ((uint32_t)0x34000008) /*!< FIFO 1 Full Flag */
#define CAN_FLAG_FOV1 ((uint32_t)0x34000010) /*!< FIFO 1 Overrun Flag */
/* Operating Mode Flags */
#define CAN_FLAG_WKU ((uint32_t)0x31000008) /*!< Wake up Flag */
#define CAN_FLAG_SLAK ((uint32_t)0x31000012) /*!< Sleep acknowledge Flag */
/* Note: When SLAK intterupt is disabled (SLKIE=0), no polling on SLAKI is possible.
In this case the SLAK bit can be polled.*/
/* Error Flags */
#define CAN_FLAG_EWG ((uint32_t)0x10F00001) /*!< Error Warning Flag */
#define CAN_FLAG_EPV ((uint32_t)0x10F00002) /*!< Error Passive Flag */
#define CAN_FLAG_BOF ((uint32_t)0x10F00004) /*!< Bus-Off Flag */
#define CAN_FLAG_LEC ((uint32_t)0x30F00070) /*!< Last error code Flag */
#define IS_CAN_GET_FLAG(FLAG) (((FLAG) == CAN_FLAG_LEC) || ((FLAG) == CAN_FLAG_BOF) || \
((FLAG) == CAN_FLAG_EPV) || ((FLAG) == CAN_FLAG_EWG) || \
((FLAG) == CAN_FLAG_WKU) || ((FLAG) == CAN_FLAG_FOV0) || \
((FLAG) == CAN_FLAG_FF0) || ((FLAG) == CAN_FLAG_FMP0) || \
((FLAG) == CAN_FLAG_FOV1) || ((FLAG) == CAN_FLAG_FF1) || \
((FLAG) == CAN_FLAG_FMP1) || ((FLAG) == CAN_FLAG_RQCP2) || \
((FLAG) == CAN_FLAG_RQCP1)|| ((FLAG) == CAN_FLAG_RQCP0) || \
((FLAG) == CAN_FLAG_SLAK ))
#define IS_CAN_CLEAR_FLAG(FLAG)(((FLAG) == CAN_FLAG_LEC) || ((FLAG) == CAN_FLAG_RQCP2) || \
((FLAG) == CAN_FLAG_RQCP1) || ((FLAG) == CAN_FLAG_RQCP0) || \
((FLAG) == CAN_FLAG_FF0) || ((FLAG) == CAN_FLAG_FOV0) ||\
((FLAG) == CAN_FLAG_FF1) || ((FLAG) == CAN_FLAG_FOV1) || \
((FLAG) == CAN_FLAG_WKU) || ((FLAG) == CAN_FLAG_SLAK))
/**
* @}
*/
/** @defgroup CAN_interrupts
* @{
*/
#define CAN_IT_TME ((uint32_t)0x00000001) /*!< Transmit mailbox empty Interrupt*/
/* Receive Interrupts */
#define CAN_IT_FMP0 ((uint32_t)0x00000002) /*!< FIFO 0 message pending Interrupt*/
#define CAN_IT_FF0 ((uint32_t)0x00000004) /*!< FIFO 0 full Interrupt*/
#define CAN_IT_FOV0 ((uint32_t)0x00000008) /*!< FIFO 0 overrun Interrupt*/
#define CAN_IT_FMP1 ((uint32_t)0x00000010) /*!< FIFO 1 message pending Interrupt*/
#define CAN_IT_FF1 ((uint32_t)0x00000020) /*!< FIFO 1 full Interrupt*/
#define CAN_IT_FOV1 ((uint32_t)0x00000040) /*!< FIFO 1 overrun Interrupt*/
/* Operating Mode Interrupts */
#define CAN_IT_WKU ((uint32_t)0x00010000) /*!< Wake-up Interrupt*/
#define CAN_IT_SLK ((uint32_t)0x00020000) /*!< Sleep acknowledge Interrupt*/
/* Error Interrupts */
#define CAN_IT_EWG ((uint32_t)0x00000100) /*!< Error warning Interrupt*/
#define CAN_IT_EPV ((uint32_t)0x00000200) /*!< Error passive Interrupt*/
#define CAN_IT_BOF ((uint32_t)0x00000400) /*!< Bus-off Interrupt*/
#define CAN_IT_LEC ((uint32_t)0x00000800) /*!< Last error code Interrupt*/
#define CAN_IT_ERR ((uint32_t)0x00008000) /*!< Error Interrupt*/
/* Flags named as Interrupts : kept only for FW compatibility */
#define CAN_IT_RQCP0 CAN_IT_TME
#define CAN_IT_RQCP1 CAN_IT_TME
#define CAN_IT_RQCP2 CAN_IT_TME
#define IS_CAN_IT(IT) (((IT) == CAN_IT_TME) || ((IT) == CAN_IT_FMP0) ||\
((IT) == CAN_IT_FF0) || ((IT) == CAN_IT_FOV0) ||\
((IT) == CAN_IT_FMP1) || ((IT) == CAN_IT_FF1) ||\
((IT) == CAN_IT_FOV1) || ((IT) == CAN_IT_EWG) ||\
((IT) == CAN_IT_EPV) || ((IT) == CAN_IT_BOF) ||\
((IT) == CAN_IT_LEC) || ((IT) == CAN_IT_ERR) ||\
((IT) == CAN_IT_WKU) || ((IT) == CAN_IT_SLK))
#define IS_CAN_CLEAR_IT(IT) (((IT) == CAN_IT_TME) || ((IT) == CAN_IT_FF0) ||\
((IT) == CAN_IT_FOV0)|| ((IT) == CAN_IT_FF1) ||\
((IT) == CAN_IT_FOV1)|| ((IT) == CAN_IT_EWG) ||\
((IT) == CAN_IT_EPV) || ((IT) == CAN_IT_BOF) ||\
((IT) == CAN_IT_LEC) || ((IT) == CAN_IT_ERR) ||\
((IT) == CAN_IT_WKU) || ((IT) == CAN_IT_SLK))
/**
* @}
*/
/** @defgroup CAN_Legacy
* @{
*/
#define CANINITFAILED CAN_InitStatus_Failed
#define CANINITOK CAN_InitStatus_Success
#define CAN_FilterFIFO0 CAN_Filter_FIFO0
#define CAN_FilterFIFO1 CAN_Filter_FIFO1
#define CAN_ID_STD CAN_Id_Standard
#define CAN_ID_EXT CAN_Id_Extended
#define CAN_RTR_DATA CAN_RTR_Data
#define CAN_RTR_REMOTE CAN_RTR_Remote
#define CANTXFAILE CAN_TxStatus_Failed
#define CANTXOK CAN_TxStatus_Ok
#define CANTXPENDING CAN_TxStatus_Pending
#define CAN_NO_MB CAN_TxStatus_NoMailBox
#define CANSLEEPFAILED CAN_Sleep_Failed
#define CANSLEEPOK CAN_Sleep_Ok
#define CANWAKEUPFAILED CAN_WakeUp_Failed
#define CANWAKEUPOK CAN_WakeUp_Ok
/**
* @}
*/
/**
* @}
*/
/** @defgroup CAN_Exported_Macros
* @{
*/
/**
* @}
*/
/** @defgroup CAN_Exported_Functions
* @{
*/
/* Function used to set the CAN configuration to the default reset state *****/
void CAN_DeInit(CAN_TypeDef* CANx);
/* Initialization and Configuration functions *********************************/
uint8_t CAN_Init(CAN_TypeDef* CANx, CAN_InitTypeDef* CAN_InitStruct);
void CAN_FilterInit(CAN_FilterInitTypeDef* CAN_FilterInitStruct);
void CAN_StructInit(CAN_InitTypeDef* CAN_InitStruct);
void CAN_SlaveStartBank(uint8_t CAN_BankNumber);
void CAN_DBGFreeze(CAN_TypeDef* CANx, FunctionalState NewState);
void CAN_TTComModeCmd(CAN_TypeDef* CANx, FunctionalState NewState);
/* Transmit functions *********************************************************/
uint8_t CAN_Transmit(CAN_TypeDef* CANx, CanTxMsg* TxMessage);
uint8_t CAN_TransmitStatus(CAN_TypeDef* CANx, uint8_t TransmitMailbox);
void CAN_CancelTransmit(CAN_TypeDef* CANx, uint8_t Mailbox);
/* Receive functions **********************************************************/
void CAN_Receive(CAN_TypeDef* CANx, uint8_t FIFONumber, CanRxMsg* RxMessage);
void CAN_FIFORelease(CAN_TypeDef* CANx, uint8_t FIFONumber);
uint8_t CAN_MessagePending(CAN_TypeDef* CANx, uint8_t FIFONumber);
/* Operation modes functions **************************************************/
uint8_t CAN_OperatingModeRequest(CAN_TypeDef* CANx, uint8_t CAN_OperatingMode);
uint8_t CAN_Sleep(CAN_TypeDef* CANx);
uint8_t CAN_WakeUp(CAN_TypeDef* CANx);
/* Error management functions *************************************************/
uint8_t CAN_GetLastErrorCode(CAN_TypeDef* CANx);
uint8_t CAN_GetReceiveErrorCounter(CAN_TypeDef* CANx);
uint8_t CAN_GetLSBTransmitErrorCounter(CAN_TypeDef* CANx);
/* Interrupts and flags management functions **********************************/
void CAN_ITConfig(CAN_TypeDef* CANx, uint32_t CAN_IT, FunctionalState NewState);
FlagStatus CAN_GetFlagStatus(CAN_TypeDef* CANx, uint32_t CAN_FLAG);
void CAN_ClearFlag(CAN_TypeDef* CANx, uint32_t CAN_FLAG);
ITStatus CAN_GetITStatus(CAN_TypeDef* CANx, uint32_t CAN_IT);
void CAN_ClearITPendingBit(CAN_TypeDef* CANx, uint32_t CAN_IT);
#ifdef __cplusplus
}
#endif
#endif /* __STM32F10x_CAN_H */
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/

View File

@ -1,210 +0,0 @@
/**
******************************************************************************
* @file stm32f10x_cec.h
* @author MCD Application Team
* @version V3.5.0
* @date 11-March-2011
* @brief This file contains all the functions prototypes for the CEC firmware
* library.
******************************************************************************
* @attention
*
* 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, STMICROELECTRONICS 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 2011 STMicroelectronics</center></h2>
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32F10x_CEC_H
#define __STM32F10x_CEC_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32f10x.h"
/** @addtogroup STM32F10x_StdPeriph_Driver
* @{
*/
/** @addtogroup CEC
* @{
*/
/** @defgroup CEC_Exported_Types
* @{
*/
/**
* @brief CEC Init structure definition
*/
typedef struct
{
uint16_t CEC_BitTimingMode; /*!< Configures the CEC Bit Timing Error Mode.
This parameter can be a value of @ref CEC_BitTiming_Mode */
uint16_t CEC_BitPeriodMode; /*!< Configures the CEC Bit Period Error Mode.
This parameter can be a value of @ref CEC_BitPeriod_Mode */
}CEC_InitTypeDef;
/**
* @}
*/
/** @defgroup CEC_Exported_Constants
* @{
*/
/** @defgroup CEC_BitTiming_Mode
* @{
*/
#define CEC_BitTimingStdMode ((uint16_t)0x00) /*!< Bit timing error Standard Mode */
#define CEC_BitTimingErrFreeMode CEC_CFGR_BTEM /*!< Bit timing error Free Mode */
#define IS_CEC_BIT_TIMING_ERROR_MODE(MODE) (((MODE) == CEC_BitTimingStdMode) || \
((MODE) == CEC_BitTimingErrFreeMode))
/**
* @}
*/
/** @defgroup CEC_BitPeriod_Mode
* @{
*/
#define CEC_BitPeriodStdMode ((uint16_t)0x00) /*!< Bit period error Standard Mode */
#define CEC_BitPeriodFlexibleMode CEC_CFGR_BPEM /*!< Bit period error Flexible Mode */
#define IS_CEC_BIT_PERIOD_ERROR_MODE(MODE) (((MODE) == CEC_BitPeriodStdMode) || \
((MODE) == CEC_BitPeriodFlexibleMode))
/**
* @}
*/
/** @defgroup CEC_interrupts_definition
* @{
*/
#define CEC_IT_TERR CEC_CSR_TERR
#define CEC_IT_TBTRF CEC_CSR_TBTRF
#define CEC_IT_RERR CEC_CSR_RERR
#define CEC_IT_RBTF CEC_CSR_RBTF
#define IS_CEC_GET_IT(IT) (((IT) == CEC_IT_TERR) || ((IT) == CEC_IT_TBTRF) || \
((IT) == CEC_IT_RERR) || ((IT) == CEC_IT_RBTF))
/**
* @}
*/
/** @defgroup CEC_Own_Address
* @{
*/
#define IS_CEC_ADDRESS(ADDRESS) ((ADDRESS) < 0x10)
/**
* @}
*/
/** @defgroup CEC_Prescaler
* @{
*/
#define IS_CEC_PRESCALER(PRESCALER) ((PRESCALER) <= 0x3FFF)
/**
* @}
*/
/** @defgroup CEC_flags_definition
* @{
*/
/**
* @brief ESR register flags
*/
#define CEC_FLAG_BTE ((uint32_t)0x10010000)
#define CEC_FLAG_BPE ((uint32_t)0x10020000)
#define CEC_FLAG_RBTFE ((uint32_t)0x10040000)
#define CEC_FLAG_SBE ((uint32_t)0x10080000)
#define CEC_FLAG_ACKE ((uint32_t)0x10100000)
#define CEC_FLAG_LINE ((uint32_t)0x10200000)
#define CEC_FLAG_TBTFE ((uint32_t)0x10400000)
/**
* @brief CSR register flags
*/
#define CEC_FLAG_TEOM ((uint32_t)0x00000002)
#define CEC_FLAG_TERR ((uint32_t)0x00000004)
#define CEC_FLAG_TBTRF ((uint32_t)0x00000008)
#define CEC_FLAG_RSOM ((uint32_t)0x00000010)
#define CEC_FLAG_REOM ((uint32_t)0x00000020)
#define CEC_FLAG_RERR ((uint32_t)0x00000040)
#define CEC_FLAG_RBTF ((uint32_t)0x00000080)
#define IS_CEC_CLEAR_FLAG(FLAG) ((((FLAG) & (uint32_t)0xFFFFFF03) == 0x00) && ((FLAG) != 0x00))
#define IS_CEC_GET_FLAG(FLAG) (((FLAG) == CEC_FLAG_BTE) || ((FLAG) == CEC_FLAG_BPE) || \
((FLAG) == CEC_FLAG_RBTFE) || ((FLAG)== CEC_FLAG_SBE) || \
((FLAG) == CEC_FLAG_ACKE) || ((FLAG) == CEC_FLAG_LINE) || \
((FLAG) == CEC_FLAG_TBTFE) || ((FLAG) == CEC_FLAG_TEOM) || \
((FLAG) == CEC_FLAG_TERR) || ((FLAG) == CEC_FLAG_TBTRF) || \
((FLAG) == CEC_FLAG_RSOM) || ((FLAG) == CEC_FLAG_REOM) || \
((FLAG) == CEC_FLAG_RERR) || ((FLAG) == CEC_FLAG_RBTF))
/**
* @}
*/
/**
* @}
*/
/** @defgroup CEC_Exported_Macros
* @{
*/
/**
* @}
*/
/** @defgroup CEC_Exported_Functions
* @{
*/
void CEC_DeInit(void);
void CEC_Init(CEC_InitTypeDef* CEC_InitStruct);
void CEC_Cmd(FunctionalState NewState);
void CEC_ITConfig(FunctionalState NewState);
void CEC_OwnAddressConfig(uint8_t CEC_OwnAddress);
void CEC_SetPrescaler(uint16_t CEC_Prescaler);
void CEC_SendDataByte(uint8_t Data);
uint8_t CEC_ReceiveDataByte(void);
void CEC_StartOfMessage(void);
void CEC_EndOfMessageCmd(FunctionalState NewState);
FlagStatus CEC_GetFlagStatus(uint32_t CEC_FLAG);
void CEC_ClearFlag(uint32_t CEC_FLAG);
ITStatus CEC_GetITStatus(uint8_t CEC_IT);
void CEC_ClearITPendingBit(uint16_t CEC_IT);
#ifdef __cplusplus
}
#endif
#endif /* __STM32F10x_CEC_H */
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/

View File

@ -1,94 +0,0 @@
/**
******************************************************************************
* @file stm32f10x_crc.h
* @author MCD Application Team
* @version V3.5.0
* @date 11-March-2011
* @brief This file contains all the functions prototypes for the CRC firmware
* library.
******************************************************************************
* @attention
*
* 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, STMICROELECTRONICS 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 2011 STMicroelectronics</center></h2>
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32F10x_CRC_H
#define __STM32F10x_CRC_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32f10x.h"
/** @addtogroup STM32F10x_StdPeriph_Driver
* @{
*/
/** @addtogroup CRC
* @{
*/
/** @defgroup CRC_Exported_Types
* @{
*/
/**
* @}
*/
/** @defgroup CRC_Exported_Constants
* @{
*/
/**
* @}
*/
/** @defgroup CRC_Exported_Macros
* @{
*/
/**
* @}
*/
/** @defgroup CRC_Exported_Functions
* @{
*/
void CRC_ResetDR(void);
uint32_t CRC_CalcCRC(uint32_t Data);
uint32_t CRC_CalcBlockCRC(uint32_t pBuffer[], uint32_t BufferLength);
uint32_t CRC_GetCRC(void);
void CRC_SetIDRegister(uint8_t IDValue);
uint8_t CRC_GetIDRegister(void);
#ifdef __cplusplus
}
#endif
#endif /* __STM32F10x_CRC_H */
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/

View File

@ -1,317 +0,0 @@
/**
******************************************************************************
* @file stm32f10x_dac.h
* @author MCD Application Team
* @version V3.5.0
* @date 11-March-2011
* @brief This file contains all the functions prototypes for the DAC firmware
* library.
******************************************************************************
* @attention
*
* 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, STMICROELECTRONICS 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 2011 STMicroelectronics</center></h2>
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32F10x_DAC_H
#define __STM32F10x_DAC_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32f10x.h"
/** @addtogroup STM32F10x_StdPeriph_Driver
* @{
*/
/** @addtogroup DAC
* @{
*/
/** @defgroup DAC_Exported_Types
* @{
*/
/**
* @brief DAC Init structure definition
*/
typedef struct
{
uint32_t DAC_Trigger; /*!< Specifies the external trigger for the selected DAC channel.
This parameter can be a value of @ref DAC_trigger_selection */
uint32_t DAC_WaveGeneration; /*!< Specifies whether DAC channel noise waves or triangle waves
are generated, or whether no wave is generated.
This parameter can be a value of @ref DAC_wave_generation */
uint32_t DAC_LFSRUnmask_TriangleAmplitude; /*!< Specifies the LFSR mask for noise wave generation or
the maximum amplitude triangle generation for the DAC channel.
This parameter can be a value of @ref DAC_lfsrunmask_triangleamplitude */
uint32_t DAC_OutputBuffer; /*!< Specifies whether the DAC channel output buffer is enabled or disabled.
This parameter can be a value of @ref DAC_output_buffer */
}DAC_InitTypeDef;
/**
* @}
*/
/** @defgroup DAC_Exported_Constants
* @{
*/
/** @defgroup DAC_trigger_selection
* @{
*/
#define DAC_Trigger_None ((uint32_t)0x00000000) /*!< Conversion is automatic once the DAC1_DHRxxxx register
has been loaded, and not by external trigger */
#define DAC_Trigger_T6_TRGO ((uint32_t)0x00000004) /*!< TIM6 TRGO selected as external conversion trigger for DAC channel */
#define DAC_Trigger_T8_TRGO ((uint32_t)0x0000000C) /*!< TIM8 TRGO selected as external conversion trigger for DAC channel
only in High-density devices*/
#define DAC_Trigger_T3_TRGO ((uint32_t)0x0000000C) /*!< TIM8 TRGO selected as external conversion trigger for DAC channel
only in Connectivity line, Medium-density and Low-density Value Line devices */
#define DAC_Trigger_T7_TRGO ((uint32_t)0x00000014) /*!< TIM7 TRGO selected as external conversion trigger for DAC channel */
#define DAC_Trigger_T5_TRGO ((uint32_t)0x0000001C) /*!< TIM5 TRGO selected as external conversion trigger for DAC channel */
#define DAC_Trigger_T15_TRGO ((uint32_t)0x0000001C) /*!< TIM15 TRGO selected as external conversion trigger for DAC channel
only in Medium-density and Low-density Value Line devices*/
#define DAC_Trigger_T2_TRGO ((uint32_t)0x00000024) /*!< TIM2 TRGO selected as external conversion trigger for DAC channel */
#define DAC_Trigger_T4_TRGO ((uint32_t)0x0000002C) /*!< TIM4 TRGO selected as external conversion trigger for DAC channel */
#define DAC_Trigger_Ext_IT9 ((uint32_t)0x00000034) /*!< EXTI Line9 event selected as external conversion trigger for DAC channel */
#define DAC_Trigger_Software ((uint32_t)0x0000003C) /*!< Conversion started by software trigger for DAC channel */
#define IS_DAC_TRIGGER(TRIGGER) (((TRIGGER) == DAC_Trigger_None) || \
((TRIGGER) == DAC_Trigger_T6_TRGO) || \
((TRIGGER) == DAC_Trigger_T8_TRGO) || \
((TRIGGER) == DAC_Trigger_T7_TRGO) || \
((TRIGGER) == DAC_Trigger_T5_TRGO) || \
((TRIGGER) == DAC_Trigger_T2_TRGO) || \
((TRIGGER) == DAC_Trigger_T4_TRGO) || \
((TRIGGER) == DAC_Trigger_Ext_IT9) || \
((TRIGGER) == DAC_Trigger_Software))
/**
* @}
*/
/** @defgroup DAC_wave_generation
* @{
*/
#define DAC_WaveGeneration_None ((uint32_t)0x00000000)
#define DAC_WaveGeneration_Noise ((uint32_t)0x00000040)
#define DAC_WaveGeneration_Triangle ((uint32_t)0x00000080)
#define IS_DAC_GENERATE_WAVE(WAVE) (((WAVE) == DAC_WaveGeneration_None) || \
((WAVE) == DAC_WaveGeneration_Noise) || \
((WAVE) == DAC_WaveGeneration_Triangle))
/**
* @}
*/
/** @defgroup DAC_lfsrunmask_triangleamplitude
* @{
*/
#define DAC_LFSRUnmask_Bit0 ((uint32_t)0x00000000) /*!< Unmask DAC channel LFSR bit0 for noise wave generation */
#define DAC_LFSRUnmask_Bits1_0 ((uint32_t)0x00000100) /*!< Unmask DAC channel LFSR bit[1:0] for noise wave generation */
#define DAC_LFSRUnmask_Bits2_0 ((uint32_t)0x00000200) /*!< Unmask DAC channel LFSR bit[2:0] for noise wave generation */
#define DAC_LFSRUnmask_Bits3_0 ((uint32_t)0x00000300) /*!< Unmask DAC channel LFSR bit[3:0] for noise wave generation */
#define DAC_LFSRUnmask_Bits4_0 ((uint32_t)0x00000400) /*!< Unmask DAC channel LFSR bit[4:0] for noise wave generation */
#define DAC_LFSRUnmask_Bits5_0 ((uint32_t)0x00000500) /*!< Unmask DAC channel LFSR bit[5:0] for noise wave generation */
#define DAC_LFSRUnmask_Bits6_0 ((uint32_t)0x00000600) /*!< Unmask DAC channel LFSR bit[6:0] for noise wave generation */
#define DAC_LFSRUnmask_Bits7_0 ((uint32_t)0x00000700) /*!< Unmask DAC channel LFSR bit[7:0] for noise wave generation */
#define DAC_LFSRUnmask_Bits8_0 ((uint32_t)0x00000800) /*!< Unmask DAC channel LFSR bit[8:0] for noise wave generation */
#define DAC_LFSRUnmask_Bits9_0 ((uint32_t)0x00000900) /*!< Unmask DAC channel LFSR bit[9:0] for noise wave generation */
#define DAC_LFSRUnmask_Bits10_0 ((uint32_t)0x00000A00) /*!< Unmask DAC channel LFSR bit[10:0] for noise wave generation */
#define DAC_LFSRUnmask_Bits11_0 ((uint32_t)0x00000B00) /*!< Unmask DAC channel LFSR bit[11:0] for noise wave generation */
#define DAC_TriangleAmplitude_1 ((uint32_t)0x00000000) /*!< Select max triangle amplitude of 1 */
#define DAC_TriangleAmplitude_3 ((uint32_t)0x00000100) /*!< Select max triangle amplitude of 3 */
#define DAC_TriangleAmplitude_7 ((uint32_t)0x00000200) /*!< Select max triangle amplitude of 7 */
#define DAC_TriangleAmplitude_15 ((uint32_t)0x00000300) /*!< Select max triangle amplitude of 15 */
#define DAC_TriangleAmplitude_31 ((uint32_t)0x00000400) /*!< Select max triangle amplitude of 31 */
#define DAC_TriangleAmplitude_63 ((uint32_t)0x00000500) /*!< Select max triangle amplitude of 63 */
#define DAC_TriangleAmplitude_127 ((uint32_t)0x00000600) /*!< Select max triangle amplitude of 127 */
#define DAC_TriangleAmplitude_255 ((uint32_t)0x00000700) /*!< Select max triangle amplitude of 255 */
#define DAC_TriangleAmplitude_511 ((uint32_t)0x00000800) /*!< Select max triangle amplitude of 511 */
#define DAC_TriangleAmplitude_1023 ((uint32_t)0x00000900) /*!< Select max triangle amplitude of 1023 */
#define DAC_TriangleAmplitude_2047 ((uint32_t)0x00000A00) /*!< Select max triangle amplitude of 2047 */
#define DAC_TriangleAmplitude_4095 ((uint32_t)0x00000B00) /*!< Select max triangle amplitude of 4095 */
#define IS_DAC_LFSR_UNMASK_TRIANGLE_AMPLITUDE(VALUE) (((VALUE) == DAC_LFSRUnmask_Bit0) || \
((VALUE) == DAC_LFSRUnmask_Bits1_0) || \
((VALUE) == DAC_LFSRUnmask_Bits2_0) || \
((VALUE) == DAC_LFSRUnmask_Bits3_0) || \
((VALUE) == DAC_LFSRUnmask_Bits4_0) || \
((VALUE) == DAC_LFSRUnmask_Bits5_0) || \
((VALUE) == DAC_LFSRUnmask_Bits6_0) || \
((VALUE) == DAC_LFSRUnmask_Bits7_0) || \
((VALUE) == DAC_LFSRUnmask_Bits8_0) || \
((VALUE) == DAC_LFSRUnmask_Bits9_0) || \
((VALUE) == DAC_LFSRUnmask_Bits10_0) || \
((VALUE) == DAC_LFSRUnmask_Bits11_0) || \
((VALUE) == DAC_TriangleAmplitude_1) || \
((VALUE) == DAC_TriangleAmplitude_3) || \
((VALUE) == DAC_TriangleAmplitude_7) || \
((VALUE) == DAC_TriangleAmplitude_15) || \
((VALUE) == DAC_TriangleAmplitude_31) || \
((VALUE) == DAC_TriangleAmplitude_63) || \
((VALUE) == DAC_TriangleAmplitude_127) || \
((VALUE) == DAC_TriangleAmplitude_255) || \
((VALUE) == DAC_TriangleAmplitude_511) || \
((VALUE) == DAC_TriangleAmplitude_1023) || \
((VALUE) == DAC_TriangleAmplitude_2047) || \
((VALUE) == DAC_TriangleAmplitude_4095))
/**
* @}
*/
/** @defgroup DAC_output_buffer
* @{
*/
#define DAC_OutputBuffer_Enable ((uint32_t)0x00000000)
#define DAC_OutputBuffer_Disable ((uint32_t)0x00000002)
#define IS_DAC_OUTPUT_BUFFER_STATE(STATE) (((STATE) == DAC_OutputBuffer_Enable) || \
((STATE) == DAC_OutputBuffer_Disable))
/**
* @}
*/
/** @defgroup DAC_Channel_selection
* @{
*/
#define DAC_Channel_1 ((uint32_t)0x00000000)
#define DAC_Channel_2 ((uint32_t)0x00000010)
#define IS_DAC_CHANNEL(CHANNEL) (((CHANNEL) == DAC_Channel_1) || \
((CHANNEL) == DAC_Channel_2))
/**
* @}
*/
/** @defgroup DAC_data_alignment
* @{
*/
#define DAC_Align_12b_R ((uint32_t)0x00000000)
#define DAC_Align_12b_L ((uint32_t)0x00000004)
#define DAC_Align_8b_R ((uint32_t)0x00000008)
#define IS_DAC_ALIGN(ALIGN) (((ALIGN) == DAC_Align_12b_R) || \
((ALIGN) == DAC_Align_12b_L) || \
((ALIGN) == DAC_Align_8b_R))
/**
* @}
*/
/** @defgroup DAC_wave_generation
* @{
*/
#define DAC_Wave_Noise ((uint32_t)0x00000040)
#define DAC_Wave_Triangle ((uint32_t)0x00000080)
#define IS_DAC_WAVE(WAVE) (((WAVE) == DAC_Wave_Noise) || \
((WAVE) == DAC_Wave_Triangle))
/**
* @}
*/
/** @defgroup DAC_data
* @{
*/
#define IS_DAC_DATA(DATA) ((DATA) <= 0xFFF0)
/**
* @}
*/
#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL)
/** @defgroup DAC_interrupts_definition
* @{
*/
#define DAC_IT_DMAUDR ((uint32_t)0x00002000)
#define IS_DAC_IT(IT) (((IT) == DAC_IT_DMAUDR))
/**
* @}
*/
/** @defgroup DAC_flags_definition
* @{
*/
#define DAC_FLAG_DMAUDR ((uint32_t)0x00002000)
#define IS_DAC_FLAG(FLAG) (((FLAG) == DAC_FLAG_DMAUDR))
/**
* @}
*/
#endif
/**
* @}
*/
/** @defgroup DAC_Exported_Macros
* @{
*/
/**
* @}
*/
/** @defgroup DAC_Exported_Functions
* @{
*/
void DAC_DeInit(void);
void DAC_Init(uint32_t DAC_Channel, DAC_InitTypeDef* DAC_InitStruct);
void DAC_StructInit(DAC_InitTypeDef* DAC_InitStruct);
void DAC_Cmd(uint32_t DAC_Channel, FunctionalState NewState);
#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL)
void DAC_ITConfig(uint32_t DAC_Channel, uint32_t DAC_IT, FunctionalState NewState);
#endif
void DAC_DMACmd(uint32_t DAC_Channel, FunctionalState NewState);
void DAC_SoftwareTriggerCmd(uint32_t DAC_Channel, FunctionalState NewState);
void DAC_DualSoftwareTriggerCmd(FunctionalState NewState);
void DAC_WaveGenerationCmd(uint32_t DAC_Channel, uint32_t DAC_Wave, FunctionalState NewState);
void DAC_SetChannel1Data(uint32_t DAC_Align, uint16_t Data);
void DAC_SetChannel2Data(uint32_t DAC_Align, uint16_t Data);
void DAC_SetDualChannelData(uint32_t DAC_Align, uint16_t Data2, uint16_t Data1);
uint16_t DAC_GetDataOutputValue(uint32_t DAC_Channel);
#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL)
FlagStatus DAC_GetFlagStatus(uint32_t DAC_Channel, uint32_t DAC_FLAG);
void DAC_ClearFlag(uint32_t DAC_Channel, uint32_t DAC_FLAG);
ITStatus DAC_GetITStatus(uint32_t DAC_Channel, uint32_t DAC_IT);
void DAC_ClearITPendingBit(uint32_t DAC_Channel, uint32_t DAC_IT);
#endif
#ifdef __cplusplus
}
#endif
#endif /*__STM32F10x_DAC_H */
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/

View File

@ -1,119 +0,0 @@
/**
******************************************************************************
* @file stm32f10x_dbgmcu.h
* @author MCD Application Team
* @version V3.5.0
* @date 11-March-2011
* @brief This file contains all the functions prototypes for the DBGMCU
* firmware library.
******************************************************************************
* @attention
*
* 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, STMICROELECTRONICS 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 2011 STMicroelectronics</center></h2>
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32F10x_DBGMCU_H
#define __STM32F10x_DBGMCU_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32f10x.h"
/** @addtogroup STM32F10x_StdPeriph_Driver
* @{
*/
/** @addtogroup DBGMCU
* @{
*/
/** @defgroup DBGMCU_Exported_Types
* @{
*/
/**
* @}
*/
/** @defgroup DBGMCU_Exported_Constants
* @{
*/
#define DBGMCU_SLEEP ((uint32_t)0x00000001)
#define DBGMCU_STOP ((uint32_t)0x00000002)
#define DBGMCU_STANDBY ((uint32_t)0x00000004)
#define DBGMCU_IWDG_STOP ((uint32_t)0x00000100)
#define DBGMCU_WWDG_STOP ((uint32_t)0x00000200)
#define DBGMCU_TIM1_STOP ((uint32_t)0x00000400)
#define DBGMCU_TIM2_STOP ((uint32_t)0x00000800)
#define DBGMCU_TIM3_STOP ((uint32_t)0x00001000)
#define DBGMCU_TIM4_STOP ((uint32_t)0x00002000)
#define DBGMCU_CAN1_STOP ((uint32_t)0x00004000)
#define DBGMCU_I2C1_SMBUS_TIMEOUT ((uint32_t)0x00008000)
#define DBGMCU_I2C2_SMBUS_TIMEOUT ((uint32_t)0x00010000)
#define DBGMCU_TIM8_STOP ((uint32_t)0x00020000)
#define DBGMCU_TIM5_STOP ((uint32_t)0x00040000)
#define DBGMCU_TIM6_STOP ((uint32_t)0x00080000)
#define DBGMCU_TIM7_STOP ((uint32_t)0x00100000)
#define DBGMCU_CAN2_STOP ((uint32_t)0x00200000)
#define DBGMCU_TIM15_STOP ((uint32_t)0x00400000)
#define DBGMCU_TIM16_STOP ((uint32_t)0x00800000)
#define DBGMCU_TIM17_STOP ((uint32_t)0x01000000)
#define DBGMCU_TIM12_STOP ((uint32_t)0x02000000)
#define DBGMCU_TIM13_STOP ((uint32_t)0x04000000)
#define DBGMCU_TIM14_STOP ((uint32_t)0x08000000)
#define DBGMCU_TIM9_STOP ((uint32_t)0x10000000)
#define DBGMCU_TIM10_STOP ((uint32_t)0x20000000)
#define DBGMCU_TIM11_STOP ((uint32_t)0x40000000)
#define IS_DBGMCU_PERIPH(PERIPH) ((((PERIPH) & 0x800000F8) == 0x00) && ((PERIPH) != 0x00))
/**
* @}
*/
/** @defgroup DBGMCU_Exported_Macros
* @{
*/
/**
* @}
*/
/** @defgroup DBGMCU_Exported_Functions
* @{
*/
uint32_t DBGMCU_GetREVID(void);
uint32_t DBGMCU_GetDEVID(void);
void DBGMCU_Config(uint32_t DBGMCU_Periph, FunctionalState NewState);
#ifdef __cplusplus
}
#endif
#endif /* __STM32F10x_DBGMCU_H */
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/

View File

@ -1,439 +0,0 @@
/**
******************************************************************************
* @file stm32f10x_dma.h
* @author MCD Application Team
* @version V3.5.0
* @date 11-March-2011
* @brief This file contains all the functions prototypes for the DMA firmware
* library.
******************************************************************************
* @attention
*
* 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, STMICROELECTRONICS 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 2011 STMicroelectronics</center></h2>
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32F10x_DMA_H
#define __STM32F10x_DMA_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32f10x.h"
/** @addtogroup STM32F10x_StdPeriph_Driver
* @{
*/
/** @addtogroup DMA
* @{
*/
/** @defgroup DMA_Exported_Types
* @{
*/
/**
* @brief DMA Init structure definition
*/
typedef struct
{
uint32_t DMA_PeripheralBaseAddr; /*!< Specifies the peripheral base address for DMAy Channelx. */
uint32_t DMA_MemoryBaseAddr; /*!< Specifies the memory base address for DMAy Channelx. */
uint32_t DMA_DIR; /*!< Specifies if the peripheral is the source or destination.
This parameter can be a value of @ref DMA_data_transfer_direction */
uint32_t DMA_BufferSize; /*!< Specifies the buffer size, in data unit, of the specified Channel.
The data unit is equal to the configuration set in DMA_PeripheralDataSize
or DMA_MemoryDataSize members depending in the transfer direction. */
uint32_t DMA_PeripheralInc; /*!< Specifies whether the Peripheral address register is incremented or not.
This parameter can be a value of @ref DMA_peripheral_incremented_mode */
uint32_t DMA_MemoryInc; /*!< Specifies whether the memory address register is incremented or not.
This parameter can be a value of @ref DMA_memory_incremented_mode */
uint32_t DMA_PeripheralDataSize; /*!< Specifies the Peripheral data width.
This parameter can be a value of @ref DMA_peripheral_data_size */
uint32_t DMA_MemoryDataSize; /*!< Specifies the Memory data width.
This parameter can be a value of @ref DMA_memory_data_size */
uint32_t DMA_Mode; /*!< Specifies the operation mode of the DMAy Channelx.
This parameter can be a value of @ref DMA_circular_normal_mode.
@note: The circular buffer mode cannot be used if the memory-to-memory
data transfer is configured on the selected Channel */
uint32_t DMA_Priority; /*!< Specifies the software priority for the DMAy Channelx.
This parameter can be a value of @ref DMA_priority_level */
uint32_t DMA_M2M; /*!< Specifies if the DMAy Channelx will be used in memory-to-memory transfer.
This parameter can be a value of @ref DMA_memory_to_memory */
}DMA_InitTypeDef;
/**
* @}
*/
/** @defgroup DMA_Exported_Constants
* @{
*/
#define IS_DMA_ALL_PERIPH(PERIPH) (((PERIPH) == DMA1_Channel1) || \
((PERIPH) == DMA1_Channel2) || \
((PERIPH) == DMA1_Channel3) || \
((PERIPH) == DMA1_Channel4) || \
((PERIPH) == DMA1_Channel5) || \
((PERIPH) == DMA1_Channel6) || \
((PERIPH) == DMA1_Channel7) || \
((PERIPH) == DMA2_Channel1) || \
((PERIPH) == DMA2_Channel2) || \
((PERIPH) == DMA2_Channel3) || \
((PERIPH) == DMA2_Channel4) || \
((PERIPH) == DMA2_Channel5))
/** @defgroup DMA_data_transfer_direction
* @{
*/
#define DMA_DIR_PeripheralDST ((uint32_t)0x00000010)
#define DMA_DIR_PeripheralSRC ((uint32_t)0x00000000)
#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))
#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 DMA1_IT_GL6 ((uint32_t)0x00100000)
#define DMA1_IT_TC6 ((uint32_t)0x00200000)
#define DMA1_IT_HT6 ((uint32_t)0x00400000)
#define DMA1_IT_TE6 ((uint32_t)0x00800000)
#define DMA1_IT_GL7 ((uint32_t)0x01000000)
#define DMA1_IT_TC7 ((uint32_t)0x02000000)
#define DMA1_IT_HT7 ((uint32_t)0x04000000)
#define DMA1_IT_TE7 ((uint32_t)0x08000000)
#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 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) || \
((IT) == DMA1_IT_GL6) || ((IT) == DMA1_IT_TC6) || \
((IT) == DMA1_IT_HT6) || ((IT) == DMA1_IT_TE6) || \
((IT) == DMA1_IT_GL7) || ((IT) == DMA1_IT_TC7) || \
((IT) == DMA1_IT_HT7) || ((IT) == DMA1_IT_TE7) || \
((IT) == DMA2_IT_GL1) || ((IT) == DMA2_IT_TC1) || \
((IT) == DMA2_IT_HT1) || ((IT) == DMA2_IT_TE1) || \
((IT) == DMA2_IT_GL2) || ((IT) == DMA2_IT_TC2) || \
((IT) == DMA2_IT_HT2) || ((IT) == DMA2_IT_TE2) || \
((IT) == DMA2_IT_GL3) || ((IT) == DMA2_IT_TC3) || \
((IT) == DMA2_IT_HT3) || ((IT) == DMA2_IT_TE3) || \
((IT) == DMA2_IT_GL4) || ((IT) == DMA2_IT_TC4) || \
((IT) == DMA2_IT_HT4) || ((IT) == DMA2_IT_TE4) || \
((IT) == DMA2_IT_GL5) || ((IT) == DMA2_IT_TC5) || \
((IT) == DMA2_IT_HT5) || ((IT) == DMA2_IT_TE5))
/**
* @}
*/
/** @defgroup DMA_flags_definition
* @{
*/
#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 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 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) || \
((FLAG) == DMA1_FLAG_GL6) || ((FLAG) == DMA1_FLAG_TC6) || \
((FLAG) == DMA1_FLAG_HT6) || ((FLAG) == DMA1_FLAG_TE6) || \
((FLAG) == DMA1_FLAG_GL7) || ((FLAG) == DMA1_FLAG_TC7) || \
((FLAG) == DMA1_FLAG_HT7) || ((FLAG) == DMA1_FLAG_TE7) || \
((FLAG) == DMA2_FLAG_GL1) || ((FLAG) == DMA2_FLAG_TC1) || \
((FLAG) == DMA2_FLAG_HT1) || ((FLAG) == DMA2_FLAG_TE1) || \
((FLAG) == DMA2_FLAG_GL2) || ((FLAG) == DMA2_FLAG_TC2) || \
((FLAG) == DMA2_FLAG_HT2) || ((FLAG) == DMA2_FLAG_TE2) || \
((FLAG) == DMA2_FLAG_GL3) || ((FLAG) == DMA2_FLAG_TC3) || \
((FLAG) == DMA2_FLAG_HT3) || ((FLAG) == DMA2_FLAG_TE3) || \
((FLAG) == DMA2_FLAG_GL4) || ((FLAG) == DMA2_FLAG_TC4) || \
((FLAG) == DMA2_FLAG_HT4) || ((FLAG) == DMA2_FLAG_TE4) || \
((FLAG) == DMA2_FLAG_GL5) || ((FLAG) == DMA2_FLAG_TC5) || \
((FLAG) == DMA2_FLAG_HT5) || ((FLAG) == DMA2_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);
void DMA_SetCurrDataCounter(DMA_Channel_TypeDef* DMAy_Channelx, uint16_t DataNumber);
uint16_t DMA_GetCurrDataCounter(DMA_Channel_TypeDef* DMAy_Channelx);
FlagStatus DMA_GetFlagStatus(uint32_t DMAy_FLAG);
void DMA_ClearFlag(uint32_t DMAy_FLAG);
ITStatus DMA_GetITStatus(uint32_t DMAy_IT);
void DMA_ClearITPendingBit(uint32_t DMAy_IT);
#ifdef __cplusplus
}
#endif
#endif /*__STM32F10x_DMA_H */
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/

View File

@ -1,184 +0,0 @@
/**
******************************************************************************
* @file stm32f10x_exti.h
* @author MCD Application Team
* @version V3.5.0
* @date 11-March-2011
* @brief This file contains all the functions prototypes for the EXTI firmware
* library.
******************************************************************************
* @attention
*
* 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, STMICROELECTRONICS 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 2011 STMicroelectronics</center></h2>
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32F10x_EXTI_H
#define __STM32F10x_EXTI_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32f10x.h"
/** @addtogroup STM32F10x_StdPeriph_Driver
* @{
*/
/** @addtogroup EXTI
* @{
*/
/** @defgroup EXTI_Exported_Types
* @{
*/
/**
* @brief EXTI mode enumeration
*/
typedef enum
{
EXTI_Mode_Interrupt = 0x00,
EXTI_Mode_Event = 0x04
}EXTIMode_TypeDef;
#define IS_EXTI_MODE(MODE) (((MODE) == EXTI_Mode_Interrupt) || ((MODE) == EXTI_Mode_Event))
/**
* @brief EXTI Trigger enumeration
*/
typedef enum
{
EXTI_Trigger_Rising = 0x08,
EXTI_Trigger_Falling = 0x0C,
EXTI_Trigger_Rising_Falling = 0x10
}EXTITrigger_TypeDef;
#define IS_EXTI_TRIGGER(TRIGGER) (((TRIGGER) == EXTI_Trigger_Rising) || \
((TRIGGER) == EXTI_Trigger_Falling) || \
((TRIGGER) == EXTI_Trigger_Rising_Falling))
/**
* @brief EXTI Init Structure definition
*/
typedef struct
{
uint32_t EXTI_Line; /*!< Specifies the EXTI lines to be enabled or disabled.
This parameter can be any combination of @ref EXTI_Lines */
EXTIMode_TypeDef EXTI_Mode; /*!< Specifies the mode for the EXTI lines.
This parameter can be a value of @ref EXTIMode_TypeDef */
EXTITrigger_TypeDef EXTI_Trigger; /*!< Specifies the trigger signal active edge for the EXTI lines.
This parameter can be a value of @ref EXTIMode_TypeDef */
FunctionalState EXTI_LineCmd; /*!< Specifies the new state of the selected EXTI lines.
This parameter can be set either to ENABLE or DISABLE */
}EXTI_InitTypeDef;
/**
* @}
*/
/** @defgroup EXTI_Exported_Constants
* @{
*/
/** @defgroup EXTI_Lines
* @{
*/
#define EXTI_Line0 ((uint32_t)0x00001) /*!< External interrupt line 0 */
#define EXTI_Line1 ((uint32_t)0x00002) /*!< External interrupt line 1 */
#define EXTI_Line2 ((uint32_t)0x00004) /*!< External interrupt line 2 */
#define EXTI_Line3 ((uint32_t)0x00008) /*!< External interrupt line 3 */
#define EXTI_Line4 ((uint32_t)0x00010) /*!< External interrupt line 4 */
#define EXTI_Line5 ((uint32_t)0x00020) /*!< External interrupt line 5 */
#define EXTI_Line6 ((uint32_t)0x00040) /*!< External interrupt line 6 */
#define EXTI_Line7 ((uint32_t)0x00080) /*!< External interrupt line 7 */
#define EXTI_Line8 ((uint32_t)0x00100) /*!< External interrupt line 8 */
#define EXTI_Line9 ((uint32_t)0x00200) /*!< External interrupt line 9 */
#define EXTI_Line10 ((uint32_t)0x00400) /*!< External interrupt line 10 */
#define EXTI_Line11 ((uint32_t)0x00800) /*!< External interrupt line 11 */
#define EXTI_Line12 ((uint32_t)0x01000) /*!< External interrupt line 12 */
#define EXTI_Line13 ((uint32_t)0x02000) /*!< External interrupt line 13 */
#define EXTI_Line14 ((uint32_t)0x04000) /*!< External interrupt line 14 */
#define EXTI_Line15 ((uint32_t)0x08000) /*!< External interrupt line 15 */
#define EXTI_Line16 ((uint32_t)0x10000) /*!< External interrupt line 16 Connected to the PVD Output */
#define EXTI_Line17 ((uint32_t)0x20000) /*!< External interrupt line 17 Connected to the RTC Alarm event */
#define EXTI_Line18 ((uint32_t)0x40000) /*!< External interrupt line 18 Connected to the USB Device/USB OTG FS
Wakeup from suspend event */
#define EXTI_Line19 ((uint32_t)0x80000) /*!< External interrupt line 19 Connected to the Ethernet Wakeup event */
#define IS_EXTI_LINE(LINE) ((((LINE) & (uint32_t)0xFFF00000) == 0x00) && ((LINE) != (uint16_t)0x00))
#define IS_GET_EXTI_LINE(LINE) (((LINE) == EXTI_Line0) || ((LINE) == EXTI_Line1) || \
((LINE) == EXTI_Line2) || ((LINE) == EXTI_Line3) || \
((LINE) == EXTI_Line4) || ((LINE) == EXTI_Line5) || \
((LINE) == EXTI_Line6) || ((LINE) == EXTI_Line7) || \
((LINE) == EXTI_Line8) || ((LINE) == EXTI_Line9) || \
((LINE) == EXTI_Line10) || ((LINE) == EXTI_Line11) || \
((LINE) == EXTI_Line12) || ((LINE) == EXTI_Line13) || \
((LINE) == EXTI_Line14) || ((LINE) == EXTI_Line15) || \
((LINE) == EXTI_Line16) || ((LINE) == EXTI_Line17) || \
((LINE) == EXTI_Line18) || ((LINE) == EXTI_Line19))
/**
* @}
*/
/**
* @}
*/
/** @defgroup EXTI_Exported_Macros
* @{
*/
/**
* @}
*/
/** @defgroup EXTI_Exported_Functions
* @{
*/
void EXTI_DeInit(void);
void EXTI_Init(EXTI_InitTypeDef* EXTI_InitStruct);
void EXTI_StructInit(EXTI_InitTypeDef* EXTI_InitStruct);
void EXTI_GenerateSWInterrupt(uint32_t EXTI_Line);
FlagStatus EXTI_GetFlagStatus(uint32_t EXTI_Line);
void EXTI_ClearFlag(uint32_t EXTI_Line);
ITStatus EXTI_GetITStatus(uint32_t EXTI_Line);
void EXTI_ClearITPendingBit(uint32_t EXTI_Line);
#ifdef __cplusplus
}
#endif
#endif /* __STM32F10x_EXTI_H */
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/

View File

@ -1,426 +0,0 @@
/**
******************************************************************************
* @file stm32f10x_flash.h
* @author MCD Application Team
* @version V3.5.0
* @date 11-March-2011
* @brief This file contains all the functions prototypes for the FLASH
* firmware library.
******************************************************************************
* @attention
*
* 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, STMICROELECTRONICS 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 2011 STMicroelectronics</center></h2>
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32F10x_FLASH_H
#define __STM32F10x_FLASH_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32f10x.h"
/** @addtogroup STM32F10x_StdPeriph_Driver
* @{
*/
/** @addtogroup FLASH
* @{
*/
/** @defgroup FLASH_Exported_Types
* @{
*/
/**
* @brief FLASH Status
*/
typedef enum
{
FLASH_BUSY = 1,
FLASH_ERROR_PG,
FLASH_ERROR_WRP,
FLASH_COMPLETE,
FLASH_TIMEOUT
}FLASH_Status;
/**
* @}
*/
/** @defgroup FLASH_Exported_Constants
* @{
*/
/** @defgroup Flash_Latency
* @{
*/
#define FLASH_Latency_0 ((uint32_t)0x00000000) /*!< FLASH Zero Latency cycle */
#define FLASH_Latency_1 ((uint32_t)0x00000001) /*!< FLASH One Latency cycle */
#define FLASH_Latency_2 ((uint32_t)0x00000002) /*!< FLASH Two Latency cycles */
#define IS_FLASH_LATENCY(LATENCY) (((LATENCY) == FLASH_Latency_0) || \
((LATENCY) == FLASH_Latency_1) || \
((LATENCY) == FLASH_Latency_2))
/**
* @}
*/
/** @defgroup Half_Cycle_Enable_Disable
* @{
*/
#define FLASH_HalfCycleAccess_Enable ((uint32_t)0x00000008) /*!< FLASH Half Cycle Enable */
#define FLASH_HalfCycleAccess_Disable ((uint32_t)0x00000000) /*!< FLASH Half Cycle Disable */
#define IS_FLASH_HALFCYCLEACCESS_STATE(STATE) (((STATE) == FLASH_HalfCycleAccess_Enable) || \
((STATE) == FLASH_HalfCycleAccess_Disable))
/**
* @}
*/
/** @defgroup Prefetch_Buffer_Enable_Disable
* @{
*/
#define FLASH_PrefetchBuffer_Enable ((uint32_t)0x00000010) /*!< FLASH Prefetch Buffer Enable */
#define FLASH_PrefetchBuffer_Disable ((uint32_t)0x00000000) /*!< FLASH Prefetch Buffer Disable */
#define IS_FLASH_PREFETCHBUFFER_STATE(STATE) (((STATE) == FLASH_PrefetchBuffer_Enable) || \
((STATE) == FLASH_PrefetchBuffer_Disable))
/**
* @}
*/
/** @defgroup Option_Bytes_Write_Protection
* @{
*/
/* Values to be used with STM32 Low and Medium density devices */
#define FLASH_WRProt_Pages0to3 ((uint32_t)0x00000001) /*!< STM32 Low and Medium density devices: Write protection of page 0 to 3 */
#define FLASH_WRProt_Pages4to7 ((uint32_t)0x00000002) /*!< STM32 Low and Medium density devices: Write protection of page 4 to 7 */
#define FLASH_WRProt_Pages8to11 ((uint32_t)0x00000004) /*!< STM32 Low and Medium density devices: Write protection of page 8 to 11 */
#define FLASH_WRProt_Pages12to15 ((uint32_t)0x00000008) /*!< STM32 Low and Medium density devices: Write protection of page 12 to 15 */
#define FLASH_WRProt_Pages16to19 ((uint32_t)0x00000010) /*!< STM32 Low and Medium density devices: Write protection of page 16 to 19 */
#define FLASH_WRProt_Pages20to23 ((uint32_t)0x00000020) /*!< STM32 Low and Medium density devices: Write protection of page 20 to 23 */
#define FLASH_WRProt_Pages24to27 ((uint32_t)0x00000040) /*!< STM32 Low and Medium density devices: Write protection of page 24 to 27 */
#define FLASH_WRProt_Pages28to31 ((uint32_t)0x00000080) /*!< STM32 Low and Medium density devices: Write protection of page 28 to 31 */
/* Values to be used with STM32 Medium-density devices */
#define FLASH_WRProt_Pages32to35 ((uint32_t)0x00000100) /*!< STM32 Medium-density devices: Write protection of page 32 to 35 */
#define FLASH_WRProt_Pages36to39 ((uint32_t)0x00000200) /*!< STM32 Medium-density devices: Write protection of page 36 to 39 */
#define FLASH_WRProt_Pages40to43 ((uint32_t)0x00000400) /*!< STM32 Medium-density devices: Write protection of page 40 to 43 */
#define FLASH_WRProt_Pages44to47 ((uint32_t)0x00000800) /*!< STM32 Medium-density devices: Write protection of page 44 to 47 */
#define FLASH_WRProt_Pages48to51 ((uint32_t)0x00001000) /*!< STM32 Medium-density devices: Write protection of page 48 to 51 */
#define FLASH_WRProt_Pages52to55 ((uint32_t)0x00002000) /*!< STM32 Medium-density devices: Write protection of page 52 to 55 */
#define FLASH_WRProt_Pages56to59 ((uint32_t)0x00004000) /*!< STM32 Medium-density devices: Write protection of page 56 to 59 */
#define FLASH_WRProt_Pages60to63 ((uint32_t)0x00008000) /*!< STM32 Medium-density devices: Write protection of page 60 to 63 */
#define FLASH_WRProt_Pages64to67 ((uint32_t)0x00010000) /*!< STM32 Medium-density devices: Write protection of page 64 to 67 */
#define FLASH_WRProt_Pages68to71 ((uint32_t)0x00020000) /*!< STM32 Medium-density devices: Write protection of page 68 to 71 */
#define FLASH_WRProt_Pages72to75 ((uint32_t)0x00040000) /*!< STM32 Medium-density devices: Write protection of page 72 to 75 */
#define FLASH_WRProt_Pages76to79 ((uint32_t)0x00080000) /*!< STM32 Medium-density devices: Write protection of page 76 to 79 */
#define FLASH_WRProt_Pages80to83 ((uint32_t)0x00100000) /*!< STM32 Medium-density devices: Write protection of page 80 to 83 */
#define FLASH_WRProt_Pages84to87 ((uint32_t)0x00200000) /*!< STM32 Medium-density devices: Write protection of page 84 to 87 */
#define FLASH_WRProt_Pages88to91 ((uint32_t)0x00400000) /*!< STM32 Medium-density devices: Write protection of page 88 to 91 */
#define FLASH_WRProt_Pages92to95 ((uint32_t)0x00800000) /*!< STM32 Medium-density devices: Write protection of page 92 to 95 */
#define FLASH_WRProt_Pages96to99 ((uint32_t)0x01000000) /*!< STM32 Medium-density devices: Write protection of page 96 to 99 */
#define FLASH_WRProt_Pages100to103 ((uint32_t)0x02000000) /*!< STM32 Medium-density devices: Write protection of page 100 to 103 */
#define FLASH_WRProt_Pages104to107 ((uint32_t)0x04000000) /*!< STM32 Medium-density devices: Write protection of page 104 to 107 */
#define FLASH_WRProt_Pages108to111 ((uint32_t)0x08000000) /*!< STM32 Medium-density devices: Write protection of page 108 to 111 */
#define FLASH_WRProt_Pages112to115 ((uint32_t)0x10000000) /*!< STM32 Medium-density devices: Write protection of page 112 to 115 */
#define FLASH_WRProt_Pages116to119 ((uint32_t)0x20000000) /*!< STM32 Medium-density devices: Write protection of page 115 to 119 */
#define FLASH_WRProt_Pages120to123 ((uint32_t)0x40000000) /*!< STM32 Medium-density devices: Write protection of page 120 to 123 */
#define FLASH_WRProt_Pages124to127 ((uint32_t)0x80000000) /*!< STM32 Medium-density devices: Write protection of page 124 to 127 */
/* Values to be used with STM32 High-density and STM32F10X Connectivity line devices */
#define FLASH_WRProt_Pages0to1 ((uint32_t)0x00000001) /*!< STM32 High-density, XL-density and Connectivity line devices:
Write protection of page 0 to 1 */
#define FLASH_WRProt_Pages2to3 ((uint32_t)0x00000002) /*!< STM32 High-density, XL-density and Connectivity line devices:
Write protection of page 2 to 3 */
#define FLASH_WRProt_Pages4to5 ((uint32_t)0x00000004) /*!< STM32 High-density, XL-density and Connectivity line devices:
Write protection of page 4 to 5 */
#define FLASH_WRProt_Pages6to7 ((uint32_t)0x00000008) /*!< STM32 High-density, XL-density and Connectivity line devices:
Write protection of page 6 to 7 */
#define FLASH_WRProt_Pages8to9 ((uint32_t)0x00000010) /*!< STM32 High-density, XL-density and Connectivity line devices:
Write protection of page 8 to 9 */
#define FLASH_WRProt_Pages10to11 ((uint32_t)0x00000020) /*!< STM32 High-density, XL-density and Connectivity line devices:
Write protection of page 10 to 11 */
#define FLASH_WRProt_Pages12to13 ((uint32_t)0x00000040) /*!< STM32 High-density, XL-density and Connectivity line devices:
Write protection of page 12 to 13 */
#define FLASH_WRProt_Pages14to15 ((uint32_t)0x00000080) /*!< STM32 High-density, XL-density and Connectivity line devices:
Write protection of page 14 to 15 */
#define FLASH_WRProt_Pages16to17 ((uint32_t)0x00000100) /*!< STM32 High-density, XL-density and Connectivity line devices:
Write protection of page 16 to 17 */
#define FLASH_WRProt_Pages18to19 ((uint32_t)0x00000200) /*!< STM32 High-density, XL-density and Connectivity line devices:
Write protection of page 18 to 19 */
#define FLASH_WRProt_Pages20to21 ((uint32_t)0x00000400) /*!< STM32 High-density, XL-density and Connectivity line devices:
Write protection of page 20 to 21 */
#define FLASH_WRProt_Pages22to23 ((uint32_t)0x00000800) /*!< STM32 High-density, XL-density and Connectivity line devices:
Write protection of page 22 to 23 */
#define FLASH_WRProt_Pages24to25 ((uint32_t)0x00001000) /*!< STM32 High-density, XL-density and Connectivity line devices:
Write protection of page 24 to 25 */
#define FLASH_WRProt_Pages26to27 ((uint32_t)0x00002000) /*!< STM32 High-density, XL-density and Connectivity line devices:
Write protection of page 26 to 27 */
#define FLASH_WRProt_Pages28to29 ((uint32_t)0x00004000) /*!< STM32 High-density, XL-density and Connectivity line devices:
Write protection of page 28 to 29 */
#define FLASH_WRProt_Pages30to31 ((uint32_t)0x00008000) /*!< STM32 High-density, XL-density and Connectivity line devices:
Write protection of page 30 to 31 */
#define FLASH_WRProt_Pages32to33 ((uint32_t)0x00010000) /*!< STM32 High-density, XL-density and Connectivity line devices:
Write protection of page 32 to 33 */
#define FLASH_WRProt_Pages34to35 ((uint32_t)0x00020000) /*!< STM32 High-density, XL-density and Connectivity line devices:
Write protection of page 34 to 35 */
#define FLASH_WRProt_Pages36to37 ((uint32_t)0x00040000) /*!< STM32 High-density, XL-density and Connectivity line devices:
Write protection of page 36 to 37 */
#define FLASH_WRProt_Pages38to39 ((uint32_t)0x00080000) /*!< STM32 High-density, XL-density and Connectivity line devices:
Write protection of page 38 to 39 */
#define FLASH_WRProt_Pages40to41 ((uint32_t)0x00100000) /*!< STM32 High-density, XL-density and Connectivity line devices:
Write protection of page 40 to 41 */
#define FLASH_WRProt_Pages42to43 ((uint32_t)0x00200000) /*!< STM32 High-density, XL-density and Connectivity line devices:
Write protection of page 42 to 43 */
#define FLASH_WRProt_Pages44to45 ((uint32_t)0x00400000) /*!< STM32 High-density, XL-density and Connectivity line devices:
Write protection of page 44 to 45 */
#define FLASH_WRProt_Pages46to47 ((uint32_t)0x00800000) /*!< STM32 High-density, XL-density and Connectivity line devices:
Write protection of page 46 to 47 */
#define FLASH_WRProt_Pages48to49 ((uint32_t)0x01000000) /*!< STM32 High-density, XL-density and Connectivity line devices:
Write protection of page 48 to 49 */
#define FLASH_WRProt_Pages50to51 ((uint32_t)0x02000000) /*!< STM32 High-density, XL-density and Connectivity line devices:
Write protection of page 50 to 51 */
#define FLASH_WRProt_Pages52to53 ((uint32_t)0x04000000) /*!< STM32 High-density, XL-density and Connectivity line devices:
Write protection of page 52 to 53 */
#define FLASH_WRProt_Pages54to55 ((uint32_t)0x08000000) /*!< STM32 High-density, XL-density and Connectivity line devices:
Write protection of page 54 to 55 */
#define FLASH_WRProt_Pages56to57 ((uint32_t)0x10000000) /*!< STM32 High-density, XL-density and Connectivity line devices:
Write protection of page 56 to 57 */
#define FLASH_WRProt_Pages58to59 ((uint32_t)0x20000000) /*!< STM32 High-density, XL-density and Connectivity line devices:
Write protection of page 58 to 59 */
#define FLASH_WRProt_Pages60to61 ((uint32_t)0x40000000) /*!< STM32 High-density, XL-density and Connectivity line devices:
Write protection of page 60 to 61 */
#define FLASH_WRProt_Pages62to127 ((uint32_t)0x80000000) /*!< STM32 Connectivity line devices: Write protection of page 62 to 127 */
#define FLASH_WRProt_Pages62to255 ((uint32_t)0x80000000) /*!< STM32 Medium-density devices: Write protection of page 62 to 255 */
#define FLASH_WRProt_Pages62to511 ((uint32_t)0x80000000) /*!< STM32 XL-density devices: Write protection of page 62 to 511 */
#define FLASH_WRProt_AllPages ((uint32_t)0xFFFFFFFF) /*!< Write protection of all Pages */
#define IS_FLASH_WRPROT_PAGE(PAGE) (((PAGE) != 0x00000000))
#define IS_FLASH_ADDRESS(ADDRESS) (((ADDRESS) >= 0x08000000) && ((ADDRESS) < 0x080FFFFF))
#define IS_OB_DATA_ADDRESS(ADDRESS) (((ADDRESS) == 0x1FFFF804) || ((ADDRESS) == 0x1FFFF806))
/**
* @}
*/
/** @defgroup Option_Bytes_IWatchdog
* @{
*/
#define OB_IWDG_SW ((uint16_t)0x0001) /*!< Software IWDG selected */
#define OB_IWDG_HW ((uint16_t)0x0000) /*!< Hardware IWDG selected */
#define IS_OB_IWDG_SOURCE(SOURCE) (((SOURCE) == OB_IWDG_SW) || ((SOURCE) == OB_IWDG_HW))
/**
* @}
*/
/** @defgroup Option_Bytes_nRST_STOP
* @{
*/
#define OB_STOP_NoRST ((uint16_t)0x0002) /*!< No reset generated when entering in STOP */
#define OB_STOP_RST ((uint16_t)0x0000) /*!< Reset generated when entering in STOP */
#define IS_OB_STOP_SOURCE(SOURCE) (((SOURCE) == OB_STOP_NoRST) || ((SOURCE) == OB_STOP_RST))
/**
* @}
*/
/** @defgroup Option_Bytes_nRST_STDBY
* @{
*/
#define OB_STDBY_NoRST ((uint16_t)0x0004) /*!< No reset generated when entering in STANDBY */
#define OB_STDBY_RST ((uint16_t)0x0000) /*!< Reset generated when entering in STANDBY */
#define IS_OB_STDBY_SOURCE(SOURCE) (((SOURCE) == OB_STDBY_NoRST) || ((SOURCE) == OB_STDBY_RST))
#ifdef STM32F10X_XL
/**
* @}
*/
/** @defgroup FLASH_Boot
* @{
*/
#define FLASH_BOOT_Bank1 ((uint16_t)0x0000) /*!< At startup, if boot pins are set in boot from user Flash position
and this parameter is selected the device will boot from Bank1(Default) */
#define FLASH_BOOT_Bank2 ((uint16_t)0x0001) /*!< At startup, if boot pins are set in boot from user Flash position
and this parameter is selected the device will boot from Bank 2 or Bank 1,
depending on the activation of the bank */
#define IS_FLASH_BOOT(BOOT) (((BOOT) == FLASH_BOOT_Bank1) || ((BOOT) == FLASH_BOOT_Bank2))
#endif
/**
* @}
*/
/** @defgroup FLASH_Interrupts
* @{
*/
#ifdef STM32F10X_XL
#define FLASH_IT_BANK2_ERROR ((uint32_t)0x80000400) /*!< FPEC BANK2 error interrupt source */
#define FLASH_IT_BANK2_EOP ((uint32_t)0x80001000) /*!< End of FLASH BANK2 Operation Interrupt source */
#define FLASH_IT_BANK1_ERROR FLASH_IT_ERROR /*!< FPEC BANK1 error interrupt source */
#define FLASH_IT_BANK1_EOP FLASH_IT_EOP /*!< End of FLASH BANK1 Operation Interrupt source */
#define FLASH_IT_ERROR ((uint32_t)0x00000400) /*!< FPEC BANK1 error interrupt source */
#define FLASH_IT_EOP ((uint32_t)0x00001000) /*!< End of FLASH BANK1 Operation Interrupt source */
#define IS_FLASH_IT(IT) ((((IT) & (uint32_t)0x7FFFEBFF) == 0x00000000) && (((IT) != 0x00000000)))
#else
#define FLASH_IT_ERROR ((uint32_t)0x00000400) /*!< FPEC error interrupt source */
#define FLASH_IT_EOP ((uint32_t)0x00001000) /*!< End of FLASH Operation Interrupt source */
#define FLASH_IT_BANK1_ERROR FLASH_IT_ERROR /*!< FPEC BANK1 error interrupt source */
#define FLASH_IT_BANK1_EOP FLASH_IT_EOP /*!< End of FLASH BANK1 Operation Interrupt source */
#define IS_FLASH_IT(IT) ((((IT) & (uint32_t)0xFFFFEBFF) == 0x00000000) && (((IT) != 0x00000000)))
#endif
/**
* @}
*/
/** @defgroup FLASH_Flags
* @{
*/
#ifdef STM32F10X_XL
#define FLASH_FLAG_BANK2_BSY ((uint32_t)0x80000001) /*!< FLASH BANK2 Busy flag */
#define FLASH_FLAG_BANK2_EOP ((uint32_t)0x80000020) /*!< FLASH BANK2 End of Operation flag */
#define FLASH_FLAG_BANK2_PGERR ((uint32_t)0x80000004) /*!< FLASH BANK2 Program error flag */
#define FLASH_FLAG_BANK2_WRPRTERR ((uint32_t)0x80000010) /*!< FLASH BANK2 Write protected error flag */
#define FLASH_FLAG_BANK1_BSY FLASH_FLAG_BSY /*!< FLASH BANK1 Busy flag*/
#define FLASH_FLAG_BANK1_EOP FLASH_FLAG_EOP /*!< FLASH BANK1 End of Operation flag */
#define FLASH_FLAG_BANK1_PGERR FLASH_FLAG_PGERR /*!< FLASH BANK1 Program error flag */
#define FLASH_FLAG_BANK1_WRPRTERR FLASH_FLAG_WRPRTERR /*!< FLASH BANK1 Write protected error flag */
#define FLASH_FLAG_BSY ((uint32_t)0x00000001) /*!< FLASH Busy flag */
#define FLASH_FLAG_EOP ((uint32_t)0x00000020) /*!< FLASH End of Operation flag */
#define FLASH_FLAG_PGERR ((uint32_t)0x00000004) /*!< FLASH Program error flag */
#define FLASH_FLAG_WRPRTERR ((uint32_t)0x00000010) /*!< FLASH Write protected error flag */
#define FLASH_FLAG_OPTERR ((uint32_t)0x00000001) /*!< FLASH Option Byte error flag */
#define IS_FLASH_CLEAR_FLAG(FLAG) ((((FLAG) & (uint32_t)0x7FFFFFCA) == 0x00000000) && ((FLAG) != 0x00000000))
#define IS_FLASH_GET_FLAG(FLAG) (((FLAG) == FLASH_FLAG_BSY) || ((FLAG) == FLASH_FLAG_EOP) || \
((FLAG) == FLASH_FLAG_PGERR) || ((FLAG) == FLASH_FLAG_WRPRTERR) || \
((FLAG) == FLASH_FLAG_OPTERR)|| \
((FLAG) == FLASH_FLAG_BANK1_BSY) || ((FLAG) == FLASH_FLAG_BANK1_EOP) || \
((FLAG) == FLASH_FLAG_BANK1_PGERR) || ((FLAG) == FLASH_FLAG_BANK1_WRPRTERR) || \
((FLAG) == FLASH_FLAG_BANK2_BSY) || ((FLAG) == FLASH_FLAG_BANK2_EOP) || \
((FLAG) == FLASH_FLAG_BANK2_PGERR) || ((FLAG) == FLASH_FLAG_BANK2_WRPRTERR))
#else
#define FLASH_FLAG_BSY ((uint32_t)0x00000001) /*!< FLASH Busy flag */
#define FLASH_FLAG_EOP ((uint32_t)0x00000020) /*!< FLASH End of Operation flag */
#define FLASH_FLAG_PGERR ((uint32_t)0x00000004) /*!< FLASH Program error flag */
#define FLASH_FLAG_WRPRTERR ((uint32_t)0x00000010) /*!< FLASH Write protected error flag */
#define FLASH_FLAG_OPTERR ((uint32_t)0x00000001) /*!< FLASH Option Byte error flag */
#define FLASH_FLAG_BANK1_BSY FLASH_FLAG_BSY /*!< FLASH BANK1 Busy flag*/
#define FLASH_FLAG_BANK1_EOP FLASH_FLAG_EOP /*!< FLASH BANK1 End of Operation flag */
#define FLASH_FLAG_BANK1_PGERR FLASH_FLAG_PGERR /*!< FLASH BANK1 Program error flag */
#define FLASH_FLAG_BANK1_WRPRTERR FLASH_FLAG_WRPRTERR /*!< FLASH BANK1 Write protected error flag */
#define IS_FLASH_CLEAR_FLAG(FLAG) ((((FLAG) & (uint32_t)0xFFFFFFCA) == 0x00000000) && ((FLAG) != 0x00000000))
#define IS_FLASH_GET_FLAG(FLAG) (((FLAG) == FLASH_FLAG_BSY) || ((FLAG) == FLASH_FLAG_EOP) || \
((FLAG) == FLASH_FLAG_PGERR) || ((FLAG) == FLASH_FLAG_WRPRTERR) || \
((FLAG) == FLASH_FLAG_BANK1_BSY) || ((FLAG) == FLASH_FLAG_BANK1_EOP) || \
((FLAG) == FLASH_FLAG_BANK1_PGERR) || ((FLAG) == FLASH_FLAG_BANK1_WRPRTERR) || \
((FLAG) == FLASH_FLAG_OPTERR))
#endif
/**
* @}
*/
/**
* @}
*/
/** @defgroup FLASH_Exported_Macros
* @{
*/
/**
* @}
*/
/** @defgroup FLASH_Exported_Functions
* @{
*/
/*------------ Functions used for all STM32F10x devices -----*/
void FLASH_SetLatency(uint32_t FLASH_Latency);
void FLASH_HalfCycleAccessCmd(uint32_t FLASH_HalfCycleAccess);
void FLASH_PrefetchBufferCmd(uint32_t FLASH_PrefetchBuffer);
void FLASH_Unlock(void);
void FLASH_Lock(void);
FLASH_Status FLASH_ErasePage(uint32_t Page_Address);
FLASH_Status FLASH_EraseAllPages(void);
FLASH_Status FLASH_EraseOptionBytes(void);
FLASH_Status FLASH_ProgramWord(uint32_t Address, uint32_t Data);
FLASH_Status FLASH_ProgramHalfWord(uint32_t Address, uint16_t Data);
FLASH_Status FLASH_ProgramOptionByteData(uint32_t Address, uint8_t Data);
FLASH_Status FLASH_EnableWriteProtection(uint32_t FLASH_Pages);
FLASH_Status FLASH_ReadOutProtection(FunctionalState NewState);
FLASH_Status FLASH_UserOptionByteConfig(uint16_t OB_IWDG, uint16_t OB_STOP, uint16_t OB_STDBY);
uint32_t FLASH_GetUserOptionByte(void);
uint32_t FLASH_GetWriteProtectionOptionByte(void);
FlagStatus FLASH_GetReadOutProtectionStatus(void);
FlagStatus FLASH_GetPrefetchBufferStatus(void);
void FLASH_ITConfig(uint32_t FLASH_IT, FunctionalState NewState);
FlagStatus FLASH_GetFlagStatus(uint32_t FLASH_FLAG);
void FLASH_ClearFlag(uint32_t FLASH_FLAG);
FLASH_Status FLASH_GetStatus(void);
FLASH_Status FLASH_WaitForLastOperation(uint32_t Timeout);
/*------------ New function used for all STM32F10x devices -----*/
void FLASH_UnlockBank1(void);
void FLASH_LockBank1(void);
FLASH_Status FLASH_EraseAllBank1Pages(void);
FLASH_Status FLASH_GetBank1Status(void);
FLASH_Status FLASH_WaitForLastBank1Operation(uint32_t Timeout);
#ifdef STM32F10X_XL
/*---- New Functions used only with STM32F10x_XL density devices -----*/
void FLASH_UnlockBank2(void);
void FLASH_LockBank2(void);
FLASH_Status FLASH_EraseAllBank2Pages(void);
FLASH_Status FLASH_GetBank2Status(void);
FLASH_Status FLASH_WaitForLastBank2Operation(uint32_t Timeout);
FLASH_Status FLASH_BootConfig(uint16_t FLASH_BOOT);
#endif
#ifdef __cplusplus
}
#endif
#endif /* __STM32F10x_FLASH_H */
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/

View File

@ -1,733 +0,0 @@
/**
******************************************************************************
* @file stm32f10x_fsmc.h
* @author MCD Application Team
* @version V3.5.0
* @date 11-March-2011
* @brief This file contains all the functions prototypes for the FSMC firmware
* library.
******************************************************************************
* @attention
*
* 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, STMICROELECTRONICS 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 2011 STMicroelectronics</center></h2>
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32F10x_FSMC_H
#define __STM32F10x_FSMC_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32f10x.h"
/** @addtogroup STM32F10x_StdPeriph_Driver
* @{
*/
/** @addtogroup FSMC
* @{
*/
/** @defgroup FSMC_Exported_Types
* @{
*/
/**
* @brief Timing parameters For NOR/SRAM Banks
*/
typedef struct
{
uint32_t FSMC_AddressSetupTime; /*!< Defines the number of HCLK cycles to configure
the duration of the address setup time.
This parameter can be a value between 0 and 0xF.
@note: It is not used with synchronous NOR Flash memories. */
uint32_t FSMC_AddressHoldTime; /*!< Defines the number of HCLK cycles to configure
the duration of the address hold time.
This parameter can be a value between 0 and 0xF.
@note: It is not used with synchronous NOR Flash memories.*/
uint32_t FSMC_DataSetupTime; /*!< Defines the number of HCLK cycles to configure
the duration of the data setup time.
This parameter can be a value between 0 and 0xFF.
@note: It is used for SRAMs, ROMs and asynchronous multiplexed NOR Flash memories. */
uint32_t FSMC_BusTurnAroundDuration; /*!< Defines the number of HCLK cycles to configure
the duration of the bus turnaround.
This parameter can be a value between 0 and 0xF.
@note: It is only used for multiplexed NOR Flash memories. */
uint32_t FSMC_CLKDivision; /*!< Defines the period of CLK clock output signal, expressed in number of HCLK cycles.
This parameter can be a value between 1 and 0xF.
@note: This parameter is not used for asynchronous NOR Flash, SRAM or ROM accesses. */
uint32_t FSMC_DataLatency; /*!< Defines the number of memory clock cycles to issue
to the memory before getting the first data.
The value of this parameter depends on the memory type as shown below:
- It must be set to 0 in case of a CRAM
- It is don't care in asynchronous NOR, SRAM or ROM accesses
- It may assume a value between 0 and 0xF in NOR Flash memories
with synchronous burst mode enable */
uint32_t FSMC_AccessMode; /*!< Specifies the asynchronous access mode.
This parameter can be a value of @ref FSMC_Access_Mode */
}FSMC_NORSRAMTimingInitTypeDef;
/**
* @brief FSMC NOR/SRAM Init structure definition
*/
typedef struct
{
uint32_t FSMC_Bank; /*!< Specifies the NOR/SRAM memory bank that will be used.
This parameter can be a value of @ref FSMC_NORSRAM_Bank */
uint32_t FSMC_DataAddressMux; /*!< Specifies whether the address and data values are
multiplexed on the databus or not.
This parameter can be a value of @ref FSMC_Data_Address_Bus_Multiplexing */
uint32_t FSMC_MemoryType; /*!< Specifies the type of external memory attached to
the corresponding memory bank.
This parameter can be a value of @ref FSMC_Memory_Type */
uint32_t FSMC_MemoryDataWidth; /*!< Specifies the external memory device width.
This parameter can be a value of @ref FSMC_Data_Width */
uint32_t FSMC_BurstAccessMode; /*!< Enables or disables the burst access mode for Flash memory,
valid only with synchronous burst Flash memories.
This parameter can be a value of @ref FSMC_Burst_Access_Mode */
uint32_t FSMC_AsynchronousWait; /*!< Enables or disables wait signal during asynchronous transfers,
valid only with asynchronous Flash memories.
This parameter can be a value of @ref FSMC_AsynchronousWait */
uint32_t FSMC_WaitSignalPolarity; /*!< Specifies the wait signal polarity, valid only when accessing
the Flash memory in burst mode.
This parameter can be a value of @ref FSMC_Wait_Signal_Polarity */
uint32_t FSMC_WrapMode; /*!< Enables or disables the Wrapped burst access mode for Flash
memory, valid only when accessing Flash memories in burst mode.
This parameter can be a value of @ref FSMC_Wrap_Mode */
uint32_t FSMC_WaitSignalActive; /*!< Specifies if the wait signal is asserted by the memory one
clock cycle before the wait state or during the wait state,
valid only when accessing memories in burst mode.
This parameter can be a value of @ref FSMC_Wait_Timing */
uint32_t FSMC_WriteOperation; /*!< Enables or disables the write operation in the selected bank by the FSMC.
This parameter can be a value of @ref FSMC_Write_Operation */
uint32_t FSMC_WaitSignal; /*!< Enables or disables the wait-state insertion via wait
signal, valid for Flash memory access in burst mode.
This parameter can be a value of @ref FSMC_Wait_Signal */
uint32_t FSMC_ExtendedMode; /*!< Enables or disables the extended mode.
This parameter can be a value of @ref FSMC_Extended_Mode */
uint32_t FSMC_WriteBurst; /*!< Enables or disables the write burst operation.
This parameter can be a value of @ref FSMC_Write_Burst */
FSMC_NORSRAMTimingInitTypeDef* FSMC_ReadWriteTimingStruct; /*!< Timing Parameters for write and read access if the ExtendedMode is not used*/
FSMC_NORSRAMTimingInitTypeDef* FSMC_WriteTimingStruct; /*!< Timing Parameters for write access if the ExtendedMode is used*/
}FSMC_NORSRAMInitTypeDef;
/**
* @brief Timing parameters For FSMC NAND and PCCARD Banks
*/
typedef struct
{
uint32_t FSMC_SetupTime; /*!< Defines the number of HCLK cycles to setup address before
the command assertion for NAND-Flash read or write access
to common/Attribute or I/O memory space (depending on
the memory space timing to be configured).
This parameter can be a value between 0 and 0xFF.*/
uint32_t FSMC_WaitSetupTime; /*!< Defines the minimum number of HCLK cycles to assert the
command for NAND-Flash read or write access to
common/Attribute or I/O memory space (depending on the
memory space timing to be configured).
This parameter can be a number between 0x00 and 0xFF */
uint32_t FSMC_HoldSetupTime; /*!< Defines the number of HCLK clock cycles to hold address
(and data for write access) after the command deassertion
for NAND-Flash read or write access to common/Attribute
or I/O memory space (depending on the memory space timing
to be configured).
This parameter can be a number between 0x00 and 0xFF */
uint32_t FSMC_HiZSetupTime; /*!< Defines the number of HCLK clock cycles during which the
databus is kept in HiZ after the start of a NAND-Flash
write access to common/Attribute or I/O memory space (depending
on the memory space timing to be configured).
This parameter can be a number between 0x00 and 0xFF */
}FSMC_NAND_PCCARDTimingInitTypeDef;
/**
* @brief FSMC NAND Init structure definition
*/
typedef struct
{
uint32_t FSMC_Bank; /*!< Specifies the NAND memory bank that will be used.
This parameter can be a value of @ref FSMC_NAND_Bank */
uint32_t FSMC_Waitfeature; /*!< Enables or disables the Wait feature for the NAND Memory Bank.
This parameter can be any value of @ref FSMC_Wait_feature */
uint32_t FSMC_MemoryDataWidth; /*!< Specifies the external memory device width.
This parameter can be any value of @ref FSMC_Data_Width */
uint32_t FSMC_ECC; /*!< Enables or disables the ECC computation.
This parameter can be any value of @ref FSMC_ECC */
uint32_t FSMC_ECCPageSize; /*!< Defines the page size for the extended ECC.
This parameter can be any value of @ref FSMC_ECC_Page_Size */
uint32_t FSMC_TCLRSetupTime; /*!< Defines the number of HCLK cycles to configure the
delay between CLE low and RE low.
This parameter can be a value between 0 and 0xFF. */
uint32_t FSMC_TARSetupTime; /*!< Defines the number of HCLK cycles to configure the
delay between ALE low and RE low.
This parameter can be a number between 0x0 and 0xFF */
FSMC_NAND_PCCARDTimingInitTypeDef* FSMC_CommonSpaceTimingStruct; /*!< FSMC Common Space Timing */
FSMC_NAND_PCCARDTimingInitTypeDef* FSMC_AttributeSpaceTimingStruct; /*!< FSMC Attribute Space Timing */
}FSMC_NANDInitTypeDef;
/**
* @brief FSMC PCCARD Init structure definition
*/
typedef struct
{
uint32_t FSMC_Waitfeature; /*!< Enables or disables the Wait feature for the Memory Bank.
This parameter can be any value of @ref FSMC_Wait_feature */
uint32_t FSMC_TCLRSetupTime; /*!< Defines the number of HCLK cycles to configure the
delay between CLE low and RE low.
This parameter can be a value between 0 and 0xFF. */
uint32_t FSMC_TARSetupTime; /*!< Defines the number of HCLK cycles to configure the
delay between ALE low and RE low.
This parameter can be a number between 0x0 and 0xFF */
FSMC_NAND_PCCARDTimingInitTypeDef* FSMC_CommonSpaceTimingStruct; /*!< FSMC Common Space Timing */
FSMC_NAND_PCCARDTimingInitTypeDef* FSMC_AttributeSpaceTimingStruct; /*!< FSMC Attribute Space Timing */
FSMC_NAND_PCCARDTimingInitTypeDef* FSMC_IOSpaceTimingStruct; /*!< FSMC IO Space Timing */
}FSMC_PCCARDInitTypeDef;
/**
* @}
*/
/** @defgroup FSMC_Exported_Constants
* @{
*/
/** @defgroup FSMC_NORSRAM_Bank
* @{
*/
#define FSMC_Bank1_NORSRAM1 ((uint32_t)0x00000000)
#define FSMC_Bank1_NORSRAM2 ((uint32_t)0x00000002)
#define FSMC_Bank1_NORSRAM3 ((uint32_t)0x00000004)
#define FSMC_Bank1_NORSRAM4 ((uint32_t)0x00000006)
/**
* @}
*/
/** @defgroup FSMC_NAND_Bank
* @{
*/
#define FSMC_Bank2_NAND ((uint32_t)0x00000010)
#define FSMC_Bank3_NAND ((uint32_t)0x00000100)
/**
* @}
*/
/** @defgroup FSMC_PCCARD_Bank
* @{
*/
#define FSMC_Bank4_PCCARD ((uint32_t)0x00001000)
/**
* @}
*/
#define IS_FSMC_NORSRAM_BANK(BANK) (((BANK) == FSMC_Bank1_NORSRAM1) || \
((BANK) == FSMC_Bank1_NORSRAM2) || \
((BANK) == FSMC_Bank1_NORSRAM3) || \
((BANK) == FSMC_Bank1_NORSRAM4))
#define IS_FSMC_NAND_BANK(BANK) (((BANK) == FSMC_Bank2_NAND) || \
((BANK) == FSMC_Bank3_NAND))
#define IS_FSMC_GETFLAG_BANK(BANK) (((BANK) == FSMC_Bank2_NAND) || \
((BANK) == FSMC_Bank3_NAND) || \
((BANK) == FSMC_Bank4_PCCARD))
#define IS_FSMC_IT_BANK(BANK) (((BANK) == FSMC_Bank2_NAND) || \
((BANK) == FSMC_Bank3_NAND) || \
((BANK) == FSMC_Bank4_PCCARD))
/** @defgroup NOR_SRAM_Controller
* @{
*/
/** @defgroup FSMC_Data_Address_Bus_Multiplexing
* @{
*/
#define FSMC_DataAddressMux_Disable ((uint32_t)0x00000000)
#define FSMC_DataAddressMux_Enable ((uint32_t)0x00000002)
#define IS_FSMC_MUX(MUX) (((MUX) == FSMC_DataAddressMux_Disable) || \
((MUX) == FSMC_DataAddressMux_Enable))
/**
* @}
*/
/** @defgroup FSMC_Memory_Type
* @{
*/
#define FSMC_MemoryType_SRAM ((uint32_t)0x00000000)
#define FSMC_MemoryType_PSRAM ((uint32_t)0x00000004)
#define FSMC_MemoryType_NOR ((uint32_t)0x00000008)
#define IS_FSMC_MEMORY(MEMORY) (((MEMORY) == FSMC_MemoryType_SRAM) || \
((MEMORY) == FSMC_MemoryType_PSRAM)|| \
((MEMORY) == FSMC_MemoryType_NOR))
/**
* @}
*/
/** @defgroup FSMC_Data_Width
* @{
*/
#define FSMC_MemoryDataWidth_8b ((uint32_t)0x00000000)
#define FSMC_MemoryDataWidth_16b ((uint32_t)0x00000010)
#define IS_FSMC_MEMORY_WIDTH(WIDTH) (((WIDTH) == FSMC_MemoryDataWidth_8b) || \
((WIDTH) == FSMC_MemoryDataWidth_16b))
/**
* @}
*/
/** @defgroup FSMC_Burst_Access_Mode
* @{
*/
#define FSMC_BurstAccessMode_Disable ((uint32_t)0x00000000)
#define FSMC_BurstAccessMode_Enable ((uint32_t)0x00000100)
#define IS_FSMC_BURSTMODE(STATE) (((STATE) == FSMC_BurstAccessMode_Disable) || \
((STATE) == FSMC_BurstAccessMode_Enable))
/**
* @}
*/
/** @defgroup FSMC_AsynchronousWait
* @{
*/
#define FSMC_AsynchronousWait_Disable ((uint32_t)0x00000000)
#define FSMC_AsynchronousWait_Enable ((uint32_t)0x00008000)
#define IS_FSMC_ASYNWAIT(STATE) (((STATE) == FSMC_AsynchronousWait_Disable) || \
((STATE) == FSMC_AsynchronousWait_Enable))
/**
* @}
*/
/** @defgroup FSMC_Wait_Signal_Polarity
* @{
*/
#define FSMC_WaitSignalPolarity_Low ((uint32_t)0x00000000)
#define FSMC_WaitSignalPolarity_High ((uint32_t)0x00000200)
#define IS_FSMC_WAIT_POLARITY(POLARITY) (((POLARITY) == FSMC_WaitSignalPolarity_Low) || \
((POLARITY) == FSMC_WaitSignalPolarity_High))
/**
* @}
*/
/** @defgroup FSMC_Wrap_Mode
* @{
*/
#define FSMC_WrapMode_Disable ((uint32_t)0x00000000)
#define FSMC_WrapMode_Enable ((uint32_t)0x00000400)
#define IS_FSMC_WRAP_MODE(MODE) (((MODE) == FSMC_WrapMode_Disable) || \
((MODE) == FSMC_WrapMode_Enable))
/**
* @}
*/
/** @defgroup FSMC_Wait_Timing
* @{
*/
#define FSMC_WaitSignalActive_BeforeWaitState ((uint32_t)0x00000000)
#define FSMC_WaitSignalActive_DuringWaitState ((uint32_t)0x00000800)
#define IS_FSMC_WAIT_SIGNAL_ACTIVE(ACTIVE) (((ACTIVE) == FSMC_WaitSignalActive_BeforeWaitState) || \
((ACTIVE) == FSMC_WaitSignalActive_DuringWaitState))
/**
* @}
*/
/** @defgroup FSMC_Write_Operation
* @{
*/
#define FSMC_WriteOperation_Disable ((uint32_t)0x00000000)
#define FSMC_WriteOperation_Enable ((uint32_t)0x00001000)
#define IS_FSMC_WRITE_OPERATION(OPERATION) (((OPERATION) == FSMC_WriteOperation_Disable) || \
((OPERATION) == FSMC_WriteOperation_Enable))
/**
* @}
*/
/** @defgroup FSMC_Wait_Signal
* @{
*/
#define FSMC_WaitSignal_Disable ((uint32_t)0x00000000)
#define FSMC_WaitSignal_Enable ((uint32_t)0x00002000)
#define IS_FSMC_WAITE_SIGNAL(SIGNAL) (((SIGNAL) == FSMC_WaitSignal_Disable) || \
((SIGNAL) == FSMC_WaitSignal_Enable))
/**
* @}
*/
/** @defgroup FSMC_Extended_Mode
* @{
*/
#define FSMC_ExtendedMode_Disable ((uint32_t)0x00000000)
#define FSMC_ExtendedMode_Enable ((uint32_t)0x00004000)
#define IS_FSMC_EXTENDED_MODE(MODE) (((MODE) == FSMC_ExtendedMode_Disable) || \
((MODE) == FSMC_ExtendedMode_Enable))
/**
* @}
*/
/** @defgroup FSMC_Write_Burst
* @{
*/
#define FSMC_WriteBurst_Disable ((uint32_t)0x00000000)
#define FSMC_WriteBurst_Enable ((uint32_t)0x00080000)
#define IS_FSMC_WRITE_BURST(BURST) (((BURST) == FSMC_WriteBurst_Disable) || \
((BURST) == FSMC_WriteBurst_Enable))
/**
* @}
*/
/** @defgroup FSMC_Address_Setup_Time
* @{
*/
#define IS_FSMC_ADDRESS_SETUP_TIME(TIME) ((TIME) <= 0xF)
/**
* @}
*/
/** @defgroup FSMC_Address_Hold_Time
* @{
*/
#define IS_FSMC_ADDRESS_HOLD_TIME(TIME) ((TIME) <= 0xF)
/**
* @}
*/
/** @defgroup FSMC_Data_Setup_Time
* @{
*/
#define IS_FSMC_DATASETUP_TIME(TIME) (((TIME) > 0) && ((TIME) <= 0xFF))
/**
* @}
*/
/** @defgroup FSMC_Bus_Turn_around_Duration
* @{
*/
#define IS_FSMC_TURNAROUND_TIME(TIME) ((TIME) <= 0xF)
/**
* @}
*/
/** @defgroup FSMC_CLK_Division
* @{
*/
#define IS_FSMC_CLK_DIV(DIV) ((DIV) <= 0xF)
/**
* @}
*/
/** @defgroup FSMC_Data_Latency
* @{
*/
#define IS_FSMC_DATA_LATENCY(LATENCY) ((LATENCY) <= 0xF)
/**
* @}
*/
/** @defgroup FSMC_Access_Mode
* @{
*/
#define FSMC_AccessMode_A ((uint32_t)0x00000000)
#define FSMC_AccessMode_B ((uint32_t)0x10000000)
#define FSMC_AccessMode_C ((uint32_t)0x20000000)
#define FSMC_AccessMode_D ((uint32_t)0x30000000)
#define IS_FSMC_ACCESS_MODE(MODE) (((MODE) == FSMC_AccessMode_A) || \
((MODE) == FSMC_AccessMode_B) || \
((MODE) == FSMC_AccessMode_C) || \
((MODE) == FSMC_AccessMode_D))
/**
* @}
*/
/**
* @}
*/
/** @defgroup NAND_PCCARD_Controller
* @{
*/
/** @defgroup FSMC_Wait_feature
* @{
*/
#define FSMC_Waitfeature_Disable ((uint32_t)0x00000000)
#define FSMC_Waitfeature_Enable ((uint32_t)0x00000002)
#define IS_FSMC_WAIT_FEATURE(FEATURE) (((FEATURE) == FSMC_Waitfeature_Disable) || \
((FEATURE) == FSMC_Waitfeature_Enable))
/**
* @}
*/
/** @defgroup FSMC_ECC
* @{
*/
#define FSMC_ECC_Disable ((uint32_t)0x00000000)
#define FSMC_ECC_Enable ((uint32_t)0x00000040)
#define IS_FSMC_ECC_STATE(STATE) (((STATE) == FSMC_ECC_Disable) || \
((STATE) == FSMC_ECC_Enable))
/**
* @}
*/
/** @defgroup FSMC_ECC_Page_Size
* @{
*/
#define FSMC_ECCPageSize_256Bytes ((uint32_t)0x00000000)
#define FSMC_ECCPageSize_512Bytes ((uint32_t)0x00020000)
#define FSMC_ECCPageSize_1024Bytes ((uint32_t)0x00040000)
#define FSMC_ECCPageSize_2048Bytes ((uint32_t)0x00060000)
#define FSMC_ECCPageSize_4096Bytes ((uint32_t)0x00080000)
#define FSMC_ECCPageSize_8192Bytes ((uint32_t)0x000A0000)
#define IS_FSMC_ECCPAGE_SIZE(SIZE) (((SIZE) == FSMC_ECCPageSize_256Bytes) || \
((SIZE) == FSMC_ECCPageSize_512Bytes) || \
((SIZE) == FSMC_ECCPageSize_1024Bytes) || \
((SIZE) == FSMC_ECCPageSize_2048Bytes) || \
((SIZE) == FSMC_ECCPageSize_4096Bytes) || \
((SIZE) == FSMC_ECCPageSize_8192Bytes))
/**
* @}
*/
/** @defgroup FSMC_TCLR_Setup_Time
* @{
*/
#define IS_FSMC_TCLR_TIME(TIME) ((TIME) <= 0xFF)
/**
* @}
*/
/** @defgroup FSMC_TAR_Setup_Time
* @{
*/
#define IS_FSMC_TAR_TIME(TIME) ((TIME) <= 0xFF)
/**
* @}
*/
/** @defgroup FSMC_Setup_Time
* @{
*/
#define IS_FSMC_SETUP_TIME(TIME) ((TIME) <= 0xFF)
/**
* @}
*/
/** @defgroup FSMC_Wait_Setup_Time
* @{
*/
#define IS_FSMC_WAIT_TIME(TIME) ((TIME) <= 0xFF)
/**
* @}
*/
/** @defgroup FSMC_Hold_Setup_Time
* @{
*/
#define IS_FSMC_HOLD_TIME(TIME) ((TIME) <= 0xFF)
/**
* @}
*/
/** @defgroup FSMC_HiZ_Setup_Time
* @{
*/
#define IS_FSMC_HIZ_TIME(TIME) ((TIME) <= 0xFF)
/**
* @}
*/
/** @defgroup FSMC_Interrupt_sources
* @{
*/
#define FSMC_IT_RisingEdge ((uint32_t)0x00000008)
#define FSMC_IT_Level ((uint32_t)0x00000010)
#define FSMC_IT_FallingEdge ((uint32_t)0x00000020)
#define IS_FSMC_IT(IT) ((((IT) & (uint32_t)0xFFFFFFC7) == 0x00000000) && ((IT) != 0x00000000))
#define IS_FSMC_GET_IT(IT) (((IT) == FSMC_IT_RisingEdge) || \
((IT) == FSMC_IT_Level) || \
((IT) == FSMC_IT_FallingEdge))
/**
* @}
*/
/** @defgroup FSMC_Flags
* @{
*/
#define FSMC_FLAG_RisingEdge ((uint32_t)0x00000001)
#define FSMC_FLAG_Level ((uint32_t)0x00000002)
#define FSMC_FLAG_FallingEdge ((uint32_t)0x00000004)
#define FSMC_FLAG_FEMPT ((uint32_t)0x00000040)
#define IS_FSMC_GET_FLAG(FLAG) (((FLAG) == FSMC_FLAG_RisingEdge) || \
((FLAG) == FSMC_FLAG_Level) || \
((FLAG) == FSMC_FLAG_FallingEdge) || \
((FLAG) == FSMC_FLAG_FEMPT))
#define IS_FSMC_CLEAR_FLAG(FLAG) ((((FLAG) & (uint32_t)0xFFFFFFF8) == 0x00000000) && ((FLAG) != 0x00000000))
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/** @defgroup FSMC_Exported_Macros
* @{
*/
/**
* @}
*/
/** @defgroup FSMC_Exported_Functions
* @{
*/
void FSMC_NORSRAMDeInit(uint32_t FSMC_Bank);
void FSMC_NANDDeInit(uint32_t FSMC_Bank);
void FSMC_PCCARDDeInit(void);
void FSMC_NORSRAMInit(FSMC_NORSRAMInitTypeDef* FSMC_NORSRAMInitStruct);
void FSMC_NANDInit(FSMC_NANDInitTypeDef* FSMC_NANDInitStruct);
void FSMC_PCCARDInit(FSMC_PCCARDInitTypeDef* FSMC_PCCARDInitStruct);
void FSMC_NORSRAMStructInit(FSMC_NORSRAMInitTypeDef* FSMC_NORSRAMInitStruct);
void FSMC_NANDStructInit(FSMC_NANDInitTypeDef* FSMC_NANDInitStruct);
void FSMC_PCCARDStructInit(FSMC_PCCARDInitTypeDef* FSMC_PCCARDInitStruct);
void FSMC_NORSRAMCmd(uint32_t FSMC_Bank, FunctionalState NewState);
void FSMC_NANDCmd(uint32_t FSMC_Bank, FunctionalState NewState);
void FSMC_PCCARDCmd(FunctionalState NewState);
void FSMC_NANDECCCmd(uint32_t FSMC_Bank, FunctionalState NewState);
uint32_t FSMC_GetECC(uint32_t FSMC_Bank);
void FSMC_ITConfig(uint32_t FSMC_Bank, uint32_t FSMC_IT, FunctionalState NewState);
FlagStatus FSMC_GetFlagStatus(uint32_t FSMC_Bank, uint32_t FSMC_FLAG);
void FSMC_ClearFlag(uint32_t FSMC_Bank, uint32_t FSMC_FLAG);
ITStatus FSMC_GetITStatus(uint32_t FSMC_Bank, uint32_t FSMC_IT);
void FSMC_ClearITPendingBit(uint32_t FSMC_Bank, uint32_t FSMC_IT);
#ifdef __cplusplus
}
#endif
#endif /*__STM32F10x_FSMC_H */
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/

View File

@ -1,388 +0,0 @@
/**
******************************************************************************
* @file stm32f10x_gpio.h
* @author MCD Application Team
* @version V3.5.0
* @date 11-March-2011
* @brief This file contains all the functions prototypes for the GPIO
* firmware library.
******************************************************************************
* @attention
*
* 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, STMICROELECTRONICS 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 2011 STMicroelectronics</center></h2>
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32F10x_GPIO_H
#define __STM32F10x_GPIO_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32f10x.h"
/** @addtogroup STM32F10x_StdPeriph_Driver
* @{
*/
/** @addtogroup GPIO
* @{
*/
/** @defgroup GPIO_Exported_Types
* @{
*/
#define IS_GPIO_ALL_PERIPH(PERIPH) (((PERIPH) == GPIOA) || \
((PERIPH) == GPIOB) || \
((PERIPH) == GPIOC) || \
((PERIPH) == GPIOD) || \
((PERIPH) == GPIOE) || \
((PERIPH) == GPIOF) || \
((PERIPH) == GPIOG))
/**
* @brief Output Maximum frequency selection
*/
typedef enum
{
GPIO_Speed_10MHz = 1,
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
*/
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
}GPIOMode_TypeDef;
#define IS_GPIO_MODE(MODE) (((MODE) == GPIO_Mode_AIN) || ((MODE) == GPIO_Mode_IN_FLOATING) || \
((MODE) == GPIO_Mode_IPD) || ((MODE) == GPIO_Mode_IPU) || \
((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
*/
typedef struct
{
uint16_t GPIO_Pin; /*!< Specifies the GPIO pins to be configured.
This parameter can be any value of @ref GPIO_pins_define */
GPIOSpeed_TypeDef GPIO_Speed; /*!< Specifies the speed for the selected pins.
This parameter can be a value of @ref GPIOSpeed_TypeDef */
GPIOMode_TypeDef GPIO_Mode; /*!< Specifies the operating mode for the selected pins.
This parameter can be a value of @ref GPIOMode_TypeDef */
}GPIO_InitTypeDef;
/**
* @brief Bit_SET and Bit_RESET enumeration
*/
typedef enum
{ Bit_RESET = 0,
Bit_SET
}BitAction;
#define IS_GPIO_BIT_ACTION(ACTION) (((ACTION) == Bit_RESET) || ((ACTION) == Bit_SET))
/**
* @}
*/
/** @defgroup GPIO_Exported_Constants
* @{
*/
/** @defgroup GPIO_pins_define
* @{
*/
#define GPIO_Pin_0 ((uint16_t)0x0001) /*!< Pin 0 selected */
#define GPIO_Pin_1 ((uint16_t)0x0002) /*!< Pin 1 selected */
#define GPIO_Pin_2 ((uint16_t)0x0004) /*!< Pin 2 selected */
#define GPIO_Pin_3 ((uint16_t)0x0008) /*!< Pin 3 selected */
#define GPIO_Pin_4 ((uint16_t)0x0010) /*!< Pin 4 selected */
#define GPIO_Pin_5 ((uint16_t)0x0020) /*!< Pin 5 selected */
#define GPIO_Pin_6 ((uint16_t)0x0040) /*!< Pin 6 selected */
#define GPIO_Pin_7 ((uint16_t)0x0080) /*!< Pin 7 selected */
#define GPIO_Pin_8 ((uint16_t)0x0100) /*!< Pin 8 selected */
#define GPIO_Pin_9 ((uint16_t)0x0200) /*!< Pin 9 selected */
#define GPIO_Pin_10 ((uint16_t)0x0400) /*!< Pin 10 selected */
#define GPIO_Pin_11 ((uint16_t)0x0800) /*!< Pin 11 selected */
#define GPIO_Pin_12 ((uint16_t)0x1000) /*!< Pin 12 selected */
#define GPIO_Pin_13 ((uint16_t)0x2000) /*!< Pin 13 selected */
#define GPIO_Pin_14 ((uint16_t)0x4000) /*!< Pin 14 selected */
#define GPIO_Pin_15 ((uint16_t)0x8000) /*!< Pin 15 selected */
#define GPIO_Pin_All ((uint16_t)0xFFFF) /*!< All pins selected */
#define IS_GPIO_PIN(PIN) ((((PIN) & (uint16_t)0x00) == 0x00) && ((PIN) != (uint16_t)0x00))
#define IS_GET_GPIO_PIN(PIN) (((PIN) == GPIO_Pin_0) || \
((PIN) == GPIO_Pin_1) || \
((PIN) == GPIO_Pin_2) || \
((PIN) == GPIO_Pin_3) || \
((PIN) == GPIO_Pin_4) || \
((PIN) == GPIO_Pin_5) || \
((PIN) == GPIO_Pin_6) || \
((PIN) == GPIO_Pin_7) || \
((PIN) == GPIO_Pin_8) || \
((PIN) == GPIO_Pin_9) || \
((PIN) == GPIO_Pin_10) || \
((PIN) == GPIO_Pin_11) || \
((PIN) == GPIO_Pin_12) || \
((PIN) == GPIO_Pin_13) || \
((PIN) == GPIO_Pin_14) || \
((PIN) == GPIO_Pin_15))
/**
* @}
*/
/** @defgroup GPIO_Remap_define
* @{
*/
#define GPIO_Remap_SPI1 ((uint32_t)0x00000001) /*!< SPI1 Alternate Function mapping */
#define GPIO_Remap_I2C1 ((uint32_t)0x00000002) /*!< I2C1 Alternate Function mapping */
#define GPIO_Remap_USART1 ((uint32_t)0x00000004) /*!< USART1 Alternate Function mapping */
#define GPIO_Remap_USART2 ((uint32_t)0x00000008) /*!< USART2 Alternate Function mapping */
#define GPIO_PartialRemap_USART3 ((uint32_t)0x00140010) /*!< USART3 Partial Alternate Function mapping */
#define GPIO_FullRemap_USART3 ((uint32_t)0x00140030) /*!< USART3 Full Alternate Function mapping */
#define GPIO_PartialRemap_TIM1 ((uint32_t)0x00160040) /*!< TIM1 Partial Alternate Function mapping */
#define GPIO_FullRemap_TIM1 ((uint32_t)0x001600C0) /*!< TIM1 Full Alternate Function mapping */
#define GPIO_PartialRemap1_TIM2 ((uint32_t)0x00180100) /*!< TIM2 Partial1 Alternate Function mapping */
#define GPIO_PartialRemap2_TIM2 ((uint32_t)0x00180200) /*!< TIM2 Partial2 Alternate Function mapping */
#define GPIO_FullRemap_TIM2 ((uint32_t)0x00180300) /*!< TIM2 Full Alternate Function mapping */
#define GPIO_PartialRemap_TIM3 ((uint32_t)0x001A0800) /*!< TIM3 Partial Alternate Function mapping */
#define GPIO_FullRemap_TIM3 ((uint32_t)0x001A0C00) /*!< TIM3 Full Alternate Function mapping */
#define GPIO_Remap_TIM4 ((uint32_t)0x00001000) /*!< TIM4 Alternate Function mapping */
#define GPIO_Remap1_CAN1 ((uint32_t)0x001D4000) /*!< CAN1 Alternate Function mapping */
#define GPIO_Remap2_CAN1 ((uint32_t)0x001D6000) /*!< CAN1 Alternate Function mapping */
#define GPIO_Remap_PD01 ((uint32_t)0x00008000) /*!< PD01 Alternate Function mapping */
#define GPIO_Remap_TIM5CH4_LSI ((uint32_t)0x00200001) /*!< LSI connected to TIM5 Channel4 input capture for calibration */
#define GPIO_Remap_ADC1_ETRGINJ ((uint32_t)0x00200002) /*!< ADC1 External Trigger Injected Conversion remapping */
#define GPIO_Remap_ADC1_ETRGREG ((uint32_t)0x00200004) /*!< ADC1 External Trigger Regular Conversion remapping */
#define GPIO_Remap_ADC2_ETRGINJ ((uint32_t)0x00200008) /*!< ADC2 External Trigger Injected Conversion remapping */
#define GPIO_Remap_ADC2_ETRGREG ((uint32_t)0x00200010) /*!< ADC2 External Trigger Regular Conversion remapping */
#define GPIO_Remap_ETH ((uint32_t)0x00200020) /*!< Ethernet remapping (only for Connectivity line devices) */
#define GPIO_Remap_CAN2 ((uint32_t)0x00200040) /*!< CAN2 remapping (only for Connectivity line devices) */
#define GPIO_Remap_SWJ_NoJTRST ((uint32_t)0x00300100) /*!< Full SWJ Enabled (JTAG-DP + SW-DP) but without JTRST */
#define GPIO_Remap_SWJ_JTAGDisable ((uint32_t)0x00300200) /*!< JTAG-DP Disabled and SW-DP Enabled */
#define GPIO_Remap_SWJ_Disable ((uint32_t)0x00300400) /*!< Full SWJ Disabled (JTAG-DP + SW-DP) */
#define GPIO_Remap_SPI3 ((uint32_t)0x00201100) /*!< SPI3/I2S3 Alternate Function mapping (only for Connectivity line devices) */
#define GPIO_Remap_TIM2ITR1_PTP_SOF ((uint32_t)0x00202000) /*!< Ethernet PTP output or USB OTG SOF (Start of Frame) connected
to TIM2 Internal Trigger 1 for calibration
(only for Connectivity line devices) */
#define GPIO_Remap_PTP_PPS ((uint32_t)0x00204000) /*!< Ethernet MAC PPS_PTS output on PB05 (only for Connectivity line devices) */
#define GPIO_Remap_TIM15 ((uint32_t)0x80000001) /*!< TIM15 Alternate Function mapping (only for Value line devices) */
#define GPIO_Remap_TIM16 ((uint32_t)0x80000002) /*!< TIM16 Alternate Function mapping (only for Value line devices) */
#define GPIO_Remap_TIM17 ((uint32_t)0x80000004) /*!< TIM17 Alternate Function mapping (only for Value line devices) */
#define GPIO_Remap_CEC ((uint32_t)0x80000008) /*!< CEC Alternate Function mapping (only for Value line devices) */
#define GPIO_Remap_TIM1_DMA ((uint32_t)0x80000010) /*!< TIM1 DMA requests mapping (only for Value line devices) */
#define GPIO_Remap_TIM9 ((uint32_t)0x80000020) /*!< TIM9 Alternate Function mapping (only for XL-density devices) */
#define GPIO_Remap_TIM10 ((uint32_t)0x80000040) /*!< TIM10 Alternate Function mapping (only for XL-density devices) */
#define GPIO_Remap_TIM11 ((uint32_t)0x80000080) /*!< TIM11 Alternate Function mapping (only for XL-density devices) */
#define GPIO_Remap_TIM13 ((uint32_t)0x80000100) /*!< TIM13 Alternate Function mapping (only for High density Value line and XL-density devices) */
#define GPIO_Remap_TIM14 ((uint32_t)0x80000200) /*!< TIM14 Alternate Function mapping (only for High density Value line and XL-density devices) */
#define GPIO_Remap_FSMC_NADV ((uint32_t)0x80000400) /*!< FSMC_NADV Alternate Function mapping (only for High density Value line and XL-density devices) */
#define GPIO_Remap_TIM67_DAC_DMA ((uint32_t)0x80000800) /*!< TIM6/TIM7 and DAC DMA requests remapping (only for High density Value line devices) */
#define GPIO_Remap_TIM12 ((uint32_t)0x80001000) /*!< TIM12 Alternate Function mapping (only for High density Value line devices) */
#define GPIO_Remap_MISC ((uint32_t)0x80002000) /*!< Miscellaneous Remap (DMA2 Channel5 Position and DAC Trigger remapping,
only for High density Value line devices) */
#define IS_GPIO_REMAP(REMAP) (((REMAP) == GPIO_Remap_SPI1) || ((REMAP) == GPIO_Remap_I2C1) || \
((REMAP) == GPIO_Remap_USART1) || ((REMAP) == GPIO_Remap_USART2) || \
((REMAP) == GPIO_PartialRemap_USART3) || ((REMAP) == GPIO_FullRemap_USART3) || \
((REMAP) == GPIO_PartialRemap_TIM1) || ((REMAP) == GPIO_FullRemap_TIM1) || \
((REMAP) == GPIO_PartialRemap1_TIM2) || ((REMAP) == GPIO_PartialRemap2_TIM2) || \
((REMAP) == GPIO_FullRemap_TIM2) || ((REMAP) == GPIO_PartialRemap_TIM3) || \
((REMAP) == GPIO_FullRemap_TIM3) || ((REMAP) == GPIO_Remap_TIM4) || \
((REMAP) == GPIO_Remap1_CAN1) || ((REMAP) == GPIO_Remap2_CAN1) || \
((REMAP) == GPIO_Remap_PD01) || ((REMAP) == GPIO_Remap_TIM5CH4_LSI) || \
((REMAP) == GPIO_Remap_ADC1_ETRGINJ) ||((REMAP) == GPIO_Remap_ADC1_ETRGREG) || \
((REMAP) == GPIO_Remap_ADC2_ETRGINJ) ||((REMAP) == GPIO_Remap_ADC2_ETRGREG) || \
((REMAP) == GPIO_Remap_ETH) ||((REMAP) == GPIO_Remap_CAN2) || \
((REMAP) == GPIO_Remap_SWJ_NoJTRST) || ((REMAP) == GPIO_Remap_SWJ_JTAGDisable) || \
((REMAP) == GPIO_Remap_SWJ_Disable)|| ((REMAP) == GPIO_Remap_SPI3) || \
((REMAP) == GPIO_Remap_TIM2ITR1_PTP_SOF) || ((REMAP) == GPIO_Remap_PTP_PPS) || \
((REMAP) == GPIO_Remap_TIM15) || ((REMAP) == GPIO_Remap_TIM16) || \
((REMAP) == GPIO_Remap_TIM17) || ((REMAP) == GPIO_Remap_CEC) || \
((REMAP) == GPIO_Remap_TIM1_DMA) || ((REMAP) == GPIO_Remap_TIM9) || \
((REMAP) == GPIO_Remap_TIM10) || ((REMAP) == GPIO_Remap_TIM11) || \
((REMAP) == GPIO_Remap_TIM13) || ((REMAP) == GPIO_Remap_TIM14) || \
((REMAP) == GPIO_Remap_FSMC_NADV) || ((REMAP) == GPIO_Remap_TIM67_DAC_DMA) || \
((REMAP) == GPIO_Remap_TIM12) || ((REMAP) == GPIO_Remap_MISC))
/**
* @}
*/
/** @defgroup GPIO_Port_Sources
* @{
*/
#define GPIO_PortSourceGPIOA ((uint8_t)0x00)
#define GPIO_PortSourceGPIOB ((uint8_t)0x01)
#define GPIO_PortSourceGPIOC ((uint8_t)0x02)
#define GPIO_PortSourceGPIOD ((uint8_t)0x03)
#define GPIO_PortSourceGPIOE ((uint8_t)0x04)
#define GPIO_PortSourceGPIOF ((uint8_t)0x05)
#define GPIO_PortSourceGPIOG ((uint8_t)0x06)
#define IS_GPIO_EVENTOUT_PORT_SOURCE(PORTSOURCE) (((PORTSOURCE) == GPIO_PortSourceGPIOA) || \
((PORTSOURCE) == GPIO_PortSourceGPIOB) || \
((PORTSOURCE) == GPIO_PortSourceGPIOC) || \
((PORTSOURCE) == GPIO_PortSourceGPIOD) || \
((PORTSOURCE) == GPIO_PortSourceGPIOE))
#define IS_GPIO_EXTI_PORT_SOURCE(PORTSOURCE) (((PORTSOURCE) == GPIO_PortSourceGPIOA) || \
((PORTSOURCE) == GPIO_PortSourceGPIOB) || \
((PORTSOURCE) == GPIO_PortSourceGPIOC) || \
((PORTSOURCE) == GPIO_PortSourceGPIOD) || \
((PORTSOURCE) == GPIO_PortSourceGPIOE) || \
((PORTSOURCE) == GPIO_PortSourceGPIOF) || \
((PORTSOURCE) == GPIO_PortSourceGPIOG))
/**
* @}
*/
/** @defgroup GPIO_Pin_sources
* @{
*/
#define GPIO_PinSource0 ((uint8_t)0x00)
#define GPIO_PinSource1 ((uint8_t)0x01)
#define GPIO_PinSource2 ((uint8_t)0x02)
#define GPIO_PinSource3 ((uint8_t)0x03)
#define GPIO_PinSource4 ((uint8_t)0x04)
#define GPIO_PinSource5 ((uint8_t)0x05)
#define GPIO_PinSource6 ((uint8_t)0x06)
#define GPIO_PinSource7 ((uint8_t)0x07)
#define GPIO_PinSource8 ((uint8_t)0x08)
#define GPIO_PinSource9 ((uint8_t)0x09)
#define GPIO_PinSource10 ((uint8_t)0x0A)
#define GPIO_PinSource11 ((uint8_t)0x0B)
#define GPIO_PinSource12 ((uint8_t)0x0C)
#define GPIO_PinSource13 ((uint8_t)0x0D)
#define GPIO_PinSource14 ((uint8_t)0x0E)
#define GPIO_PinSource15 ((uint8_t)0x0F)
#define IS_GPIO_PIN_SOURCE(PINSOURCE) (((PINSOURCE) == GPIO_PinSource0) || \
((PINSOURCE) == GPIO_PinSource1) || \
((PINSOURCE) == GPIO_PinSource2) || \
((PINSOURCE) == GPIO_PinSource3) || \
((PINSOURCE) == GPIO_PinSource4) || \
((PINSOURCE) == GPIO_PinSource5) || \
((PINSOURCE) == GPIO_PinSource6) || \
((PINSOURCE) == GPIO_PinSource7) || \
((PINSOURCE) == GPIO_PinSource8) || \
((PINSOURCE) == GPIO_PinSource9) || \
((PINSOURCE) == GPIO_PinSource10) || \
((PINSOURCE) == GPIO_PinSource11) || \
((PINSOURCE) == GPIO_PinSource12) || \
((PINSOURCE) == GPIO_PinSource13) || \
((PINSOURCE) == GPIO_PinSource14) || \
((PINSOURCE) == GPIO_PinSource15))
/**
* @}
*/
/** @defgroup Ethernet_Media_Interface
* @{
*/
#define GPIO_ETH_MediaInterface_MII ((u32)0x00000000)
#define GPIO_ETH_MediaInterface_RMII ((u32)0x00000001)
#define IS_GPIO_ETH_MEDIA_INTERFACE(INTERFACE) (((INTERFACE) == GPIO_ETH_MediaInterface_MII) || \
((INTERFACE) == GPIO_ETH_MediaInterface_RMII))
/**
* @}
*/
/**
* @}
*/
/** @defgroup GPIO_Exported_Macros
* @{
*/
/**
* @}
*/
/** @defgroup GPIO_Exported_Functions
* @{
*/
void GPIO_DeInit(GPIO_TypeDef* GPIOx);
void GPIO_AFIODeInit(void);
void GPIO_Init(GPIO_TypeDef* GPIOx, GPIO_InitTypeDef* GPIO_InitStruct);
void GPIO_StructInit(GPIO_InitTypeDef* GPIO_InitStruct);
uint8_t GPIO_ReadInputDataBit(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin);
uint16_t GPIO_ReadInputData(GPIO_TypeDef* GPIOx);
uint8_t GPIO_ReadOutputDataBit(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin);
uint16_t GPIO_ReadOutputData(GPIO_TypeDef* GPIOx);
void GPIO_SetBits(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin);
void GPIO_ResetBits(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin);
void GPIO_WriteBit(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin, BitAction BitVal);
void GPIO_Write(GPIO_TypeDef* GPIOx, uint16_t PortVal);
void GPIO_PinLockConfig(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin);
void GPIO_EventOutputConfig(uint8_t GPIO_PortSource, uint8_t GPIO_PinSource);
void GPIO_EventOutputCmd(FunctionalState NewState);
void GPIO_PinRemapConfig(uint32_t GPIO_Remap, FunctionalState NewState);
void GPIO_EXTILineConfig(uint8_t GPIO_PortSource, uint8_t GPIO_PinSource);
void GPIO_ETH_MediaInterfaceConfig(uint32_t GPIO_ETH_MediaInterface);
void GPIO_ToggleBits(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin);
#ifdef __cplusplus
}
#endif
#endif /* __STM32F10x_GPIO_H */
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/

View File

@ -1,684 +0,0 @@
/**
******************************************************************************
* @file stm32f10x_i2c.h
* @author MCD Application Team
* @version V3.5.0
* @date 11-March-2011
* @brief This file contains all the functions prototypes for the I2C firmware
* library.
******************************************************************************
* @attention
*
* 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, STMICROELECTRONICS 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 2011 STMicroelectronics</center></h2>
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32F10x_I2C_H
#define __STM32F10x_I2C_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32f10x.h"
/** @addtogroup STM32F10x_StdPeriph_Driver
* @{
*/
/** @addtogroup I2C
* @{
*/
/** @defgroup I2C_Exported_Types
* @{
*/
/**
* @brief I2C Init structure definition
*/
typedef struct
{
uint32_t I2C_ClockSpeed; /*!< Specifies the clock frequency.
This parameter must be set to a value lower than 400kHz */
uint16_t I2C_Mode; /*!< Specifies the I2C mode.
This parameter can be a value of @ref I2C_mode */
uint16_t I2C_DutyCycle; /*!< Specifies the I2C fast mode duty cycle.
This parameter can be a value of @ref I2C_duty_cycle_in_fast_mode */
uint16_t I2C_OwnAddress1; /*!< Specifies the first device own address.
This parameter can be a 7-bit or 10-bit address. */
uint16_t I2C_Ack; /*!< Enables or disables the acknowledgement.
This parameter can be a value of @ref I2C_acknowledgement */
uint16_t I2C_AcknowledgedAddress; /*!< Specifies if 7-bit or 10-bit address is acknowledged.
This parameter can be a value of @ref I2C_acknowledged_address */
}I2C_InitTypeDef;
/**
* @}
*/
/** @defgroup I2C_Exported_Constants
* @{
*/
#define IS_I2C_ALL_PERIPH(PERIPH) (((PERIPH) == I2C1) || \
((PERIPH) == I2C2))
/** @defgroup I2C_mode
* @{
*/
#define I2C_Mode_I2C ((uint16_t)0x0000)
#define I2C_Mode_SMBusDevice ((uint16_t)0x0002)
#define I2C_Mode_SMBusHost ((uint16_t)0x000A)
#define IS_I2C_MODE(MODE) (((MODE) == I2C_Mode_I2C) || \
((MODE) == I2C_Mode_SMBusDevice) || \
((MODE) == I2C_Mode_SMBusHost))
/**
* @}
*/
/** @defgroup I2C_duty_cycle_in_fast_mode
* @{
*/
#define I2C_DutyCycle_16_9 ((uint16_t)0x4000) /*!< I2C fast mode Tlow/Thigh = 16/9 */
#define I2C_DutyCycle_2 ((uint16_t)0xBFFF) /*!< I2C fast mode Tlow/Thigh = 2 */
#define IS_I2C_DUTY_CYCLE(CYCLE) (((CYCLE) == I2C_DutyCycle_16_9) || \
((CYCLE) == I2C_DutyCycle_2))
/**
* @}
*/
/** @defgroup I2C_acknowledgement
* @{
*/
#define I2C_Ack_Enable ((uint16_t)0x0400)
#define I2C_Ack_Disable ((uint16_t)0x0000)
#define IS_I2C_ACK_STATE(STATE) (((STATE) == I2C_Ack_Enable) || \
((STATE) == I2C_Ack_Disable))
/**
* @}
*/
/** @defgroup I2C_transfer_direction
* @{
*/
#define I2C_Direction_Transmitter ((uint8_t)0x00)
#define I2C_Direction_Receiver ((uint8_t)0x01)
#define IS_I2C_DIRECTION(DIRECTION) (((DIRECTION) == I2C_Direction_Transmitter) || \
((DIRECTION) == I2C_Direction_Receiver))
/**
* @}
*/
/** @defgroup I2C_acknowledged_address
* @{
*/
#define I2C_AcknowledgedAddress_7bit ((uint16_t)0x4000)
#define I2C_AcknowledgedAddress_10bit ((uint16_t)0xC000)
#define IS_I2C_ACKNOWLEDGE_ADDRESS(ADDRESS) (((ADDRESS) == I2C_AcknowledgedAddress_7bit) || \
((ADDRESS) == I2C_AcknowledgedAddress_10bit))
/**
* @}
*/
/** @defgroup I2C_registers
* @{
*/
#define I2C_Register_CR1 ((uint8_t)0x00)
#define I2C_Register_CR2 ((uint8_t)0x04)
#define I2C_Register_OAR1 ((uint8_t)0x08)
#define I2C_Register_OAR2 ((uint8_t)0x0C)
#define I2C_Register_DR ((uint8_t)0x10)
#define I2C_Register_SR1 ((uint8_t)0x14)
#define I2C_Register_SR2 ((uint8_t)0x18)
#define I2C_Register_CCR ((uint8_t)0x1C)
#define I2C_Register_TRISE ((uint8_t)0x20)
#define IS_I2C_REGISTER(REGISTER) (((REGISTER) == I2C_Register_CR1) || \
((REGISTER) == I2C_Register_CR2) || \
((REGISTER) == I2C_Register_OAR1) || \
((REGISTER) == I2C_Register_OAR2) || \
((REGISTER) == I2C_Register_DR) || \
((REGISTER) == I2C_Register_SR1) || \
((REGISTER) == I2C_Register_SR2) || \
((REGISTER) == I2C_Register_CCR) || \
((REGISTER) == I2C_Register_TRISE))
/**
* @}
*/
/** @defgroup I2C_SMBus_alert_pin_level
* @{
*/
#define I2C_SMBusAlert_Low ((uint16_t)0x2000)
#define I2C_SMBusAlert_High ((uint16_t)0xDFFF)
#define IS_I2C_SMBUS_ALERT(ALERT) (((ALERT) == I2C_SMBusAlert_Low) || \
((ALERT) == I2C_SMBusAlert_High))
/**
* @}
*/
/** @defgroup I2C_PEC_position
* @{
*/
#define I2C_PECPosition_Next ((uint16_t)0x0800)
#define I2C_PECPosition_Current ((uint16_t)0xF7FF)
#define IS_I2C_PEC_POSITION(POSITION) (((POSITION) == I2C_PECPosition_Next) || \
((POSITION) == I2C_PECPosition_Current))
/**
* @}
*/
/** @defgroup I2C_NCAK_position
* @{
*/
#define I2C_NACKPosition_Next ((uint16_t)0x0800)
#define I2C_NACKPosition_Current ((uint16_t)0xF7FF)
#define IS_I2C_NACK_POSITION(POSITION) (((POSITION) == I2C_NACKPosition_Next) || \
((POSITION) == I2C_NACKPosition_Current))
/**
* @}
*/
/** @defgroup I2C_interrupts_definition
* @{
*/
#define I2C_IT_BUF ((uint16_t)0x0400)
#define I2C_IT_EVT ((uint16_t)0x0200)
#define I2C_IT_ERR ((uint16_t)0x0100)
#define IS_I2C_CONFIG_IT(IT) ((((IT) & (uint16_t)0xF8FF) == 0x00) && ((IT) != 0x00))
/**
* @}
*/
/** @defgroup I2C_interrupts_definition
* @{
*/
#define I2C_IT_SMBALERT ((uint32_t)0x01008000)
#define I2C_IT_TIMEOUT ((uint32_t)0x01004000)
#define I2C_IT_PECERR ((uint32_t)0x01001000)
#define I2C_IT_OVR ((uint32_t)0x01000800)
#define I2C_IT_AF ((uint32_t)0x01000400)
#define I2C_IT_ARLO ((uint32_t)0x01000200)
#define I2C_IT_BERR ((uint32_t)0x01000100)
#define I2C_IT_TXE ((uint32_t)0x06000080)
#define I2C_IT_RXNE ((uint32_t)0x06000040)
#define I2C_IT_STOPF ((uint32_t)0x02000010)
#define I2C_IT_ADD10 ((uint32_t)0x02000008)
#define I2C_IT_BTF ((uint32_t)0x02000004)
#define I2C_IT_ADDR ((uint32_t)0x02000002)
#define I2C_IT_SB ((uint32_t)0x02000001)
#define IS_I2C_CLEAR_IT(IT) ((((IT) & (uint16_t)0x20FF) == 0x00) && ((IT) != (uint16_t)0x00))
#define IS_I2C_GET_IT(IT) (((IT) == I2C_IT_SMBALERT) || ((IT) == I2C_IT_TIMEOUT) || \
((IT) == I2C_IT_PECERR) || ((IT) == I2C_IT_OVR) || \
((IT) == I2C_IT_AF) || ((IT) == I2C_IT_ARLO) || \
((IT) == I2C_IT_BERR) || ((IT) == I2C_IT_TXE) || \
((IT) == I2C_IT_RXNE) || ((IT) == I2C_IT_STOPF) || \
((IT) == I2C_IT_ADD10) || ((IT) == I2C_IT_BTF) || \
((IT) == I2C_IT_ADDR) || ((IT) == I2C_IT_SB))
/**
* @}
*/
/** @defgroup I2C_flags_definition
* @{
*/
/**
* @brief SR2 register flags
*/
#define I2C_FLAG_DUALF ((uint32_t)0x00800000)
#define I2C_FLAG_SMBHOST ((uint32_t)0x00400000)
#define I2C_FLAG_SMBDEFAULT ((uint32_t)0x00200000)
#define I2C_FLAG_GENCALL ((uint32_t)0x00100000)
#define I2C_FLAG_TRA ((uint32_t)0x00040000)
#define I2C_FLAG_BUSY ((uint32_t)0x00020000)
#define I2C_FLAG_MSL ((uint32_t)0x00010000)
/**
* @brief SR1 register flags
*/
#define I2C_FLAG_SMBALERT ((uint32_t)0x10008000)
#define I2C_FLAG_TIMEOUT ((uint32_t)0x10004000)
#define I2C_FLAG_PECERR ((uint32_t)0x10001000)
#define I2C_FLAG_OVR ((uint32_t)0x10000800)
#define I2C_FLAG_AF ((uint32_t)0x10000400)
#define I2C_FLAG_ARLO ((uint32_t)0x10000200)
#define I2C_FLAG_BERR ((uint32_t)0x10000100)
#define I2C_FLAG_TXE ((uint32_t)0x10000080)
#define I2C_FLAG_RXNE ((uint32_t)0x10000040)
#define I2C_FLAG_STOPF ((uint32_t)0x10000010)
#define I2C_FLAG_ADD10 ((uint32_t)0x10000008)
#define I2C_FLAG_BTF ((uint32_t)0x10000004)
#define I2C_FLAG_ADDR ((uint32_t)0x10000002)
#define I2C_FLAG_SB ((uint32_t)0x10000001)
#define IS_I2C_CLEAR_FLAG(FLAG) ((((FLAG) & (uint16_t)0x20FF) == 0x00) && ((FLAG) != (uint16_t)0x00))
#define IS_I2C_GET_FLAG(FLAG) (((FLAG) == I2C_FLAG_DUALF) || ((FLAG) == I2C_FLAG_SMBHOST) || \
((FLAG) == I2C_FLAG_SMBDEFAULT) || ((FLAG) == I2C_FLAG_GENCALL) || \
((FLAG) == I2C_FLAG_TRA) || ((FLAG) == I2C_FLAG_BUSY) || \
((FLAG) == I2C_FLAG_MSL) || ((FLAG) == I2C_FLAG_SMBALERT) || \
((FLAG) == I2C_FLAG_TIMEOUT) || ((FLAG) == I2C_FLAG_PECERR) || \
((FLAG) == I2C_FLAG_OVR) || ((FLAG) == I2C_FLAG_AF) || \
((FLAG) == I2C_FLAG_ARLO) || ((FLAG) == I2C_FLAG_BERR) || \
((FLAG) == I2C_FLAG_TXE) || ((FLAG) == I2C_FLAG_RXNE) || \
((FLAG) == I2C_FLAG_STOPF) || ((FLAG) == I2C_FLAG_ADD10) || \
((FLAG) == I2C_FLAG_BTF) || ((FLAG) == I2C_FLAG_ADDR) || \
((FLAG) == I2C_FLAG_SB))
/**
* @}
*/
/** @defgroup I2C_Events
* @{
*/
/*========================================
I2C Master Events (Events grouped in order of communication)
==========================================*/
/**
* @brief Communication start
*
* After sending the START condition (I2C_GenerateSTART() function) the master
* has to wait for this event. It means that the Start condition has been correctly
* released on the I2C bus (the bus is free, no other devices is communicating).
*
*/
/* --EV5 */
#define I2C_EVENT_MASTER_MODE_SELECT ((uint32_t)0x00030001) /* BUSY, MSL and SB flag */
/**
* @brief Address Acknowledge
*
* After checking on EV5 (start condition correctly released on the bus), the
* master sends the address of the slave(s) with which it will communicate
* (I2C_Send7bitAddress() function, it also determines the direction of the communication:
* Master transmitter or Receiver). Then the master has to wait that a slave acknowledges
* his address. If an acknowledge is sent on the bus, one of the following events will
* be set:
*
* 1) In case of Master Receiver (7-bit addressing): the I2C_EVENT_MASTER_RECEIVER_MODE_SELECTED
* event is set.
*
* 2) In case of Master Transmitter (7-bit addressing): the I2C_EVENT_MASTER_TRANSMITTER_MODE_SELECTED
* is set
*
* 3) In case of 10-Bit addressing mode, the master (just after generating the START
* and checking on EV5) has to send the header of 10-bit addressing mode (I2C_SendData()
* function). Then master should wait on EV9. It means that the 10-bit addressing
* header has been correctly sent on the bus. Then master should send the second part of
* the 10-bit address (LSB) using the function I2C_Send7bitAddress(). Then master
* should wait for event EV6.
*
*/
/* --EV6 */
#define I2C_EVENT_MASTER_TRANSMITTER_MODE_SELECTED ((uint32_t)0x00070082) /* BUSY, MSL, ADDR, TXE and TRA flags */
#define I2C_EVENT_MASTER_RECEIVER_MODE_SELECTED ((uint32_t)0x00030002) /* BUSY, MSL and ADDR flags */
/* --EV9 */
#define I2C_EVENT_MASTER_MODE_ADDRESS10 ((uint32_t)0x00030008) /* BUSY, MSL and ADD10 flags */
/**
* @brief Communication events
*
* If a communication is established (START condition generated and slave address
* acknowledged) then the master has to check on one of the following events for
* communication procedures:
*
* 1) Master Receiver mode: The master has to wait on the event EV7 then to read
* the data received from the slave (I2C_ReceiveData() function).
*
* 2) Master Transmitter mode: The master has to send data (I2C_SendData()
* function) then to wait on event EV8 or EV8_2.
* These two events are similar:
* - EV8 means that the data has been written in the data register and is
* being shifted out.
* - EV8_2 means that the data has been physically shifted out and output
* on the bus.
* In most cases, using EV8 is sufficient for the application.
* Using EV8_2 leads to a slower communication but ensure more reliable test.
* EV8_2 is also more suitable than EV8 for testing on the last data transmission
* (before Stop condition generation).
*
* @note In case the user software does not guarantee that this event EV7 is
* managed before the current byte end of transfer, then user may check on EV7
* and BTF flag at the same time (ie. (I2C_EVENT_MASTER_BYTE_RECEIVED | I2C_FLAG_BTF)).
* In this case the communication may be slower.
*
*/
/* Master RECEIVER mode -----------------------------*/
/* --EV7 */
#define I2C_EVENT_MASTER_BYTE_RECEIVED ((uint32_t)0x00030040) /* BUSY, MSL and RXNE flags */
/* Master TRANSMITTER mode --------------------------*/
/* --EV8 */
#define I2C_EVENT_MASTER_BYTE_TRANSMITTING ((uint32_t)0x00070080) /* TRA, BUSY, MSL, TXE flags */
/* --EV8_2 */
#define I2C_EVENT_MASTER_BYTE_TRANSMITTED ((uint32_t)0x00070084) /* TRA, BUSY, MSL, TXE and BTF flags */
/*========================================
I2C Slave Events (Events grouped in order of communication)
==========================================*/
/**
* @brief Communication start events
*
* Wait on one of these events at the start of the communication. It means that
* the I2C peripheral detected a Start condition on the bus (generated by master
* device) followed by the peripheral address. The peripheral generates an ACK
* condition on the bus (if the acknowledge feature is enabled through function
* I2C_AcknowledgeConfig()) and the events listed above are set :
*
* 1) In normal case (only one address managed by the slave), when the address
* sent by the master matches the own address of the peripheral (configured by
* I2C_OwnAddress1 field) the I2C_EVENT_SLAVE_XXX_ADDRESS_MATCHED event is set
* (where XXX could be TRANSMITTER or RECEIVER).
*
* 2) In case the address sent by the master matches the second address of the
* peripheral (configured by the function I2C_OwnAddress2Config() and enabled
* by the function I2C_DualAddressCmd()) the events I2C_EVENT_SLAVE_XXX_SECONDADDRESS_MATCHED
* (where XXX could be TRANSMITTER or RECEIVER) are set.
*
* 3) In case the address sent by the master is General Call (address 0x00) and
* if the General Call is enabled for the peripheral (using function I2C_GeneralCallCmd())
* the following event is set I2C_EVENT_SLAVE_GENERALCALLADDRESS_MATCHED.
*
*/
/* --EV1 (all the events below are variants of EV1) */
/* 1) Case of One Single Address managed by the slave */
#define I2C_EVENT_SLAVE_RECEIVER_ADDRESS_MATCHED ((uint32_t)0x00020002) /* BUSY and ADDR flags */
#define I2C_EVENT_SLAVE_TRANSMITTER_ADDRESS_MATCHED ((uint32_t)0x00060082) /* TRA, BUSY, TXE and ADDR flags */
/* 2) Case of Dual address managed by the slave */
#define I2C_EVENT_SLAVE_RECEIVER_SECONDADDRESS_MATCHED ((uint32_t)0x00820000) /* DUALF and BUSY flags */
#define I2C_EVENT_SLAVE_TRANSMITTER_SECONDADDRESS_MATCHED ((uint32_t)0x00860080) /* DUALF, TRA, BUSY and TXE flags */
/* 3) Case of General Call enabled for the slave */
#define I2C_EVENT_SLAVE_GENERALCALLADDRESS_MATCHED ((uint32_t)0x00120000) /* GENCALL and BUSY flags */
/**
* @brief Communication events
*
* Wait on one of these events when EV1 has already been checked and:
*
* - Slave RECEIVER mode:
* - EV2: When the application is expecting a data byte to be received.
* - EV4: When the application is expecting the end of the communication: master
* sends a stop condition and data transmission is stopped.
*
* - Slave Transmitter mode:
* - EV3: When a byte has been transmitted by the slave and the application is expecting
* the end of the byte transmission. The two events I2C_EVENT_SLAVE_BYTE_TRANSMITTED and
* I2C_EVENT_SLAVE_BYTE_TRANSMITTING are similar. The second one can optionally be
* used when the user software doesn't guarantee the EV3 is managed before the
* current byte end of transfer.
* - EV3_2: When the master sends a NACK in order to tell slave that data transmission
* shall end (before sending the STOP condition). In this case slave has to stop sending
* data bytes and expect a Stop condition on the bus.
*
* @note In case the user software does not guarantee that the event EV2 is
* managed before the current byte end of transfer, then user may check on EV2
* and BTF flag at the same time (ie. (I2C_EVENT_SLAVE_BYTE_RECEIVED | I2C_FLAG_BTF)).
* In this case the communication may be slower.
*
*/
/* Slave RECEIVER mode --------------------------*/
/* --EV2 */
#define I2C_EVENT_SLAVE_BYTE_RECEIVED ((uint32_t)0x00020040) /* BUSY and RXNE flags */
/* --EV4 */
#define I2C_EVENT_SLAVE_STOP_DETECTED ((uint32_t)0x00000010) /* STOPF flag */
/* Slave TRANSMITTER mode -----------------------*/
/* --EV3 */
#define I2C_EVENT_SLAVE_BYTE_TRANSMITTED ((uint32_t)0x00060084) /* TRA, BUSY, TXE and BTF flags */
#define I2C_EVENT_SLAVE_BYTE_TRANSMITTING ((uint32_t)0x00060080) /* TRA, BUSY and TXE flags */
/* --EV3_2 */
#define I2C_EVENT_SLAVE_ACK_FAILURE ((uint32_t)0x00000400) /* AF flag */
/*=========================== End of Events Description ==========================================*/
#define IS_I2C_EVENT(EVENT) (((EVENT) == I2C_EVENT_SLAVE_TRANSMITTER_ADDRESS_MATCHED) || \
((EVENT) == I2C_EVENT_SLAVE_RECEIVER_ADDRESS_MATCHED) || \
((EVENT) == I2C_EVENT_SLAVE_TRANSMITTER_SECONDADDRESS_MATCHED) || \
((EVENT) == I2C_EVENT_SLAVE_RECEIVER_SECONDADDRESS_MATCHED) || \
((EVENT) == I2C_EVENT_SLAVE_GENERALCALLADDRESS_MATCHED) || \
((EVENT) == I2C_EVENT_SLAVE_BYTE_RECEIVED) || \
((EVENT) == (I2C_EVENT_SLAVE_BYTE_RECEIVED | I2C_FLAG_DUALF)) || \
((EVENT) == (I2C_EVENT_SLAVE_BYTE_RECEIVED | I2C_FLAG_GENCALL)) || \
((EVENT) == I2C_EVENT_SLAVE_BYTE_TRANSMITTED) || \
((EVENT) == (I2C_EVENT_SLAVE_BYTE_TRANSMITTED | I2C_FLAG_DUALF)) || \
((EVENT) == (I2C_EVENT_SLAVE_BYTE_TRANSMITTED | I2C_FLAG_GENCALL)) || \
((EVENT) == I2C_EVENT_SLAVE_STOP_DETECTED) || \
((EVENT) == I2C_EVENT_MASTER_MODE_SELECT) || \
((EVENT) == I2C_EVENT_MASTER_TRANSMITTER_MODE_SELECTED) || \
((EVENT) == I2C_EVENT_MASTER_RECEIVER_MODE_SELECTED) || \
((EVENT) == I2C_EVENT_MASTER_BYTE_RECEIVED) || \
((EVENT) == I2C_EVENT_MASTER_BYTE_TRANSMITTED) || \
((EVENT) == I2C_EVENT_MASTER_BYTE_TRANSMITTING) || \
((EVENT) == I2C_EVENT_MASTER_MODE_ADDRESS10) || \
((EVENT) == I2C_EVENT_SLAVE_ACK_FAILURE))
/**
* @}
*/
/** @defgroup I2C_own_address1
* @{
*/
#define IS_I2C_OWN_ADDRESS1(ADDRESS1) ((ADDRESS1) <= 0x3FF)
/**
* @}
*/
/** @defgroup I2C_clock_speed
* @{
*/
#define IS_I2C_CLOCK_SPEED(SPEED) (((SPEED) >= 0x1) && ((SPEED) <= 400000))
/**
* @}
*/
/**
* @}
*/
/** @defgroup I2C_Exported_Macros
* @{
*/
/**
* @}
*/
/** @defgroup I2C_Exported_Functions
* @{
*/
void I2C_DeInit(I2C_TypeDef* I2Cx);
void I2C_Init(I2C_TypeDef* I2Cx, I2C_InitTypeDef* I2C_InitStruct);
void I2C_StructInit(I2C_InitTypeDef* I2C_InitStruct);
void I2C_Cmd(I2C_TypeDef* I2Cx, FunctionalState NewState);
void I2C_DMACmd(I2C_TypeDef* I2Cx, FunctionalState NewState);
void I2C_DMALastTransferCmd(I2C_TypeDef* I2Cx, FunctionalState NewState);
void I2C_GenerateSTART(I2C_TypeDef* I2Cx, FunctionalState NewState);
void I2C_GenerateSTOP(I2C_TypeDef* I2Cx, FunctionalState NewState);
void I2C_AcknowledgeConfig(I2C_TypeDef* I2Cx, FunctionalState NewState);
void I2C_OwnAddress2Config(I2C_TypeDef* I2Cx, uint8_t Address);
void I2C_DualAddressCmd(I2C_TypeDef* I2Cx, FunctionalState NewState);
void I2C_GeneralCallCmd(I2C_TypeDef* I2Cx, FunctionalState NewState);
void I2C_ITConfig(I2C_TypeDef* I2Cx, uint16_t I2C_IT, FunctionalState NewState);
void I2C_SendData(I2C_TypeDef* I2Cx, uint8_t Data);
uint8_t I2C_ReceiveData(I2C_TypeDef* I2Cx);
void I2C_Send7bitAddress(I2C_TypeDef* I2Cx, uint8_t Address, uint8_t I2C_Direction);
uint16_t I2C_ReadRegister(I2C_TypeDef* I2Cx, uint8_t I2C_Register);
void I2C_SoftwareResetCmd(I2C_TypeDef* I2Cx, FunctionalState NewState);
void I2C_NACKPositionConfig(I2C_TypeDef* I2Cx, uint16_t I2C_NACKPosition);
void I2C_SMBusAlertConfig(I2C_TypeDef* I2Cx, uint16_t I2C_SMBusAlert);
void I2C_TransmitPEC(I2C_TypeDef* I2Cx, FunctionalState NewState);
void I2C_PECPositionConfig(I2C_TypeDef* I2Cx, uint16_t I2C_PECPosition);
void I2C_CalculatePEC(I2C_TypeDef* I2Cx, FunctionalState NewState);
uint8_t I2C_GetPEC(I2C_TypeDef* I2Cx);
void I2C_ARPCmd(I2C_TypeDef* I2Cx, FunctionalState NewState);
void I2C_StretchClockCmd(I2C_TypeDef* I2Cx, FunctionalState NewState);
void I2C_FastModeDutyCycleConfig(I2C_TypeDef* I2Cx, uint16_t I2C_DutyCycle);
/**
* @brief
****************************************************************************************
*
* I2C State Monitoring Functions
*
****************************************************************************************
* This I2C driver provides three different ways for I2C state monitoring
* depending on the application requirements and constraints:
*
*
* 1) Basic state monitoring:
* Using I2C_CheckEvent() function:
* It compares the status registers (SR1 and SR2) content to a given event
* (can be the combination of one or more flags).
* It returns SUCCESS if the current status includes the given flags
* and returns ERROR if one or more flags are missing in the current status.
* - When to use:
* - This function is suitable for most applications as well as for startup
* activity since the events are fully described in the product reference manual
* (RM0008).
* - It is also suitable for users who need to define their own events.
* - Limitations:
* - If an error occurs (ie. error flags are set besides to the monitored flags),
* the I2C_CheckEvent() function may return SUCCESS despite the communication
* hold or corrupted real state.
* In this case, it is advised to use error interrupts to monitor the error
* events and handle them in the interrupt IRQ handler.
*
* @note
* For error management, it is advised to use the following functions:
* - I2C_ITConfig() to configure and enable the error interrupts (I2C_IT_ERR).
* - I2Cx_ER_IRQHandler() which is called when the error interrupt occurs.
* Where x is the peripheral instance (I2C1, I2C2 ...)
* - I2C_GetFlagStatus() or I2C_GetITStatus() to be called into I2Cx_ER_IRQHandler()
* in order to determine which error occurred.
* - I2C_ClearFlag() or I2C_ClearITPendingBit() and/or I2C_SoftwareResetCmd()
* and/or I2C_GenerateStop() in order to clear the error flag and source,
* and return to correct communication status.
*
*
* 2) Advanced state monitoring:
* Using the function I2C_GetLastEvent() which returns the image of both status
* registers in a single word (uint32_t) (Status Register 2 value is shifted left
* by 16 bits and concatenated to Status Register 1).
* - When to use:
* - This function is suitable for the same applications above but it allows to
* overcome the limitations of I2C_GetFlagStatus() function (see below).
* The returned value could be compared to events already defined in the
* library (stm32f10x_i2c.h) or to custom values defined by user.
* - This function is suitable when multiple flags are monitored at the same time.
* - At the opposite of I2C_CheckEvent() function, this function allows user to
* choose when an event is accepted (when all events flags are set and no
* other flags are set or just when the needed flags are set like
* I2C_CheckEvent() function).
* - Limitations:
* - User may need to define his own events.
* - Same remark concerning the error management is applicable for this
* function if user decides to check only regular communication flags (and
* ignores error flags).
*
*
* 3) Flag-based state monitoring:
* Using the function I2C_GetFlagStatus() which simply returns the status of
* one single flag (ie. I2C_FLAG_RXNE ...).
* - When to use:
* - This function could be used for specific applications or in debug phase.
* - It is suitable when only one flag checking is needed (most I2C events
* are monitored through multiple flags).
* - Limitations:
* - When calling this function, the Status register is accessed. Some flags are
* cleared when the status register is accessed. So checking the status
* of one Flag, may clear other ones.
* - Function may need to be called twice or more in order to monitor one
* single event.
*
*/
/**
*
* 1) Basic state monitoring
*******************************************************************************
*/
ErrorStatus I2C_CheckEvent(I2C_TypeDef* I2Cx, uint32_t I2C_EVENT);
/**
*
* 2) Advanced state monitoring
*******************************************************************************
*/
uint32_t I2C_GetLastEvent(I2C_TypeDef* I2Cx);
/**
*
* 3) Flag-based state monitoring
*******************************************************************************
*/
FlagStatus I2C_GetFlagStatus(I2C_TypeDef* I2Cx, uint32_t I2C_FLAG);
/**
*
*******************************************************************************
*/
void I2C_ClearFlag(I2C_TypeDef* I2Cx, uint32_t I2C_FLAG);
ITStatus I2C_GetITStatus(I2C_TypeDef* I2Cx, uint32_t I2C_IT);
void I2C_ClearITPendingBit(I2C_TypeDef* I2Cx, uint32_t I2C_IT);
#ifdef __cplusplus
}
#endif
#endif /*__STM32F10x_I2C_H */
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/

View File

@ -1,140 +0,0 @@
/**
******************************************************************************
* @file stm32f10x_iwdg.h
* @author MCD Application Team
* @version V3.5.0
* @date 11-March-2011
* @brief This file contains all the functions prototypes for the IWDG
* firmware library.
******************************************************************************
* @attention
*
* 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, STMICROELECTRONICS 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 2011 STMicroelectronics</center></h2>
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32F10x_IWDG_H
#define __STM32F10x_IWDG_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32f10x.h"
/** @addtogroup STM32F10x_StdPeriph_Driver
* @{
*/
/** @addtogroup IWDG
* @{
*/
/** @defgroup IWDG_Exported_Types
* @{
*/
/**
* @}
*/
/** @defgroup IWDG_Exported_Constants
* @{
*/
/** @defgroup IWDG_WriteAccess
* @{
*/
#define IWDG_WriteAccess_Enable ((uint16_t)0x5555)
#define IWDG_WriteAccess_Disable ((uint16_t)0x0000)
#define IS_IWDG_WRITE_ACCESS(ACCESS) (((ACCESS) == IWDG_WriteAccess_Enable) || \
((ACCESS) == IWDG_WriteAccess_Disable))
/**
* @}
*/
/** @defgroup IWDG_prescaler
* @{
*/
#define IWDG_Prescaler_4 ((uint8_t)0x00)
#define IWDG_Prescaler_8 ((uint8_t)0x01)
#define IWDG_Prescaler_16 ((uint8_t)0x02)
#define IWDG_Prescaler_32 ((uint8_t)0x03)
#define IWDG_Prescaler_64 ((uint8_t)0x04)
#define IWDG_Prescaler_128 ((uint8_t)0x05)
#define IWDG_Prescaler_256 ((uint8_t)0x06)
#define IS_IWDG_PRESCALER(PRESCALER) (((PRESCALER) == IWDG_Prescaler_4) || \
((PRESCALER) == IWDG_Prescaler_8) || \
((PRESCALER) == IWDG_Prescaler_16) || \
((PRESCALER) == IWDG_Prescaler_32) || \
((PRESCALER) == IWDG_Prescaler_64) || \
((PRESCALER) == IWDG_Prescaler_128)|| \
((PRESCALER) == IWDG_Prescaler_256))
/**
* @}
*/
/** @defgroup IWDG_Flag
* @{
*/
#define IWDG_FLAG_PVU ((uint16_t)0x0001)
#define IWDG_FLAG_RVU ((uint16_t)0x0002)
#define IS_IWDG_FLAG(FLAG) (((FLAG) == IWDG_FLAG_PVU) || ((FLAG) == IWDG_FLAG_RVU))
#define IS_IWDG_RELOAD(RELOAD) ((RELOAD) <= 0xFFF)
/**
* @}
*/
/**
* @}
*/
/** @defgroup IWDG_Exported_Macros
* @{
*/
/**
* @}
*/
/** @defgroup IWDG_Exported_Functions
* @{
*/
void IWDG_WriteAccessCmd(uint16_t IWDG_WriteAccess);
void IWDG_SetPrescaler(uint8_t IWDG_Prescaler);
void IWDG_SetReload(uint16_t Reload);
void IWDG_ReloadCounter(void);
void IWDG_Enable(void);
FlagStatus IWDG_GetFlagStatus(uint16_t IWDG_FLAG);
#ifdef __cplusplus
}
#endif
#endif /* __STM32F10x_IWDG_H */
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/

View File

@ -1,156 +0,0 @@
/**
******************************************************************************
* @file stm32f10x_pwr.h
* @author MCD Application Team
* @version V3.5.0
* @date 11-March-2011
* @brief This file contains all the functions prototypes for the PWR firmware
* library.
******************************************************************************
* @attention
*
* 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, STMICROELECTRONICS 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 2011 STMicroelectronics</center></h2>
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32F10x_PWR_H
#define __STM32F10x_PWR_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32f10x.h"
/** @addtogroup STM32F10x_StdPeriph_Driver
* @{
*/
/** @addtogroup PWR
* @{
*/
/** @defgroup PWR_Exported_Types
* @{
*/
/**
* @}
*/
/** @defgroup PWR_Exported_Constants
* @{
*/
/** @defgroup PVD_detection_level
* @{
*/
#define PWR_PVDLevel_2V2 ((uint32_t)0x00000000)
#define PWR_PVDLevel_2V3 ((uint32_t)0x00000020)
#define PWR_PVDLevel_2V4 ((uint32_t)0x00000040)
#define PWR_PVDLevel_2V5 ((uint32_t)0x00000060)
#define PWR_PVDLevel_2V6 ((uint32_t)0x00000080)
#define PWR_PVDLevel_2V7 ((uint32_t)0x000000A0)
#define PWR_PVDLevel_2V8 ((uint32_t)0x000000C0)
#define PWR_PVDLevel_2V9 ((uint32_t)0x000000E0)
#define IS_PWR_PVD_LEVEL(LEVEL) (((LEVEL) == PWR_PVDLevel_2V2) || ((LEVEL) == PWR_PVDLevel_2V3)|| \
((LEVEL) == PWR_PVDLevel_2V4) || ((LEVEL) == PWR_PVDLevel_2V5)|| \
((LEVEL) == PWR_PVDLevel_2V6) || ((LEVEL) == PWR_PVDLevel_2V7)|| \
((LEVEL) == PWR_PVDLevel_2V8) || ((LEVEL) == PWR_PVDLevel_2V9))
/**
* @}
*/
/** @defgroup Regulator_state_is_STOP_mode
* @{
*/
#define PWR_Regulator_ON ((uint32_t)0x00000000)
#define PWR_Regulator_LowPower ((uint32_t)0x00000001)
#define IS_PWR_REGULATOR(REGULATOR) (((REGULATOR) == PWR_Regulator_ON) || \
((REGULATOR) == PWR_Regulator_LowPower))
/**
* @}
*/
/** @defgroup STOP_mode_entry
* @{
*/
#define PWR_STOPEntry_WFI ((uint8_t)0x01)
#define PWR_STOPEntry_WFE ((uint8_t)0x02)
#define IS_PWR_STOP_ENTRY(ENTRY) (((ENTRY) == PWR_STOPEntry_WFI) || ((ENTRY) == PWR_STOPEntry_WFE))
/**
* @}
*/
/** @defgroup PWR_Flag
* @{
*/
#define PWR_FLAG_WU ((uint32_t)0x00000001)
#define PWR_FLAG_SB ((uint32_t)0x00000002)
#define PWR_FLAG_PVDO ((uint32_t)0x00000004)
#define IS_PWR_GET_FLAG(FLAG) (((FLAG) == PWR_FLAG_WU) || ((FLAG) == PWR_FLAG_SB) || \
((FLAG) == PWR_FLAG_PVDO))
#define IS_PWR_CLEAR_FLAG(FLAG) (((FLAG) == PWR_FLAG_WU) || ((FLAG) == PWR_FLAG_SB))
/**
* @}
*/
/**
* @}
*/
/** @defgroup PWR_Exported_Macros
* @{
*/
/**
* @}
*/
/** @defgroup PWR_Exported_Functions
* @{
*/
void PWR_DeInit(void);
void PWR_BackupAccessCmd(FunctionalState NewState);
void PWR_PVDCmd(FunctionalState NewState);
void PWR_PVDLevelConfig(uint32_t PWR_PVDLevel);
void PWR_WakeUpPinCmd(FunctionalState NewState);
void PWR_EnterSTOPMode(uint32_t PWR_Regulator, uint8_t PWR_STOPEntry);
void PWR_EnterSTANDBYMode(void);
FlagStatus PWR_GetFlagStatus(uint32_t PWR_FLAG);
void PWR_ClearFlag(uint32_t PWR_FLAG);
#ifdef __cplusplus
}
#endif
#endif /* __STM32F10x_PWR_H */
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/

View File

@ -1,727 +0,0 @@
/**
******************************************************************************
* @file stm32f10x_rcc.h
* @author MCD Application Team
* @version V3.5.0
* @date 11-March-2011
* @brief This file contains all the functions prototypes for the RCC firmware
* library.
******************************************************************************
* @attention
*
* 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, STMICROELECTRONICS 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 2011 STMicroelectronics</center></h2>
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32F10x_RCC_H
#define __STM32F10x_RCC_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32f10x.h"
/** @addtogroup STM32F10x_StdPeriph_Driver
* @{
*/
/** @addtogroup RCC
* @{
*/
/** @defgroup RCC_Exported_Types
* @{
*/
typedef struct
{
uint32_t SYSCLK_Frequency; /*!< returns SYSCLK clock frequency expressed in Hz */
uint32_t HCLK_Frequency; /*!< returns HCLK clock frequency expressed in Hz */
uint32_t PCLK1_Frequency; /*!< returns PCLK1 clock frequency expressed in Hz */
uint32_t PCLK2_Frequency; /*!< returns PCLK2 clock frequency expressed in Hz */
uint32_t ADCCLK_Frequency; /*!< returns ADCCLK clock frequency expressed in Hz */
}RCC_ClocksTypeDef;
/**
* @}
*/
/** @defgroup RCC_Exported_Constants
* @{
*/
/** @defgroup HSE_configuration
* @{
*/
#define RCC_HSE_OFF ((uint32_t)0x00000000)
#define RCC_HSE_ON ((uint32_t)0x00010000)
#define RCC_HSE_Bypass ((uint32_t)0x00040000)
#define IS_RCC_HSE(HSE) (((HSE) == RCC_HSE_OFF) || ((HSE) == RCC_HSE_ON) || \
((HSE) == RCC_HSE_Bypass))
/**
* @}
*/
/** @defgroup PLL_entry_clock_source
* @{
*/
#define RCC_PLLSource_HSI_Div2 ((uint32_t)0x00000000)
#if !defined (STM32F10X_LD_VL) && !defined (STM32F10X_MD_VL) && !defined (STM32F10X_HD_VL) && !defined (STM32F10X_CL)
#define RCC_PLLSource_HSE_Div1 ((uint32_t)0x00010000)
#define RCC_PLLSource_HSE_Div2 ((uint32_t)0x00030000)
#define IS_RCC_PLL_SOURCE(SOURCE) (((SOURCE) == RCC_PLLSource_HSI_Div2) || \
((SOURCE) == RCC_PLLSource_HSE_Div1) || \
((SOURCE) == RCC_PLLSource_HSE_Div2))
#else
#define RCC_PLLSource_PREDIV1 ((uint32_t)0x00010000)
#define IS_RCC_PLL_SOURCE(SOURCE) (((SOURCE) == RCC_PLLSource_HSI_Div2) || \
((SOURCE) == RCC_PLLSource_PREDIV1))
#endif /* STM32F10X_CL */
/**
* @}
*/
/** @defgroup PLL_multiplication_factor
* @{
*/
#ifndef STM32F10X_CL
#define RCC_PLLMul_2 ((uint32_t)0x00000000)
#define RCC_PLLMul_3 ((uint32_t)0x00040000)
#define RCC_PLLMul_4 ((uint32_t)0x00080000)
#define RCC_PLLMul_5 ((uint32_t)0x000C0000)
#define RCC_PLLMul_6 ((uint32_t)0x00100000)
#define RCC_PLLMul_7 ((uint32_t)0x00140000)
#define RCC_PLLMul_8 ((uint32_t)0x00180000)
#define RCC_PLLMul_9 ((uint32_t)0x001C0000)
#define RCC_PLLMul_10 ((uint32_t)0x00200000)
#define RCC_PLLMul_11 ((uint32_t)0x00240000)
#define RCC_PLLMul_12 ((uint32_t)0x00280000)
#define RCC_PLLMul_13 ((uint32_t)0x002C0000)
#define RCC_PLLMul_14 ((uint32_t)0x00300000)
#define RCC_PLLMul_15 ((uint32_t)0x00340000)
#define RCC_PLLMul_16 ((uint32_t)0x00380000)
#define IS_RCC_PLL_MUL(MUL) (((MUL) == RCC_PLLMul_2) || ((MUL) == RCC_PLLMul_3) || \
((MUL) == RCC_PLLMul_4) || ((MUL) == RCC_PLLMul_5) || \
((MUL) == RCC_PLLMul_6) || ((MUL) == RCC_PLLMul_7) || \
((MUL) == RCC_PLLMul_8) || ((MUL) == RCC_PLLMul_9) || \
((MUL) == RCC_PLLMul_10) || ((MUL) == RCC_PLLMul_11) || \
((MUL) == RCC_PLLMul_12) || ((MUL) == RCC_PLLMul_13) || \
((MUL) == RCC_PLLMul_14) || ((MUL) == RCC_PLLMul_15) || \
((MUL) == RCC_PLLMul_16))
#else
#define RCC_PLLMul_4 ((uint32_t)0x00080000)
#define RCC_PLLMul_5 ((uint32_t)0x000C0000)
#define RCC_PLLMul_6 ((uint32_t)0x00100000)
#define RCC_PLLMul_7 ((uint32_t)0x00140000)
#define RCC_PLLMul_8 ((uint32_t)0x00180000)
#define RCC_PLLMul_9 ((uint32_t)0x001C0000)
#define RCC_PLLMul_6_5 ((uint32_t)0x00340000)
#define IS_RCC_PLL_MUL(MUL) (((MUL) == RCC_PLLMul_4) || ((MUL) == RCC_PLLMul_5) || \
((MUL) == RCC_PLLMul_6) || ((MUL) == RCC_PLLMul_7) || \
((MUL) == RCC_PLLMul_8) || ((MUL) == RCC_PLLMul_9) || \
((MUL) == RCC_PLLMul_6_5))
#endif /* STM32F10X_CL */
/**
* @}
*/
/** @defgroup PREDIV1_division_factor
* @{
*/
#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) || defined (STM32F10X_CL)
#define RCC_PREDIV1_Div1 ((uint32_t)0x00000000)
#define RCC_PREDIV1_Div2 ((uint32_t)0x00000001)
#define RCC_PREDIV1_Div3 ((uint32_t)0x00000002)
#define RCC_PREDIV1_Div4 ((uint32_t)0x00000003)
#define RCC_PREDIV1_Div5 ((uint32_t)0x00000004)
#define RCC_PREDIV1_Div6 ((uint32_t)0x00000005)
#define RCC_PREDIV1_Div7 ((uint32_t)0x00000006)
#define RCC_PREDIV1_Div8 ((uint32_t)0x00000007)
#define RCC_PREDIV1_Div9 ((uint32_t)0x00000008)
#define RCC_PREDIV1_Div10 ((uint32_t)0x00000009)
#define RCC_PREDIV1_Div11 ((uint32_t)0x0000000A)
#define RCC_PREDIV1_Div12 ((uint32_t)0x0000000B)
#define RCC_PREDIV1_Div13 ((uint32_t)0x0000000C)
#define RCC_PREDIV1_Div14 ((uint32_t)0x0000000D)
#define RCC_PREDIV1_Div15 ((uint32_t)0x0000000E)
#define RCC_PREDIV1_Div16 ((uint32_t)0x0000000F)
#define IS_RCC_PREDIV1(PREDIV1) (((PREDIV1) == RCC_PREDIV1_Div1) || ((PREDIV1) == RCC_PREDIV1_Div2) || \
((PREDIV1) == RCC_PREDIV1_Div3) || ((PREDIV1) == RCC_PREDIV1_Div4) || \
((PREDIV1) == RCC_PREDIV1_Div5) || ((PREDIV1) == RCC_PREDIV1_Div6) || \
((PREDIV1) == RCC_PREDIV1_Div7) || ((PREDIV1) == RCC_PREDIV1_Div8) || \
((PREDIV1) == RCC_PREDIV1_Div9) || ((PREDIV1) == RCC_PREDIV1_Div10) || \
((PREDIV1) == RCC_PREDIV1_Div11) || ((PREDIV1) == RCC_PREDIV1_Div12) || \
((PREDIV1) == RCC_PREDIV1_Div13) || ((PREDIV1) == RCC_PREDIV1_Div14) || \
((PREDIV1) == RCC_PREDIV1_Div15) || ((PREDIV1) == RCC_PREDIV1_Div16))
#endif
/**
* @}
*/
/** @defgroup PREDIV1_clock_source
* @{
*/
#ifdef STM32F10X_CL
/* PREDIV1 clock source (for STM32 connectivity line devices) */
#define RCC_PREDIV1_Source_HSE ((uint32_t)0x00000000)
#define RCC_PREDIV1_Source_PLL2 ((uint32_t)0x00010000)
#define IS_RCC_PREDIV1_SOURCE(SOURCE) (((SOURCE) == RCC_PREDIV1_Source_HSE) || \
((SOURCE) == RCC_PREDIV1_Source_PLL2))
#elif defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL)
/* PREDIV1 clock source (for STM32 Value line devices) */
#define RCC_PREDIV1_Source_HSE ((uint32_t)0x00000000)
#define IS_RCC_PREDIV1_SOURCE(SOURCE) (((SOURCE) == RCC_PREDIV1_Source_HSE))
#endif
/**
* @}
*/
#ifdef STM32F10X_CL
/** @defgroup PREDIV2_division_factor
* @{
*/
#define RCC_PREDIV2_Div1 ((uint32_t)0x00000000)
#define RCC_PREDIV2_Div2 ((uint32_t)0x00000010)
#define RCC_PREDIV2_Div3 ((uint32_t)0x00000020)
#define RCC_PREDIV2_Div4 ((uint32_t)0x00000030)
#define RCC_PREDIV2_Div5 ((uint32_t)0x00000040)
#define RCC_PREDIV2_Div6 ((uint32_t)0x00000050)
#define RCC_PREDIV2_Div7 ((uint32_t)0x00000060)
#define RCC_PREDIV2_Div8 ((uint32_t)0x00000070)
#define RCC_PREDIV2_Div9 ((uint32_t)0x00000080)
#define RCC_PREDIV2_Div10 ((uint32_t)0x00000090)
#define RCC_PREDIV2_Div11 ((uint32_t)0x000000A0)
#define RCC_PREDIV2_Div12 ((uint32_t)0x000000B0)
#define RCC_PREDIV2_Div13 ((uint32_t)0x000000C0)
#define RCC_PREDIV2_Div14 ((uint32_t)0x000000D0)
#define RCC_PREDIV2_Div15 ((uint32_t)0x000000E0)
#define RCC_PREDIV2_Div16 ((uint32_t)0x000000F0)
#define IS_RCC_PREDIV2(PREDIV2) (((PREDIV2) == RCC_PREDIV2_Div1) || ((PREDIV2) == RCC_PREDIV2_Div2) || \
((PREDIV2) == RCC_PREDIV2_Div3) || ((PREDIV2) == RCC_PREDIV2_Div4) || \
((PREDIV2) == RCC_PREDIV2_Div5) || ((PREDIV2) == RCC_PREDIV2_Div6) || \
((PREDIV2) == RCC_PREDIV2_Div7) || ((PREDIV2) == RCC_PREDIV2_Div8) || \
((PREDIV2) == RCC_PREDIV2_Div9) || ((PREDIV2) == RCC_PREDIV2_Div10) || \
((PREDIV2) == RCC_PREDIV2_Div11) || ((PREDIV2) == RCC_PREDIV2_Div12) || \
((PREDIV2) == RCC_PREDIV2_Div13) || ((PREDIV2) == RCC_PREDIV2_Div14) || \
((PREDIV2) == RCC_PREDIV2_Div15) || ((PREDIV2) == RCC_PREDIV2_Div16))
/**
* @}
*/
/** @defgroup PLL2_multiplication_factor
* @{
*/
#define RCC_PLL2Mul_8 ((uint32_t)0x00000600)
#define RCC_PLL2Mul_9 ((uint32_t)0x00000700)
#define RCC_PLL2Mul_10 ((uint32_t)0x00000800)
#define RCC_PLL2Mul_11 ((uint32_t)0x00000900)
#define RCC_PLL2Mul_12 ((uint32_t)0x00000A00)
#define RCC_PLL2Mul_13 ((uint32_t)0x00000B00)
#define RCC_PLL2Mul_14 ((uint32_t)0x00000C00)
#define RCC_PLL2Mul_16 ((uint32_t)0x00000E00)
#define RCC_PLL2Mul_20 ((uint32_t)0x00000F00)
#define IS_RCC_PLL2_MUL(MUL) (((MUL) == RCC_PLL2Mul_8) || ((MUL) == RCC_PLL2Mul_9) || \
((MUL) == RCC_PLL2Mul_10) || ((MUL) == RCC_PLL2Mul_11) || \
((MUL) == RCC_PLL2Mul_12) || ((MUL) == RCC_PLL2Mul_13) || \
((MUL) == RCC_PLL2Mul_14) || ((MUL) == RCC_PLL2Mul_16) || \
((MUL) == RCC_PLL2Mul_20))
/**
* @}
*/
/** @defgroup PLL3_multiplication_factor
* @{
*/
#define RCC_PLL3Mul_8 ((uint32_t)0x00006000)
#define RCC_PLL3Mul_9 ((uint32_t)0x00007000)
#define RCC_PLL3Mul_10 ((uint32_t)0x00008000)
#define RCC_PLL3Mul_11 ((uint32_t)0x00009000)
#define RCC_PLL3Mul_12 ((uint32_t)0x0000A000)
#define RCC_PLL3Mul_13 ((uint32_t)0x0000B000)
#define RCC_PLL3Mul_14 ((uint32_t)0x0000C000)
#define RCC_PLL3Mul_16 ((uint32_t)0x0000E000)
#define RCC_PLL3Mul_20 ((uint32_t)0x0000F000)
#define IS_RCC_PLL3_MUL(MUL) (((MUL) == RCC_PLL3Mul_8) || ((MUL) == RCC_PLL3Mul_9) || \
((MUL) == RCC_PLL3Mul_10) || ((MUL) == RCC_PLL3Mul_11) || \
((MUL) == RCC_PLL3Mul_12) || ((MUL) == RCC_PLL3Mul_13) || \
((MUL) == RCC_PLL3Mul_14) || ((MUL) == RCC_PLL3Mul_16) || \
((MUL) == RCC_PLL3Mul_20))
/**
* @}
*/
#endif /* STM32F10X_CL */
/** @defgroup System_clock_source
* @{
*/
#define RCC_SYSCLKSource_HSI ((uint32_t)0x00000000)
#define RCC_SYSCLKSource_HSE ((uint32_t)0x00000001)
#define RCC_SYSCLKSource_PLLCLK ((uint32_t)0x00000002)
#define IS_RCC_SYSCLK_SOURCE(SOURCE) (((SOURCE) == RCC_SYSCLKSource_HSI) || \
((SOURCE) == RCC_SYSCLKSource_HSE) || \
((SOURCE) == RCC_SYSCLKSource_PLLCLK))
/**
* @}
*/
/** @defgroup AHB_clock_source
* @{
*/
#define RCC_SYSCLK_Div1 ((uint32_t)0x00000000)
#define RCC_SYSCLK_Div2 ((uint32_t)0x00000080)
#define RCC_SYSCLK_Div4 ((uint32_t)0x00000090)
#define RCC_SYSCLK_Div8 ((uint32_t)0x000000A0)
#define RCC_SYSCLK_Div16 ((uint32_t)0x000000B0)
#define RCC_SYSCLK_Div64 ((uint32_t)0x000000C0)
#define RCC_SYSCLK_Div128 ((uint32_t)0x000000D0)
#define RCC_SYSCLK_Div256 ((uint32_t)0x000000E0)
#define RCC_SYSCLK_Div512 ((uint32_t)0x000000F0)
#define IS_RCC_HCLK(HCLK) (((HCLK) == RCC_SYSCLK_Div1) || ((HCLK) == RCC_SYSCLK_Div2) || \
((HCLK) == RCC_SYSCLK_Div4) || ((HCLK) == RCC_SYSCLK_Div8) || \
((HCLK) == RCC_SYSCLK_Div16) || ((HCLK) == RCC_SYSCLK_Div64) || \
((HCLK) == RCC_SYSCLK_Div128) || ((HCLK) == RCC_SYSCLK_Div256) || \
((HCLK) == RCC_SYSCLK_Div512))
/**
* @}
*/
/** @defgroup APB1_APB2_clock_source
* @{
*/
#define RCC_HCLK_Div1 ((uint32_t)0x00000000)
#define RCC_HCLK_Div2 ((uint32_t)0x00000400)
#define RCC_HCLK_Div4 ((uint32_t)0x00000500)
#define RCC_HCLK_Div8 ((uint32_t)0x00000600)
#define RCC_HCLK_Div16 ((uint32_t)0x00000700)
#define IS_RCC_PCLK(PCLK) (((PCLK) == RCC_HCLK_Div1) || ((PCLK) == RCC_HCLK_Div2) || \
((PCLK) == RCC_HCLK_Div4) || ((PCLK) == RCC_HCLK_Div8) || \
((PCLK) == RCC_HCLK_Div16))
/**
* @}
*/
/** @defgroup RCC_Interrupt_source
* @{
*/
#define RCC_IT_LSIRDY ((uint8_t)0x01)
#define RCC_IT_LSERDY ((uint8_t)0x02)
#define RCC_IT_HSIRDY ((uint8_t)0x04)
#define RCC_IT_HSERDY ((uint8_t)0x08)
#define RCC_IT_PLLRDY ((uint8_t)0x10)
#define RCC_IT_CSS ((uint8_t)0x80)
#ifndef STM32F10X_CL
#define IS_RCC_IT(IT) ((((IT) & (uint8_t)0xE0) == 0x00) && ((IT) != 0x00))
#define IS_RCC_GET_IT(IT) (((IT) == RCC_IT_LSIRDY) || ((IT) == RCC_IT_LSERDY) || \
((IT) == RCC_IT_HSIRDY) || ((IT) == RCC_IT_HSERDY) || \
((IT) == RCC_IT_PLLRDY) || ((IT) == RCC_IT_CSS))
#define IS_RCC_CLEAR_IT(IT) ((((IT) & (uint8_t)0x60) == 0x00) && ((IT) != 0x00))
#else
#define RCC_IT_PLL2RDY ((uint8_t)0x20)
#define RCC_IT_PLL3RDY ((uint8_t)0x40)
#define IS_RCC_IT(IT) ((((IT) & (uint8_t)0x80) == 0x00) && ((IT) != 0x00))
#define IS_RCC_GET_IT(IT) (((IT) == RCC_IT_LSIRDY) || ((IT) == RCC_IT_LSERDY) || \
((IT) == RCC_IT_HSIRDY) || ((IT) == RCC_IT_HSERDY) || \
((IT) == RCC_IT_PLLRDY) || ((IT) == RCC_IT_CSS) || \
((IT) == RCC_IT_PLL2RDY) || ((IT) == RCC_IT_PLL3RDY))
#define IS_RCC_CLEAR_IT(IT) ((IT) != 0x00)
#endif /* STM32F10X_CL */
/**
* @}
*/
#ifndef STM32F10X_CL
/** @defgroup USB_Device_clock_source
* @{
*/
#define RCC_USBCLKSource_PLLCLK_1Div5 ((uint8_t)0x00)
#define RCC_USBCLKSource_PLLCLK_Div1 ((uint8_t)0x01)
#define IS_RCC_USBCLK_SOURCE(SOURCE) (((SOURCE) == RCC_USBCLKSource_PLLCLK_1Div5) || \
((SOURCE) == RCC_USBCLKSource_PLLCLK_Div1))
/**
* @}
*/
#else
/** @defgroup USB_OTG_FS_clock_source
* @{
*/
#define RCC_OTGFSCLKSource_PLLVCO_Div3 ((uint8_t)0x00)
#define RCC_OTGFSCLKSource_PLLVCO_Div2 ((uint8_t)0x01)
#define IS_RCC_OTGFSCLK_SOURCE(SOURCE) (((SOURCE) == RCC_OTGFSCLKSource_PLLVCO_Div3) || \
((SOURCE) == RCC_OTGFSCLKSource_PLLVCO_Div2))
/**
* @}
*/
#endif /* STM32F10X_CL */
#ifdef STM32F10X_CL
/** @defgroup I2S2_clock_source
* @{
*/
#define RCC_I2S2CLKSource_SYSCLK ((uint8_t)0x00)
#define RCC_I2S2CLKSource_PLL3_VCO ((uint8_t)0x01)
#define IS_RCC_I2S2CLK_SOURCE(SOURCE) (((SOURCE) == RCC_I2S2CLKSource_SYSCLK) || \
((SOURCE) == RCC_I2S2CLKSource_PLL3_VCO))
/**
* @}
*/
/** @defgroup I2S3_clock_source
* @{
*/
#define RCC_I2S3CLKSource_SYSCLK ((uint8_t)0x00)
#define RCC_I2S3CLKSource_PLL3_VCO ((uint8_t)0x01)
#define IS_RCC_I2S3CLK_SOURCE(SOURCE) (((SOURCE) == RCC_I2S3CLKSource_SYSCLK) || \
((SOURCE) == RCC_I2S3CLKSource_PLL3_VCO))
/**
* @}
*/
#endif /* STM32F10X_CL */
/** @defgroup ADC_clock_source
* @{
*/
#define RCC_PCLK2_Div2 ((uint32_t)0x00000000)
#define RCC_PCLK2_Div4 ((uint32_t)0x00004000)
#define RCC_PCLK2_Div6 ((uint32_t)0x00008000)
#define RCC_PCLK2_Div8 ((uint32_t)0x0000C000)
#define IS_RCC_ADCCLK(ADCCLK) (((ADCCLK) == RCC_PCLK2_Div2) || ((ADCCLK) == RCC_PCLK2_Div4) || \
((ADCCLK) == RCC_PCLK2_Div6) || ((ADCCLK) == RCC_PCLK2_Div8))
/**
* @}
*/
/** @defgroup LSE_configuration
* @{
*/
#define RCC_LSE_OFF ((uint8_t)0x00)
#define RCC_LSE_ON ((uint8_t)0x01)
#define RCC_LSE_Bypass ((uint8_t)0x04)
#define IS_RCC_LSE(LSE) (((LSE) == RCC_LSE_OFF) || ((LSE) == RCC_LSE_ON) || \
((LSE) == RCC_LSE_Bypass))
/**
* @}
*/
/** @defgroup RTC_clock_source
* @{
*/
#define RCC_RTCCLKSource_LSE ((uint32_t)0x00000100)
#define RCC_RTCCLKSource_LSI ((uint32_t)0x00000200)
#define RCC_RTCCLKSource_HSE_Div128 ((uint32_t)0x00000300)
#define IS_RCC_RTCCLK_SOURCE(SOURCE) (((SOURCE) == RCC_RTCCLKSource_LSE) || \
((SOURCE) == RCC_RTCCLKSource_LSI) || \
((SOURCE) == RCC_RTCCLKSource_HSE_Div128))
/**
* @}
*/
/** @defgroup AHB_peripheral
* @{
*/
#define RCC_AHBPeriph_DMA1 ((uint32_t)0x00000001)
#define RCC_AHBPeriph_DMA2 ((uint32_t)0x00000002)
#define RCC_AHBPeriph_SRAM ((uint32_t)0x00000004)
#define RCC_AHBPeriph_FLITF ((uint32_t)0x00000010)
#define RCC_AHBPeriph_CRC ((uint32_t)0x00000040)
#ifndef STM32F10X_CL
#define RCC_AHBPeriph_FSMC ((uint32_t)0x00000100)
#define RCC_AHBPeriph_SDIO ((uint32_t)0x00000400)
#define IS_RCC_AHB_PERIPH(PERIPH) ((((PERIPH) & 0xFFFFFAA8) == 0x00) && ((PERIPH) != 0x00))
#else
#define RCC_AHBPeriph_OTG_FS ((uint32_t)0x00001000)
#define RCC_AHBPeriph_ETH_MAC ((uint32_t)0x00004000)
#define RCC_AHBPeriph_ETH_MAC_Tx ((uint32_t)0x00008000)
#define RCC_AHBPeriph_ETH_MAC_Rx ((uint32_t)0x00010000)
#define IS_RCC_AHB_PERIPH(PERIPH) ((((PERIPH) & 0xFFFE2FA8) == 0x00) && ((PERIPH) != 0x00))
#define IS_RCC_AHB_PERIPH_RESET(PERIPH) ((((PERIPH) & 0xFFFFAFFF) == 0x00) && ((PERIPH) != 0x00))
#endif /* STM32F10X_CL */
/**
* @}
*/
/** @defgroup APB2_peripheral
* @{
*/
#define RCC_APB2Periph_AFIO ((uint32_t)0x00000001)
#define RCC_APB2Periph_GPIOA ((uint32_t)0x00000004)
#define RCC_APB2Periph_GPIOB ((uint32_t)0x00000008)
#define RCC_APB2Periph_GPIOC ((uint32_t)0x00000010)
#define RCC_APB2Periph_GPIOD ((uint32_t)0x00000020)
#define RCC_APB2Periph_GPIOE ((uint32_t)0x00000040)
#define RCC_APB2Periph_GPIOF ((uint32_t)0x00000080)
#define RCC_APB2Periph_GPIOG ((uint32_t)0x00000100)
#define RCC_APB2Periph_ADC1 ((uint32_t)0x00000200)
#define RCC_APB2Periph_ADC2 ((uint32_t)0x00000400)
#define RCC_APB2Periph_TIM1 ((uint32_t)0x00000800)
#define RCC_APB2Periph_SPI1 ((uint32_t)0x00001000)
#define RCC_APB2Periph_TIM8 ((uint32_t)0x00002000)
#define RCC_APB2Periph_USART1 ((uint32_t)0x00004000)
#define RCC_APB2Periph_ADC3 ((uint32_t)0x00008000)
#define RCC_APB2Periph_TIM15 ((uint32_t)0x00010000)
#define RCC_APB2Periph_TIM16 ((uint32_t)0x00020000)
#define RCC_APB2Periph_TIM17 ((uint32_t)0x00040000)
#define RCC_APB2Periph_TIM9 ((uint32_t)0x00080000)
#define RCC_APB2Periph_TIM10 ((uint32_t)0x00100000)
#define RCC_APB2Periph_TIM11 ((uint32_t)0x00200000)
#define IS_RCC_APB2_PERIPH(PERIPH) ((((PERIPH) & 0xFFC00002) == 0x00) && ((PERIPH) != 0x00))
/**
* @}
*/
/** @defgroup APB1_peripheral
* @{
*/
#define RCC_APB1Periph_TIM2 ((uint32_t)0x00000001)
#define RCC_APB1Periph_TIM3 ((uint32_t)0x00000002)
#define RCC_APB1Periph_TIM4 ((uint32_t)0x00000004)
#define RCC_APB1Periph_TIM5 ((uint32_t)0x00000008)
#define RCC_APB1Periph_TIM6 ((uint32_t)0x00000010)
#define RCC_APB1Periph_TIM7 ((uint32_t)0x00000020)
#define RCC_APB1Periph_TIM12 ((uint32_t)0x00000040)
#define RCC_APB1Periph_TIM13 ((uint32_t)0x00000080)
#define RCC_APB1Periph_TIM14 ((uint32_t)0x00000100)
#define RCC_APB1Periph_WWDG ((uint32_t)0x00000800)
#define RCC_APB1Periph_SPI2 ((uint32_t)0x00004000)
#define RCC_APB1Periph_SPI3 ((uint32_t)0x00008000)
#define RCC_APB1Periph_USART2 ((uint32_t)0x00020000)
#define RCC_APB1Periph_USART3 ((uint32_t)0x00040000)
#define RCC_APB1Periph_UART4 ((uint32_t)0x00080000)
#define RCC_APB1Periph_UART5 ((uint32_t)0x00100000)
#define RCC_APB1Periph_I2C1 ((uint32_t)0x00200000)
#define RCC_APB1Periph_I2C2 ((uint32_t)0x00400000)
#define RCC_APB1Periph_USB ((uint32_t)0x00800000)
#define RCC_APB1Periph_CAN1 ((uint32_t)0x02000000)
#define RCC_APB1Periph_CAN2 ((uint32_t)0x04000000)
#define RCC_APB1Periph_BKP ((uint32_t)0x08000000)
#define RCC_APB1Periph_PWR ((uint32_t)0x10000000)
#define RCC_APB1Periph_DAC ((uint32_t)0x20000000)
#define RCC_APB1Periph_CEC ((uint32_t)0x40000000)
#define IS_RCC_APB1_PERIPH(PERIPH) ((((PERIPH) & 0x81013600) == 0x00) && ((PERIPH) != 0x00))
/**
* @}
*/
/** @defgroup Clock_source_to_output_on_MCO_pin
* @{
*/
#define RCC_MCO_NoClock ((uint8_t)0x00)
#define RCC_MCO_SYSCLK ((uint8_t)0x04)
#define RCC_MCO_HSI ((uint8_t)0x05)
#define RCC_MCO_HSE ((uint8_t)0x06)
#define RCC_MCO_PLLCLK_Div2 ((uint8_t)0x07)
#ifndef STM32F10X_CL
#define IS_RCC_MCO(MCO) (((MCO) == RCC_MCO_NoClock) || ((MCO) == RCC_MCO_HSI) || \
((MCO) == RCC_MCO_SYSCLK) || ((MCO) == RCC_MCO_HSE) || \
((MCO) == RCC_MCO_PLLCLK_Div2))
#else
#define RCC_MCO_PLL2CLK ((uint8_t)0x08)
#define RCC_MCO_PLL3CLK_Div2 ((uint8_t)0x09)
#define RCC_MCO_XT1 ((uint8_t)0x0A)
#define RCC_MCO_PLL3CLK ((uint8_t)0x0B)
#define IS_RCC_MCO(MCO) (((MCO) == RCC_MCO_NoClock) || ((MCO) == RCC_MCO_HSI) || \
((MCO) == RCC_MCO_SYSCLK) || ((MCO) == RCC_MCO_HSE) || \
((MCO) == RCC_MCO_PLLCLK_Div2) || ((MCO) == RCC_MCO_PLL2CLK) || \
((MCO) == RCC_MCO_PLL3CLK_Div2) || ((MCO) == RCC_MCO_XT1) || \
((MCO) == RCC_MCO_PLL3CLK))
#endif /* STM32F10X_CL */
/**
* @}
*/
/** @defgroup RCC_Flag
* @{
*/
#define RCC_FLAG_HSIRDY ((uint8_t)0x21)
#define RCC_FLAG_HSERDY ((uint8_t)0x31)
#define RCC_FLAG_PLLRDY ((uint8_t)0x39)
#define RCC_FLAG_LSERDY ((uint8_t)0x41)
#define RCC_FLAG_LSIRDY ((uint8_t)0x61)
#define RCC_FLAG_PINRST ((uint8_t)0x7A)
#define RCC_FLAG_PORRST ((uint8_t)0x7B)
#define RCC_FLAG_SFTRST ((uint8_t)0x7C)
#define RCC_FLAG_IWDGRST ((uint8_t)0x7D)
#define RCC_FLAG_WWDGRST ((uint8_t)0x7E)
#define RCC_FLAG_LPWRRST ((uint8_t)0x7F)
#ifndef STM32F10X_CL
#define IS_RCC_FLAG(FLAG) (((FLAG) == RCC_FLAG_HSIRDY) || ((FLAG) == RCC_FLAG_HSERDY) || \
((FLAG) == RCC_FLAG_PLLRDY) || ((FLAG) == RCC_FLAG_LSERDY) || \
((FLAG) == RCC_FLAG_LSIRDY) || ((FLAG) == RCC_FLAG_PINRST) || \
((FLAG) == RCC_FLAG_PORRST) || ((FLAG) == RCC_FLAG_SFTRST) || \
((FLAG) == RCC_FLAG_IWDGRST)|| ((FLAG) == RCC_FLAG_WWDGRST)|| \
((FLAG) == RCC_FLAG_LPWRRST))
#else
#define RCC_FLAG_PLL2RDY ((uint8_t)0x3B)
#define RCC_FLAG_PLL3RDY ((uint8_t)0x3D)
#define IS_RCC_FLAG(FLAG) (((FLAG) == RCC_FLAG_HSIRDY) || ((FLAG) == RCC_FLAG_HSERDY) || \
((FLAG) == RCC_FLAG_PLLRDY) || ((FLAG) == RCC_FLAG_LSERDY) || \
((FLAG) == RCC_FLAG_PLL2RDY) || ((FLAG) == RCC_FLAG_PLL3RDY) || \
((FLAG) == RCC_FLAG_LSIRDY) || ((FLAG) == RCC_FLAG_PINRST) || \
((FLAG) == RCC_FLAG_PORRST) || ((FLAG) == RCC_FLAG_SFTRST) || \
((FLAG) == RCC_FLAG_IWDGRST)|| ((FLAG) == RCC_FLAG_WWDGRST)|| \
((FLAG) == RCC_FLAG_LPWRRST))
#endif /* STM32F10X_CL */
#define IS_RCC_CALIBRATION_VALUE(VALUE) ((VALUE) <= 0x1F)
/**
* @}
*/
/**
* @}
*/
/** @defgroup RCC_Exported_Macros
* @{
*/
/**
* @}
*/
/** @defgroup RCC_Exported_Functions
* @{
*/
void RCC_DeInit(void);
void RCC_HSEConfig(uint32_t RCC_HSE);
ErrorStatus RCC_WaitForHSEStartUp(void);
void RCC_AdjustHSICalibrationValue(uint8_t HSICalibrationValue);
void RCC_HSICmd(FunctionalState NewState);
void RCC_PLLConfig(uint32_t RCC_PLLSource, uint32_t RCC_PLLMul);
void RCC_PLLCmd(FunctionalState NewState);
#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) || defined (STM32F10X_CL)
void RCC_PREDIV1Config(uint32_t RCC_PREDIV1_Source, uint32_t RCC_PREDIV1_Div);
#endif
#ifdef STM32F10X_CL
void RCC_PREDIV2Config(uint32_t RCC_PREDIV2_Div);
void RCC_PLL2Config(uint32_t RCC_PLL2Mul);
void RCC_PLL2Cmd(FunctionalState NewState);
void RCC_PLL3Config(uint32_t RCC_PLL3Mul);
void RCC_PLL3Cmd(FunctionalState NewState);
#endif /* STM32F10X_CL */
void RCC_SYSCLKConfig(uint32_t RCC_SYSCLKSource);
uint8_t RCC_GetSYSCLKSource(void);
void RCC_HCLKConfig(uint32_t RCC_SYSCLK);
void RCC_PCLK1Config(uint32_t RCC_HCLK);
void RCC_PCLK2Config(uint32_t RCC_HCLK);
void RCC_ITConfig(uint8_t RCC_IT, FunctionalState NewState);
#ifndef STM32F10X_CL
void RCC_USBCLKConfig(uint32_t RCC_USBCLKSource);
#else
void RCC_OTGFSCLKConfig(uint32_t RCC_OTGFSCLKSource);
#endif /* STM32F10X_CL */
void RCC_ADCCLKConfig(uint32_t RCC_PCLK2);
#ifdef STM32F10X_CL
void RCC_I2S2CLKConfig(uint32_t RCC_I2S2CLKSource);
void RCC_I2S3CLKConfig(uint32_t RCC_I2S3CLKSource);
#endif /* STM32F10X_CL */
void RCC_LSEConfig(uint8_t RCC_LSE);
void RCC_LSICmd(FunctionalState NewState);
void RCC_RTCCLKConfig(uint32_t RCC_RTCCLKSource);
void RCC_RTCCLKCmd(FunctionalState NewState);
void RCC_GetClocksFreq(RCC_ClocksTypeDef* RCC_Clocks);
void RCC_AHBPeriphClockCmd(uint32_t RCC_AHBPeriph, FunctionalState NewState);
void RCC_APB2PeriphClockCmd(uint32_t RCC_APB2Periph, FunctionalState NewState);
void RCC_APB1PeriphClockCmd(uint32_t RCC_APB1Periph, FunctionalState NewState);
#ifdef STM32F10X_CL
void RCC_AHBPeriphResetCmd(uint32_t RCC_AHBPeriph, FunctionalState NewState);
#endif /* STM32F10X_CL */
void RCC_APB2PeriphResetCmd(uint32_t RCC_APB2Periph, FunctionalState NewState);
void RCC_APB1PeriphResetCmd(uint32_t RCC_APB1Periph, FunctionalState NewState);
void RCC_BackupResetCmd(FunctionalState NewState);
void RCC_ClockSecuritySystemCmd(FunctionalState NewState);
void RCC_MCOConfig(uint8_t RCC_MCO);
FlagStatus RCC_GetFlagStatus(uint8_t RCC_FLAG);
void RCC_ClearFlag(void);
ITStatus RCC_GetITStatus(uint8_t RCC_IT);
void RCC_ClearITPendingBit(uint8_t RCC_IT);
#ifdef __cplusplus
}
#endif
#endif /* __STM32F10x_RCC_H */
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/

View File

@ -1,135 +0,0 @@
/**
******************************************************************************
* @file stm32f10x_rtc.h
* @author MCD Application Team
* @version V3.5.0
* @date 11-March-2011
* @brief This file contains all the functions prototypes for the RTC firmware
* library.
******************************************************************************
* @attention
*
* 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, STMICROELECTRONICS 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 2011 STMicroelectronics</center></h2>
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32F10x_RTC_H
#define __STM32F10x_RTC_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32f10x.h"
/** @addtogroup STM32F10x_StdPeriph_Driver
* @{
*/
/** @addtogroup RTC
* @{
*/
/** @defgroup RTC_Exported_Types
* @{
*/
/**
* @}
*/
/** @defgroup RTC_Exported_Constants
* @{
*/
/** @defgroup RTC_interrupts_define
* @{
*/
#define RTC_IT_OW ((uint16_t)0x0004) /*!< Overflow interrupt */
#define RTC_IT_ALR ((uint16_t)0x0002) /*!< Alarm interrupt */
#define RTC_IT_SEC ((uint16_t)0x0001) /*!< Second interrupt */
#define IS_RTC_IT(IT) ((((IT) & (uint16_t)0xFFF8) == 0x00) && ((IT) != 0x00))
#define IS_RTC_GET_IT(IT) (((IT) == RTC_IT_OW) || ((IT) == RTC_IT_ALR) || \
((IT) == RTC_IT_SEC))
/**
* @}
*/
/** @defgroup RTC_interrupts_flags
* @{
*/
#define RTC_FLAG_RTOFF ((uint16_t)0x0020) /*!< RTC Operation OFF flag */
#define RTC_FLAG_RSF ((uint16_t)0x0008) /*!< Registers Synchronized flag */
#define RTC_FLAG_OW ((uint16_t)0x0004) /*!< Overflow flag */
#define RTC_FLAG_ALR ((uint16_t)0x0002) /*!< Alarm flag */
#define RTC_FLAG_SEC ((uint16_t)0x0001) /*!< Second flag */
#define IS_RTC_CLEAR_FLAG(FLAG) ((((FLAG) & (uint16_t)0xFFF0) == 0x00) && ((FLAG) != 0x00))
#define IS_RTC_GET_FLAG(FLAG) (((FLAG) == RTC_FLAG_RTOFF) || ((FLAG) == RTC_FLAG_RSF) || \
((FLAG) == RTC_FLAG_OW) || ((FLAG) == RTC_FLAG_ALR) || \
((FLAG) == RTC_FLAG_SEC))
#define IS_RTC_PRESCALER(PRESCALER) ((PRESCALER) <= 0xFFFFF)
/**
* @}
*/
/**
* @}
*/
/** @defgroup RTC_Exported_Macros
* @{
*/
/**
* @}
*/
/** @defgroup RTC_Exported_Functions
* @{
*/
void RTC_ITConfig(uint16_t RTC_IT, FunctionalState NewState);
void RTC_EnterConfigMode(void);
void RTC_ExitConfigMode(void);
uint32_t RTC_GetCounter(void);
void RTC_SetCounter(uint32_t CounterValue);
void RTC_SetPrescaler(uint32_t PrescalerValue);
void RTC_SetAlarm(uint32_t AlarmValue);
uint32_t RTC_GetDivider(void);
void RTC_WaitForLastTask(void);
void RTC_WaitForSynchro(void);
FlagStatus RTC_GetFlagStatus(uint16_t RTC_FLAG);
void RTC_ClearFlag(uint16_t RTC_FLAG);
ITStatus RTC_GetITStatus(uint16_t RTC_IT);
void RTC_ClearITPendingBit(uint16_t RTC_IT);
#ifdef __cplusplus
}
#endif
#endif /* __STM32F10x_RTC_H */
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/

View File

@ -1,531 +0,0 @@
/**
******************************************************************************
* @file stm32f10x_sdio.h
* @author MCD Application Team
* @version V3.5.0
* @date 11-March-2011
* @brief This file contains all the functions prototypes for the SDIO firmware
* library.
******************************************************************************
* @attention
*
* 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, STMICROELECTRONICS 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 2011 STMicroelectronics</center></h2>
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32F10x_SDIO_H
#define __STM32F10x_SDIO_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32f10x.h"
/** @addtogroup STM32F10x_StdPeriph_Driver
* @{
*/
/** @addtogroup SDIO
* @{
*/
/** @defgroup SDIO_Exported_Types
* @{
*/
typedef struct
{
uint32_t SDIO_ClockEdge; /*!< Specifies the clock transition on which the bit capture is made.
This parameter can be a value of @ref SDIO_Clock_Edge */
uint32_t SDIO_ClockBypass; /*!< Specifies whether the SDIO Clock divider bypass is
enabled or disabled.
This parameter can be a value of @ref SDIO_Clock_Bypass */
uint32_t SDIO_ClockPowerSave; /*!< Specifies whether SDIO Clock output is enabled or
disabled when the bus is idle.
This parameter can be a value of @ref SDIO_Clock_Power_Save */
uint32_t SDIO_BusWide; /*!< Specifies the SDIO bus width.
This parameter can be a value of @ref SDIO_Bus_Wide */
uint32_t SDIO_HardwareFlowControl; /*!< Specifies whether the SDIO hardware flow control is enabled or disabled.
This parameter can be a value of @ref SDIO_Hardware_Flow_Control */
uint8_t SDIO_ClockDiv; /*!< Specifies the clock frequency of the SDIO controller.
This parameter can be a value between 0x00 and 0xFF. */
} SDIO_InitTypeDef;
typedef struct
{
uint32_t SDIO_Argument; /*!< Specifies the SDIO command argument which is sent
to a card as part of a command message. If a command
contains an argument, it must be loaded into this register
before writing the command to the command register */
uint32_t SDIO_CmdIndex; /*!< Specifies the SDIO command index. It must be lower than 0x40. */
uint32_t SDIO_Response; /*!< Specifies the SDIO response type.
This parameter can be a value of @ref SDIO_Response_Type */
uint32_t SDIO_Wait; /*!< Specifies whether SDIO wait-for-interrupt request is enabled or disabled.
This parameter can be a value of @ref SDIO_Wait_Interrupt_State */
uint32_t SDIO_CPSM; /*!< Specifies whether SDIO Command path state machine (CPSM)
is enabled or disabled.
This parameter can be a value of @ref SDIO_CPSM_State */
} SDIO_CmdInitTypeDef;
typedef struct
{
uint32_t SDIO_DataTimeOut; /*!< Specifies the data timeout period in card bus clock periods. */
uint32_t SDIO_DataLength; /*!< Specifies the number of data bytes to be transferred. */
uint32_t SDIO_DataBlockSize; /*!< Specifies the data block size for block transfer.
This parameter can be a value of @ref SDIO_Data_Block_Size */
uint32_t SDIO_TransferDir; /*!< Specifies the data transfer direction, whether the transfer
is a read or write.
This parameter can be a value of @ref SDIO_Transfer_Direction */
uint32_t SDIO_TransferMode; /*!< Specifies whether data transfer is in stream or block mode.
This parameter can be a value of @ref SDIO_Transfer_Type */
uint32_t SDIO_DPSM; /*!< Specifies whether SDIO Data path state machine (DPSM)
is enabled or disabled.
This parameter can be a value of @ref SDIO_DPSM_State */
} SDIO_DataInitTypeDef;
/**
* @}
*/
/** @defgroup SDIO_Exported_Constants
* @{
*/
/** @defgroup SDIO_Clock_Edge
* @{
*/
#define SDIO_ClockEdge_Rising ((uint32_t)0x00000000)
#define SDIO_ClockEdge_Falling ((uint32_t)0x00002000)
#define IS_SDIO_CLOCK_EDGE(EDGE) (((EDGE) == SDIO_ClockEdge_Rising) || \
((EDGE) == SDIO_ClockEdge_Falling))
/**
* @}
*/
/** @defgroup SDIO_Clock_Bypass
* @{
*/
#define SDIO_ClockBypass_Disable ((uint32_t)0x00000000)
#define SDIO_ClockBypass_Enable ((uint32_t)0x00000400)
#define IS_SDIO_CLOCK_BYPASS(BYPASS) (((BYPASS) == SDIO_ClockBypass_Disable) || \
((BYPASS) == SDIO_ClockBypass_Enable))
/**
* @}
*/
/** @defgroup SDIO_Clock_Power_Save
* @{
*/
#define SDIO_ClockPowerSave_Disable ((uint32_t)0x00000000)
#define SDIO_ClockPowerSave_Enable ((uint32_t)0x00000200)
#define IS_SDIO_CLOCK_POWER_SAVE(SAVE) (((SAVE) == SDIO_ClockPowerSave_Disable) || \
((SAVE) == SDIO_ClockPowerSave_Enable))
/**
* @}
*/
/** @defgroup SDIO_Bus_Wide
* @{
*/
#define SDIO_BusWide_1b ((uint32_t)0x00000000)
#define SDIO_BusWide_4b ((uint32_t)0x00000800)
#define SDIO_BusWide_8b ((uint32_t)0x00001000)
#define IS_SDIO_BUS_WIDE(WIDE) (((WIDE) == SDIO_BusWide_1b) || ((WIDE) == SDIO_BusWide_4b) || \
((WIDE) == SDIO_BusWide_8b))
/**
* @}
*/
/** @defgroup SDIO_Hardware_Flow_Control
* @{
*/
#define SDIO_HardwareFlowControl_Disable ((uint32_t)0x00000000)
#define SDIO_HardwareFlowControl_Enable ((uint32_t)0x00004000)
#define IS_SDIO_HARDWARE_FLOW_CONTROL(CONTROL) (((CONTROL) == SDIO_HardwareFlowControl_Disable) || \
((CONTROL) == SDIO_HardwareFlowControl_Enable))
/**
* @}
*/
/** @defgroup SDIO_Power_State
* @{
*/
#define SDIO_PowerState_OFF ((uint32_t)0x00000000)
#define SDIO_PowerState_ON ((uint32_t)0x00000003)
#define IS_SDIO_POWER_STATE(STATE) (((STATE) == SDIO_PowerState_OFF) || ((STATE) == SDIO_PowerState_ON))
/**
* @}
*/
/** @defgroup SDIO_Interrupt_sources
* @{
*/
#define SDIO_IT_CCRCFAIL ((uint32_t)0x00000001)
#define SDIO_IT_DCRCFAIL ((uint32_t)0x00000002)
#define SDIO_IT_CTIMEOUT ((uint32_t)0x00000004)
#define SDIO_IT_DTIMEOUT ((uint32_t)0x00000008)
#define SDIO_IT_TXUNDERR ((uint32_t)0x00000010)
#define SDIO_IT_RXOVERR ((uint32_t)0x00000020)
#define SDIO_IT_CMDREND ((uint32_t)0x00000040)
#define SDIO_IT_CMDSENT ((uint32_t)0x00000080)
#define SDIO_IT_DATAEND ((uint32_t)0x00000100)
#define SDIO_IT_STBITERR ((uint32_t)0x00000200)
#define SDIO_IT_DBCKEND ((uint32_t)0x00000400)
#define SDIO_IT_CMDACT ((uint32_t)0x00000800)
#define SDIO_IT_TXACT ((uint32_t)0x00001000)
#define SDIO_IT_RXACT ((uint32_t)0x00002000)
#define SDIO_IT_TXFIFOHE ((uint32_t)0x00004000)
#define SDIO_IT_RXFIFOHF ((uint32_t)0x00008000)
#define SDIO_IT_TXFIFOF ((uint32_t)0x00010000)
#define SDIO_IT_RXFIFOF ((uint32_t)0x00020000)
#define SDIO_IT_TXFIFOE ((uint32_t)0x00040000)
#define SDIO_IT_RXFIFOE ((uint32_t)0x00080000)
#define SDIO_IT_TXDAVL ((uint32_t)0x00100000)
#define SDIO_IT_RXDAVL ((uint32_t)0x00200000)
#define SDIO_IT_SDIOIT ((uint32_t)0x00400000)
#define SDIO_IT_CEATAEND ((uint32_t)0x00800000)
#define IS_SDIO_IT(IT) ((((IT) & (uint32_t)0xFF000000) == 0x00) && ((IT) != (uint32_t)0x00))
/**
* @}
*/
/** @defgroup SDIO_Command_Index
* @{
*/
#define IS_SDIO_CMD_INDEX(INDEX) ((INDEX) < 0x40)
/**
* @}
*/
/** @defgroup SDIO_Response_Type
* @{
*/
#define SDIO_Response_No ((uint32_t)0x00000000)
#define SDIO_Response_Short ((uint32_t)0x00000040)
#define SDIO_Response_Long ((uint32_t)0x000000C0)
#define IS_SDIO_RESPONSE(RESPONSE) (((RESPONSE) == SDIO_Response_No) || \
((RESPONSE) == SDIO_Response_Short) || \
((RESPONSE) == SDIO_Response_Long))
/**
* @}
*/
/** @defgroup SDIO_Wait_Interrupt_State
* @{
*/
#define SDIO_Wait_No ((uint32_t)0x00000000) /*!< SDIO No Wait, TimeOut is enabled */
#define SDIO_Wait_IT ((uint32_t)0x00000100) /*!< SDIO Wait Interrupt Request */
#define SDIO_Wait_Pend ((uint32_t)0x00000200) /*!< SDIO Wait End of transfer */
#define IS_SDIO_WAIT(WAIT) (((WAIT) == SDIO_Wait_No) || ((WAIT) == SDIO_Wait_IT) || \
((WAIT) == SDIO_Wait_Pend))
/**
* @}
*/
/** @defgroup SDIO_CPSM_State
* @{
*/
#define SDIO_CPSM_Disable ((uint32_t)0x00000000)
#define SDIO_CPSM_Enable ((uint32_t)0x00000400)
#define IS_SDIO_CPSM(CPSM) (((CPSM) == SDIO_CPSM_Enable) || ((CPSM) == SDIO_CPSM_Disable))
/**
* @}
*/
/** @defgroup SDIO_Response_Registers
* @{
*/
#define SDIO_RESP1 ((uint32_t)0x00000000)
#define SDIO_RESP2 ((uint32_t)0x00000004)
#define SDIO_RESP3 ((uint32_t)0x00000008)
#define SDIO_RESP4 ((uint32_t)0x0000000C)
#define IS_SDIO_RESP(RESP) (((RESP) == SDIO_RESP1) || ((RESP) == SDIO_RESP2) || \
((RESP) == SDIO_RESP3) || ((RESP) == SDIO_RESP4))
/**
* @}
*/
/** @defgroup SDIO_Data_Length
* @{
*/
#define IS_SDIO_DATA_LENGTH(LENGTH) ((LENGTH) <= 0x01FFFFFF)
/**
* @}
*/
/** @defgroup SDIO_Data_Block_Size
* @{
*/
#define SDIO_DataBlockSize_1b ((uint32_t)0x00000000)
#define SDIO_DataBlockSize_2b ((uint32_t)0x00000010)
#define SDIO_DataBlockSize_4b ((uint32_t)0x00000020)
#define SDIO_DataBlockSize_8b ((uint32_t)0x00000030)
#define SDIO_DataBlockSize_16b ((uint32_t)0x00000040)
#define SDIO_DataBlockSize_32b ((uint32_t)0x00000050)
#define SDIO_DataBlockSize_64b ((uint32_t)0x00000060)
#define SDIO_DataBlockSize_128b ((uint32_t)0x00000070)
#define SDIO_DataBlockSize_256b ((uint32_t)0x00000080)
#define SDIO_DataBlockSize_512b ((uint32_t)0x00000090)
#define SDIO_DataBlockSize_1024b ((uint32_t)0x000000A0)
#define SDIO_DataBlockSize_2048b ((uint32_t)0x000000B0)
#define SDIO_DataBlockSize_4096b ((uint32_t)0x000000C0)
#define SDIO_DataBlockSize_8192b ((uint32_t)0x000000D0)
#define SDIO_DataBlockSize_16384b ((uint32_t)0x000000E0)
#define IS_SDIO_BLOCK_SIZE(SIZE) (((SIZE) == SDIO_DataBlockSize_1b) || \
((SIZE) == SDIO_DataBlockSize_2b) || \
((SIZE) == SDIO_DataBlockSize_4b) || \
((SIZE) == SDIO_DataBlockSize_8b) || \
((SIZE) == SDIO_DataBlockSize_16b) || \
((SIZE) == SDIO_DataBlockSize_32b) || \
((SIZE) == SDIO_DataBlockSize_64b) || \
((SIZE) == SDIO_DataBlockSize_128b) || \
((SIZE) == SDIO_DataBlockSize_256b) || \
((SIZE) == SDIO_DataBlockSize_512b) || \
((SIZE) == SDIO_DataBlockSize_1024b) || \
((SIZE) == SDIO_DataBlockSize_2048b) || \
((SIZE) == SDIO_DataBlockSize_4096b) || \
((SIZE) == SDIO_DataBlockSize_8192b) || \
((SIZE) == SDIO_DataBlockSize_16384b))
/**
* @}
*/
/** @defgroup SDIO_Transfer_Direction
* @{
*/
#define SDIO_TransferDir_ToCard ((uint32_t)0x00000000)
#define SDIO_TransferDir_ToSDIO ((uint32_t)0x00000002)
#define IS_SDIO_TRANSFER_DIR(DIR) (((DIR) == SDIO_TransferDir_ToCard) || \
((DIR) == SDIO_TransferDir_ToSDIO))
/**
* @}
*/
/** @defgroup SDIO_Transfer_Type
* @{
*/
#define SDIO_TransferMode_Block ((uint32_t)0x00000000)
#define SDIO_TransferMode_Stream ((uint32_t)0x00000004)
#define IS_SDIO_TRANSFER_MODE(MODE) (((MODE) == SDIO_TransferMode_Stream) || \
((MODE) == SDIO_TransferMode_Block))
/**
* @}
*/
/** @defgroup SDIO_DPSM_State
* @{
*/
#define SDIO_DPSM_Disable ((uint32_t)0x00000000)
#define SDIO_DPSM_Enable ((uint32_t)0x00000001)
#define IS_SDIO_DPSM(DPSM) (((DPSM) == SDIO_DPSM_Enable) || ((DPSM) == SDIO_DPSM_Disable))
/**
* @}
*/
/** @defgroup SDIO_Flags
* @{
*/
#define SDIO_FLAG_CCRCFAIL ((uint32_t)0x00000001)
#define SDIO_FLAG_DCRCFAIL ((uint32_t)0x00000002)
#define SDIO_FLAG_CTIMEOUT ((uint32_t)0x00000004)
#define SDIO_FLAG_DTIMEOUT ((uint32_t)0x00000008)
#define SDIO_FLAG_TXUNDERR ((uint32_t)0x00000010)
#define SDIO_FLAG_RXOVERR ((uint32_t)0x00000020)
#define SDIO_FLAG_CMDREND ((uint32_t)0x00000040)
#define SDIO_FLAG_CMDSENT ((uint32_t)0x00000080)
#define SDIO_FLAG_DATAEND ((uint32_t)0x00000100)
#define SDIO_FLAG_STBITERR ((uint32_t)0x00000200)
#define SDIO_FLAG_DBCKEND ((uint32_t)0x00000400)
#define SDIO_FLAG_CMDACT ((uint32_t)0x00000800)
#define SDIO_FLAG_TXACT ((uint32_t)0x00001000)
#define SDIO_FLAG_RXACT ((uint32_t)0x00002000)
#define SDIO_FLAG_TXFIFOHE ((uint32_t)0x00004000)
#define SDIO_FLAG_RXFIFOHF ((uint32_t)0x00008000)
#define SDIO_FLAG_TXFIFOF ((uint32_t)0x00010000)
#define SDIO_FLAG_RXFIFOF ((uint32_t)0x00020000)
#define SDIO_FLAG_TXFIFOE ((uint32_t)0x00040000)
#define SDIO_FLAG_RXFIFOE ((uint32_t)0x00080000)
#define SDIO_FLAG_TXDAVL ((uint32_t)0x00100000)
#define SDIO_FLAG_RXDAVL ((uint32_t)0x00200000)
#define SDIO_FLAG_SDIOIT ((uint32_t)0x00400000)
#define SDIO_FLAG_CEATAEND ((uint32_t)0x00800000)
#define IS_SDIO_FLAG(FLAG) (((FLAG) == SDIO_FLAG_CCRCFAIL) || \
((FLAG) == SDIO_FLAG_DCRCFAIL) || \
((FLAG) == SDIO_FLAG_CTIMEOUT) || \
((FLAG) == SDIO_FLAG_DTIMEOUT) || \
((FLAG) == SDIO_FLAG_TXUNDERR) || \
((FLAG) == SDIO_FLAG_RXOVERR) || \
((FLAG) == SDIO_FLAG_CMDREND) || \
((FLAG) == SDIO_FLAG_CMDSENT) || \
((FLAG) == SDIO_FLAG_DATAEND) || \
((FLAG) == SDIO_FLAG_STBITERR) || \
((FLAG) == SDIO_FLAG_DBCKEND) || \
((FLAG) == SDIO_FLAG_CMDACT) || \
((FLAG) == SDIO_FLAG_TXACT) || \
((FLAG) == SDIO_FLAG_RXACT) || \
((FLAG) == SDIO_FLAG_TXFIFOHE) || \
((FLAG) == SDIO_FLAG_RXFIFOHF) || \
((FLAG) == SDIO_FLAG_TXFIFOF) || \
((FLAG) == SDIO_FLAG_RXFIFOF) || \
((FLAG) == SDIO_FLAG_TXFIFOE) || \
((FLAG) == SDIO_FLAG_RXFIFOE) || \
((FLAG) == SDIO_FLAG_TXDAVL) || \
((FLAG) == SDIO_FLAG_RXDAVL) || \
((FLAG) == SDIO_FLAG_SDIOIT) || \
((FLAG) == SDIO_FLAG_CEATAEND))
#define IS_SDIO_CLEAR_FLAG(FLAG) ((((FLAG) & (uint32_t)0xFF3FF800) == 0x00) && ((FLAG) != (uint32_t)0x00))
#define IS_SDIO_GET_IT(IT) (((IT) == SDIO_IT_CCRCFAIL) || \
((IT) == SDIO_IT_DCRCFAIL) || \
((IT) == SDIO_IT_CTIMEOUT) || \
((IT) == SDIO_IT_DTIMEOUT) || \
((IT) == SDIO_IT_TXUNDERR) || \
((IT) == SDIO_IT_RXOVERR) || \
((IT) == SDIO_IT_CMDREND) || \
((IT) == SDIO_IT_CMDSENT) || \
((IT) == SDIO_IT_DATAEND) || \
((IT) == SDIO_IT_STBITERR) || \
((IT) == SDIO_IT_DBCKEND) || \
((IT) == SDIO_IT_CMDACT) || \
((IT) == SDIO_IT_TXACT) || \
((IT) == SDIO_IT_RXACT) || \
((IT) == SDIO_IT_TXFIFOHE) || \
((IT) == SDIO_IT_RXFIFOHF) || \
((IT) == SDIO_IT_TXFIFOF) || \
((IT) == SDIO_IT_RXFIFOF) || \
((IT) == SDIO_IT_TXFIFOE) || \
((IT) == SDIO_IT_RXFIFOE) || \
((IT) == SDIO_IT_TXDAVL) || \
((IT) == SDIO_IT_RXDAVL) || \
((IT) == SDIO_IT_SDIOIT) || \
((IT) == SDIO_IT_CEATAEND))
#define IS_SDIO_CLEAR_IT(IT) ((((IT) & (uint32_t)0xFF3FF800) == 0x00) && ((IT) != (uint32_t)0x00))
/**
* @}
*/
/** @defgroup SDIO_Read_Wait_Mode
* @{
*/
#define SDIO_ReadWaitMode_CLK ((uint32_t)0x00000001)
#define SDIO_ReadWaitMode_DATA2 ((uint32_t)0x00000000)
#define IS_SDIO_READWAIT_MODE(MODE) (((MODE) == SDIO_ReadWaitMode_CLK) || \
((MODE) == SDIO_ReadWaitMode_DATA2))
/**
* @}
*/
/**
* @}
*/
/** @defgroup SDIO_Exported_Macros
* @{
*/
/**
* @}
*/
/** @defgroup SDIO_Exported_Functions
* @{
*/
void SDIO_DeInit(void);
void SDIO_Init(SDIO_InitTypeDef* SDIO_InitStruct);
void SDIO_StructInit(SDIO_InitTypeDef* SDIO_InitStruct);
void SDIO_ClockCmd(FunctionalState NewState);
void SDIO_SetPowerState(uint32_t SDIO_PowerState);
uint32_t SDIO_GetPowerState(void);
void SDIO_ITConfig(uint32_t SDIO_IT, FunctionalState NewState);
void SDIO_DMACmd(FunctionalState NewState);
void SDIO_SendCommand(SDIO_CmdInitTypeDef *SDIO_CmdInitStruct);
void SDIO_CmdStructInit(SDIO_CmdInitTypeDef* SDIO_CmdInitStruct);
uint8_t SDIO_GetCommandResponse(void);
uint32_t SDIO_GetResponse(uint32_t SDIO_RESP);
void SDIO_DataConfig(SDIO_DataInitTypeDef* SDIO_DataInitStruct);
void SDIO_DataStructInit(SDIO_DataInitTypeDef* SDIO_DataInitStruct);
uint32_t SDIO_GetDataCounter(void);
uint32_t SDIO_ReadData(void);
void SDIO_WriteData(uint32_t Data);
uint32_t SDIO_GetFIFOCount(void);
void SDIO_StartSDIOReadWait(FunctionalState NewState);
void SDIO_StopSDIOReadWait(FunctionalState NewState);
void SDIO_SetSDIOReadWaitMode(uint32_t SDIO_ReadWaitMode);
void SDIO_SetSDIOOperation(FunctionalState NewState);
void SDIO_SendSDIOSuspendCmd(FunctionalState NewState);
void SDIO_CommandCompletionCmd(FunctionalState NewState);
void SDIO_CEATAITCmd(FunctionalState NewState);
void SDIO_SendCEATACmd(FunctionalState NewState);
FlagStatus SDIO_GetFlagStatus(uint32_t SDIO_FLAG);
void SDIO_ClearFlag(uint32_t SDIO_FLAG);
ITStatus SDIO_GetITStatus(uint32_t SDIO_IT);
void SDIO_ClearITPendingBit(uint32_t SDIO_IT);
#ifdef __cplusplus
}
#endif
#endif /* __STM32F10x_SDIO_H */
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/

View File

@ -1,487 +0,0 @@
/**
******************************************************************************
* @file stm32f10x_spi.h
* @author MCD Application Team
* @version V3.5.0
* @date 11-March-2011
* @brief This file contains all the functions prototypes for the SPI firmware
* library.
******************************************************************************
* @attention
*
* 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, STMICROELECTRONICS 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 2011 STMicroelectronics</center></h2>
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32F10x_SPI_H
#define __STM32F10x_SPI_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32f10x.h"
/** @addtogroup STM32F10x_StdPeriph_Driver
* @{
*/
/** @addtogroup SPI
* @{
*/
/** @defgroup SPI_Exported_Types
* @{
*/
/**
* @brief SPI Init structure definition
*/
typedef struct
{
uint16_t SPI_Direction; /*!< Specifies the SPI unidirectional or bidirectional data mode.
This parameter can be a value of @ref SPI_data_direction */
uint16_t SPI_Mode; /*!< Specifies the SPI operating mode.
This parameter can be a value of @ref SPI_mode */
uint16_t SPI_DataSize; /*!< Specifies the SPI data size.
This parameter can be a value of @ref SPI_data_size */
uint16_t SPI_CPOL; /*!< Specifies the serial clock steady state.
This parameter can be a value of @ref SPI_Clock_Polarity */
uint16_t SPI_CPHA; /*!< Specifies the clock active edge for the bit capture.
This parameter can be a value of @ref SPI_Clock_Phase */
uint16_t SPI_NSS; /*!< Specifies whether the NSS signal is managed by
hardware (NSS pin) or by software using the SSI bit.
This parameter can be a value of @ref SPI_Slave_Select_management */
uint16_t SPI_BaudRatePrescaler; /*!< Specifies the Baud Rate prescaler value which will be
used to configure the transmit and receive SCK clock.
This parameter can be a value of @ref SPI_BaudRate_Prescaler.
@note The communication clock is derived from the master
clock. The slave clock does not need to be set. */
uint16_t SPI_FirstBit; /*!< Specifies whether data transfers start from MSB or LSB bit.
This parameter can be a value of @ref SPI_MSB_LSB_transmission */
uint16_t SPI_CRCPolynomial; /*!< Specifies the polynomial used for the CRC calculation. */
}SPI_InitTypeDef;
/**
* @brief I2S Init structure definition
*/
typedef struct
{
uint16_t I2S_Mode; /*!< Specifies the I2S operating mode.
This parameter can be a value of @ref I2S_Mode */
uint16_t I2S_Standard; /*!< Specifies the standard used for the I2S communication.
This parameter can be a value of @ref I2S_Standard */
uint16_t I2S_DataFormat; /*!< Specifies the data format for the I2S communication.
This parameter can be a value of @ref I2S_Data_Format */
uint16_t I2S_MCLKOutput; /*!< Specifies whether the I2S MCLK output is enabled or not.
This parameter can be a value of @ref I2S_MCLK_Output */
uint32_t I2S_AudioFreq; /*!< Specifies the frequency selected for the I2S communication.
This parameter can be a value of @ref I2S_Audio_Frequency */
uint16_t I2S_CPOL; /*!< Specifies the idle state of the I2S clock.
This parameter can be a value of @ref I2S_Clock_Polarity */
}I2S_InitTypeDef;
/**
* @}
*/
/** @defgroup SPI_Exported_Constants
* @{
*/
#define IS_SPI_ALL_PERIPH(PERIPH) (((PERIPH) == SPI1) || \
((PERIPH) == SPI2) || \
((PERIPH) == SPI3))
#define IS_SPI_23_PERIPH(PERIPH) (((PERIPH) == SPI2) || \
((PERIPH) == SPI3))
/** @defgroup SPI_data_direction
* @{
*/
#define SPI_Direction_2Lines_FullDuplex ((uint16_t)0x0000)
#define SPI_Direction_2Lines_RxOnly ((uint16_t)0x0400)
#define SPI_Direction_1Line_Rx ((uint16_t)0x8000)
#define SPI_Direction_1Line_Tx ((uint16_t)0xC000)
#define IS_SPI_DIRECTION_MODE(MODE) (((MODE) == SPI_Direction_2Lines_FullDuplex) || \
((MODE) == SPI_Direction_2Lines_RxOnly) || \
((MODE) == SPI_Direction_1Line_Rx) || \
((MODE) == SPI_Direction_1Line_Tx))
/**
* @}
*/
/** @defgroup SPI_mode
* @{
*/
#define SPI_Mode_Master ((uint16_t)0x0104)
#define SPI_Mode_Slave ((uint16_t)0x0000)
#define IS_SPI_MODE(MODE) (((MODE) == SPI_Mode_Master) || \
((MODE) == SPI_Mode_Slave))
/**
* @}
*/
/** @defgroup SPI_data_size
* @{
*/
#define SPI_DataSize_16b ((uint16_t)0x0800)
#define SPI_DataSize_8b ((uint16_t)0x0000)
#define IS_SPI_DATASIZE(DATASIZE) (((DATASIZE) == SPI_DataSize_16b) || \
((DATASIZE) == SPI_DataSize_8b))
/**
* @}
*/
/** @defgroup SPI_Clock_Polarity
* @{
*/
#define SPI_CPOL_Low ((uint16_t)0x0000)
#define SPI_CPOL_High ((uint16_t)0x0002)
#define IS_SPI_CPOL(CPOL) (((CPOL) == SPI_CPOL_Low) || \
((CPOL) == SPI_CPOL_High))
/**
* @}
*/
/** @defgroup SPI_Clock_Phase
* @{
*/
#define SPI_CPHA_1Edge ((uint16_t)0x0000)
#define SPI_CPHA_2Edge ((uint16_t)0x0001)
#define IS_SPI_CPHA(CPHA) (((CPHA) == SPI_CPHA_1Edge) || \
((CPHA) == SPI_CPHA_2Edge))
/**
* @}
*/
/** @defgroup SPI_Slave_Select_management
* @{
*/
#define SPI_NSS_Soft ((uint16_t)0x0200)
#define SPI_NSS_Hard ((uint16_t)0x0000)
#define IS_SPI_NSS(NSS) (((NSS) == SPI_NSS_Soft) || \
((NSS) == SPI_NSS_Hard))
/**
* @}
*/
/** @defgroup SPI_BaudRate_Prescaler
* @{
*/
#define SPI_BaudRatePrescaler_2 ((uint16_t)0x0000)
#define SPI_BaudRatePrescaler_4 ((uint16_t)0x0008)
#define SPI_BaudRatePrescaler_8 ((uint16_t)0x0010)
#define SPI_BaudRatePrescaler_16 ((uint16_t)0x0018)
#define SPI_BaudRatePrescaler_32 ((uint16_t)0x0020)
#define SPI_BaudRatePrescaler_64 ((uint16_t)0x0028)
#define SPI_BaudRatePrescaler_128 ((uint16_t)0x0030)
#define SPI_BaudRatePrescaler_256 ((uint16_t)0x0038)
#define IS_SPI_BAUDRATE_PRESCALER(PRESCALER) (((PRESCALER) == SPI_BaudRatePrescaler_2) || \
((PRESCALER) == SPI_BaudRatePrescaler_4) || \
((PRESCALER) == SPI_BaudRatePrescaler_8) || \
((PRESCALER) == SPI_BaudRatePrescaler_16) || \
((PRESCALER) == SPI_BaudRatePrescaler_32) || \
((PRESCALER) == SPI_BaudRatePrescaler_64) || \
((PRESCALER) == SPI_BaudRatePrescaler_128) || \
((PRESCALER) == SPI_BaudRatePrescaler_256))
/**
* @}
*/
/** @defgroup SPI_MSB_LSB_transmission
* @{
*/
#define SPI_FirstBit_MSB ((uint16_t)0x0000)
#define SPI_FirstBit_LSB ((uint16_t)0x0080)
#define IS_SPI_FIRST_BIT(BIT) (((BIT) == SPI_FirstBit_MSB) || \
((BIT) == SPI_FirstBit_LSB))
/**
* @}
*/
/** @defgroup I2S_Mode
* @{
*/
#define I2S_Mode_SlaveTx ((uint16_t)0x0000)
#define I2S_Mode_SlaveRx ((uint16_t)0x0100)
#define I2S_Mode_MasterTx ((uint16_t)0x0200)
#define I2S_Mode_MasterRx ((uint16_t)0x0300)
#define IS_I2S_MODE(MODE) (((MODE) == I2S_Mode_SlaveTx) || \
((MODE) == I2S_Mode_SlaveRx) || \
((MODE) == I2S_Mode_MasterTx) || \
((MODE) == I2S_Mode_MasterRx) )
/**
* @}
*/
/** @defgroup I2S_Standard
* @{
*/
#define I2S_Standard_Phillips ((uint16_t)0x0000)
#define I2S_Standard_MSB ((uint16_t)0x0010)
#define I2S_Standard_LSB ((uint16_t)0x0020)
#define I2S_Standard_PCMShort ((uint16_t)0x0030)
#define I2S_Standard_PCMLong ((uint16_t)0x00B0)
#define IS_I2S_STANDARD(STANDARD) (((STANDARD) == I2S_Standard_Phillips) || \
((STANDARD) == I2S_Standard_MSB) || \
((STANDARD) == I2S_Standard_LSB) || \
((STANDARD) == I2S_Standard_PCMShort) || \
((STANDARD) == I2S_Standard_PCMLong))
/**
* @}
*/
/** @defgroup I2S_Data_Format
* @{
*/
#define I2S_DataFormat_16b ((uint16_t)0x0000)
#define I2S_DataFormat_16bextended ((uint16_t)0x0001)
#define I2S_DataFormat_24b ((uint16_t)0x0003)
#define I2S_DataFormat_32b ((uint16_t)0x0005)
#define IS_I2S_DATA_FORMAT(FORMAT) (((FORMAT) == I2S_DataFormat_16b) || \
((FORMAT) == I2S_DataFormat_16bextended) || \
((FORMAT) == I2S_DataFormat_24b) || \
((FORMAT) == I2S_DataFormat_32b))
/**
* @}
*/
/** @defgroup I2S_MCLK_Output
* @{
*/
#define I2S_MCLKOutput_Enable ((uint16_t)0x0200)
#define I2S_MCLKOutput_Disable ((uint16_t)0x0000)
#define IS_I2S_MCLK_OUTPUT(OUTPUT) (((OUTPUT) == I2S_MCLKOutput_Enable) || \
((OUTPUT) == I2S_MCLKOutput_Disable))
/**
* @}
*/
/** @defgroup I2S_Audio_Frequency
* @{
*/
#define I2S_AudioFreq_192k ((uint32_t)192000)
#define I2S_AudioFreq_96k ((uint32_t)96000)
#define I2S_AudioFreq_48k ((uint32_t)48000)
#define I2S_AudioFreq_44k ((uint32_t)44100)
#define I2S_AudioFreq_32k ((uint32_t)32000)
#define I2S_AudioFreq_22k ((uint32_t)22050)
#define I2S_AudioFreq_16k ((uint32_t)16000)
#define I2S_AudioFreq_11k ((uint32_t)11025)
#define I2S_AudioFreq_8k ((uint32_t)8000)
#define I2S_AudioFreq_Default ((uint32_t)2)
#define IS_I2S_AUDIO_FREQ(FREQ) ((((FREQ) >= I2S_AudioFreq_8k) && \
((FREQ) <= I2S_AudioFreq_192k)) || \
((FREQ) == I2S_AudioFreq_Default))
/**
* @}
*/
/** @defgroup I2S_Clock_Polarity
* @{
*/
#define I2S_CPOL_Low ((uint16_t)0x0000)
#define I2S_CPOL_High ((uint16_t)0x0008)
#define IS_I2S_CPOL(CPOL) (((CPOL) == I2S_CPOL_Low) || \
((CPOL) == I2S_CPOL_High))
/**
* @}
*/
/** @defgroup SPI_I2S_DMA_transfer_requests
* @{
*/
#define SPI_I2S_DMAReq_Tx ((uint16_t)0x0002)
#define SPI_I2S_DMAReq_Rx ((uint16_t)0x0001)
#define IS_SPI_I2S_DMAREQ(DMAREQ) ((((DMAREQ) & (uint16_t)0xFFFC) == 0x00) && ((DMAREQ) != 0x00))
/**
* @}
*/
/** @defgroup SPI_NSS_internal_software_management
* @{
*/
#define SPI_NSSInternalSoft_Set ((uint16_t)0x0100)
#define SPI_NSSInternalSoft_Reset ((uint16_t)0xFEFF)
#define IS_SPI_NSS_INTERNAL(INTERNAL) (((INTERNAL) == SPI_NSSInternalSoft_Set) || \
((INTERNAL) == SPI_NSSInternalSoft_Reset))
/**
* @}
*/
/** @defgroup SPI_CRC_Transmit_Receive
* @{
*/
#define SPI_CRC_Tx ((uint8_t)0x00)
#define SPI_CRC_Rx ((uint8_t)0x01)
#define IS_SPI_CRC(CRC) (((CRC) == SPI_CRC_Tx) || ((CRC) == SPI_CRC_Rx))
/**
* @}
*/
/** @defgroup SPI_direction_transmit_receive
* @{
*/
#define SPI_Direction_Rx ((uint16_t)0xBFFF)
#define SPI_Direction_Tx ((uint16_t)0x4000)
#define IS_SPI_DIRECTION(DIRECTION) (((DIRECTION) == SPI_Direction_Rx) || \
((DIRECTION) == SPI_Direction_Tx))
/**
* @}
*/
/** @defgroup SPI_I2S_interrupts_definition
* @{
*/
#define SPI_I2S_IT_TXE ((uint8_t)0x71)
#define SPI_I2S_IT_RXNE ((uint8_t)0x60)
#define SPI_I2S_IT_ERR ((uint8_t)0x50)
#define IS_SPI_I2S_CONFIG_IT(IT) (((IT) == SPI_I2S_IT_TXE) || \
((IT) == SPI_I2S_IT_RXNE) || \
((IT) == SPI_I2S_IT_ERR))
#define SPI_I2S_IT_OVR ((uint8_t)0x56)
#define SPI_IT_MODF ((uint8_t)0x55)
#define SPI_IT_CRCERR ((uint8_t)0x54)
#define I2S_IT_UDR ((uint8_t)0x53)
#define IS_SPI_I2S_CLEAR_IT(IT) (((IT) == SPI_IT_CRCERR))
#define IS_SPI_I2S_GET_IT(IT) (((IT) == SPI_I2S_IT_RXNE) || ((IT) == SPI_I2S_IT_TXE) || \
((IT) == I2S_IT_UDR) || ((IT) == SPI_IT_CRCERR) || \
((IT) == SPI_IT_MODF) || ((IT) == SPI_I2S_IT_OVR))
/**
* @}
*/
/** @defgroup SPI_I2S_flags_definition
* @{
*/
#define SPI_I2S_FLAG_RXNE ((uint16_t)0x0001)
#define SPI_I2S_FLAG_TXE ((uint16_t)0x0002)
#define I2S_FLAG_CHSIDE ((uint16_t)0x0004)
#define I2S_FLAG_UDR ((uint16_t)0x0008)
#define SPI_FLAG_CRCERR ((uint16_t)0x0010)
#define SPI_FLAG_MODF ((uint16_t)0x0020)
#define SPI_I2S_FLAG_OVR ((uint16_t)0x0040)
#define SPI_I2S_FLAG_BSY ((uint16_t)0x0080)
#define IS_SPI_I2S_CLEAR_FLAG(FLAG) (((FLAG) == SPI_FLAG_CRCERR))
#define IS_SPI_I2S_GET_FLAG(FLAG) (((FLAG) == SPI_I2S_FLAG_BSY) || ((FLAG) == SPI_I2S_FLAG_OVR) || \
((FLAG) == SPI_FLAG_MODF) || ((FLAG) == SPI_FLAG_CRCERR) || \
((FLAG) == I2S_FLAG_UDR) || ((FLAG) == I2S_FLAG_CHSIDE) || \
((FLAG) == SPI_I2S_FLAG_TXE) || ((FLAG) == SPI_I2S_FLAG_RXNE))
/**
* @}
*/
/** @defgroup SPI_CRC_polynomial
* @{
*/
#define IS_SPI_CRC_POLYNOMIAL(POLYNOMIAL) ((POLYNOMIAL) >= 0x1)
/**
* @}
*/
/**
* @}
*/
/** @defgroup SPI_Exported_Macros
* @{
*/
/**
* @}
*/
/** @defgroup SPI_Exported_Functions
* @{
*/
void SPI_I2S_DeInit(SPI_TypeDef* SPIx);
void SPI_Init(SPI_TypeDef* SPIx, SPI_InitTypeDef* SPI_InitStruct);
void I2S_Init(SPI_TypeDef* SPIx, I2S_InitTypeDef* I2S_InitStruct);
void SPI_StructInit(SPI_InitTypeDef* SPI_InitStruct);
void I2S_StructInit(I2S_InitTypeDef* I2S_InitStruct);
void SPI_Cmd(SPI_TypeDef* SPIx, FunctionalState NewState);
void I2S_Cmd(SPI_TypeDef* SPIx, FunctionalState NewState);
void SPI_I2S_ITConfig(SPI_TypeDef* SPIx, uint8_t SPI_I2S_IT, FunctionalState NewState);
void SPI_I2S_DMACmd(SPI_TypeDef* SPIx, uint16_t SPI_I2S_DMAReq, FunctionalState NewState);
void SPI_I2S_SendData(SPI_TypeDef* SPIx, uint16_t Data);
uint16_t SPI_I2S_ReceiveData(SPI_TypeDef* SPIx);
void SPI_NSSInternalSoftwareConfig(SPI_TypeDef* SPIx, uint16_t SPI_NSSInternalSoft);
void SPI_SSOutputCmd(SPI_TypeDef* SPIx, FunctionalState NewState);
void SPI_DataSizeConfig(SPI_TypeDef* SPIx, uint16_t SPI_DataSize);
void SPI_TransmitCRC(SPI_TypeDef* SPIx);
void SPI_CalculateCRC(SPI_TypeDef* SPIx, FunctionalState NewState);
uint16_t SPI_GetCRC(SPI_TypeDef* SPIx, uint8_t SPI_CRC);
uint16_t SPI_GetCRCPolynomial(SPI_TypeDef* SPIx);
void SPI_BiDirectionalLineConfig(SPI_TypeDef* SPIx, uint16_t SPI_Direction);
FlagStatus SPI_I2S_GetFlagStatus(SPI_TypeDef* SPIx, uint16_t SPI_I2S_FLAG);
void SPI_I2S_ClearFlag(SPI_TypeDef* SPIx, uint16_t SPI_I2S_FLAG);
ITStatus SPI_I2S_GetITStatus(SPI_TypeDef* SPIx, uint8_t SPI_I2S_IT);
void SPI_I2S_ClearITPendingBit(SPI_TypeDef* SPIx, uint8_t SPI_I2S_IT);
#ifdef __cplusplus
}
#endif
#endif /*__STM32F10x_SPI_H */
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/

View File

@ -1,412 +0,0 @@
/**
******************************************************************************
* @file stm32f10x_usart.h
* @author MCD Application Team
* @version V3.5.0
* @date 11-March-2011
* @brief This file contains all the functions prototypes for the USART
* firmware library.
******************************************************************************
* @attention
*
* 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, STMICROELECTRONICS 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 2011 STMicroelectronics</center></h2>
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32F10x_USART_H
#define __STM32F10x_USART_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32f10x.h"
/** @addtogroup STM32F10x_StdPeriph_Driver
* @{
*/
/** @addtogroup USART
* @{
*/
/** @defgroup USART_Exported_Types
* @{
*/
/**
* @brief USART Init Structure definition
*/
typedef struct
{
uint32_t USART_BaudRate; /*!< This member configures the USART communication baud rate.
The baud rate is computed using the following formula:
- IntegerDivider = ((PCLKx) / (16 * (USART_InitStruct->USART_BaudRate)))
- FractionalDivider = ((IntegerDivider - ((u32) IntegerDivider)) * 16) + 0.5 */
uint16_t USART_WordLength; /*!< Specifies the number of data bits transmitted or received in a frame.
This parameter can be a value of @ref USART_Word_Length */
uint16_t USART_StopBits; /*!< Specifies the number of stop bits transmitted.
This parameter can be a value of @ref USART_Stop_Bits */
uint16_t USART_Parity; /*!< Specifies the parity mode.
This parameter can be a value of @ref USART_Parity
@note When parity is enabled, the computed parity is inserted
at the MSB position of the transmitted data (9th bit when
the word length is set to 9 data bits; 8th bit when the
word length is set to 8 data bits). */
uint16_t USART_Mode; /*!< Specifies wether the Receive or Transmit mode is enabled or disabled.
This parameter can be a value of @ref USART_Mode */
uint16_t USART_HardwareFlowControl; /*!< Specifies wether the hardware flow control mode is enabled
or disabled.
This parameter can be a value of @ref USART_Hardware_Flow_Control */
} USART_InitTypeDef;
/**
* @brief USART Clock Init Structure definition
*/
typedef struct
{
uint16_t USART_Clock; /*!< Specifies whether the USART clock is enabled or disabled.
This parameter can be a value of @ref USART_Clock */
uint16_t USART_CPOL; /*!< Specifies the steady state value of the serial clock.
This parameter can be a value of @ref USART_Clock_Polarity */
uint16_t USART_CPHA; /*!< Specifies the clock transition on which the bit capture is made.
This parameter can be a value of @ref USART_Clock_Phase */
uint16_t USART_LastBit; /*!< Specifies whether the clock pulse corresponding to the last transmitted
data bit (MSB) has to be output on the SCLK pin in synchronous mode.
This parameter can be a value of @ref USART_Last_Bit */
} USART_ClockInitTypeDef;
/**
* @}
*/
/** @defgroup USART_Exported_Constants
* @{
*/
#define IS_USART_ALL_PERIPH(PERIPH) (((PERIPH) == USART1) || \
((PERIPH) == USART2) || \
((PERIPH) == USART3) || \
((PERIPH) == UART4) || \
((PERIPH) == UART5))
#define IS_USART_123_PERIPH(PERIPH) (((PERIPH) == USART1) || \
((PERIPH) == USART2) || \
((PERIPH) == USART3))
#define IS_USART_1234_PERIPH(PERIPH) (((PERIPH) == USART1) || \
((PERIPH) == USART2) || \
((PERIPH) == USART3) || \
((PERIPH) == UART4))
/** @defgroup USART_Word_Length
* @{
*/
#define USART_WordLength_8b ((uint16_t)0x0000)
#define USART_WordLength_9b ((uint16_t)0x1000)
#define IS_USART_WORD_LENGTH(LENGTH) (((LENGTH) == USART_WordLength_8b) || \
((LENGTH) == USART_WordLength_9b))
/**
* @}
*/
/** @defgroup USART_Stop_Bits
* @{
*/
#define USART_StopBits_1 ((uint16_t)0x0000)
#define USART_StopBits_0_5 ((uint16_t)0x1000)
#define USART_StopBits_2 ((uint16_t)0x2000)
#define USART_StopBits_1_5 ((uint16_t)0x3000)
#define IS_USART_STOPBITS(STOPBITS) (((STOPBITS) == USART_StopBits_1) || \
((STOPBITS) == USART_StopBits_0_5) || \
((STOPBITS) == USART_StopBits_2) || \
((STOPBITS) == USART_StopBits_1_5))
/**
* @}
*/
/** @defgroup USART_Parity
* @{
*/
#define USART_Parity_No ((uint16_t)0x0000)
#define USART_Parity_Even ((uint16_t)0x0400)
#define USART_Parity_Odd ((uint16_t)0x0600)
#define IS_USART_PARITY(PARITY) (((PARITY) == USART_Parity_No) || \
((PARITY) == USART_Parity_Even) || \
((PARITY) == USART_Parity_Odd))
/**
* @}
*/
/** @defgroup USART_Mode
* @{
*/
#define USART_Mode_Rx ((uint16_t)0x0004)
#define USART_Mode_Tx ((uint16_t)0x0008)
#define IS_USART_MODE(MODE) ((((MODE) & (uint16_t)0xFFF3) == 0x00) && ((MODE) != (uint16_t)0x00))
/**
* @}
*/
/** @defgroup USART_Hardware_Flow_Control
* @{
*/
#define USART_HardwareFlowControl_None ((uint16_t)0x0000)
#define USART_HardwareFlowControl_RTS ((uint16_t)0x0100)
#define USART_HardwareFlowControl_CTS ((uint16_t)0x0200)
#define USART_HardwareFlowControl_RTS_CTS ((uint16_t)0x0300)
#define IS_USART_HARDWARE_FLOW_CONTROL(CONTROL)\
(((CONTROL) == USART_HardwareFlowControl_None) || \
((CONTROL) == USART_HardwareFlowControl_RTS) || \
((CONTROL) == USART_HardwareFlowControl_CTS) || \
((CONTROL) == USART_HardwareFlowControl_RTS_CTS))
/**
* @}
*/
/** @defgroup USART_Clock
* @{
*/
#define USART_Clock_Disable ((uint16_t)0x0000)
#define USART_Clock_Enable ((uint16_t)0x0800)
#define IS_USART_CLOCK(CLOCK) (((CLOCK) == USART_Clock_Disable) || \
((CLOCK) == USART_Clock_Enable))
/**
* @}
*/
/** @defgroup USART_Clock_Polarity
* @{
*/
#define USART_CPOL_Low ((uint16_t)0x0000)
#define USART_CPOL_High ((uint16_t)0x0400)
#define IS_USART_CPOL(CPOL) (((CPOL) == USART_CPOL_Low) || ((CPOL) == USART_CPOL_High))
/**
* @}
*/
/** @defgroup USART_Clock_Phase
* @{
*/
#define USART_CPHA_1Edge ((uint16_t)0x0000)
#define USART_CPHA_2Edge ((uint16_t)0x0200)
#define IS_USART_CPHA(CPHA) (((CPHA) == USART_CPHA_1Edge) || ((CPHA) == USART_CPHA_2Edge))
/**
* @}
*/
/** @defgroup USART_Last_Bit
* @{
*/
#define USART_LastBit_Disable ((uint16_t)0x0000)
#define USART_LastBit_Enable ((uint16_t)0x0100)
#define IS_USART_LASTBIT(LASTBIT) (((LASTBIT) == USART_LastBit_Disable) || \
((LASTBIT) == USART_LastBit_Enable))
/**
* @}
*/
/** @defgroup USART_Interrupt_definition
* @{
*/
#define USART_IT_PE ((uint16_t)0x0028)
#define USART_IT_TXE ((uint16_t)0x0727)
#define USART_IT_TC ((uint16_t)0x0626)
#define USART_IT_RXNE ((uint16_t)0x0525)
#define USART_IT_IDLE ((uint16_t)0x0424)
#define USART_IT_LBD ((uint16_t)0x0846)
#define USART_IT_CTS ((uint16_t)0x096A)
#define USART_IT_ERR ((uint16_t)0x0060)
#define USART_IT_ORE ((uint16_t)0x0360)
#define USART_IT_NE ((uint16_t)0x0260)
#define USART_IT_FE ((uint16_t)0x0160)
#define IS_USART_CONFIG_IT(IT) (((IT) == USART_IT_PE) || ((IT) == USART_IT_TXE) || \
((IT) == USART_IT_TC) || ((IT) == USART_IT_RXNE) || \
((IT) == USART_IT_IDLE) || ((IT) == USART_IT_LBD) || \
((IT) == USART_IT_CTS) || ((IT) == USART_IT_ERR))
#define IS_USART_GET_IT(IT) (((IT) == USART_IT_PE) || ((IT) == USART_IT_TXE) || \
((IT) == USART_IT_TC) || ((IT) == USART_IT_RXNE) || \
((IT) == USART_IT_IDLE) || ((IT) == USART_IT_LBD) || \
((IT) == USART_IT_CTS) || ((IT) == USART_IT_ORE) || \
((IT) == USART_IT_NE) || ((IT) == USART_IT_FE))
#define IS_USART_CLEAR_IT(IT) (((IT) == USART_IT_TC) || ((IT) == USART_IT_RXNE) || \
((IT) == USART_IT_LBD) || ((IT) == USART_IT_CTS))
/**
* @}
*/
/** @defgroup USART_DMA_Requests
* @{
*/
#define USART_DMAReq_Tx ((uint16_t)0x0080)
#define USART_DMAReq_Rx ((uint16_t)0x0040)
#define IS_USART_DMAREQ(DMAREQ) ((((DMAREQ) & (uint16_t)0xFF3F) == 0x00) && ((DMAREQ) != (uint16_t)0x00))
/**
* @}
*/
/** @defgroup USART_WakeUp_methods
* @{
*/
#define USART_WakeUp_IdleLine ((uint16_t)0x0000)
#define USART_WakeUp_AddressMark ((uint16_t)0x0800)
#define IS_USART_WAKEUP(WAKEUP) (((WAKEUP) == USART_WakeUp_IdleLine) || \
((WAKEUP) == USART_WakeUp_AddressMark))
/**
* @}
*/
/** @defgroup USART_LIN_Break_Detection_Length
* @{
*/
#define USART_LINBreakDetectLength_10b ((uint16_t)0x0000)
#define USART_LINBreakDetectLength_11b ((uint16_t)0x0020)
#define IS_USART_LIN_BREAK_DETECT_LENGTH(LENGTH) \
(((LENGTH) == USART_LINBreakDetectLength_10b) || \
((LENGTH) == USART_LINBreakDetectLength_11b))
/**
* @}
*/
/** @defgroup USART_IrDA_Low_Power
* @{
*/
#define USART_IrDAMode_LowPower ((uint16_t)0x0004)
#define USART_IrDAMode_Normal ((uint16_t)0x0000)
#define IS_USART_IRDA_MODE(MODE) (((MODE) == USART_IrDAMode_LowPower) || \
((MODE) == USART_IrDAMode_Normal))
/**
* @}
*/
/** @defgroup USART_Flags
* @{
*/
#define USART_FLAG_CTS ((uint16_t)0x0200)
#define USART_FLAG_LBD ((uint16_t)0x0100)
#define USART_FLAG_TXE ((uint16_t)0x0080)
#define USART_FLAG_TC ((uint16_t)0x0040)
#define USART_FLAG_RXNE ((uint16_t)0x0020)
#define USART_FLAG_IDLE ((uint16_t)0x0010)
#define USART_FLAG_ORE ((uint16_t)0x0008)
#define USART_FLAG_NE ((uint16_t)0x0004)
#define USART_FLAG_FE ((uint16_t)0x0002)
#define USART_FLAG_PE ((uint16_t)0x0001)
#define IS_USART_FLAG(FLAG) (((FLAG) == USART_FLAG_PE) || ((FLAG) == USART_FLAG_TXE) || \
((FLAG) == USART_FLAG_TC) || ((FLAG) == USART_FLAG_RXNE) || \
((FLAG) == USART_FLAG_IDLE) || ((FLAG) == USART_FLAG_LBD) || \
((FLAG) == USART_FLAG_CTS) || ((FLAG) == USART_FLAG_ORE) || \
((FLAG) == USART_FLAG_NE) || ((FLAG) == USART_FLAG_FE))
#define IS_USART_CLEAR_FLAG(FLAG) ((((FLAG) & (uint16_t)0xFC9F) == 0x00) && ((FLAG) != (uint16_t)0x00))
#define IS_USART_PERIPH_FLAG(PERIPH, USART_FLAG) ((((*(uint32_t*)&(PERIPH)) != UART4_BASE) &&\
((*(uint32_t*)&(PERIPH)) != UART5_BASE)) \
|| ((USART_FLAG) != USART_FLAG_CTS))
#define IS_USART_BAUDRATE(BAUDRATE) (((BAUDRATE) > 0) && ((BAUDRATE) < 0x0044AA21))
#define IS_USART_ADDRESS(ADDRESS) ((ADDRESS) <= 0xF)
#define IS_USART_DATA(DATA) ((DATA) <= 0x1FF)
/**
* @}
*/
/**
* @}
*/
/** @defgroup USART_Exported_Macros
* @{
*/
/**
* @}
*/
/** @defgroup USART_Exported_Functions
* @{
*/
void USART_DeInit(USART_TypeDef* USARTx);
void USART_Init(USART_TypeDef* USARTx, USART_InitTypeDef* USART_InitStruct);
void USART_StructInit(USART_InitTypeDef* USART_InitStruct);
void USART_ClockInit(USART_TypeDef* USARTx, USART_ClockInitTypeDef* USART_ClockInitStruct);
void USART_ClockStructInit(USART_ClockInitTypeDef* USART_ClockInitStruct);
void USART_Cmd(USART_TypeDef* USARTx, FunctionalState NewState);
void USART_ITConfig(USART_TypeDef* USARTx, uint16_t USART_IT, FunctionalState NewState);
void USART_DMACmd(USART_TypeDef* USARTx, uint16_t USART_DMAReq, FunctionalState NewState);
void USART_SetAddress(USART_TypeDef* USARTx, uint8_t USART_Address);
void USART_WakeUpConfig(USART_TypeDef* USARTx, uint16_t USART_WakeUp);
void USART_ReceiverWakeUpCmd(USART_TypeDef* USARTx, FunctionalState NewState);
void USART_LINBreakDetectLengthConfig(USART_TypeDef* USARTx, uint16_t USART_LINBreakDetectLength);
void USART_LINCmd(USART_TypeDef* USARTx, FunctionalState NewState);
void USART_SendData(USART_TypeDef* USARTx, uint16_t Data);
uint16_t USART_ReceiveData(USART_TypeDef* USARTx);
void USART_SendBreak(USART_TypeDef* USARTx);
void USART_SetGuardTime(USART_TypeDef* USARTx, uint8_t USART_GuardTime);
void USART_SetPrescaler(USART_TypeDef* USARTx, uint8_t USART_Prescaler);
void USART_SmartCardCmd(USART_TypeDef* USARTx, FunctionalState NewState);
void USART_SmartCardNACKCmd(USART_TypeDef* USARTx, FunctionalState NewState);
void USART_HalfDuplexCmd(USART_TypeDef* USARTx, FunctionalState NewState);
void USART_OverSampling8Cmd(USART_TypeDef* USARTx, FunctionalState NewState);
void USART_OneBitMethodCmd(USART_TypeDef* USARTx, FunctionalState NewState);
void USART_IrDAConfig(USART_TypeDef* USARTx, uint16_t USART_IrDAMode);
void USART_IrDACmd(USART_TypeDef* USARTx, FunctionalState NewState);
FlagStatus USART_GetFlagStatus(USART_TypeDef* USARTx, uint16_t USART_FLAG);
void USART_ClearFlag(USART_TypeDef* USARTx, uint16_t USART_FLAG);
ITStatus USART_GetITStatus(USART_TypeDef* USARTx, uint16_t USART_IT);
void USART_ClearITPendingBit(USART_TypeDef* USARTx, uint16_t USART_IT);
#ifdef __cplusplus
}
#endif
#endif /* __STM32F10x_USART_H */
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/

View File

@ -1,115 +0,0 @@
/**
******************************************************************************
* @file stm32f10x_wwdg.h
* @author MCD Application Team
* @version V3.5.0
* @date 11-March-2011
* @brief This file contains all the functions prototypes for the WWDG firmware
* library.
******************************************************************************
* @attention
*
* 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, STMICROELECTRONICS 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 2011 STMicroelectronics</center></h2>
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32F10x_WWDG_H
#define __STM32F10x_WWDG_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32f10x.h"
/** @addtogroup STM32F10x_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);
#ifdef __cplusplus
}
#endif
#endif /* __STM32F10x_WWDG_H */
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/

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