138 #define CR1_CLEAR_MASK ((uint16_t)0x3040) 139 #define CR2_LDMA_MASK ((uint16_t)0x9FFF) 141 #define I2SCFGR_CLEAR_MASK ((uint16_t)0xF040) 202 else if (SPIx ==
SPI2)
292 (uint16_t)((uint16_t)(SPI_InitStruct->
SPI_CPOL | SPI_InitStruct->
SPI_CPHA) |
301 tmpreg &= (uint16_t)~SPI_CR2_DS;
314 tmpreg &= (uint16_t)~SPI_CR2_DS;
333 (uint16_t)((uint16_t)(SPI_InitStruct->
SPI_CPOL | SPI_InitStruct->
SPI_CPHA) |
393 uint16_t tmpreg = 0, i2sdiv = 2, i2sodd = 0, packetlength = 1;
396 uint32_t sourceclock = 0;
410 SPIx->
I2SPR = 0x0002;
418 i2sodd = (uint16_t)0;
419 i2sdiv = (uint16_t)2;
446 tmp = (uint16_t)(((((sourceclock / 256) * 10) / I2S_InitStruct->
I2S_AudioFreq)) + 5);
451 tmp = (uint16_t)(((((sourceclock / (32 * packetlength)) *10 ) / I2S_InitStruct->
I2S_AudioFreq)) + 5);
458 i2sodd = (uint16_t)(tmp & (uint16_t)0x0001);
461 i2sdiv = (uint16_t)((tmp - i2sodd) / 2);
464 i2sodd = (uint16_t) (i2sodd << 8);
468 if ((i2sdiv < 2) || (i2sdiv > 0xFF))
476 SPIx->
I2SPR = (uint16_t)(i2sdiv | (uint16_t)(i2sodd | (uint16_t)I2S_InitStruct->
I2S_MCLKOutput));
597 tmpreg &= (uint16_t)~SPI_CR2_DS;
599 tmpreg |= SPI_DataSize;
621 SPIx->
CR2 &= (uint16_t)~((uint16_t)SPI_CR2_FRXTH);
624 SPIx->
CR2 |= SPI_RxFIFOThreshold;
703 uint16_t tmpreg = 0, tmp = 0;
715 I2Sxext->
I2SPR = 0x0002;
737 (uint16_t)I2S_InitStruct->
I2S_CPOL))));
790 SPIx->
CR2 |= SPI_CR2_NSSP;
795 SPIx->
CR2 &= (uint16_t)~((uint16_t)SPI_CR2_NSSP);
832 uint32_t spixbase = 0x00;
837 spixbase = (uint32_t)SPIx;
840 *(
__IO uint8_t *) spixbase = Data;
855 SPIx->
DR = (uint16_t)Data;
865 uint32_t spixbase = 0x00;
870 spixbase = (uint32_t)SPIx;
873 return *(
__IO uint8_t *) spixbase;
971 SPIx->
CR1 &= (uint16_t)~((uint16_t)SPI_CR1_CRCL);
974 SPIx->
CR1 |= SPI_CRCLength;
1027 uint16_t crcreg = 0;
1098 SPIx->
CR2 |= SPI_I2S_DMAReq;
1103 SPIx->
CR2 &= (uint16_t)~SPI_I2S_DMAReq;
1135 SPIx->
CR2 |= SPI_LastDMATransfer;
1226 uint16_t itpos = 0, itmask = 0 ;
1234 itpos = SPI_I2S_IT >> 4;
1237 itmask = (uint16_t)1 << (uint16_t)itpos;
1242 SPIx->
CR2 |= itmask;
1247 SPIx->
CR2 &= (uint16_t)~itmask;
1263 return (uint16_t)((SPIx->
SR & SPI_SR_FTLVL));
1278 return (uint16_t)((SPIx->
SR & SPI_SR_FRLVL));
1306 if ((SPIx->
SR & SPI_I2S_FLAG) != (uint16_t)
RESET)
1341 SPIx->
SR = (uint16_t)~SPI_I2S_FLAG;
1361 uint16_t itpos = 0, itmask = 0, enablestatus = 0;
1368 itpos = 0x01 << (SPI_I2S_IT & 0x0F);
1371 itmask = SPI_I2S_IT >> 4;
1374 itmask = 0x01 << itmask;
1377 enablestatus = (SPIx->
CR2 & itmask) ;
1380 if (((SPIx->
SR & itpos) != (uint16_t)
RESET) && enablestatus)
#define IS_SPI_RX_FIFO_THRESHOLD(THRESHOLD)
#define IS_SPI_NSS_INTERNAL(INTERNAL)
void I2S_Init(SPI_TypeDef *SPIx, I2S_InitTypeDef *I2S_InitStruct)
Initializes the SPIx peripheral according to the specified parameters in the I2S_InitStruct.
#define IS_SPI_I2S_GET_IT(IT)
#define IS_SPI_ALL_PERIPH(PERIPH)
#define IS_SPI_CLEAR_FLAG(FLAG)
#define I2SCFGR_CLEAR_MASK
#define IS_I2S_AUDIO_FREQ(FREQ)
This file contains all the functions prototypes for the SPI firmware library.
void I2S_StructInit(I2S_InitTypeDef *I2S_InitStruct)
Fills each I2S_InitStruct member with its default value.
uint16_t SPI_BaudRatePrescaler
#define I2S_MCLKOutput_Disable
void SPI_CRCLengthConfig(SPI_TypeDef *SPIx, uint16_t SPI_CRCLength)
Configures the CRC calculation length for the selected SPI.
uint16_t SPI_CRCPolynomial
void SPI_I2S_DeInit(SPI_TypeDef *SPIx)
Deinitializes the SPIx peripheral registers to their default reset values.
void SPI_I2S_ITConfig(SPI_TypeDef *SPIx, uint8_t SPI_I2S_IT, FunctionalState NewState)
Enables or disables the specified SPI/I2S interrupts.
void SPI_TransmitCRC(SPI_TypeDef *SPIx)
Transmits the SPIx CRC value.
void assert_param(int val)
ITStatus SPI_I2S_GetITStatus(SPI_TypeDef *SPIx, uint8_t SPI_I2S_IT)
Checks whether the specified SPI/I2S interrupt has occurred or not.
void I2S_FullDuplexConfig(SPI_TypeDef *I2Sxext, I2S_InitTypeDef *I2S_InitStruct)
Configures the full duplex mode for the I2Sx peripheral using its extension I2Sxext according to the ...
FlagStatus SPI_I2S_GetFlagStatus(SPI_TypeDef *SPIx, uint16_t SPI_I2S_FLAG)
Checks whether the specified SPI flag is set or not.
#define IS_SPI_DATA_SIZE(SIZE)
#define IS_SPI_DIRECTION(DIRECTION)
#define IS_FUNCTIONAL_STATE(STATE)
uint8_t SPI_ReceiveData8(SPI_TypeDef *SPIx)
Returns the most recent received data by the SPIx peripheral.
Serial Peripheral Interface.
#define RCC_APB1Periph_SPI2
#define RCC_APB2Periph_SPI1
uint16_t SPI_I2S_ReceiveData16(SPI_TypeDef *SPIx)
Returns the most recent received data by the SPIx peripheral.
void SPI_I2S_ClearFlag(SPI_TypeDef *SPIx, uint16_t SPI_I2S_FLAG)
Clears the SPIx CRC Error (CRCERR) flag.
void SPI_CalculateCRC(SPI_TypeDef *SPIx, FunctionalState NewState)
Enables or disables the CRC value calculation of the transferred bytes.
uint16_t SPI_GetCRC(SPI_TypeDef *SPIx, uint8_t SPI_CRC)
Returns the transmit or the receive CRC register value for the specified SPI.
#define IS_SPI_FIRST_BIT(BIT)
void RCC_APB1PeriphResetCmd(uint32_t RCC_APB1Periph, FunctionalState NewState)
Forces or releases Low Speed APB (APB1) peripheral reset.
void SPI_DataSizeConfig(SPI_TypeDef *SPIx, uint16_t SPI_DataSize)
Configures the data size for the selected SPI.
This file contains all the functions prototypes for the RCC firmware library.
#define SPI_NSSInternalSoft_Set
#define IS_I2S_CPOL(CPOL)
void SPI_SSOutputCmd(SPI_TypeDef *SPIx, FunctionalState NewState)
Enables or disables the SS output for the selected SPI.
#define I2S_Mode_MasterTx
void SPI_I2S_DMACmd(SPI_TypeDef *SPIx, uint16_t SPI_I2S_DMAReq, FunctionalState NewState)
Enables or disables the SPIx/I2Sx DMA interface.
#define SPI_BaudRatePrescaler_2
#define IS_I2S_MODE(MODE)
SPI Init structure definition.
#define SPI_Direction_2Lines_FullDuplex
#define I2S_Mode_MasterRx
#define IS_SPI_MODE(MODE)
void SPI_SendData8(SPI_TypeDef *SPIx, uint8_t Data)
Transmits a Data through the SPIx peripheral.
void SPI_LastDMATransferCmd(SPI_TypeDef *SPIx, uint16_t SPI_LastDMATransfer)
Configures the number of data to transfer type(Even/Odd) for the DMA last transfers and for the selec...
#define I2S_Standard_Phillips
#define IS_SPI_LAST_DMA_TRANSFER(TRANSFER)
#define IS_SPI_CPHA(CPHA)
#define SPI_NSSInternalSoft_Reset
void SPI_NSSPulseModeCmd(SPI_TypeDef *SPIx, FunctionalState NewState)
Enables or disables the NSS pulse management mode.
void SPI_Cmd(SPI_TypeDef *SPIx, FunctionalState NewState)
Enables or disables the specified SPI peripheral.
#define IS_SPI_I2S_DMA_REQ(REQ)
void SPI_Init(SPI_TypeDef *SPIx, SPI_InitTypeDef *SPI_InitStruct)
Initializes the SPIx peripheral according to the specified parameters in the SPI_InitStruct.
void SPI_I2S_SendData16(SPI_TypeDef *SPIx, uint16_t Data)
Transmits a Data through the SPIx/I2Sx peripheral.
#define IS_I2S_STANDARD(STANDARD)
#define IS_SPI_I2S_GET_FLAG(FLAG)
void SPI_StructInit(SPI_InitTypeDef *SPI_InitStruct)
Fills each SPI_InitStruct member with its default value.
void I2S_Cmd(SPI_TypeDef *SPIx, FunctionalState NewState)
Enables or disables the specified SPI peripheral (in I2S mode).
#define IS_SPI_23_PERIPH(PERIPH)
void SPI_RxFIFOThresholdConfig(SPI_TypeDef *SPIx, uint16_t SPI_RxFIFOThreshold)
Configures the FIFO reception threshold for the selected SPI.
#define IS_SPI_I2S_CONFIG_IT(IT)
void RCC_APB2PeriphResetCmd(uint32_t RCC_APB2Periph, FunctionalState NewState)
Forces or releases High Speed APB (APB2) peripheral reset.
uint16_t SPI_GetCRCPolynomial(SPI_TypeDef *SPIx)
Returns the CRC Polynomial register value for the specified SPI.
void SPI_NSSInternalSoftwareConfig(SPI_TypeDef *SPIx, uint16_t SPI_NSSInternalSoft)
Configures internally by software the NSS pin for the selected SPI.
#define IS_SPI_CRC_LENGTH(LENGTH)
#define SPI_I2SCFGR_I2SMOD
#define IS_SPI_CPOL(CPOL)
I2S Init structure definition.
#define IS_SPI_BAUDRATE_PRESCALER(PRESCALER)
#define RCC_APB1Periph_SPI3
#define IS_I2S_EXT_PERIPH(PERIPH)
uint16_t SPI_GetReceptionFIFOStatus(SPI_TypeDef *SPIx)
Returns the current SPIx Reception FIFO filled level.
#define I2S_MCLKOutput_Enable
uint32_t SYSCLK_Frequency
#define IS_SPI_ALL_PERIPH_EXT(PERIPH)
void RCC_GetClocksFreq(RCC_ClocksTypeDef *RCC_Clocks)
Returns the frequencies of different on chip clocks; SYSCLK, HCLK, PCLK1 and PCLK2.
#define IS_SPI_DIRECTION_MODE(MODE)
void SPI_BiDirectionalLineConfig(SPI_TypeDef *SPIx, uint16_t SPI_Direction)
Selects the data transfer direction in bidirectional mode for the specified SPI.
#define IS_I2S_MCLK_OUTPUT(OUTPUT)
#define IS_SPI_CRC_POLYNOMIAL(POLYNOMIAL)
#define IS_SPI_23_PERIPH_EXT(PERIPH)
#define I2S_AudioFreq_Default
void SPI_TIModeCmd(SPI_TypeDef *SPIx, FunctionalState NewState)
Enables or disables the TI Mode.
uint16_t SPI_GetTransmissionFIFOStatus(SPI_TypeDef *SPIx)
Returns the current SPIx Transmission FIFO filled level.