This file contains all the functions prototypes for the USART firmware library. More...
#include "stm32f30x.h"
Go to the source code of this file.
Classes | |
struct | USART_ClockInitTypeDef |
USART Clock Init Structure definition. More... | |
struct | USART_InitTypeDef |
USART Init Structure definition. More... | |
Macros | |
#define | IS_USART_1234_PERIPH(PERIPH) |
#define | IS_USART_123_PERIPH(PERIPH) |
#define | IS_USART_ADDRESS_DETECTION(ADDRESS) |
#define | IS_USART_ALL_PERIPH(PERIPH) |
#define | IS_USART_AUTO_RETRY_COUNTER(COUNTER) ((COUNTER) <= 0x7) |
#define | IS_USART_AUTOBAUDRATE_MODE(MODE) |
#define | IS_USART_BAUDRATE(BAUDRATE) (((BAUDRATE) > 0) && ((BAUDRATE) < 0x005B8D81)) |
#define | IS_USART_CLEAR_FLAG(FLAG) |
#define | IS_USART_CLEAR_IT(IT) |
#define | IS_USART_CLOCK(CLOCK) |
#define | IS_USART_CONFIG_IT(IT) |
#define | IS_USART_CPHA(CPHA) (((CPHA) == USART_CPHA_1Edge) || ((CPHA) == USART_CPHA_2Edge)) |
#define | IS_USART_CPOL(CPOL) (((CPOL) == USART_CPOL_Low) || ((CPOL) == USART_CPOL_High)) |
#define | IS_USART_DATA(DATA) ((DATA) <= 0x1FF) |
#define | IS_USART_DE_ASSERTION_DEASSERTION_TIME(TIME) ((TIME) <= 0x1F) |
#define | IS_USART_DE_POLARITY(POLARITY) |
#define | IS_USART_DMAONERROR(DMAERROR) |
#define | IS_USART_DMAREQ(DMAREQ) |
#define | IS_USART_FLAG(FLAG) |
#define | IS_USART_GET_IT(IT) |
#define | IS_USART_HARDWARE_FLOW_CONTROL(CONTROL) |
#define | IS_USART_INVERSTION_PIN(PIN) |
#define | IS_USART_IRDA_MODE(MODE) |
#define | IS_USART_LASTBIT(LASTBIT) |
#define | IS_USART_LIN_BREAK_DETECT_LENGTH(LENGTH) |
#define | IS_USART_MODE(MODE) |
#define | IS_USART_MUTEMODE_WAKEUP(WAKEUP) |
#define | IS_USART_OVRDETECTION(OVR) |
#define | IS_USART_PARITY(PARITY) |
#define | IS_USART_REQUEST(REQUEST) |
#define | IS_USART_STOPBITS(STOPBITS) |
#define | IS_USART_STOPMODE_WAKEUPSOURCE(SOURCE) |
#define | IS_USART_TIMEOUT(TIMEOUT) ((TIMEOUT) <= 0x00FFFFFF) |
#define | IS_USART_WORD_LENGTH(LENGTH) |
#define | USART_AddressLength_4b ((uint32_t)0x00000000) |
#define | USART_AddressLength_7b USART_CR2_ADDM7 |
#define | USART_AutoBaudRate_0x55Frame (USART_CR2_ABRMODE_0 | USART_CR2_ABRMODE_1) |
#define | USART_AutoBaudRate_0x7FFrame USART_CR2_ABRMODE_1 |
#define | USART_AutoBaudRate_FallingEdge USART_CR2_ABRMODE_0 |
#define | USART_AutoBaudRate_StartBit ((uint32_t)0x00000000) |
#define | USART_Clock_Disable ((uint32_t)0x00000000) |
#define | USART_Clock_Enable USART_CR2_CLKEN |
#define | USART_CPHA_1Edge ((uint32_t)0x00000000) |
#define | USART_CPHA_2Edge USART_CR2_CPHA |
#define | USART_CPOL_High USART_CR2_CPOL |
#define | USART_CPOL_Low ((uint32_t)0x00000000) |
#define | USART_DEPolarity_High ((uint32_t)0x00000000) |
#define | USART_DEPolarity_Low USART_CR3_DEP |
#define | USART_DMAOnError_Disable USART_CR3_DDRE |
#define | USART_DMAOnError_Enable ((uint32_t)0x00000000) |
#define | USART_DMAReq_Rx USART_CR3_DMAR |
#define | USART_DMAReq_Tx USART_CR3_DMAT |
#define | USART_FLAG_ABRE USART_ISR_ABRE |
#define | USART_FLAG_ABRF USART_ISR_ABRF |
#define | USART_FLAG_BUSY USART_ISR_BUSY |
#define | USART_FLAG_CM USART_ISR_CMF |
#define | USART_FLAG_CTS USART_ISR_CTSIF |
#define | USART_FLAG_EOB USART_ISR_EOBF |
#define | USART_FLAG_FE USART_ISR_FE |
#define | USART_FLAG_IDLE USART_ISR_IDLE |
#define | USART_FLAG_LBD USART_ISR_LBD |
#define | USART_FLAG_nCTSS USART_ISR_CTS |
#define | USART_FLAG_NE USART_ISR_NE |
#define | USART_FLAG_ORE USART_ISR_ORE |
#define | USART_FLAG_PE USART_ISR_PE |
#define | USART_FLAG_REACK USART_ISR_REACK |
#define | USART_FLAG_RTO USART_ISR_RTOF |
#define | USART_FLAG_RWU USART_ISR_RWU |
#define | USART_FLAG_RXNE USART_ISR_RXNE |
#define | USART_FLAG_SBK USART_ISR_SBKF |
#define | USART_FLAG_TC USART_ISR_TC |
#define | USART_FLAG_TEACK USART_ISR_TEACK |
#define | USART_FLAG_TXE USART_ISR_TXE |
#define | USART_FLAG_WU USART_ISR_WUF |
#define | USART_HardwareFlowControl_CTS USART_CR3_CTSE |
#define | USART_HardwareFlowControl_None ((uint32_t)0x00000000) |
#define | USART_HardwareFlowControl_RTS USART_CR3_RTSE |
#define | USART_HardwareFlowControl_RTS_CTS (USART_CR3_RTSE | USART_CR3_CTSE) |
#define | USART_InvPin_Rx USART_CR2_RXINV |
#define | USART_InvPin_Tx USART_CR2_TXINV |
#define | USART_IrDAMode_LowPower USART_CR3_IRLP |
#define | USART_IrDAMode_Normal ((uint32_t)0x00000000) |
#define | USART_IT_CM ((uint32_t)0x0011010E) |
#define | USART_IT_CTS ((uint32_t)0x0009030A) |
#define | USART_IT_EOB ((uint32_t)0x000C011B) |
#define | USART_IT_ERR ((uint32_t)0x00000300) |
#define | USART_IT_FE ((uint32_t)0x00010300) |
#define | USART_IT_IDLE ((uint32_t)0x00040104) |
#define | USART_IT_LBD ((uint32_t)0x00080206) |
#define | USART_IT_NE ((uint32_t)0x00020300) |
#define | USART_IT_ORE ((uint32_t)0x00030300) |
#define | USART_IT_PE ((uint32_t)0x00000108) |
#define | USART_IT_RTO ((uint32_t)0x000B011A) |
#define | USART_IT_RXNE ((uint32_t)0x00050105) |
#define | USART_IT_TC ((uint32_t)0x00060106) |
#define | USART_IT_TXE ((uint32_t)0x00070107) |
#define | USART_IT_WU ((uint32_t)0x00140316) |
#define | USART_LastBit_Disable ((uint32_t)0x00000000) |
#define | USART_LastBit_Enable USART_CR2_LBCL |
#define | USART_LINBreakDetectLength_10b ((uint32_t)0x00000000) |
#define | USART_LINBreakDetectLength_11b USART_CR2_LBDL |
#define | USART_Mode_Rx USART_CR1_RE |
#define | USART_Mode_Tx USART_CR1_TE |
#define | USART_OVRDetection_Disable USART_CR3_OVRDIS |
#define | USART_OVRDetection_Enable ((uint32_t)0x00000000) |
#define | USART_Parity_Even USART_CR1_PCE |
#define | USART_Parity_No ((uint32_t)0x00000000) |
#define | USART_Parity_Odd (USART_CR1_PCE | USART_CR1_PS) |
#define | USART_Request_ABRRQ USART_RQR_ABRRQ |
#define | USART_Request_MMRQ USART_RQR_MMRQ |
#define | USART_Request_RXFRQ USART_RQR_RXFRQ |
#define | USART_Request_SBKRQ USART_RQR_SBKRQ |
#define | USART_Request_TXFRQ USART_RQR_TXFRQ |
#define | USART_StopBits_1 ((uint32_t)0x00000000) |
#define | USART_StopBits_1_5 (USART_CR2_STOP_0 | USART_CR2_STOP_1) |
#define | USART_StopBits_2 USART_CR2_STOP_1 |
#define | USART_WakeUp_AddressMark USART_CR1_WAKE |
#define | USART_WakeUp_IdleLine ((uint32_t)0x00000000) |
#define | USART_WakeUpSource_AddressMatch ((uint32_t)0x00000000) |
#define | USART_WakeUpSource_RXNE (uint32_t)(USART_CR3_WUS_0 | USART_CR3_WUS_1) |
#define | USART_WakeUpSource_StartBit USART_CR3_WUS_1 |
#define | USART_WordLength_8b ((uint32_t)0x00000000) |
#define | USART_WordLength_9b USART_CR1_M |
Functions | |
void | USART_AddressDetectionConfig (USART_TypeDef *USARTx, uint32_t USART_AddressLength) |
Configure the the USART Address detection length. More... | |
void | USART_AutoBaudRateCmd (USART_TypeDef *USARTx, FunctionalState NewState) |
Enables or disables the Auto Baud Rate. More... | |
void | USART_AutoBaudRateConfig (USART_TypeDef *USARTx, uint32_t USART_AutoBaudRate) |
Selects the USART auto baud rate method. More... | |
void | USART_ClearFlag (USART_TypeDef *USARTx, uint32_t USART_FLAG) |
Clears the USARTx's pending flags. More... | |
void | USART_ClearITPendingBit (USART_TypeDef *USARTx, uint32_t USART_IT) |
Clears the USARTx's interrupt pending bits. More... | |
void | USART_ClockInit (USART_TypeDef *USARTx, USART_ClockInitTypeDef *USART_ClockInitStruct) |
Initializes the USARTx peripheral Clock according to the specified parameters in the USART_ClockInitStruct. More... | |
void | USART_ClockStructInit (USART_ClockInitTypeDef *USART_ClockInitStruct) |
Fills each USART_ClockInitStruct member with its default value. More... | |
void | USART_Cmd (USART_TypeDef *USARTx, FunctionalState NewState) |
Enables or disables the specified USART peripheral. More... | |
void | USART_DataInvCmd (USART_TypeDef *USARTx, FunctionalState NewState) |
Enables or disables the binary data inversion. More... | |
void | USART_DECmd (USART_TypeDef *USARTx, FunctionalState NewState) |
Enables or disables the USART's DE functionality. More... | |
void | USART_DeInit (USART_TypeDef *USARTx) |
Deinitializes the USARTx peripheral registers to their default reset values. More... | |
void | USART_DEPolarityConfig (USART_TypeDef *USARTx, uint32_t USART_DEPolarity) |
Configures the USART's DE polarity. More... | |
void | USART_DirectionModeCmd (USART_TypeDef *USARTx, uint32_t USART_DirectionMode, FunctionalState NewState) |
Enables or disables the USART's transmitter or receiver. More... | |
void | USART_DMACmd (USART_TypeDef *USARTx, uint32_t USART_DMAReq, FunctionalState NewState) |
Enables or disables the USART's DMA interface. More... | |
void | USART_DMAReceptionErrorConfig (USART_TypeDef *USARTx, uint32_t USART_DMAOnError) |
Enables or disables the USART's DMA interface when reception error occurs. More... | |
FlagStatus | USART_GetFlagStatus (USART_TypeDef *USARTx, uint32_t USART_FLAG) |
Checks whether the specified USART flag is set or not. More... | |
ITStatus | USART_GetITStatus (USART_TypeDef *USARTx, uint32_t USART_IT) |
Checks whether the specified USART interrupt has occurred or not. More... | |
void | USART_HalfDuplexCmd (USART_TypeDef *USARTx, FunctionalState NewState) |
Enables or disables the USART's Half Duplex communication. More... | |
void | USART_Init (USART_TypeDef *USARTx, USART_InitTypeDef *USART_InitStruct) |
Initializes the USARTx peripheral according to the specified parameters in the USART_InitStruct . More... | |
void | USART_InvPinCmd (USART_TypeDef *USARTx, uint32_t USART_InvPin, FunctionalState NewState) |
Enables or disables the Pin(s) active level inversion. More... | |
void | USART_IrDACmd (USART_TypeDef *USARTx, FunctionalState NewState) |
Enables or disables the USART's IrDA interface. More... | |
void | USART_IrDAConfig (USART_TypeDef *USARTx, uint32_t USART_IrDAMode) |
Configures the USART's IrDA interface. More... | |
void | USART_ITConfig (USART_TypeDef *USARTx, uint32_t USART_IT, FunctionalState NewState) |
Enables or disables the specified USART interrupts. More... | |
void | USART_LINBreakDetectLengthConfig (USART_TypeDef *USARTx, uint32_t USART_LINBreakDetectLength) |
Sets the USART LIN Break detection length. More... | |
void | USART_LINCmd (USART_TypeDef *USARTx, FunctionalState NewState) |
Enables or disables the USART's LIN mode. More... | |
void | USART_MSBFirstCmd (USART_TypeDef *USARTx, FunctionalState NewState) |
Enables or disables the USART's most significant bit first transmitted/received following the start bit. More... | |
void | USART_MuteModeCmd (USART_TypeDef *USARTx, FunctionalState NewState) |
Enables or disables the USART's mute mode. More... | |
void | USART_MuteModeWakeUpConfig (USART_TypeDef *USARTx, uint32_t USART_WakeUp) |
Selects the USART WakeUp method from mute mode. More... | |
void | USART_OneBitMethodCmd (USART_TypeDef *USARTx, FunctionalState NewState) |
Enables or disables the USART's one bit sampling method. More... | |
void | USART_OverrunDetectionConfig (USART_TypeDef *USARTx, uint32_t USART_OVRDetection) |
Enables or disables the USART's Overrun detection. More... | |
void | USART_OverSampling8Cmd (USART_TypeDef *USARTx, FunctionalState NewState) |
Enables or disables the USART's 8x oversampling mode. More... | |
uint16_t | USART_ReceiveData (USART_TypeDef *USARTx) |
Returns the most recent received data by the USARTx peripheral. More... | |
void | USART_ReceiverTimeOutCmd (USART_TypeDef *USARTx, FunctionalState NewState) |
Enables or disables the receiver Time Out feature. More... | |
void | USART_RequestCmd (USART_TypeDef *USARTx, uint32_t USART_Request, FunctionalState NewState) |
Enables the specified USART's Request. More... | |
void | USART_SendData (USART_TypeDef *USARTx, uint16_t Data) |
Transmits single data through the USARTx peripheral. More... | |
void | USART_SetAddress (USART_TypeDef *USARTx, uint8_t USART_Address) |
Sets the address of the USART node. More... | |
void | USART_SetAutoRetryCount (USART_TypeDef *USARTx, uint8_t USART_AutoCount) |
Sets the Smart Card number of retries in transmit and receive. More... | |
void | USART_SetBlockLength (USART_TypeDef *USARTx, uint8_t USART_BlockLength) |
Sets the Smart Card Block length. More... | |
void | USART_SetDEAssertionTime (USART_TypeDef *USARTx, uint32_t USART_DEAssertionTime) |
Sets the specified RS485 DE assertion time. More... | |
void | USART_SetDEDeassertionTime (USART_TypeDef *USARTx, uint32_t USART_DEDeassertionTime) |
Sets the specified RS485 DE deassertion time. More... | |
void | USART_SetGuardTime (USART_TypeDef *USARTx, uint8_t USART_GuardTime) |
Sets the specified USART guard time. More... | |
void | USART_SetPrescaler (USART_TypeDef *USARTx, uint8_t USART_Prescaler) |
Sets the system clock prescaler. More... | |
void | USART_SetReceiverTimeOut (USART_TypeDef *USARTx, uint32_t USART_ReceiverTimeOut) |
Sets the receiver Time Out value. More... | |
void | USART_SmartCardCmd (USART_TypeDef *USARTx, FunctionalState NewState) |
Enables or disables the USART's Smart Card mode. More... | |
void | USART_SmartCardNACKCmd (USART_TypeDef *USARTx, FunctionalState NewState) |
Enables or disables NACK transmission. More... | |
void | USART_STOPModeCmd (USART_TypeDef *USARTx, FunctionalState NewState) |
Enables or disables the specified USART peripheral in STOP Mode. More... | |
void | USART_StopModeWakeUpSourceConfig (USART_TypeDef *USARTx, uint32_t USART_WakeUpSource) |
Selects the USART WakeUp method form stop mode. More... | |
void | USART_StructInit (USART_InitTypeDef *USART_InitStruct) |
Fills each USART_InitStruct member with its default value. More... | |
void | USART_SWAPPinCmd (USART_TypeDef *USARTx, FunctionalState NewState) |
Enables or disables the swap Tx/Rx pins. More... | |
This file contains all the functions prototypes for the USART firmware library.
Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); You may not use this file except in compliance with the License. You may obtain a copy of the License at:
http://www.st.com/software_license_agreement_liberty_v2
Unless required by applicable law or agreed to in writing, software distributed under the License is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the License for the specific language governing permissions and limitations under the License.
Definition in file stm32f30x_usart.h.