2 ******************************************************************************
3 * @file stm32f1xx_ll_i2c.h
4 * @author MCD Application Team
7 * @brief Header file of I2C LL module.
8 ******************************************************************************
11 * <h2><center>© COPYRIGHT(c) 2016 STMicroelectronics</center></h2>
13 * Redistribution and use in source and binary forms, with or without modification,
14 * are permitted provided that the following conditions are met:
15 * 1. Redistributions of source code must retain the above copyright notice,
16 * this list of conditions and the following disclaimer.
17 * 2. Redistributions in binary form must reproduce the above copyright notice,
18 * this list of conditions and the following disclaimer in the documentation
19 * and/or other materials provided with the distribution.
20 * 3. Neither the name of STMicroelectronics nor the names of its contributors
21 * may be used to endorse or promote products derived from this software
22 * without specific prior written permission.
24 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
25 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
26 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
27 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
28 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
29 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
30 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
32 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
33 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
35 ******************************************************************************
38 /* Define to prevent recursive inclusion -------------------------------------*/
39 #ifndef __STM32F1xx_LL_I2C_H
40 #define __STM32F1xx_LL_I2C_H
46 /* Includes ------------------------------------------------------------------*/
47 #include "stm32f1xx.h"
49 /** @addtogroup STM32F1xx_LL_Driver
53 #if defined (I2C1) || defined (I2C2)
55 /** @defgroup I2C_LL I2C
59 /* Private types -------------------------------------------------------------*/
60 /* Private variables ---------------------------------------------------------*/
62 /* Private constants ---------------------------------------------------------*/
63 /** @defgroup I2C_LL_Private_Constants I2C Private Constants
67 /* Defines used to perform compute and check in the macros */
68 #define LL_I2C_MAX_SPEED_STANDARD 100000U
69 #define LL_I2C_MAX_SPEED_FAST 400000U
74 /* Private macros ------------------------------------------------------------*/
75 #if defined(USE_FULL_LL_DRIVER)
76 /** @defgroup I2C_LL_Private_Macros I2C Private Macros
82 #endif /*USE_FULL_LL_DRIVER*/
84 /* Exported types ------------------------------------------------------------*/
85 #if defined(USE_FULL_LL_DRIVER)
86 /** @defgroup I2C_LL_ES_INIT I2C Exported Init structure
91 uint32_t PeripheralMode
; /*!< Specifies the peripheral mode.
92 This parameter can be a value of @ref I2C_LL_EC_PERIPHERAL_MODE
94 This feature can be modified afterwards using unitary function @ref LL_I2C_SetMode(). */
96 uint32_t ClockSpeed
; /*!< Specifies the clock frequency.
97 This parameter must be set to a value lower than 400kHz (in Hz)
99 This feature can be modified afterwards using unitary function @ref LL_I2C_SetClockPeriod()
100 or @ref LL_I2C_SetDutyCycle() or @ref LL_I2C_SetClockSpeedMode() or @ref LL_I2C_ConfigSpeed(). */
102 uint32_t DutyCycle
; /*!< Specifies the I2C fast mode duty cycle.
103 This parameter can be a value of @ref I2C_LL_EC_DUTYCYCLE
105 This feature can be modified afterwards using unitary function @ref LL_I2C_SetDutyCycle(). */
107 uint32_t OwnAddress1
; /*!< Specifies the device own address 1.
108 This parameter must be a value between Min_Data = 0x00 and Max_Data = 0x3FF
110 This feature can be modified afterwards using unitary function @ref LL_I2C_SetOwnAddress1(). */
112 uint32_t TypeAcknowledge
; /*!< Specifies the ACKnowledge or Non ACKnowledge condition after the address receive match code or next received byte.
113 This parameter can be a value of @ref I2C_LL_EC_I2C_ACKNOWLEDGE
115 This feature can be modified afterwards using unitary function @ref LL_I2C_AcknowledgeNextData(). */
117 uint32_t OwnAddrSize
; /*!< Specifies the device own address 1 size (7-bit or 10-bit).
118 This parameter can be a value of @ref I2C_LL_EC_OWNADDRESS1
120 This feature can be modified afterwards using unitary function @ref LL_I2C_SetOwnAddress1(). */
121 } LL_I2C_InitTypeDef
;
125 #endif /*USE_FULL_LL_DRIVER*/
127 /* Exported constants --------------------------------------------------------*/
128 /** @defgroup I2C_LL_Exported_Constants I2C Exported Constants
132 /** @defgroup I2C_LL_EC_GET_FLAG Get Flags Defines
133 * @brief Flags defines which can be used with LL_I2C_ReadReg function
136 #define LL_I2C_SR1_SB I2C_SR1_SB /*!< Start Bit (master mode) */
137 #define LL_I2C_SR1_ADDR I2C_SR1_ADDR /*!< Address sent (master mode) or
138 Address matched flag (slave mode) */
139 #define LL_I2C_SR1_BTF I2C_SR1_BTF /*!< Byte Transfer Finished flag */
140 #define LL_I2C_SR1_ADD10 I2C_SR1_ADD10 /*!< 10-bit header sent (master mode) */
141 #define LL_I2C_SR1_STOPF I2C_SR1_STOPF /*!< Stop detection flag (slave mode) */
142 #define LL_I2C_SR1_RXNE I2C_SR1_RXNE /*!< Data register not empty (receivers) */
143 #define LL_I2C_SR1_TXE I2C_SR1_TXE /*!< Data register empty (transmitters) */
144 #define LL_I2C_SR1_BERR I2C_SR1_BERR /*!< Bus error */
145 #define LL_I2C_SR1_ARLO I2C_SR1_ARLO /*!< Arbitration lost */
146 #define LL_I2C_SR1_AF I2C_SR1_AF /*!< Acknowledge failure flag */
147 #define LL_I2C_SR1_OVR I2C_SR1_OVR /*!< Overrun/Underrun */
148 #define LL_I2C_SR1_PECERR I2C_ISR_PECERR /*!< PEC Error in reception (SMBus mode) */
149 #define LL_I2C_SR1_TIMEOUT I2C_ISR_TIMEOUT /*!< Timeout detection flag (SMBus mode) */
150 #define LL_I2C_SR1_SMALERT I2C_ISR_SMALERT /*!< SMBus alert (SMBus mode) */
151 #define LL_I2C_SR2_MSL I2C_SR2_MSL /*!< Master/Slave flag */
152 #define LL_I2C_SR2_BUSY I2C_SR2_BUSY /*!< Bus busy flag */
153 #define LL_I2C_SR2_TRA I2C_SR2_TRA /*!< Transmitter/receiver direction */
154 #define LL_I2C_SR2_GENCALL I2C_SR2_GENCALL /*!< General call address (Slave mode) */
155 #define LL_I2C_SR2_SMBDEFAULT I2C_SR2_SMBDEFAULT /*!< SMBus Device default address (Slave mode) */
156 #define LL_I2C_SR2_SMBHOST I2C_SR2_SMBHOST /*!< SMBus Host address (Slave mode) */
157 #define LL_I2C_SR2_DUALF I2C_SR2_DUALF /*!< Dual flag (Slave mode) */
162 /** @defgroup I2C_LL_EC_IT IT Defines
163 * @brief IT defines which can be used with LL_I2C_ReadReg and LL_I2C_WriteReg functions
166 #define LL_I2C_CR2_ITEVTEN I2C_CR2_ITEVTEN /*!< Events interrupts enable */
167 #define LL_I2C_CR2_ITBUFEN I2C_CR2_ITBUFEN /*!< Buffer interrupts enable */
168 #define LL_I2C_CR2_ITERREN I2C_CR2_ITERREN /*!< Error interrupts enable */
173 /** @defgroup I2C_LL_EC_OWNADDRESS1 Own Address 1 Length
176 #define LL_I2C_OWNADDRESS1_7BIT 0x00004000U /*!< Own address 1 is a 7-bit address. */
177 #define LL_I2C_OWNADDRESS1_10BIT (uint32_t)(I2C_OAR1_ADDMODE | 0x00004000U) /*!< Own address 1 is a 10-bit address. */
182 /** @defgroup I2C_LL_EC_DUTYCYCLE Fast Mode Duty Cycle
185 #define LL_I2C_DUTYCYCLE_2 0x00000000U /*!< I2C fast mode Tlow/Thigh = 2 */
186 #define LL_I2C_DUTYCYCLE_16_9 I2C_CCR_DUTY /*!< I2C fast mode Tlow/Thigh = 16/9 */
191 /** @defgroup I2C_LL_EC_CLOCK_SPEED_MODE Master Clock Speed Mode
194 #define LL_I2C_CLOCK_SPEED_STANDARD_MODE 0x00000000U /*!< Master clock speed range is standard mode */
195 #define LL_I2C_CLOCK_SPEED_FAST_MODE I2C_CCR_FS /*!< Master clock speed range is fast mode */
200 /** @defgroup I2C_LL_EC_PERIPHERAL_MODE Peripheral Mode
203 #define LL_I2C_MODE_I2C 0x00000000U /*!< I2C Master or Slave mode */
204 #define LL_I2C_MODE_SMBUS_HOST (uint32_t)(I2C_CR1_SMBUS | I2C_CR1_SMBTYPE | I2C_CR1_ENARP) /*!< SMBus Host address acknowledge */
205 #define LL_I2C_MODE_SMBUS_DEVICE I2C_CR1_SMBUS /*!< SMBus Device default mode (Default address not acknowledge) */
206 #define LL_I2C_MODE_SMBUS_DEVICE_ARP (uint32_t)(I2C_CR1_SMBUS | I2C_CR1_ENARP) /*!< SMBus Device Default address acknowledge */
211 /** @defgroup I2C_LL_EC_I2C_ACKNOWLEDGE Acknowledge Generation
214 #define LL_I2C_ACK I2C_CR1_ACK /*!< ACK is sent after current received byte. */
215 #define LL_I2C_NACK 0x00000000U /*!< NACK is sent after current received byte.*/
220 /** @defgroup I2C_LL_EC_DIRECTION Read Write Direction
223 #define LL_I2C_DIRECTION_WRITE I2C_SR2_TRA /*!< Bus is in write transfer */
224 #define LL_I2C_DIRECTION_READ 0x00000000U /*!< Bus is in read transfer */
233 /* Exported macro ------------------------------------------------------------*/
234 /** @defgroup I2C_LL_Exported_Macros I2C Exported Macros
238 /** @defgroup I2C_LL_EM_WRITE_READ Common Write and read registers Macros
243 * @brief Write a value in I2C register
244 * @param __INSTANCE__ I2C Instance
245 * @param __REG__ Register to be written
246 * @param __VALUE__ Value to be written in the register
249 #define LL_I2C_WriteReg(__INSTANCE__, __REG__, __VALUE__) WRITE_REG(__INSTANCE__->__REG__, (__VALUE__))
252 * @brief Read a value in I2C register
253 * @param __INSTANCE__ I2C Instance
254 * @param __REG__ Register to be read
255 * @retval Register value
257 #define LL_I2C_ReadReg(__INSTANCE__, __REG__) READ_REG(__INSTANCE__->__REG__)
262 /** @defgroup I2C_LL_EM_Exported_Macros_Helper Exported_Macros_Helper
267 * @brief Convert Peripheral Clock Frequency in Mhz.
268 * @param __PCLK__ This parameter must be a value of peripheral clock (in Hz).
269 * @retval Value of peripheral clock (in Mhz)
271 #define __LL_I2C_FREQ_HZ_TO_MHZ(__PCLK__) (uint32_t)((__PCLK__)/1000000U)
274 * @brief Convert Peripheral Clock Frequency in Hz.
275 * @param __PCLK__ This parameter must be a value of peripheral clock (in Mhz).
276 * @retval Value of peripheral clock (in Hz)
278 #define __LL_I2C_FREQ_MHZ_TO_HZ(__PCLK__) (uint32_t)((__PCLK__)*1000000U)
281 * @brief Compute I2C Clock rising time.
282 * @param __FREQRANGE__ This parameter must be a value of peripheral clock (in Mhz).
283 * @param __SPEED__ This parameter must be a value lower than 400kHz (in Hz).
284 * @retval Value between Min_Data=0x02 and Max_Data=0x3F
286 #define __LL_I2C_RISE_TIME(__FREQRANGE__, __SPEED__) (uint32_t)(((__SPEED__) <= LL_I2C_MAX_SPEED_STANDARD) ? ((__FREQRANGE__) + 1U) : ((((__FREQRANGE__) * 300U) / 1000U) + 1U))
289 * @brief Compute Speed clock range to a Clock Control Register (I2C_CCR_CCR) value.
290 * @param __PCLK__ This parameter must be a value of peripheral clock (in Hz).
291 * @param __SPEED__ This parameter must be a value lower than 400kHz (in Hz).
292 * @param __DUTYCYCLE__ This parameter can be one of the following values:
293 * @arg @ref LL_I2C_DUTYCYCLE_2
294 * @arg @ref LL_I2C_DUTYCYCLE_16_9
295 * @retval Value between Min_Data=0x004 and Max_Data=0xFFF, except in FAST DUTY mode where Min_Data=0x001.
297 #define __LL_I2C_SPEED_TO_CCR(__PCLK__, __SPEED__, __DUTYCYCLE__) (uint32_t)(((__SPEED__) <= LL_I2C_MAX_SPEED_STANDARD)? \
298 (__LL_I2C_SPEED_STANDARD_TO_CCR((__PCLK__), (__SPEED__))) : \
299 (__LL_I2C_SPEED_FAST_TO_CCR((__PCLK__), (__SPEED__), (__DUTYCYCLE__))))
302 * @brief Compute Speed Standard clock range to a Clock Control Register (I2C_CCR_CCR) value.
303 * @param __PCLK__ This parameter must be a value of peripheral clock (in Hz).
304 * @param __SPEED__ This parameter must be a value lower than 100kHz (in Hz).
305 * @retval Value between Min_Data=0x004 and Max_Data=0xFFF.
307 #define __LL_I2C_SPEED_STANDARD_TO_CCR(__PCLK__, __SPEED__) (uint32_t)(((((__PCLK__)/((__SPEED__) << 1U)) & I2C_CCR_CCR) < 4U)? 4U:((__PCLK__) / ((__SPEED__) << 1U)))
310 * @brief Compute Speed Fast clock range to a Clock Control Register (I2C_CCR_CCR) value.
311 * @param __PCLK__ This parameter must be a value of peripheral clock (in Hz).
312 * @param __SPEED__ This parameter must be a value between Min_Data=100Khz and Max_Data=400Khz (in Hz).
313 * @param __DUTYCYCLE__ This parameter can be one of the following values:
314 * @arg @ref LL_I2C_DUTYCYCLE_2
315 * @arg @ref LL_I2C_DUTYCYCLE_16_9
316 * @retval Value between Min_Data=0x001 and Max_Data=0xFFF
318 #define __LL_I2C_SPEED_FAST_TO_CCR(__PCLK__, __SPEED__, __DUTYCYCLE__) (uint32_t)(((__DUTYCYCLE__) == LL_I2C_DUTYCYCLE_2)? \
319 (((((__PCLK__) / ((__SPEED__) * 3U)) & I2C_CCR_CCR) == 0U)? 1U:((__PCLK__) / ((__SPEED__) * 3U))) : \
320 (((((__PCLK__) / ((__SPEED__) * 25U)) & I2C_CCR_CCR) == 0U)? 1U:((__PCLK__) / ((__SPEED__) * 25U))))
323 * @brief Get the Least significant bits of a 10-Bits address.
324 * @param __ADDRESS__ This parameter must be a value of a 10-Bits slave address.
325 * @retval Value between Min_Data=0x00 and Max_Data=0xFF
327 #define __LL_I2C_10BIT_ADDRESS(__ADDRESS__) ((uint8_t)((uint16_t)((__ADDRESS__) & (uint16_t)(0x00FF))))
330 * @brief Convert a 10-Bits address to a 10-Bits header with Write direction.
331 * @param __ADDRESS__ This parameter must be a value of a 10-Bits slave address.
332 * @retval Value between Min_Data=0xF0 and Max_Data=0xF6
334 #define __LL_I2C_10BIT_HEADER_WRITE(__ADDRESS__) ((uint8_t)((uint16_t)((uint16_t)(((uint16_t)((__ADDRESS__) & (uint16_t)(0x0300))) >> 7) | (uint16_t)(0xF0))))
337 * @brief Convert a 10-Bits address to a 10-Bits header with Read direction.
338 * @param __ADDRESS__ This parameter must be a value of a 10-Bits slave address.
339 * @retval Value between Min_Data=0xF1 and Max_Data=0xF7
341 #define __LL_I2C_10BIT_HEADER_READ(__ADDRESS__) ((uint8_t)((uint16_t)((uint16_t)(((uint16_t)((__ADDRESS__) & (uint16_t)(0x0300))) >> 7) | (uint16_t)(0xF1))))
351 /* Exported functions --------------------------------------------------------*/
353 /** @defgroup I2C_LL_Exported_Functions I2C Exported Functions
357 /** @defgroup I2C_LL_EF_Configuration Configuration
362 * @brief Enable I2C peripheral (PE = 1).
363 * @rmtoll CR1 PE LL_I2C_Enable
364 * @param I2Cx I2C Instance.
367 __STATIC_INLINE
void LL_I2C_Enable(I2C_TypeDef
*I2Cx
)
369 SET_BIT(I2Cx
->CR1
, I2C_CR1_PE
);
373 * @brief Disable I2C peripheral (PE = 0).
374 * @rmtoll CR1 PE LL_I2C_Disable
375 * @param I2Cx I2C Instance.
378 __STATIC_INLINE
void LL_I2C_Disable(I2C_TypeDef
*I2Cx
)
380 CLEAR_BIT(I2Cx
->CR1
, I2C_CR1_PE
);
384 * @brief Check if the I2C peripheral is enabled or disabled.
385 * @rmtoll CR1 PE LL_I2C_IsEnabled
386 * @param I2Cx I2C Instance.
387 * @retval State of bit (1 or 0).
389 __STATIC_INLINE
uint32_t LL_I2C_IsEnabled(I2C_TypeDef
*I2Cx
)
391 return (READ_BIT(I2Cx
->CR1
, I2C_CR1_PE
) == (I2C_CR1_PE
));
396 * @brief Enable DMA transmission requests.
397 * @rmtoll CR2 DMAEN LL_I2C_EnableDMAReq_TX
398 * @param I2Cx I2C Instance.
401 __STATIC_INLINE
void LL_I2C_EnableDMAReq_TX(I2C_TypeDef
*I2Cx
)
403 SET_BIT(I2Cx
->CR2
, I2C_CR2_DMAEN
);
407 * @brief Disable DMA transmission requests.
408 * @rmtoll CR2 DMAEN LL_I2C_DisableDMAReq_TX
409 * @param I2Cx I2C Instance.
412 __STATIC_INLINE
void LL_I2C_DisableDMAReq_TX(I2C_TypeDef
*I2Cx
)
414 CLEAR_BIT(I2Cx
->CR2
, I2C_CR2_DMAEN
);
418 * @brief Check if DMA transmission requests are enabled or disabled.
419 * @rmtoll CR2 DMAEN LL_I2C_IsEnabledDMAReq_TX
420 * @param I2Cx I2C Instance.
421 * @retval State of bit (1 or 0).
423 __STATIC_INLINE
uint32_t LL_I2C_IsEnabledDMAReq_TX(I2C_TypeDef
*I2Cx
)
425 return (READ_BIT(I2Cx
->CR2
, I2C_CR2_DMAEN
) == (I2C_CR2_DMAEN
));
429 * @brief Enable DMA reception requests.
430 * @rmtoll CR2 DMAEN LL_I2C_EnableDMAReq_RX
431 * @param I2Cx I2C Instance.
434 __STATIC_INLINE
void LL_I2C_EnableDMAReq_RX(I2C_TypeDef
*I2Cx
)
436 SET_BIT(I2Cx
->CR2
, I2C_CR2_DMAEN
);
440 * @brief Disable DMA reception requests.
441 * @rmtoll CR2 DMAEN LL_I2C_DisableDMAReq_RX
442 * @param I2Cx I2C Instance.
445 __STATIC_INLINE
void LL_I2C_DisableDMAReq_RX(I2C_TypeDef
*I2Cx
)
447 CLEAR_BIT(I2Cx
->CR2
, I2C_CR2_DMAEN
);
451 * @brief Check if DMA reception requests are enabled or disabled.
452 * @rmtoll CR2 DMAEN LL_I2C_IsEnabledDMAReq_RX
453 * @param I2Cx I2C Instance.
454 * @retval State of bit (1 or 0).
456 __STATIC_INLINE
uint32_t LL_I2C_IsEnabledDMAReq_RX(I2C_TypeDef
*I2Cx
)
458 return (READ_BIT(I2Cx
->CR2
, I2C_CR2_DMAEN
) == (I2C_CR2_DMAEN
));
462 * @brief Get the data register address used for DMA transfer.
463 * @rmtoll DR DR LL_I2C_DMA_GetRegAddr
464 * @param I2Cx I2C Instance.
465 * @retval Address of data register
467 __STATIC_INLINE
uint32_t LL_I2C_DMA_GetRegAddr(I2C_TypeDef
*I2Cx
)
469 return (uint32_t) & (I2Cx
->DR
);
473 * @brief Enable Clock stretching.
474 * @note This bit can only be programmed when the I2C is disabled (PE = 0).
475 * @rmtoll CR1 NOSTRETCH LL_I2C_EnableClockStretching
476 * @param I2Cx I2C Instance.
479 __STATIC_INLINE
void LL_I2C_EnableClockStretching(I2C_TypeDef
*I2Cx
)
481 CLEAR_BIT(I2Cx
->CR1
, I2C_CR1_NOSTRETCH
);
485 * @brief Disable Clock stretching.
486 * @note This bit can only be programmed when the I2C is disabled (PE = 0).
487 * @rmtoll CR1 NOSTRETCH LL_I2C_DisableClockStretching
488 * @param I2Cx I2C Instance.
491 __STATIC_INLINE
void LL_I2C_DisableClockStretching(I2C_TypeDef
*I2Cx
)
493 SET_BIT(I2Cx
->CR1
, I2C_CR1_NOSTRETCH
);
497 * @brief Check if Clock stretching is enabled or disabled.
498 * @rmtoll CR1 NOSTRETCH LL_I2C_IsEnabledClockStretching
499 * @param I2Cx I2C Instance.
500 * @retval State of bit (1 or 0).
502 __STATIC_INLINE
uint32_t LL_I2C_IsEnabledClockStretching(I2C_TypeDef
*I2Cx
)
504 return (READ_BIT(I2Cx
->CR1
, I2C_CR1_NOSTRETCH
) != (I2C_CR1_NOSTRETCH
));
508 * @brief Enable General Call.
509 * @note When enabled the Address 0x00 is ACKed.
510 * @rmtoll CR1 ENGC LL_I2C_EnableGeneralCall
511 * @param I2Cx I2C Instance.
514 __STATIC_INLINE
void LL_I2C_EnableGeneralCall(I2C_TypeDef
*I2Cx
)
516 SET_BIT(I2Cx
->CR1
, I2C_CR1_ENGC
);
520 * @brief Disable General Call.
521 * @note When disabled the Address 0x00 is NACKed.
522 * @rmtoll CR1 ENGC LL_I2C_DisableGeneralCall
523 * @param I2Cx I2C Instance.
526 __STATIC_INLINE
void LL_I2C_DisableGeneralCall(I2C_TypeDef
*I2Cx
)
528 CLEAR_BIT(I2Cx
->CR1
, I2C_CR1_ENGC
);
532 * @brief Check if General Call is enabled or disabled.
533 * @rmtoll CR1 ENGC LL_I2C_IsEnabledGeneralCall
534 * @param I2Cx I2C Instance.
535 * @retval State of bit (1 or 0).
537 __STATIC_INLINE
uint32_t LL_I2C_IsEnabledGeneralCall(I2C_TypeDef
*I2Cx
)
539 return (READ_BIT(I2Cx
->CR1
, I2C_CR1_ENGC
) == (I2C_CR1_ENGC
));
543 * @brief Set the Own Address1.
544 * @rmtoll OAR1 ADD0 LL_I2C_SetOwnAddress1\n
545 * OAR1 ADD1_7 LL_I2C_SetOwnAddress1\n
546 * OAR1 ADD8_9 LL_I2C_SetOwnAddress1\n
547 * OAR1 ADDMODE LL_I2C_SetOwnAddress1
548 * @param I2Cx I2C Instance.
549 * @param OwnAddress1 This parameter must be a value between Min_Data=0 and Max_Data=0x3FF.
550 * @param OwnAddrSize This parameter can be one of the following values:
551 * @arg @ref LL_I2C_OWNADDRESS1_7BIT
552 * @arg @ref LL_I2C_OWNADDRESS1_10BIT
555 __STATIC_INLINE
void LL_I2C_SetOwnAddress1(I2C_TypeDef
*I2Cx
, uint32_t OwnAddress1
, uint32_t OwnAddrSize
)
557 MODIFY_REG(I2Cx
->OAR1
, I2C_OAR1_ADD0
| I2C_OAR1_ADD1_7
| I2C_OAR1_ADD8_9
| I2C_OAR1_ADDMODE
, OwnAddress1
| OwnAddrSize
);
561 * @brief Set the 7bits Own Address2.
562 * @note This action has no effect if own address2 is enabled.
563 * @rmtoll OAR2 ADD2 LL_I2C_SetOwnAddress2
564 * @param I2Cx I2C Instance.
565 * @param OwnAddress2 This parameter must be a value between Min_Data=0 and Max_Data=0x7F.
568 __STATIC_INLINE
void LL_I2C_SetOwnAddress2(I2C_TypeDef
*I2Cx
, uint32_t OwnAddress2
)
570 MODIFY_REG(I2Cx
->OAR2
, I2C_OAR2_ADD2
, OwnAddress2
);
574 * @brief Enable acknowledge on Own Address2 match address.
575 * @rmtoll OAR2 ENDUAL LL_I2C_EnableOwnAddress2
576 * @param I2Cx I2C Instance.
579 __STATIC_INLINE
void LL_I2C_EnableOwnAddress2(I2C_TypeDef
*I2Cx
)
581 SET_BIT(I2Cx
->OAR2
, I2C_OAR2_ENDUAL
);
585 * @brief Disable acknowledge on Own Address2 match address.
586 * @rmtoll OAR2 ENDUAL LL_I2C_DisableOwnAddress2
587 * @param I2Cx I2C Instance.
590 __STATIC_INLINE
void LL_I2C_DisableOwnAddress2(I2C_TypeDef
*I2Cx
)
592 CLEAR_BIT(I2Cx
->OAR2
, I2C_OAR2_ENDUAL
);
596 * @brief Check if Own Address1 acknowledge is enabled or disabled.
597 * @rmtoll OAR2 ENDUAL LL_I2C_IsEnabledOwnAddress2
598 * @param I2Cx I2C Instance.
599 * @retval State of bit (1 or 0).
601 __STATIC_INLINE
uint32_t LL_I2C_IsEnabledOwnAddress2(I2C_TypeDef
*I2Cx
)
603 return (READ_BIT(I2Cx
->OAR2
, I2C_OAR2_ENDUAL
) == (I2C_OAR2_ENDUAL
));
607 * @brief Configure the Peripheral clock frequency.
608 * @rmtoll CR2 FREQ LL_I2C_SetPeriphClock
609 * @param I2Cx I2C Instance.
610 * @param PeriphClock Peripheral Clock (in Hz)
613 __STATIC_INLINE
void LL_I2C_SetPeriphClock(I2C_TypeDef
*I2Cx
, uint32_t PeriphClock
)
615 MODIFY_REG(I2Cx
->CR2
, I2C_CR2_FREQ
, __LL_I2C_FREQ_HZ_TO_MHZ(PeriphClock
));
619 * @brief Get the Peripheral clock frequency.
620 * @rmtoll CR2 FREQ LL_I2C_GetPeriphClock
621 * @param I2Cx I2C Instance.
622 * @retval Value of Peripheral Clock (in Hz)
624 __STATIC_INLINE
uint32_t LL_I2C_GetPeriphClock(I2C_TypeDef
*I2Cx
)
626 return (uint32_t)(__LL_I2C_FREQ_MHZ_TO_HZ(READ_BIT(I2Cx
->CR2
, I2C_CR2_FREQ
)));
630 * @brief Configure the Duty cycle (Fast mode only).
631 * @rmtoll CCR DUTY LL_I2C_SetDutyCycle
632 * @param I2Cx I2C Instance.
633 * @param DutyCycle This parameter can be one of the following values:
634 * @arg @ref LL_I2C_DUTYCYCLE_2
635 * @arg @ref LL_I2C_DUTYCYCLE_16_9
638 __STATIC_INLINE
void LL_I2C_SetDutyCycle(I2C_TypeDef
*I2Cx
, uint32_t DutyCycle
)
640 MODIFY_REG(I2Cx
->CCR
, I2C_CCR_DUTY
, DutyCycle
);
644 * @brief Get the Duty cycle (Fast mode only).
645 * @rmtoll CCR DUTY LL_I2C_GetDutyCycle
646 * @param I2Cx I2C Instance.
647 * @retval Returned value can be one of the following values:
648 * @arg @ref LL_I2C_DUTYCYCLE_2
649 * @arg @ref LL_I2C_DUTYCYCLE_16_9
651 __STATIC_INLINE
uint32_t LL_I2C_GetDutyCycle(I2C_TypeDef
*I2Cx
)
653 return (uint32_t)(READ_BIT(I2Cx
->CCR
, I2C_CCR_DUTY
));
657 * @brief Configure the I2C master clock speed mode.
658 * @rmtoll CCR FS LL_I2C_SetClockSpeedMode
659 * @param I2Cx I2C Instance.
660 * @param ClockSpeedMode This parameter can be one of the following values:
661 * @arg @ref LL_I2C_CLOCK_SPEED_STANDARD_MODE
662 * @arg @ref LL_I2C_CLOCK_SPEED_FAST_MODE
665 __STATIC_INLINE
void LL_I2C_SetClockSpeedMode(I2C_TypeDef
*I2Cx
, uint32_t ClockSpeedMode
)
667 MODIFY_REG(I2Cx
->CCR
, I2C_CCR_FS
, ClockSpeedMode
);
671 * @brief Get the the I2C master speed mode.
672 * @rmtoll CCR FS LL_I2C_GetClockSpeedMode
673 * @param I2Cx I2C Instance.
674 * @retval Returned value can be one of the following values:
675 * @arg @ref LL_I2C_CLOCK_SPEED_STANDARD_MODE
676 * @arg @ref LL_I2C_CLOCK_SPEED_FAST_MODE
678 __STATIC_INLINE
uint32_t LL_I2C_GetClockSpeedMode(I2C_TypeDef
*I2Cx
)
680 return (uint32_t)(READ_BIT(I2Cx
->CCR
, I2C_CCR_FS
));
684 * @brief Configure the SCL, SDA rising time.
685 * @note This bit can only be programmed when the I2C is disabled (PE = 0).
686 * @rmtoll TRISE TRISE LL_I2C_SetRiseTime
687 * @param I2Cx I2C Instance.
688 * @param RiseTime This parameter must be a value between Min_Data=0x02 and Max_Data=0x3F.
691 __STATIC_INLINE
void LL_I2C_SetRiseTime(I2C_TypeDef
*I2Cx
, uint32_t RiseTime
)
693 MODIFY_REG(I2Cx
->TRISE
, I2C_TRISE_TRISE
, RiseTime
);
697 * @brief Get the SCL, SDA rising time.
698 * @rmtoll TRISE TRISE LL_I2C_GetRiseTime
699 * @param I2Cx I2C Instance.
700 * @retval Value between Min_Data=0x02 and Max_Data=0x3F
702 __STATIC_INLINE
uint32_t LL_I2C_GetRiseTime(I2C_TypeDef
*I2Cx
)
704 return (uint32_t)(READ_BIT(I2Cx
->TRISE
, I2C_TRISE_TRISE
));
708 * @brief Configure the SCL high and low period.
709 * @note This bit can only be programmed when the I2C is disabled (PE = 0).
710 * @rmtoll CCR CCR LL_I2C_SetClockPeriod
711 * @param I2Cx I2C Instance.
712 * @param ClockPeriod This parameter must be a value between Min_Data=0x004 and Max_Data=0xFFF, except in FAST DUTY mode where Min_Data=0x001.
715 __STATIC_INLINE
void LL_I2C_SetClockPeriod(I2C_TypeDef
*I2Cx
, uint32_t ClockPeriod
)
717 MODIFY_REG(I2Cx
->CCR
, I2C_CCR_CCR
, ClockPeriod
);
721 * @brief Get the SCL high and low period.
722 * @rmtoll CCR CCR LL_I2C_GetClockPeriod
723 * @param I2Cx I2C Instance.
724 * @retval Value between Min_Data=0x004 and Max_Data=0xFFF, except in FAST DUTY mode where Min_Data=0x001.
726 __STATIC_INLINE
uint32_t LL_I2C_GetClockPeriod(I2C_TypeDef
*I2Cx
)
728 return (uint32_t)(READ_BIT(I2Cx
->CCR
, I2C_CCR_CCR
));
732 * @brief Configure the SCL speed.
733 * @note This bit can only be programmed when the I2C is disabled (PE = 0).
734 * @rmtoll CR2 FREQ LL_I2C_ConfigSpeed\n
735 * TRISE TRISE LL_I2C_ConfigSpeed\n
736 * CCR FS LL_I2C_ConfigSpeed\n
737 * CCR DUTY LL_I2C_ConfigSpeed\n
738 * CCR CCR LL_I2C_ConfigSpeed
739 * @param I2Cx I2C Instance.
740 * @param PeriphClock Peripheral Clock (in Hz)
741 * @param ClockSpeed This parameter must be a value lower than 400kHz (in Hz).
742 * @param DutyCycle This parameter can be one of the following values:
743 * @arg @ref LL_I2C_DUTYCYCLE_2
744 * @arg @ref LL_I2C_DUTYCYCLE_16_9
747 __STATIC_INLINE
void LL_I2C_ConfigSpeed(I2C_TypeDef
*I2Cx
, uint32_t PeriphClock
, uint32_t ClockSpeed
,
750 register uint32_t freqrange
= 0x0U
;
751 register uint32_t clockconfig
= 0x0U
;
753 /* Compute frequency range */
754 freqrange
= __LL_I2C_FREQ_HZ_TO_MHZ(PeriphClock
);
756 /* Configure I2Cx: Frequency range register */
757 MODIFY_REG(I2Cx
->CR2
, I2C_CR2_FREQ
, freqrange
);
759 /* Configure I2Cx: Rise Time register */
760 MODIFY_REG(I2Cx
->TRISE
, I2C_TRISE_TRISE
, __LL_I2C_RISE_TIME(freqrange
, ClockSpeed
));
762 /* Configure Speed mode, Duty Cycle and Clock control register value */
763 if (ClockSpeed
> LL_I2C_MAX_SPEED_STANDARD
)
765 /* Set Speed mode at fast and duty cycle for Clock Speed request in fast clock range */
766 clockconfig
= LL_I2C_CLOCK_SPEED_FAST_MODE
| \
767 __LL_I2C_SPEED_FAST_TO_CCR(PeriphClock
, ClockSpeed
, DutyCycle
) | \
772 /* Set Speed mode at standard for Clock Speed request in standard clock range */
773 clockconfig
= LL_I2C_CLOCK_SPEED_STANDARD_MODE
| \
774 __LL_I2C_SPEED_STANDARD_TO_CCR(PeriphClock
, ClockSpeed
);
777 /* Configure I2Cx: Clock control register */
778 MODIFY_REG(I2Cx
->CCR
, (I2C_CCR_FS
| I2C_CCR_DUTY
| I2C_CCR_CCR
), clockconfig
);
782 * @brief Configure peripheral mode.
783 * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not
784 * SMBus feature is supported by the I2Cx Instance.
785 * @rmtoll CR1 SMBUS LL_I2C_SetMode\n
786 * CR1 SMBTYPE LL_I2C_SetMode\n
787 * CR1 ENARP LL_I2C_SetMode
788 * @param I2Cx I2C Instance.
789 * @param PeripheralMode This parameter can be one of the following values:
790 * @arg @ref LL_I2C_MODE_I2C
791 * @arg @ref LL_I2C_MODE_SMBUS_HOST
792 * @arg @ref LL_I2C_MODE_SMBUS_DEVICE
793 * @arg @ref LL_I2C_MODE_SMBUS_DEVICE_ARP
796 __STATIC_INLINE
void LL_I2C_SetMode(I2C_TypeDef
*I2Cx
, uint32_t PeripheralMode
)
798 MODIFY_REG(I2Cx
->CR1
, I2C_CR1_SMBUS
| I2C_CR1_SMBTYPE
| I2C_CR1_ENARP
, PeripheralMode
);
802 * @brief Get peripheral mode.
803 * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not
804 * SMBus feature is supported by the I2Cx Instance.
805 * @rmtoll CR1 SMBUS LL_I2C_GetMode\n
806 * CR1 SMBTYPE LL_I2C_GetMode\n
807 * CR1 ENARP LL_I2C_GetMode
808 * @param I2Cx I2C Instance.
809 * @retval Returned value can be one of the following values:
810 * @arg @ref LL_I2C_MODE_I2C
811 * @arg @ref LL_I2C_MODE_SMBUS_HOST
812 * @arg @ref LL_I2C_MODE_SMBUS_DEVICE
813 * @arg @ref LL_I2C_MODE_SMBUS_DEVICE_ARP
815 __STATIC_INLINE
uint32_t LL_I2C_GetMode(I2C_TypeDef
*I2Cx
)
817 return (uint32_t)(READ_BIT(I2Cx
->CR1
, I2C_CR1_SMBUS
| I2C_CR1_SMBTYPE
| I2C_CR1_ENARP
));
821 * @brief Enable SMBus alert (Host or Device mode)
822 * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not
823 * SMBus feature is supported by the I2Cx Instance.
824 * @note SMBus Device mode:
825 * - SMBus Alert pin is drived low and
826 * Alert Response Address Header acknowledge is enabled.
828 * - SMBus Alert pin management is supported.
829 * @rmtoll CR1 ALERT LL_I2C_EnableSMBusAlert
830 * @param I2Cx I2C Instance.
833 __STATIC_INLINE
void LL_I2C_EnableSMBusAlert(I2C_TypeDef
*I2Cx
)
835 SET_BIT(I2Cx
->CR1
, I2C_CR1_ALERT
);
839 * @brief Disable SMBus alert (Host or Device mode)
840 * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not
841 * SMBus feature is supported by the I2Cx Instance.
842 * @note SMBus Device mode:
843 * - SMBus Alert pin is not drived (can be used as a standard GPIO) and
844 * Alert Response Address Header acknowledge is disabled.
846 * - SMBus Alert pin management is not supported.
847 * @rmtoll CR1 ALERT LL_I2C_DisableSMBusAlert
848 * @param I2Cx I2C Instance.
851 __STATIC_INLINE
void LL_I2C_DisableSMBusAlert(I2C_TypeDef
*I2Cx
)
853 CLEAR_BIT(I2Cx
->CR1
, I2C_CR1_ALERT
);
857 * @brief Check if SMBus alert (Host or Device mode) is enabled or disabled.
858 * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not
859 * SMBus feature is supported by the I2Cx Instance.
860 * @rmtoll CR1 ALERT LL_I2C_IsEnabledSMBusAlert
861 * @param I2Cx I2C Instance.
862 * @retval State of bit (1 or 0).
864 __STATIC_INLINE
uint32_t LL_I2C_IsEnabledSMBusAlert(I2C_TypeDef
*I2Cx
)
866 return (READ_BIT(I2Cx
->CR1
, I2C_CR1_ALERT
) == (I2C_CR1_ALERT
));
870 * @brief Enable SMBus Packet Error Calculation (PEC).
871 * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not
872 * SMBus feature is supported by the I2Cx Instance.
873 * @rmtoll CR1 ENPEC LL_I2C_EnableSMBusPEC
874 * @param I2Cx I2C Instance.
877 __STATIC_INLINE
void LL_I2C_EnableSMBusPEC(I2C_TypeDef
*I2Cx
)
879 SET_BIT(I2Cx
->CR1
, I2C_CR1_ENPEC
);
883 * @brief Disable SMBus Packet Error Calculation (PEC).
884 * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not
885 * SMBus feature is supported by the I2Cx Instance.
886 * @rmtoll CR1 ENPEC LL_I2C_DisableSMBusPEC
887 * @param I2Cx I2C Instance.
890 __STATIC_INLINE
void LL_I2C_DisableSMBusPEC(I2C_TypeDef
*I2Cx
)
892 CLEAR_BIT(I2Cx
->CR1
, I2C_CR1_ENPEC
);
896 * @brief Check if SMBus Packet Error Calculation (PEC) is enabled or disabled.
897 * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not
898 * SMBus feature is supported by the I2Cx Instance.
899 * @rmtoll CR1 ENPEC LL_I2C_IsEnabledSMBusPEC
900 * @param I2Cx I2C Instance.
901 * @retval State of bit (1 or 0).
903 __STATIC_INLINE
uint32_t LL_I2C_IsEnabledSMBusPEC(I2C_TypeDef
*I2Cx
)
905 return (READ_BIT(I2Cx
->CR1
, I2C_CR1_ENPEC
) == (I2C_CR1_ENPEC
));
912 /** @defgroup I2C_LL_EF_IT_Management IT_Management
917 * @brief Enable TXE interrupt.
918 * @rmtoll CR2 ITEVTEN LL_I2C_EnableIT_TX\n
919 * CR2 ITBUFEN LL_I2C_EnableIT_TX
920 * @param I2Cx I2C Instance.
923 __STATIC_INLINE
void LL_I2C_EnableIT_TX(I2C_TypeDef
*I2Cx
)
925 SET_BIT(I2Cx
->CR2
, I2C_CR2_ITEVTEN
| I2C_CR2_ITBUFEN
);
929 * @brief Disable TXE interrupt.
930 * @rmtoll CR2 ITEVTEN LL_I2C_DisableIT_TX\n
931 * CR2 ITBUFEN LL_I2C_DisableIT_TX
932 * @param I2Cx I2C Instance.
935 __STATIC_INLINE
void LL_I2C_DisableIT_TX(I2C_TypeDef
*I2Cx
)
937 CLEAR_BIT(I2Cx
->CR2
, I2C_CR2_ITEVTEN
| I2C_CR2_ITBUFEN
);
941 * @brief Check if the TXE Interrupt is enabled or disabled.
942 * @rmtoll CR2 ITEVTEN LL_I2C_IsEnabledIT_TX\n
943 * CR2 ITBUFEN LL_I2C_IsEnabledIT_TX
944 * @param I2Cx I2C Instance.
945 * @retval State of bit (1 or 0).
947 __STATIC_INLINE
uint32_t LL_I2C_IsEnabledIT_TX(I2C_TypeDef
*I2Cx
)
949 return (READ_BIT(I2Cx
->CR2
, I2C_CR2_ITEVTEN
| I2C_CR2_ITBUFEN
) == (I2C_CR2_ITEVTEN
| I2C_CR2_ITBUFEN
));
953 * @brief Enable RXNE interrupt.
954 * @rmtoll CR2 ITEVTEN LL_I2C_EnableIT_RX\n
955 * CR2 ITBUFEN LL_I2C_EnableIT_RX
956 * @param I2Cx I2C Instance.
959 __STATIC_INLINE
void LL_I2C_EnableIT_RX(I2C_TypeDef
*I2Cx
)
961 SET_BIT(I2Cx
->CR2
, I2C_CR2_ITEVTEN
| I2C_CR2_ITBUFEN
);
965 * @brief Disable RXNE interrupt.
966 * @rmtoll CR2 ITEVTEN LL_I2C_DisableIT_RX\n
967 * CR2 ITBUFEN LL_I2C_DisableIT_RX
968 * @param I2Cx I2C Instance.
971 __STATIC_INLINE
void LL_I2C_DisableIT_RX(I2C_TypeDef
*I2Cx
)
973 CLEAR_BIT(I2Cx
->CR2
, I2C_CR2_ITEVTEN
| I2C_CR2_ITBUFEN
);
977 * @brief Check if the RXNE Interrupt is enabled or disabled.
978 * @rmtoll CR2 ITEVTEN LL_I2C_IsEnabledIT_RX\n
979 * CR2 ITBUFEN LL_I2C_IsEnabledIT_RX
980 * @param I2Cx I2C Instance.
981 * @retval State of bit (1 or 0).
983 __STATIC_INLINE
uint32_t LL_I2C_IsEnabledIT_RX(I2C_TypeDef
*I2Cx
)
985 return (READ_BIT(I2Cx
->CR2
, I2C_CR2_ITEVTEN
| I2C_CR2_ITBUFEN
) == (I2C_CR2_ITEVTEN
| I2C_CR2_ITBUFEN
));
989 * @brief Enable Events interrupts.
990 * @note Any of these events will generate interrupt :
992 * Address sent, Address matched (ADDR)
993 * 10-bit header sent (ADD10)
994 * Stop detection (STOPF)
995 * Byte transfer finished (BTF)
997 * @note Any of these events will generate interrupt if Buffer interrupts are enabled too(using unitary function @ref LL_I2C_EnableIT_BUF()) :
998 * Receive buffer not empty (RXNE)
999 * Transmit buffer empty (TXE)
1000 * @rmtoll CR2 ITEVTEN LL_I2C_EnableIT_EVT
1001 * @param I2Cx I2C Instance.
1004 __STATIC_INLINE
void LL_I2C_EnableIT_EVT(I2C_TypeDef
*I2Cx
)
1006 SET_BIT(I2Cx
->CR2
, I2C_CR2_ITEVTEN
);
1010 * @brief Disable Events interrupts.
1011 * @note Any of these events will generate interrupt :
1013 * Address sent, Address matched (ADDR)
1014 * 10-bit header sent (ADD10)
1015 * Stop detection (STOPF)
1016 * Byte transfer finished (BTF)
1017 * Receive buffer not empty (RXNE)
1018 * Transmit buffer empty (TXE)
1019 * @rmtoll CR2 ITEVTEN LL_I2C_DisableIT_EVT
1020 * @param I2Cx I2C Instance.
1023 __STATIC_INLINE
void LL_I2C_DisableIT_EVT(I2C_TypeDef
*I2Cx
)
1025 CLEAR_BIT(I2Cx
->CR2
, I2C_CR2_ITEVTEN
);
1029 * @brief Check if Events interrupts are enabled or disabled.
1030 * @rmtoll CR2 ITEVTEN LL_I2C_IsEnabledIT_EVT
1031 * @param I2Cx I2C Instance.
1032 * @retval State of bit (1 or 0).
1034 __STATIC_INLINE
uint32_t LL_I2C_IsEnabledIT_EVT(I2C_TypeDef
*I2Cx
)
1036 return (READ_BIT(I2Cx
->CR2
, I2C_CR2_ITEVTEN
) == (I2C_CR2_ITEVTEN
));
1040 * @brief Enable Buffer interrupts.
1041 * @note Any of these Buffer events will generate interrupt if Events interrupts are enabled too(using unitary function @ref LL_I2C_EnableIT_EVT()) :
1042 * Receive buffer not empty (RXNE)
1043 * Transmit buffer empty (TXE)
1044 * @rmtoll CR2 ITBUFEN LL_I2C_EnableIT_BUF
1045 * @param I2Cx I2C Instance.
1048 __STATIC_INLINE
void LL_I2C_EnableIT_BUF(I2C_TypeDef
*I2Cx
)
1050 SET_BIT(I2Cx
->CR2
, I2C_CR2_ITBUFEN
);
1054 * @brief Disable Buffer interrupts.
1055 * @note Any of these Buffer events will generate interrupt :
1056 * Receive buffer not empty (RXNE)
1057 * Transmit buffer empty (TXE)
1058 * @rmtoll CR2 ITBUFEN LL_I2C_DisableIT_BUF
1059 * @param I2Cx I2C Instance.
1062 __STATIC_INLINE
void LL_I2C_DisableIT_BUF(I2C_TypeDef
*I2Cx
)
1064 CLEAR_BIT(I2Cx
->CR2
, I2C_CR2_ITBUFEN
);
1068 * @brief Check if Buffer interrupts are enabled or disabled.
1069 * @rmtoll CR2 ITBUFEN LL_I2C_IsEnabledIT_BUF
1070 * @param I2Cx I2C Instance.
1071 * @retval State of bit (1 or 0).
1073 __STATIC_INLINE
uint32_t LL_I2C_IsEnabledIT_BUF(I2C_TypeDef
*I2Cx
)
1075 return (READ_BIT(I2Cx
->CR2
, I2C_CR2_ITBUFEN
) == (I2C_CR2_ITBUFEN
));
1079 * @brief Enable Error interrupts.
1080 * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not
1081 * SMBus feature is supported by the I2Cx Instance.
1082 * @note Any of these errors will generate interrupt :
1083 * Bus Error detection (BERR)
1084 * Arbitration Loss (ARLO)
1085 * Acknowledge Failure(AF)
1086 * Overrun/Underrun (OVR)
1087 * SMBus Timeout detection (TIMEOUT)
1088 * SMBus PEC error detection (PECERR)
1089 * SMBus Alert pin event detection (SMBALERT)
1090 * @rmtoll CR2 ITERREN LL_I2C_EnableIT_ERR
1091 * @param I2Cx I2C Instance.
1094 __STATIC_INLINE
void LL_I2C_EnableIT_ERR(I2C_TypeDef
*I2Cx
)
1096 SET_BIT(I2Cx
->CR2
, I2C_CR2_ITERREN
);
1100 * @brief Disable Error interrupts.
1101 * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not
1102 * SMBus feature is supported by the I2Cx Instance.
1103 * @note Any of these errors will generate interrupt :
1104 * Bus Error detection (BERR)
1105 * Arbitration Loss (ARLO)
1106 * Acknowledge Failure(AF)
1107 * Overrun/Underrun (OVR)
1108 * SMBus Timeout detection (TIMEOUT)
1109 * SMBus PEC error detection (PECERR)
1110 * SMBus Alert pin event detection (SMBALERT)
1111 * @rmtoll CR2 ITERREN LL_I2C_DisableIT_ERR
1112 * @param I2Cx I2C Instance.
1115 __STATIC_INLINE
void LL_I2C_DisableIT_ERR(I2C_TypeDef
*I2Cx
)
1117 CLEAR_BIT(I2Cx
->CR2
, I2C_CR2_ITERREN
);
1121 * @brief Check if Error interrupts are enabled or disabled.
1122 * @rmtoll CR2 ITERREN LL_I2C_IsEnabledIT_ERR
1123 * @param I2Cx I2C Instance.
1124 * @retval State of bit (1 or 0).
1126 __STATIC_INLINE
uint32_t LL_I2C_IsEnabledIT_ERR(I2C_TypeDef
*I2Cx
)
1128 return (READ_BIT(I2Cx
->CR2
, I2C_CR2_ITERREN
) == (I2C_CR2_ITERREN
));
1135 /** @defgroup I2C_LL_EF_FLAG_management FLAG_management
1140 * @brief Indicate the status of Transmit data register empty flag.
1141 * @note RESET: When next data is written in Transmit data register.
1142 * SET: When Transmit data register is empty.
1143 * @rmtoll SR1 TXE LL_I2C_IsActiveFlag_TXE
1144 * @param I2Cx I2C Instance.
1145 * @retval State of bit (1 or 0).
1147 __STATIC_INLINE
uint32_t LL_I2C_IsActiveFlag_TXE(I2C_TypeDef
*I2Cx
)
1149 return (READ_BIT(I2Cx
->SR1
, I2C_SR1_TXE
) == (I2C_SR1_TXE
));
1153 * @brief Indicate the status of Byte Transfer Finished flag.
1154 * RESET: When Data byte transfer not done.
1155 * SET: When Data byte transfer succeeded.
1156 * @rmtoll SR1 BTF LL_I2C_IsActiveFlag_BTF
1157 * @param I2Cx I2C Instance.
1158 * @retval State of bit (1 or 0).
1160 __STATIC_INLINE
uint32_t LL_I2C_IsActiveFlag_BTF(I2C_TypeDef
*I2Cx
)
1162 return (READ_BIT(I2Cx
->SR1
, I2C_SR1_BTF
) == (I2C_SR1_BTF
));
1166 * @brief Indicate the status of Receive data register not empty flag.
1167 * @note RESET: When Receive data register is read.
1168 * SET: When the received data is copied in Receive data register.
1169 * @rmtoll SR1 RXNE LL_I2C_IsActiveFlag_RXNE
1170 * @param I2Cx I2C Instance.
1171 * @retval State of bit (1 or 0).
1173 __STATIC_INLINE
uint32_t LL_I2C_IsActiveFlag_RXNE(I2C_TypeDef
*I2Cx
)
1175 return (READ_BIT(I2Cx
->SR1
, I2C_SR1_RXNE
) == (I2C_SR1_RXNE
));
1179 * @brief Indicate the status of Start Bit (master mode).
1180 * @note RESET: When No Start condition.
1181 * SET: When Start condition is generated.
1182 * @rmtoll SR1 SB LL_I2C_IsActiveFlag_SB
1183 * @param I2Cx I2C Instance.
1184 * @retval State of bit (1 or 0).
1186 __STATIC_INLINE
uint32_t LL_I2C_IsActiveFlag_SB(I2C_TypeDef
*I2Cx
)
1188 return (READ_BIT(I2Cx
->SR1
, I2C_SR1_SB
) == (I2C_SR1_SB
));
1192 * @brief Indicate the status of Address sent (master mode) or Address matched flag (slave mode).
1193 * @note RESET: Clear default value.
1194 * SET: When the address is fully sent (master mode) or when the received slave address matched with one of the enabled slave address (slave mode).
1195 * @rmtoll SR1 ADDR LL_I2C_IsActiveFlag_ADDR
1196 * @param I2Cx I2C Instance.
1197 * @retval State of bit (1 or 0).
1199 __STATIC_INLINE
uint32_t LL_I2C_IsActiveFlag_ADDR(I2C_TypeDef
*I2Cx
)
1201 return (READ_BIT(I2Cx
->SR1
, I2C_SR1_ADDR
) == (I2C_SR1_ADDR
));
1205 * @brief Indicate the status of 10-bit header sent (master mode).
1206 * @note RESET: When no ADD10 event occured.
1207 * SET: When the master has sent the first address byte (header).
1208 * @rmtoll SR1 ADD10 LL_I2C_IsActiveFlag_ADD10
1209 * @param I2Cx I2C Instance.
1210 * @retval State of bit (1 or 0).
1212 __STATIC_INLINE
uint32_t LL_I2C_IsActiveFlag_ADD10(I2C_TypeDef
*I2Cx
)
1214 return (READ_BIT(I2Cx
->SR1
, I2C_SR1_ADD10
) == (I2C_SR1_ADD10
));
1218 * @brief Indicate the status of Acknowledge failure flag.
1219 * @note RESET: No acknowledge failure.
1220 * SET: When an acknowledge failure is received after a byte transmission.
1221 * @rmtoll SR1 AF LL_I2C_IsActiveFlag_AF
1222 * @param I2Cx I2C Instance.
1223 * @retval State of bit (1 or 0).
1225 __STATIC_INLINE
uint32_t LL_I2C_IsActiveFlag_AF(I2C_TypeDef
*I2Cx
)
1227 return (READ_BIT(I2Cx
->SR1
, I2C_SR1_AF
) == (I2C_SR1_AF
));
1231 * @brief Indicate the status of Stop detection flag (slave mode).
1232 * @note RESET: Clear default value.
1233 * SET: When a Stop condition is detected.
1234 * @rmtoll SR1 STOPF LL_I2C_IsActiveFlag_STOP
1235 * @param I2Cx I2C Instance.
1236 * @retval State of bit (1 or 0).
1238 __STATIC_INLINE
uint32_t LL_I2C_IsActiveFlag_STOP(I2C_TypeDef
*I2Cx
)
1240 return (READ_BIT(I2Cx
->SR1
, I2C_SR1_STOPF
) == (I2C_SR1_STOPF
));
1244 * @brief Indicate the status of Bus error flag.
1245 * @note RESET: Clear default value.
1246 * SET: When a misplaced Start or Stop condition is detected.
1247 * @rmtoll SR1 BERR LL_I2C_IsActiveFlag_BERR
1248 * @param I2Cx I2C Instance.
1249 * @retval State of bit (1 or 0).
1251 __STATIC_INLINE
uint32_t LL_I2C_IsActiveFlag_BERR(I2C_TypeDef
*I2Cx
)
1253 return (READ_BIT(I2Cx
->SR1
, I2C_SR1_BERR
) == (I2C_SR1_BERR
));
1257 * @brief Indicate the status of Arbitration lost flag.
1258 * @note RESET: Clear default value.
1259 * SET: When arbitration lost.
1260 * @rmtoll SR1 ARLO LL_I2C_IsActiveFlag_ARLO
1261 * @param I2Cx I2C Instance.
1262 * @retval State of bit (1 or 0).
1264 __STATIC_INLINE
uint32_t LL_I2C_IsActiveFlag_ARLO(I2C_TypeDef
*I2Cx
)
1266 return (READ_BIT(I2Cx
->SR1
, I2C_SR1_ARLO
) == (I2C_SR1_ARLO
));
1270 * @brief Indicate the status of Overrun/Underrun flag.
1271 * @note RESET: Clear default value.
1272 * SET: When an overrun/underrun error occurs (Clock Stretching Disabled).
1273 * @rmtoll SR1 OVR LL_I2C_IsActiveFlag_OVR
1274 * @param I2Cx I2C Instance.
1275 * @retval State of bit (1 or 0).
1277 __STATIC_INLINE
uint32_t LL_I2C_IsActiveFlag_OVR(I2C_TypeDef
*I2Cx
)
1279 return (READ_BIT(I2Cx
->SR1
, I2C_SR1_OVR
) == (I2C_SR1_OVR
));
1283 * @brief Indicate the status of SMBus PEC error flag in reception.
1284 * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not
1285 * SMBus feature is supported by the I2Cx Instance.
1286 * @rmtoll SR1 PECERR LL_I2C_IsActiveSMBusFlag_PECERR
1287 * @param I2Cx I2C Instance.
1288 * @retval State of bit (1 or 0).
1290 __STATIC_INLINE
uint32_t LL_I2C_IsActiveSMBusFlag_PECERR(I2C_TypeDef
*I2Cx
)
1292 return (READ_BIT(I2Cx
->SR1
, I2C_SR1_PECERR
) == (I2C_SR1_PECERR
));
1296 * @brief Indicate the status of SMBus Timeout detection flag.
1297 * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not
1298 * SMBus feature is supported by the I2Cx Instance.
1299 * @rmtoll SR1 TIMEOUT LL_I2C_IsActiveSMBusFlag_TIMEOUT
1300 * @param I2Cx I2C Instance.
1301 * @retval State of bit (1 or 0).
1303 __STATIC_INLINE
uint32_t LL_I2C_IsActiveSMBusFlag_TIMEOUT(I2C_TypeDef
*I2Cx
)
1305 return (READ_BIT(I2Cx
->SR1
, I2C_SR1_TIMEOUT
) == (I2C_SR1_TIMEOUT
));
1309 * @brief Indicate the status of SMBus alert flag.
1310 * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not
1311 * SMBus feature is supported by the I2Cx Instance.
1312 * @rmtoll SR1 SMBALERT LL_I2C_IsActiveSMBusFlag_ALERT
1313 * @param I2Cx I2C Instance.
1314 * @retval State of bit (1 or 0).
1316 __STATIC_INLINE
uint32_t LL_I2C_IsActiveSMBusFlag_ALERT(I2C_TypeDef
*I2Cx
)
1318 return (READ_BIT(I2Cx
->SR1
, I2C_SR1_SMBALERT
) == (I2C_SR1_SMBALERT
));
1322 * @brief Indicate the status of Bus Busy flag.
1323 * @note RESET: Clear default value.
1324 * SET: When a Start condition is detected.
1325 * @rmtoll SR2 BUSY LL_I2C_IsActiveFlag_BUSY
1326 * @param I2Cx I2C Instance.
1327 * @retval State of bit (1 or 0).
1329 __STATIC_INLINE
uint32_t LL_I2C_IsActiveFlag_BUSY(I2C_TypeDef
*I2Cx
)
1331 return (READ_BIT(I2Cx
->SR2
, I2C_SR2_BUSY
) == (I2C_SR2_BUSY
));
1335 * @brief Indicate the status of Dual flag.
1336 * @note RESET: Received address matched with OAR1.
1337 * SET: Received address matched with OAR2.
1338 * @rmtoll SR2 DUALF LL_I2C_IsActiveFlag_DUAL
1339 * @param I2Cx I2C Instance.
1340 * @retval State of bit (1 or 0).
1342 __STATIC_INLINE
uint32_t LL_I2C_IsActiveFlag_DUAL(I2C_TypeDef
*I2Cx
)
1344 return (READ_BIT(I2Cx
->SR2
, I2C_SR2_DUALF
) == (I2C_SR2_DUALF
));
1348 * @brief Indicate the status of SMBus Host address reception (Slave mode).
1349 * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not
1350 * SMBus feature is supported by the I2Cx Instance.
1351 * @note RESET: No SMBus Host address
1352 * SET: SMBus Host address received.
1353 * @note This status is cleared by hardware after a STOP condition or repeated START condition.
1354 * @rmtoll SR2 SMBHOST LL_I2C_IsActiveSMBusFlag_SMBHOST
1355 * @param I2Cx I2C Instance.
1356 * @retval State of bit (1 or 0).
1358 __STATIC_INLINE
uint32_t LL_I2C_IsActiveSMBusFlag_SMBHOST(I2C_TypeDef
*I2Cx
)
1360 return (READ_BIT(I2Cx
->SR2
, I2C_SR2_SMBHOST
) == (I2C_SR2_SMBHOST
));
1364 * @brief Indicate the status of SMBus Device default address reception (Slave mode).
1365 * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not
1366 * SMBus feature is supported by the I2Cx Instance.
1367 * @note RESET: No SMBus Device default address
1368 * SET: SMBus Device default address received.
1369 * @note This status is cleared by hardware after a STOP condition or repeated START condition.
1370 * @rmtoll SR2 SMBDEFAULT LL_I2C_IsActiveSMBusFlag_SMBDEFAULT
1371 * @param I2Cx I2C Instance.
1372 * @retval State of bit (1 or 0).
1374 __STATIC_INLINE
uint32_t LL_I2C_IsActiveSMBusFlag_SMBDEFAULT(I2C_TypeDef
*I2Cx
)
1376 return (READ_BIT(I2Cx
->SR2
, I2C_SR2_SMBDEFAULT
) == (I2C_SR2_SMBDEFAULT
));
1380 * @brief Indicate the status of General call address reception (Slave mode).
1381 * @note RESET: No Generall call address
1382 * SET: General call address received.
1383 * @note This status is cleared by hardware after a STOP condition or repeated START condition.
1384 * @rmtoll SR2 GENCALL LL_I2C_IsActiveFlag_GENCALL
1385 * @param I2Cx I2C Instance.
1386 * @retval State of bit (1 or 0).
1388 __STATIC_INLINE
uint32_t LL_I2C_IsActiveFlag_GENCALL(I2C_TypeDef
*I2Cx
)
1390 return (READ_BIT(I2Cx
->SR2
, I2C_SR2_GENCALL
) == (I2C_SR2_GENCALL
));
1394 * @brief Indicate the status of Master/Slave flag.
1395 * @note RESET: Slave Mode.
1397 * @rmtoll SR2 MSL LL_I2C_IsActiveFlag_MSL
1398 * @param I2Cx I2C Instance.
1399 * @retval State of bit (1 or 0).
1401 __STATIC_INLINE
uint32_t LL_I2C_IsActiveFlag_MSL(I2C_TypeDef
*I2Cx
)
1403 return (READ_BIT(I2Cx
->SR2
, I2C_SR2_MSL
) == (I2C_SR2_MSL
));
1407 * @brief Clear Address Matched flag.
1408 * @note Clearing this flag is done by a read access to the I2Cx_SR1
1409 * register followed by a read access to the I2Cx_SR2 register.
1410 * @rmtoll SR1 ADDR LL_I2C_ClearFlag_ADDR
1411 * @param I2Cx I2C Instance.
1414 __STATIC_INLINE
void LL_I2C_ClearFlag_ADDR(I2C_TypeDef
*I2Cx
)
1416 __IO
uint32_t tmpreg
;
1424 * @brief Clear Acknowledge failure flag.
1425 * @rmtoll SR1 AF LL_I2C_ClearFlag_AF
1426 * @param I2Cx I2C Instance.
1429 __STATIC_INLINE
void LL_I2C_ClearFlag_AF(I2C_TypeDef
*I2Cx
)
1431 CLEAR_BIT(I2Cx
->SR1
, I2C_SR1_AF
);
1435 * @brief Clear Stop detection flag.
1436 * @note Clearing this flag is done by a read access to the I2Cx_SR1
1437 * register followed by a write access to I2Cx_CR1 register.
1438 * @rmtoll SR1 STOPF LL_I2C_ClearFlag_STOP\n
1439 * CR1 PE LL_I2C_ClearFlag_STOP
1440 * @param I2Cx I2C Instance.
1443 __STATIC_INLINE
void LL_I2C_ClearFlag_STOP(I2C_TypeDef
*I2Cx
)
1445 __IO
uint32_t tmpreg
;
1448 SET_BIT(I2Cx
->CR1
, I2C_CR1_PE
);
1452 * @brief Clear Bus error flag.
1453 * @rmtoll SR1 BERR LL_I2C_ClearFlag_BERR
1454 * @param I2Cx I2C Instance.
1457 __STATIC_INLINE
void LL_I2C_ClearFlag_BERR(I2C_TypeDef
*I2Cx
)
1459 CLEAR_BIT(I2Cx
->SR1
, I2C_SR1_BERR
);
1463 * @brief Clear Arbitration lost flag.
1464 * @rmtoll SR1 ARLO LL_I2C_ClearFlag_ARLO
1465 * @param I2Cx I2C Instance.
1468 __STATIC_INLINE
void LL_I2C_ClearFlag_ARLO(I2C_TypeDef
*I2Cx
)
1470 CLEAR_BIT(I2Cx
->SR1
, I2C_SR1_ARLO
);
1474 * @brief Clear Overrun/Underrun flag.
1475 * @rmtoll SR1 OVR LL_I2C_ClearFlag_OVR
1476 * @param I2Cx I2C Instance.
1479 __STATIC_INLINE
void LL_I2C_ClearFlag_OVR(I2C_TypeDef
*I2Cx
)
1481 CLEAR_BIT(I2Cx
->SR1
, I2C_SR1_OVR
);
1485 * @brief Clear SMBus PEC error flag.
1486 * @rmtoll SR1 PECERR LL_I2C_ClearSMBusFlag_PECERR
1487 * @param I2Cx I2C Instance.
1490 __STATIC_INLINE
void LL_I2C_ClearSMBusFlag_PECERR(I2C_TypeDef
*I2Cx
)
1492 CLEAR_BIT(I2Cx
->SR1
, I2C_SR1_PECERR
);
1496 * @brief Clear SMBus Timeout detection flag.
1497 * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not
1498 * SMBus feature is supported by the I2Cx Instance.
1499 * @rmtoll SR1 TIMEOUT LL_I2C_ClearSMBusFlag_TIMEOUT
1500 * @param I2Cx I2C Instance.
1503 __STATIC_INLINE
void LL_I2C_ClearSMBusFlag_TIMEOUT(I2C_TypeDef
*I2Cx
)
1505 CLEAR_BIT(I2Cx
->SR1
, I2C_SR1_TIMEOUT
);
1509 * @brief Clear SMBus Alert flag.
1510 * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not
1511 * SMBus feature is supported by the I2Cx Instance.
1512 * @rmtoll SR1 SMBALERT LL_I2C_ClearSMBusFlag_ALERT
1513 * @param I2Cx I2C Instance.
1516 __STATIC_INLINE
void LL_I2C_ClearSMBusFlag_ALERT(I2C_TypeDef
*I2Cx
)
1518 CLEAR_BIT(I2Cx
->SR1
, I2C_SR1_SMBALERT
);
1525 /** @defgroup I2C_LL_EF_Data_Management Data_Management
1530 * @brief Enable Reset of I2C peripheral.
1531 * @rmtoll CR1 SWRST LL_I2C_EnableReset
1532 * @param I2Cx I2C Instance.
1535 __STATIC_INLINE
void LL_I2C_EnableReset(I2C_TypeDef
*I2Cx
)
1537 SET_BIT(I2Cx
->CR1
, I2C_CR1_SWRST
);
1541 * @brief Disable Reset of I2C peripheral.
1542 * @rmtoll CR1 SWRST LL_I2C_DisableReset
1543 * @param I2Cx I2C Instance.
1546 __STATIC_INLINE
void LL_I2C_DisableReset(I2C_TypeDef
*I2Cx
)
1548 CLEAR_BIT(I2Cx
->CR1
, I2C_CR1_SWRST
);
1552 * @brief Check if the I2C peripheral is under reset state or not.
1553 * @rmtoll CR1 SWRST LL_I2C_IsResetEnabled
1554 * @param I2Cx I2C Instance.
1555 * @retval State of bit (1 or 0).
1557 __STATIC_INLINE
uint32_t LL_I2C_IsResetEnabled(I2C_TypeDef
*I2Cx
)
1559 return (READ_BIT(I2Cx
->CR1
, I2C_CR1_SWRST
) == (I2C_CR1_SWRST
));
1563 * @brief Prepare the generation of a ACKnowledge or Non ACKnowledge condition after the address receive match code or next received byte.
1564 * @note Usage in Slave or Master mode.
1565 * @rmtoll CR1 ACK LL_I2C_AcknowledgeNextData
1566 * @param I2Cx I2C Instance.
1567 * @param TypeAcknowledge This parameter can be one of the following values:
1568 * @arg @ref LL_I2C_ACK
1569 * @arg @ref LL_I2C_NACK
1572 __STATIC_INLINE
void LL_I2C_AcknowledgeNextData(I2C_TypeDef
*I2Cx
, uint32_t TypeAcknowledge
)
1574 MODIFY_REG(I2Cx
->CR1
, I2C_CR1_ACK
, TypeAcknowledge
);
1578 * @brief Generate a START or RESTART condition
1579 * @note The START bit can be set even if bus is BUSY or I2C is in slave mode.
1580 * This action has no effect when RELOAD is set.
1581 * @rmtoll CR1 START LL_I2C_GenerateStartCondition
1582 * @param I2Cx I2C Instance.
1585 __STATIC_INLINE
void LL_I2C_GenerateStartCondition(I2C_TypeDef
*I2Cx
)
1587 SET_BIT(I2Cx
->CR1
, I2C_CR1_START
);
1591 * @brief Generate a STOP condition after the current byte transfer (master mode).
1592 * @rmtoll CR1 STOP LL_I2C_GenerateStopCondition
1593 * @param I2Cx I2C Instance.
1596 __STATIC_INLINE
void LL_I2C_GenerateStopCondition(I2C_TypeDef
*I2Cx
)
1598 SET_BIT(I2Cx
->CR1
, I2C_CR1_STOP
);
1602 * @brief Enable bit POS (master/host mode).
1603 * @note In that case, the ACK bit controls the (N)ACK of the next byte received or the PEC bit indicates that the next byte in shift register is a PEC.
1604 * @rmtoll CR1 POS LL_I2C_EnableBitPOS
1605 * @param I2Cx I2C Instance.
1608 __STATIC_INLINE
void LL_I2C_EnableBitPOS(I2C_TypeDef
*I2Cx
)
1610 SET_BIT(I2Cx
->CR1
, I2C_CR1_POS
);
1614 * @brief Disable bit POS (master/host mode).
1615 * @note In that case, the ACK bit controls the (N)ACK of the current byte received or the PEC bit indicates that the current byte in shift register is a PEC.
1616 * @rmtoll CR1 POS LL_I2C_DisableBitPOS
1617 * @param I2Cx I2C Instance.
1620 __STATIC_INLINE
void LL_I2C_DisableBitPOS(I2C_TypeDef
*I2Cx
)
1622 CLEAR_BIT(I2Cx
->CR1
, I2C_CR1_POS
);
1626 * @brief Check if bit POS is enabled or disabled.
1627 * @rmtoll CR1 POS LL_I2C_IsEnabledBitPOS
1628 * @param I2Cx I2C Instance.
1629 * @retval State of bit (1 or 0).
1631 __STATIC_INLINE
uint32_t LL_I2C_IsEnabledBitPOS(I2C_TypeDef
*I2Cx
)
1633 return (READ_BIT(I2Cx
->CR1
, I2C_CR1_POS
) == (I2C_CR1_POS
));
1637 * @brief Indicate the value of transfer direction.
1638 * @note RESET: Bus is in read transfer (peripheral point of view).
1639 * SET: Bus is in write transfer (peripheral point of view).
1640 * @rmtoll SR2 TRA LL_I2C_GetTransferDirection
1641 * @param I2Cx I2C Instance.
1642 * @retval Returned value can be one of the following values:
1643 * @arg @ref LL_I2C_DIRECTION_WRITE
1644 * @arg @ref LL_I2C_DIRECTION_READ
1646 __STATIC_INLINE
uint32_t LL_I2C_GetTransferDirection(I2C_TypeDef
*I2Cx
)
1648 return (uint32_t)(READ_BIT(I2Cx
->SR2
, I2C_SR2_TRA
));
1652 * @brief Enable DMA last transfer.
1653 * @note This action mean that next DMA EOT is the last transfer.
1654 * @rmtoll CR2 LAST LL_I2C_EnableLastDMA
1655 * @param I2Cx I2C Instance.
1658 __STATIC_INLINE
void LL_I2C_EnableLastDMA(I2C_TypeDef
*I2Cx
)
1660 SET_BIT(I2Cx
->CR2
, I2C_CR2_LAST
);
1664 * @brief Disable DMA last transfer.
1665 * @note This action mean that next DMA EOT is not the last transfer.
1666 * @rmtoll CR2 LAST LL_I2C_DisableLastDMA
1667 * @param I2Cx I2C Instance.
1670 __STATIC_INLINE
void LL_I2C_DisableLastDMA(I2C_TypeDef
*I2Cx
)
1672 CLEAR_BIT(I2Cx
->CR2
, I2C_CR2_LAST
);
1676 * @brief Check if DMA last transfer is enabled or disabled.
1677 * @rmtoll CR2 LAST LL_I2C_IsEnabledLastDMA
1678 * @param I2Cx I2C Instance.
1679 * @retval State of bit (1 or 0).
1681 __STATIC_INLINE
uint32_t LL_I2C_IsEnabledLastDMA(I2C_TypeDef
*I2Cx
)
1683 return (READ_BIT(I2Cx
->CR2
, I2C_CR2_LAST
) == (I2C_CR2_LAST
));
1687 * @brief Enable transfer or internal comparison of the SMBus Packet Error byte (transmission or reception mode).
1688 * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not
1689 * SMBus feature is supported by the I2Cx Instance.
1690 * @note This feature is cleared by hardware when the PEC byte is transferred or compared,
1691 * or by a START or STOP condition, it is also cleared by software.
1692 * @rmtoll CR1 PEC LL_I2C_EnableSMBusPECCompare
1693 * @param I2Cx I2C Instance.
1696 __STATIC_INLINE
void LL_I2C_EnableSMBusPECCompare(I2C_TypeDef
*I2Cx
)
1698 SET_BIT(I2Cx
->CR1
, I2C_CR1_PEC
);
1702 * @brief Disable transfer or internal comparison of the SMBus Packet Error byte (transmission or reception mode).
1703 * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not
1704 * SMBus feature is supported by the I2Cx Instance.
1705 * @rmtoll CR1 PEC LL_I2C_DisableSMBusPECCompare
1706 * @param I2Cx I2C Instance.
1709 __STATIC_INLINE
void LL_I2C_DisableSMBusPECCompare(I2C_TypeDef
*I2Cx
)
1711 CLEAR_BIT(I2Cx
->CR1
, I2C_CR1_PEC
);
1715 * @brief Check if the SMBus Packet Error byte transfer or internal comparison is requested or not.
1716 * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not
1717 * SMBus feature is supported by the I2Cx Instance.
1718 * @rmtoll CR1 PEC LL_I2C_IsEnabledSMBusPECCompare
1719 * @param I2Cx I2C Instance.
1720 * @retval State of bit (1 or 0).
1722 __STATIC_INLINE
uint32_t LL_I2C_IsEnabledSMBusPECCompare(I2C_TypeDef
*I2Cx
)
1724 return (READ_BIT(I2Cx
->CR1
, I2C_CR1_PEC
) == (I2C_CR1_PEC
));
1728 * @brief Get the SMBus Packet Error byte calculated.
1729 * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not
1730 * SMBus feature is supported by the I2Cx Instance.
1731 * @rmtoll SR2 PEC LL_I2C_GetSMBusPEC
1732 * @param I2Cx I2C Instance.
1733 * @retval Value between Min_Data=0x00 and Max_Data=0xFF
1735 __STATIC_INLINE
uint32_t LL_I2C_GetSMBusPEC(I2C_TypeDef
*I2Cx
)
1737 return (uint32_t)(READ_BIT(I2Cx
->SR2
, I2C_SR2_PEC
) >> I2C_SR2_PEC_Pos
);
1741 * @brief Read Receive Data register.
1742 * @rmtoll DR DR LL_I2C_ReceiveData8
1743 * @param I2Cx I2C Instance.
1744 * @retval Value between Min_Data=0x0 and Max_Data=0xFF
1746 __STATIC_INLINE
uint8_t LL_I2C_ReceiveData8(I2C_TypeDef
*I2Cx
)
1748 return (uint8_t)(READ_BIT(I2Cx
->DR
, I2C_DR_DR
));
1752 * @brief Write in Transmit Data Register .
1753 * @rmtoll DR DR LL_I2C_TransmitData8
1754 * @param I2Cx I2C Instance.
1755 * @param Data Value between Min_Data=0x0 and Max_Data=0xFF
1758 __STATIC_INLINE
void LL_I2C_TransmitData8(I2C_TypeDef
*I2Cx
, uint8_t Data
)
1760 MODIFY_REG(I2Cx
->DR
, I2C_DR_DR
, Data
);
1767 #if defined(USE_FULL_LL_DRIVER)
1768 /** @defgroup I2C_LL_EF_Init Initialization and de-initialization functions
1772 uint32_t LL_I2C_Init(I2C_TypeDef
*I2Cx
, LL_I2C_InitTypeDef
*I2C_InitStruct
);
1773 uint32_t LL_I2C_DeInit(I2C_TypeDef
*I2Cx
);
1774 void LL_I2C_StructInit(LL_I2C_InitTypeDef
*I2C_InitStruct
);
1780 #endif /* USE_FULL_LL_DRIVER */
1790 #endif /* I2C1 || I2C2 */
1800 #endif /* __STM32F1xx_LL_I2C_H */
1802 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/