93 #include "stm32f4xx_rcc.h" 108 #define CR1_CLEAR_MASK ((uint16_t)(USART_CR1_M | USART_CR1_PCE | \ 109 USART_CR1_PS | USART_CR1_TE | \ 113 #define CR2_CLOCK_CLEAR_MASK ((uint16_t)(USART_CR2_CLKEN | USART_CR2_CPOL | \ 114 USART_CR2_CPHA | USART_CR2_LBCL)) 117 #define CR3_CLEAR_MASK ((uint16_t)(USART_CR3_RTSE | USART_CR3_CTSE)) 120 #define IT_MASK ((uint16_t)0x001F) 197 else if (USARTx ==
USART2)
202 else if (USARTx ==
USART3)
207 else if (USARTx ==
UART4)
212 else if (USARTx ==
UART5)
217 else if (USARTx ==
USART6)
222 else if (USARTx ==
UART7)
248 uint32_t tmpreg = 0x00, apbclock = 0x00;
249 uint32_t integerdivider = 0x00;
250 uint32_t fractionaldivider = 0x00;
269 tmpreg = USARTx->
CR2;
279 USARTx->
CR2 = (uint16_t)tmpreg;
282 tmpreg = USARTx->
CR1;
295 USARTx->
CR1 = (uint16_t)tmpreg;
298 tmpreg = USARTx->
CR3;
308 USARTx->
CR3 = (uint16_t)tmpreg;
327 integerdivider = ((25 * apbclock) / (2 * (USART_InitStruct->
USART_BaudRate)));
332 integerdivider = ((25 * apbclock) / (4 * (USART_InitStruct->
USART_BaudRate)));
334 tmpreg = (integerdivider / 100) << 4;
337 fractionaldivider = integerdivider - (100 * (tmpreg >> 4));
342 tmpreg |= ((((fractionaldivider * 8) + 50) / 100)) & ((uint8_t)0x07);
346 tmpreg |= ((((fractionaldivider * 16) + 50) / 100)) & ((uint8_t)0x0F);
350 USARTx->
BRR = (uint16_t)tmpreg;
381 uint32_t tmpreg = 0x00;
390 tmpreg = USARTx->
CR2;
401 USARTx->
CR2 = (uint16_t)tmpreg;
461 USARTx->
GTPR |= USART_Prescaler;
564 USARTx->
DR = (Data & (uint16_t)0x01FF);
579 return (uint16_t)(USARTx->
DR & (uint16_t)0x01FF);
634 USARTx->
CR2 |= USART_Address;
679 USARTx->
CR1 |= USART_WakeUp;
748 USARTx->
CR2 |= USART_LINBreakDetectLength;
928 USARTx->
GTPR |= (uint16_t)((uint16_t)USART_GuardTime << 0x08);
1042 USARTx->
CR3 |= USART_IrDAMode;
1110 USARTx->
CR3 |= USART_DMAReq;
1116 USARTx->
CR3 &= (uint16_t)~USART_DMAReq;
1233 uint32_t usartreg = 0x00, itpos = 0x00, itmask = 0x00;
1234 uint32_t usartxbase = 0x00;
1246 usartxbase = (uint32_t)USARTx;
1249 usartreg = (((uint8_t)USART_IT) >> 0x05);
1253 itmask = (((uint32_t)0x01) << itpos);
1255 if (usartreg == 0x01)
1259 else if (usartreg == 0x02)
1269 *(
__IO uint32_t*)usartxbase |= itmask;
1273 *(
__IO uint32_t*)usartxbase &= ~itmask;
1308 if ((USARTx->
SR & USART_FLAG) != (uint16_t)
RESET)
1356 USARTx->
SR = (uint16_t)~USART_FLAG;
1380 uint32_t bitpos = 0x00, itmask = 0x00, usartreg = 0x00;
1393 usartreg = (((uint8_t)USART_IT) >> 0x05);
1396 itmask = (uint32_t)0x01 << itmask;
1398 if (usartreg == 0x01)
1400 itmask &= USARTx->
CR1;
1402 else if (usartreg == 0x02)
1404 itmask &= USARTx->
CR2;
1408 itmask &= USARTx->
CR3;
1411 bitpos = USART_IT >> 0x08;
1412 bitpos = (uint32_t)0x01 << bitpos;
1413 bitpos &= USARTx->
SR;
1414 if ((itmask != (uint16_t)
RESET)&&(bitpos != (uint16_t)
RESET))
1454 uint16_t bitpos = 0x00, itmask = 0x00;
1465 bitpos = USART_IT >> 0x08;
1466 itmask = ((uint16_t)0x01 << (uint16_t)bitpos);
1467 USARTx->
SR = (uint16_t)~itmask;
ITStatus USART_GetITStatus(USART_TypeDef *USARTx, uint16_t USART_IT)
Checks whether the specified USART interrupt has occurred or not.
#define USART_LastBit_Disable
void USART_ITConfig(USART_TypeDef *USARTx, uint16_t USART_IT, FunctionalState NewState)
Enables or disables the specified USART interrupts.
#define USART_Clock_Disable
void USART_ReceiverWakeUpCmd(USART_TypeDef *USARTx, FunctionalState NewState)
Determines if the USART is in mute mode or not.
#define IS_USART_DATA(DATA)
void USART_HalfDuplexCmd(USART_TypeDef *USARTx, FunctionalState NewState)
Enables or disables the USART's Half Duplex communication.
#define IS_USART_CLOCK(CLOCK)
uint16_t USART_HardwareFlowControl
void USART_OneBitMethodCmd(USART_TypeDef *USARTx, FunctionalState NewState)
Enables or disables the USART's one bit sampling method.
Universal Synchronous Asynchronous Receiver Transmitter.
#define RCC_APB2Periph_USART1
#define IS_USART_CLEAR_FLAG(FLAG)
void USART_Cmd(USART_TypeDef *USARTx, FunctionalState NewState)
Enables or disables the specified USART peripheral.
void USART_SmartCardNACKCmd(USART_TypeDef *USARTx, FunctionalState NewState)
Enables or disables NACK transmission.
#define IS_USART_STOPBITS(STOPBITS)
#define IS_USART_MODE(MODE)
#define RCC_APB2Periph_USART6
#define IS_USART_CPOL(CPOL)
void USART_DMACmd(USART_TypeDef *USARTx, uint16_t USART_DMAReq, FunctionalState NewState)
Enables or disables the USART's DMA interface.
void assert_param(int val)
#define IS_USART_LASTBIT(LASTBIT)
#define IS_FUNCTIONAL_STATE(STATE)
FlagStatus USART_GetFlagStatus(USART_TypeDef *USARTx, uint16_t USART_FLAG)
Checks whether the specified USART flag is set or not.
#define RCC_APB1Periph_USART3
#define IS_USART_PARITY(PARITY)
#define USART_HardwareFlowControl_None
#define USART_WordLength_8b
void USART_SetAddress(USART_TypeDef *USARTx, uint8_t USART_Address)
Sets the address of the USART node.
void RCC_APB1PeriphResetCmd(uint32_t RCC_APB1Periph, FunctionalState NewState)
Forces or releases Low Speed APB (APB1) peripheral reset.
void USART_SetPrescaler(USART_TypeDef *USARTx, uint8_t USART_Prescaler)
Sets the system clock prescaler.
#define IS_USART_LIN_BREAK_DETECT_LENGTH(LENGTH)
USART Clock Init Structure definition.
#define IS_USART_BAUDRATE(BAUDRATE)
void USART_ClockStructInit(USART_ClockInitTypeDef *USART_ClockInitStruct)
Fills each USART_ClockInitStruct member with its default value.
#define IS_USART_DMAREQ(DMAREQ)
#define IS_USART_ALL_PERIPH(PERIPH)
void USART_ClearFlag(USART_TypeDef *USARTx, uint16_t USART_FLAG)
Clears the USARTx's pending flags.
#define IS_USART_CPHA(CPHA)
#define RCC_APB1Periph_UART7
uint16_t USART_WordLength
void USART_SendData(USART_TypeDef *USARTx, uint16_t Data)
Transmits single data through the USARTx peripheral.
This file contains all the functions prototypes for the USART firmware library.
#define IS_USART_1236_PERIPH(PERIPH)
void USART_SendBreak(USART_TypeDef *USARTx)
Transmits break characters.
void USART_LINCmd(USART_TypeDef *USARTx, FunctionalState NewState)
Enables or disables the USART's LIN mode.
void USART_IrDAConfig(USART_TypeDef *USARTx, uint16_t USART_IrDAMode)
Configures the USART's IrDA interface.
#define IS_USART_FLAG(FLAG)
#define CR2_CLOCK_CLEAR_MASK
void USART_WakeUpConfig(USART_TypeDef *USARTx, uint16_t USART_WakeUp)
Selects the USART WakeUp method.
void USART_ClearITPendingBit(USART_TypeDef *USARTx, uint16_t USART_IT)
Clears the USARTx's interrupt pending bits.
void RCC_APB2PeriphResetCmd(uint32_t RCC_APB2Periph, FunctionalState NewState)
Forces or releases High Speed APB (APB2) peripheral reset.
void USART_OverSampling8Cmd(USART_TypeDef *USARTx, FunctionalState NewState)
Enables or disables the USART's 8x oversampling mode.
void USART_Init(USART_TypeDef *USARTx, USART_InitTypeDef *USART_InitStruct)
Initializes the USARTx peripheral according to the specified parameters in the USART_InitStruct ...
#define RCC_APB1Periph_UART4
void USART_SmartCardCmd(USART_TypeDef *USARTx, FunctionalState NewState)
Enables or disables the USART's Smart Card mode.
void USART_DeInit(USART_TypeDef *USARTx)
Deinitializes the USARTx peripheral registers to their default reset values.
#define RCC_APB1Periph_UART5
void USART_StructInit(USART_InitTypeDef *USART_InitStruct)
Fills each USART_InitStruct member with its default value.
#define IS_USART_CONFIG_IT(IT)
void USART_SetGuardTime(USART_TypeDef *USARTx, uint8_t USART_GuardTime)
Sets the specified USART guard time.
uint16_t USART_ReceiveData(USART_TypeDef *USARTx)
Returns the most recent received data by the USARTx peripheral.
#define RCC_APB1Periph_UART8
void USART_IrDACmd(USART_TypeDef *USARTx, FunctionalState NewState)
Enables or disables the USART's IrDA interface.
#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.
#define IS_USART_ADDRESS(ADDRESS)
void USART_LINBreakDetectLengthConfig(USART_TypeDef *USARTx, uint16_t USART_LINBreakDetectLength)
Sets the USART LIN Break detection length.
#define IS_USART_WORD_LENGTH(LENGTH)
USART Init Structure definition.
#define IS_USART_HARDWARE_FLOW_CONTROL(CONTROL)
#define IS_USART_WAKEUP(WAKEUP)
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 RCC_APB1Periph_USART2
#define IS_USART_CLEAR_IT(IT)