47 #define CR1_UE_Set ((uint16_t)0x2000) 48 #define CR1_UE_Reset ((uint16_t)0xDFFF) 50 #define CR1_WAKE_Mask ((uint16_t)0xF7FF) 52 #define CR1_RWU_Set ((uint16_t)0x0002) 53 #define CR1_RWU_Reset ((uint16_t)0xFFFD) 54 #define CR1_SBK_Set ((uint16_t)0x0001) 55 #define CR1_CLEAR_Mask ((uint16_t)0xE9F3) 56 #define CR2_Address_Mask ((uint16_t)0xFFF0) 58 #define CR2_LINEN_Set ((uint16_t)0x4000) 59 #define CR2_LINEN_Reset ((uint16_t)0xBFFF) 61 #define CR2_LBDL_Mask ((uint16_t)0xFFDF) 62 #define CR2_STOP_CLEAR_Mask ((uint16_t)0xCFFF) 63 #define CR2_CLOCK_CLEAR_Mask ((uint16_t)0xF0FF) 65 #define CR3_SCEN_Set ((uint16_t)0x0020) 66 #define CR3_SCEN_Reset ((uint16_t)0xFFDF) 68 #define CR3_NACK_Set ((uint16_t)0x0010) 69 #define CR3_NACK_Reset ((uint16_t)0xFFEF) 71 #define CR3_HDSEL_Set ((uint16_t)0x0008) 72 #define CR3_HDSEL_Reset ((uint16_t)0xFFF7) 74 #define CR3_IRLP_Mask ((uint16_t)0xFFFB) 75 #define CR3_CLEAR_Mask ((uint16_t)0xFCFF) 77 #define CR3_IREN_Set ((uint16_t)0x0002) 78 #define CR3_IREN_Reset ((uint16_t)0xFFFD) 79 #define GTPR_LSB_Mask ((uint16_t)0x00FF) 80 #define GTPR_MSB_Mask ((uint16_t)0xFF00) 81 #define IT_Mask ((uint16_t)0x001F) 84 #define CR1_OVER8_Set ((u16)0x8000) 85 #define CR1_OVER8_Reset ((u16)0x7FFF) 88 #define CR3_ONEBITE_Set ((u16)0x0800) 89 #define CR3_ONEBITE_Reset ((u16)0xF7FF) 140 else if (USARTx ==
USART2)
145 else if (USARTx ==
USART3)
150 else if (USARTx ==
UART4)
178 uint32_t tmpreg = 0x00, apbclock = 0x00;
179 uint32_t integerdivider = 0x00;
180 uint32_t fractionaldivider = 0x00;
181 uint32_t usartxbase = 0;
197 usartxbase = (uint32_t)USARTx;
200 tmpreg = USARTx->
CR2;
208 USARTx->
CR2 = (uint16_t)tmpreg;
211 tmpreg = USARTx->
CR1;
221 USARTx->
CR1 = (uint16_t)tmpreg;
224 tmpreg = USARTx->
CR3;
231 USARTx->
CR3 = (uint16_t)tmpreg;
249 integerdivider = ((25 * apbclock) / (2 * (USART_InitStruct->
USART_BaudRate)));
254 integerdivider = ((25 * apbclock) / (4 * (USART_InitStruct->
USART_BaudRate)));
256 tmpreg = (integerdivider / 100) << 4;
259 fractionaldivider = integerdivider - (100 * (tmpreg >> 4));
264 tmpreg |= ((((fractionaldivider * 8) + 50) / 100)) & ((uint8_t)0x07);
268 tmpreg |= ((((fractionaldivider * 16) + 50) / 100)) & ((uint8_t)0x0F);
272 USARTx->
BRR = (uint16_t)tmpreg;
304 uint32_t tmpreg = 0x00;
313 tmpreg = USARTx->
CR2;
324 USARTx->
CR2 = (uint16_t)tmpreg;
390 uint32_t usartreg = 0x00, itpos = 0x00, itmask = 0x00;
391 uint32_t usartxbase = 0x00;
402 usartxbase = (uint32_t)USARTx;
405 usartreg = (((uint8_t)USART_IT) >> 0x05);
409 itmask = (((uint32_t)0x01) << itpos);
411 if (usartreg == 0x01)
415 else if (usartreg == 0x02)
425 *(
__IO uint32_t*)usartxbase |= itmask;
429 *(
__IO uint32_t*)usartxbase &= ~itmask;
458 USARTx->
CR3 |= USART_DMAReq;
464 USARTx->
CR3 &= (uint16_t)~USART_DMAReq;
485 USARTx->
CR2 |= USART_Address;
506 USARTx->
CR1 |= USART_WakeUp;
554 USARTx->
CR2 |= USART_LINBreakDetectLength;
599 USARTx->
DR = (Data & (uint16_t)0x01FF);
615 return (uint16_t)(USARTx->
DR & (uint16_t)0x01FF);
649 USARTx->
GTPR |= (uint16_t)((uint16_t)USART_GuardTime << 0x08);
669 USARTx->
GTPR |= USART_Prescaler;
825 USARTx->
CR3 |= USART_IrDAMode;
886 if ((USARTx->
SR & USART_FLAG) != (uint16_t)
RESET)
934 USARTx->
SR = (uint16_t)~USART_FLAG;
958 uint32_t bitpos = 0x00, itmask = 0x00, usartreg = 0x00;
970 usartreg = (((uint8_t)USART_IT) >> 0x05);
973 itmask = (uint32_t)0x01 << itmask;
975 if (usartreg == 0x01)
977 itmask &= USARTx->
CR1;
979 else if (usartreg == 0x02)
981 itmask &= USARTx->
CR2;
985 itmask &= USARTx->
CR3;
988 bitpos = USART_IT >> 0x08;
989 bitpos = (uint32_t)0x01 << bitpos;
990 bitpos &= USARTx->
SR;
991 if ((itmask != (uint16_t)
RESET)&&(bitpos != (uint16_t)
RESET))
1032 uint16_t bitpos = 0x00, itmask = 0x00;
1042 bitpos = USART_IT >> 0x08;
1043 itmask = ((uint16_t)0x01 << (uint16_t)bitpos);
1044 USARTx->
SR = (uint16_t)~itmask;
void USART_ClockStructInit(USART_ClockInitTypeDef *USART_ClockInitStruct)
Fills each USART_ClockInitStruct member with its default value.
#define USART_LastBit_Disable
#define USART_Clock_Disable
#define IS_USART_DATA(DATA)
void USART_SmartCardNACKCmd(USART_TypeDef *USARTx, FunctionalState NewState)
Enables or disables NACK transmission.
#define IS_USART_CLOCK(CLOCK)
uint16_t USART_HardwareFlowControl
This file contains all the functions prototypes for the USART firmware library.
Universal Synchronous Asynchronous Receiver Transmitter.
#define RCC_APB2Periph_USART1
#define IS_USART_CLEAR_FLAG(FLAG)
#define CR3_ONEBITE_Reset
#define IS_USART_STOPBITS(STOPBITS)
#define IS_USART_MODE(MODE)
void USART_ClearFlag(USART_TypeDef *USARTx, uint16_t USART_FLAG)
Clears the USARTx's pending flags.
#define CR2_CLOCK_CLEAR_Mask
void USART_OneBitMethodCmd(USART_TypeDef *USARTx, FunctionalState NewState)
Enables or disables the USART's one bit sampling method.
void USART_SendData(USART_TypeDef *USARTx, uint16_t Data)
Transmits single data through the USARTx peripheral.
void USART_IrDACmd(USART_TypeDef *USARTx, FunctionalState NewState)
Enables or disables the USART's IrDA interface.
#define IS_USART_CPOL(CPOL)
void USART_SetAddress(USART_TypeDef *USARTx, uint8_t USART_Address)
Sets the address of the USART node.
void assert_param(int val)
#define IS_USART_LASTBIT(LASTBIT)
void USART_ReceiverWakeUpCmd(USART_TypeDef *USARTx, FunctionalState NewState)
Determines if the USART is in mute mode or not.
void USART_DeInit(USART_TypeDef *USARTx)
Deinitializes the USARTx peripheral registers to their default reset values.
void USART_Cmd(USART_TypeDef *USARTx, FunctionalState NewState)
Enables or disables the specified USART peripheral.
#define IS_FUNCTIONAL_STATE(STATE)
void USART_IrDAConfig(USART_TypeDef *USARTx, uint16_t USART_IrDAMode)
Configures the USART's IrDA interface.
void USART_SetPrescaler(USART_TypeDef *USARTx, uint8_t USART_Prescaler)
Sets the system clock prescaler.
void USART_SendBreak(USART_TypeDef *USARTx)
Transmits break characters.
void USART_SmartCardCmd(USART_TypeDef *USARTx, FunctionalState NewState)
Enables or disables the USART’s Smart Card mode.
#define RCC_APB1Periph_USART3
#define IS_USART_PARITY(PARITY)
void USART_OverSampling8Cmd(USART_TypeDef *USARTx, FunctionalState NewState)
Enables or disables the USART's 8x oversampling mode.
#define USART_HardwareFlowControl_None
void USART_ClockInit(USART_TypeDef *USARTx, USART_ClockInitTypeDef *USART_ClockInitStruct)
Initializes the USARTx peripheral Clock according to the specified parameters in the USART_ClockInitS...
#define USART_WordLength_8b
void RCC_APB1PeriphResetCmd(uint32_t RCC_APB1Periph, FunctionalState NewState)
Forces or releases Low Speed APB (APB1) peripheral reset.
#define IS_USART_LIN_BREAK_DETECT_LENGTH(LENGTH)
USART Clock Init Structure definition.
#define IS_USART_BAUDRATE(BAUDRATE)
void USART_ClearITPendingBit(USART_TypeDef *USARTx, uint16_t USART_IT)
Clears the USARTx's interrupt pending bits.
#define IS_USART_DMAREQ(DMAREQ)
#define IS_USART_ALL_PERIPH(PERIPH)
#define IS_USART_CPHA(CPHA)
void USART_DMACmd(USART_TypeDef *USARTx, uint16_t USART_DMAReq, FunctionalState NewState)
Enables or disables the USART’s DMA interface.
void USART_LINCmd(USART_TypeDef *USARTx, FunctionalState NewState)
Enables or disables the USART’s LIN mode.
uint16_t USART_WordLength
void USART_ITConfig(USART_TypeDef *USARTx, uint16_t USART_IT, FunctionalState NewState)
Enables or disables the specified USART interrupts.
void USART_HalfDuplexCmd(USART_TypeDef *USARTx, FunctionalState NewState)
Enables or disables the USART’s Half Duplex communication.
#define CR2_STOP_CLEAR_Mask
ITStatus USART_GetITStatus(USART_TypeDef *USARTx, uint16_t USART_IT)
Checks whether the specified USART interrupt has occurred or not.
This file contains all the functions prototypes for the RCC firmware library.
#define IS_USART_FLAG(FLAG)
FlagStatus USART_GetFlagStatus(USART_TypeDef *USARTx, uint16_t USART_FLAG)
Checks whether the specified USART flag is set or not.
void RCC_APB2PeriphResetCmd(uint32_t RCC_APB2Periph, FunctionalState NewState)
Forces or releases High Speed APB (APB2) peripheral reset.
#define RCC_APB1Periph_UART4
void USART_LINBreakDetectLengthConfig(USART_TypeDef *USARTx, uint16_t USART_LINBreakDetectLength)
Sets the USART LIN Break detection length.
#define IS_USART_123_PERIPH(PERIPH)
#define RCC_APB1Periph_UART5
#define IS_USART_CONFIG_IT(IT)
void USART_StructInit(USART_InitTypeDef *USART_InitStruct)
Fills each USART_InitStruct member with its default value.
#define IS_USART_GET_IT(IT)
#define IS_USART_IRDA_MODE(MODE)
void RCC_GetClocksFreq(RCC_ClocksTypeDef *RCC_Clocks)
Returns the frequencies of different on chip clocks; SYSCLK, HCLK, PCLK1 and PCLK2.
void USART_Init(USART_TypeDef *USARTx, USART_InitTypeDef *USART_InitStruct)
Initializes the USARTx peripheral according to the specified parameters in the USART_InitStruct ...
#define IS_USART_ADDRESS(ADDRESS)
void USART_WakeUpConfig(USART_TypeDef *USARTx, uint16_t USART_WakeUp)
Selects the USART WakeUp method.
void USART_SetGuardTime(USART_TypeDef *USARTx, uint8_t USART_GuardTime)
Sets the specified USART guard time.
#define IS_USART_WORD_LENGTH(LENGTH)
USART Init Structure definition.
uint16_t USART_ReceiveData(USART_TypeDef *USARTx)
Returns the most recent received data by the USARTx peripheral.
#define IS_USART_HARDWARE_FLOW_CONTROL(CONTROL)
#define IS_USART_WAKEUP(WAKEUP)
#define RCC_APB1Periph_USART2
#define IS_USART_CLEAR_IT(IT)