Create release.yml
[betaflight.git] / lib / main / STM32F4 / Drivers / STM32F4xx_HAL_Driver / Inc / stm32f4xx_ll_i2c.h
blob54fea5eff5bbcfd6c0fd4456eb75e420b55d86d4
1 /**
2 ******************************************************************************
3 * @file stm32f4xx_ll_i2c.h
4 * @author MCD Application Team
5 * @version V1.7.1
6 * @date 14-April-2017
7 * @brief Header file of I2C LL module.
8 ******************************************************************************
9 * @attention
11 * <h2><center>&copy; COPYRIGHT(c) 2017 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 __STM32F4xx_LL_I2C_H
40 #define __STM32F4xx_LL_I2C_H
42 #ifdef __cplusplus
43 extern "C" {
44 #endif
46 /* Includes ------------------------------------------------------------------*/
47 #include "stm32f4xx.h"
49 /** @addtogroup STM32F4xx_LL_Driver
50 * @{
53 #if defined (I2C1) || defined (I2C2) || defined (I2C3)
55 /** @defgroup I2C_LL I2C
56 * @{
59 /* Private types -------------------------------------------------------------*/
60 /* Private variables ---------------------------------------------------------*/
62 /* Private constants ---------------------------------------------------------*/
63 /** @defgroup I2C_LL_Private_Constants I2C Private Constants
64 * @{
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
70 /**
71 * @}
74 /* Private macros ------------------------------------------------------------*/
75 #if defined(USE_FULL_LL_DRIVER)
76 /** @defgroup I2C_LL_Private_Macros I2C Private Macros
77 * @{
79 /**
80 * @}
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
87 * @{
89 typedef struct
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 #if defined(I2C_FLTR_ANOFF)&&defined(I2C_FLTR_DNF)
108 uint32_t AnalogFilter; /*!< Enables or disables analog noise filter.
109 This parameter can be a value of @ref I2C_LL_EC_ANALOGFILTER_SELECTION
111 This feature can be modified afterwards using unitary functions @ref LL_I2C_EnableAnalogFilter() or LL_I2C_DisableAnalogFilter(). */
113 uint32_t DigitalFilter; /*!< Configures the digital noise filter.
114 This parameter can be a number between Min_Data = 0x00 and Max_Data = 0x0F
116 This feature can be modified afterwards using unitary function @ref LL_I2C_SetDigitalFilter(). */
118 #endif
119 uint32_t OwnAddress1; /*!< Specifies the device own address 1.
120 This parameter must be a value between Min_Data = 0x00 and Max_Data = 0x3FF
122 This feature can be modified afterwards using unitary function @ref LL_I2C_SetOwnAddress1(). */
124 uint32_t TypeAcknowledge; /*!< Specifies the ACKnowledge or Non ACKnowledge condition after the address receive match code or next received byte.
125 This parameter can be a value of @ref I2C_LL_EC_I2C_ACKNOWLEDGE
127 This feature can be modified afterwards using unitary function @ref LL_I2C_AcknowledgeNextData(). */
129 uint32_t OwnAddrSize; /*!< Specifies the device own address 1 size (7-bit or 10-bit).
130 This parameter can be a value of @ref I2C_LL_EC_OWNADDRESS1
132 This feature can be modified afterwards using unitary function @ref LL_I2C_SetOwnAddress1(). */
133 } LL_I2C_InitTypeDef;
135 * @}
137 #endif /*USE_FULL_LL_DRIVER*/
139 /* Exported constants --------------------------------------------------------*/
140 /** @defgroup I2C_LL_Exported_Constants I2C Exported Constants
141 * @{
144 /** @defgroup I2C_LL_EC_GET_FLAG Get Flags Defines
145 * @brief Flags defines which can be used with LL_I2C_ReadReg function
146 * @{
148 #define LL_I2C_SR1_SB I2C_SR1_SB /*!< Start Bit (master mode) */
149 #define LL_I2C_SR1_ADDR I2C_SR1_ADDR /*!< Address sent (master mode) or
150 Address matched flag (slave mode) */
151 #define LL_I2C_SR1_BTF I2C_SR1_BTF /*!< Byte Transfer Finished flag */
152 #define LL_I2C_SR1_ADD10 I2C_SR1_ADD10 /*!< 10-bit header sent (master mode) */
153 #define LL_I2C_SR1_STOPF I2C_SR1_STOPF /*!< Stop detection flag (slave mode) */
154 #define LL_I2C_SR1_RXNE I2C_SR1_RXNE /*!< Data register not empty (receivers) */
155 #define LL_I2C_SR1_TXE I2C_SR1_TXE /*!< Data register empty (transmitters) */
156 #define LL_I2C_SR1_BERR I2C_SR1_BERR /*!< Bus error */
157 #define LL_I2C_SR1_ARLO I2C_SR1_ARLO /*!< Arbitration lost */
158 #define LL_I2C_SR1_AF I2C_SR1_AF /*!< Acknowledge failure flag */
159 #define LL_I2C_SR1_OVR I2C_SR1_OVR /*!< Overrun/Underrun */
160 #define LL_I2C_SR1_PECERR I2C_ISR_PECERR /*!< PEC Error in reception (SMBus mode) */
161 #define LL_I2C_SR1_TIMEOUT I2C_ISR_TIMEOUT /*!< Timeout detection flag (SMBus mode) */
162 #define LL_I2C_SR1_SMALERT I2C_ISR_SMALERT /*!< SMBus alert (SMBus mode) */
163 #define LL_I2C_SR2_MSL I2C_SR2_MSL /*!< Master/Slave flag */
164 #define LL_I2C_SR2_BUSY I2C_SR2_BUSY /*!< Bus busy flag */
165 #define LL_I2C_SR2_TRA I2C_SR2_TRA /*!< Transmitter/receiver direction */
166 #define LL_I2C_SR2_GENCALL I2C_SR2_GENCALL /*!< General call address (Slave mode) */
167 #define LL_I2C_SR2_SMBDEFAULT I2C_SR2_SMBDEFAULT /*!< SMBus Device default address (Slave mode) */
168 #define LL_I2C_SR2_SMBHOST I2C_SR2_SMBHOST /*!< SMBus Host address (Slave mode) */
169 #define LL_I2C_SR2_DUALF I2C_SR2_DUALF /*!< Dual flag (Slave mode) */
171 * @}
174 /** @defgroup I2C_LL_EC_IT IT Defines
175 * @brief IT defines which can be used with LL_I2C_ReadReg and LL_I2C_WriteReg functions
176 * @{
178 #define LL_I2C_CR2_ITEVTEN I2C_CR2_ITEVTEN /*!< Events interrupts enable */
179 #define LL_I2C_CR2_ITBUFEN I2C_CR2_ITBUFEN /*!< Buffer interrupts enable */
180 #define LL_I2C_CR2_ITERREN I2C_CR2_ITERREN /*!< Error interrupts enable */
182 * @}
185 #if defined(I2C_FLTR_ANOFF)
186 /** @defgroup I2C_LL_EC_ANALOGFILTER_SELECTION Analog Filter Selection
187 * @{
189 #define LL_I2C_ANALOGFILTER_ENABLE 0x00000000U /*!< Analog filter is enabled. */
190 #define LL_I2C_ANALOGFILTER_DISABLE I2C_FLTR_ANOFF /*!< Analog filter is disabled.*/
192 * @}
195 #endif
196 /** @defgroup I2C_LL_EC_OWNADDRESS1 Own Address 1 Length
197 * @{
199 #define LL_I2C_OWNADDRESS1_7BIT 0x00004000U /*!< Own address 1 is a 7-bit address. */
200 #define LL_I2C_OWNADDRESS1_10BIT (uint32_t)(I2C_OAR1_ADDMODE | 0x00004000U) /*!< Own address 1 is a 10-bit address. */
202 * @}
205 /** @defgroup I2C_LL_EC_DUTYCYCLE Fast Mode Duty Cycle
206 * @{
208 #define LL_I2C_DUTYCYCLE_2 0x00000000U /*!< I2C fast mode Tlow/Thigh = 2 */
209 #define LL_I2C_DUTYCYCLE_16_9 I2C_CCR_DUTY /*!< I2C fast mode Tlow/Thigh = 16/9 */
211 * @}
214 /** @defgroup I2C_LL_EC_CLOCK_SPEED_MODE Master Clock Speed Mode
215 * @{
217 #define LL_I2C_CLOCK_SPEED_STANDARD_MODE 0x00000000U /*!< Master clock speed range is standard mode */
218 #define LL_I2C_CLOCK_SPEED_FAST_MODE I2C_CCR_FS /*!< Master clock speed range is fast mode */
220 * @}
223 /** @defgroup I2C_LL_EC_PERIPHERAL_MODE Peripheral Mode
224 * @{
226 #define LL_I2C_MODE_I2C 0x00000000U /*!< I2C Master or Slave mode */
227 #define LL_I2C_MODE_SMBUS_HOST (uint32_t)(I2C_CR1_SMBUS | I2C_CR1_SMBTYPE | I2C_CR1_ENARP) /*!< SMBus Host address acknowledge */
228 #define LL_I2C_MODE_SMBUS_DEVICE I2C_CR1_SMBUS /*!< SMBus Device default mode (Default address not acknowledge) */
229 #define LL_I2C_MODE_SMBUS_DEVICE_ARP (uint32_t)(I2C_CR1_SMBUS | I2C_CR1_ENARP) /*!< SMBus Device Default address acknowledge */
231 * @}
234 /** @defgroup I2C_LL_EC_I2C_ACKNOWLEDGE Acknowledge Generation
235 * @{
237 #define LL_I2C_ACK I2C_CR1_ACK /*!< ACK is sent after current received byte. */
238 #define LL_I2C_NACK 0x00000000U /*!< NACK is sent after current received byte.*/
240 * @}
243 /** @defgroup I2C_LL_EC_DIRECTION Read Write Direction
244 * @{
246 #define LL_I2C_DIRECTION_WRITE I2C_SR2_TRA /*!< Bus is in write transfer */
247 #define LL_I2C_DIRECTION_READ 0x00000000U /*!< Bus is in read transfer */
249 * @}
253 * @}
256 /* Exported macro ------------------------------------------------------------*/
257 /** @defgroup I2C_LL_Exported_Macros I2C Exported Macros
258 * @{
261 /** @defgroup I2C_LL_EM_WRITE_READ Common Write and read registers Macros
262 * @{
266 * @brief Write a value in I2C register
267 * @param __INSTANCE__ I2C Instance
268 * @param __REG__ Register to be written
269 * @param __VALUE__ Value to be written in the register
270 * @retval None
272 #define LL_I2C_WriteReg(__INSTANCE__, __REG__, __VALUE__) WRITE_REG(__INSTANCE__->__REG__, (__VALUE__))
275 * @brief Read a value in I2C register
276 * @param __INSTANCE__ I2C Instance
277 * @param __REG__ Register to be read
278 * @retval Register value
280 #define LL_I2C_ReadReg(__INSTANCE__, __REG__) READ_REG(__INSTANCE__->__REG__)
282 * @}
285 /** @defgroup I2C_LL_EM_Exported_Macros_Helper Exported_Macros_Helper
286 * @{
290 * @brief Convert Peripheral Clock Frequency in Mhz.
291 * @param __PCLK__ This parameter must be a value of peripheral clock (in Hz).
292 * @retval Value of peripheral clock (in Mhz)
294 #define __LL_I2C_FREQ_HZ_TO_MHZ(__PCLK__) (uint32_t)((__PCLK__)/1000000U)
297 * @brief Convert Peripheral Clock Frequency in Hz.
298 * @param __PCLK__ This parameter must be a value of peripheral clock (in Mhz).
299 * @retval Value of peripheral clock (in Hz)
301 #define __LL_I2C_FREQ_MHZ_TO_HZ(__PCLK__) (uint32_t)((__PCLK__)*1000000U)
304 * @brief Compute I2C Clock rising time.
305 * @param __FREQRANGE__ This parameter must be a value of peripheral clock (in Mhz).
306 * @param __SPEED__ This parameter must be a value lower than 400kHz (in Hz).
307 * @retval Value between Min_Data=0x02 and Max_Data=0x3F
309 #define __LL_I2C_RISE_TIME(__FREQRANGE__, __SPEED__) (uint32_t)(((__SPEED__) <= LL_I2C_MAX_SPEED_STANDARD) ? ((__FREQRANGE__) + 1U) : ((((__FREQRANGE__) * 300U) / 1000U) + 1U))
312 * @brief Compute Speed clock range to a Clock Control Register (I2C_CCR_CCR) value.
313 * @param __PCLK__ This parameter must be a value of peripheral clock (in Hz).
314 * @param __SPEED__ This parameter must be a value lower than 400kHz (in Hz).
315 * @param __DUTYCYCLE__ This parameter can be one of the following values:
316 * @arg @ref LL_I2C_DUTYCYCLE_2
317 * @arg @ref LL_I2C_DUTYCYCLE_16_9
318 * @retval Value between Min_Data=0x004 and Max_Data=0xFFF, except in FAST DUTY mode where Min_Data=0x001.
320 #define __LL_I2C_SPEED_TO_CCR(__PCLK__, __SPEED__, __DUTYCYCLE__) (uint32_t)(((__SPEED__) <= LL_I2C_MAX_SPEED_STANDARD)? \
321 (__LL_I2C_SPEED_STANDARD_TO_CCR((__PCLK__), (__SPEED__))) : \
322 (__LL_I2C_SPEED_FAST_TO_CCR((__PCLK__), (__SPEED__), (__DUTYCYCLE__))))
325 * @brief Compute Speed Standard clock range to a Clock Control Register (I2C_CCR_CCR) value.
326 * @param __PCLK__ This parameter must be a value of peripheral clock (in Hz).
327 * @param __SPEED__ This parameter must be a value lower than 100kHz (in Hz).
328 * @retval Value between Min_Data=0x004 and Max_Data=0xFFF.
330 #define __LL_I2C_SPEED_STANDARD_TO_CCR(__PCLK__, __SPEED__) (uint32_t)(((((__PCLK__)/((__SPEED__) << 1U)) & I2C_CCR_CCR) < 4U)? 4U:((__PCLK__) / ((__SPEED__) << 1U)))
333 * @brief Compute Speed Fast clock range to a Clock Control Register (I2C_CCR_CCR) value.
334 * @param __PCLK__ This parameter must be a value of peripheral clock (in Hz).
335 * @param __SPEED__ This parameter must be a value between Min_Data=100Khz and Max_Data=400Khz (in Hz).
336 * @param __DUTYCYCLE__ This parameter can be one of the following values:
337 * @arg @ref LL_I2C_DUTYCYCLE_2
338 * @arg @ref LL_I2C_DUTYCYCLE_16_9
339 * @retval Value between Min_Data=0x001 and Max_Data=0xFFF
341 #define __LL_I2C_SPEED_FAST_TO_CCR(__PCLK__, __SPEED__, __DUTYCYCLE__) (uint32_t)(((__DUTYCYCLE__) == LL_I2C_DUTYCYCLE_2)? \
342 (((((__PCLK__) / ((__SPEED__) * 3U)) & I2C_CCR_CCR) == 0U)? 1U:((__PCLK__) / ((__SPEED__) * 3U))) : \
343 (((((__PCLK__) / ((__SPEED__) * 25U)) & I2C_CCR_CCR) == 0U)? 1U:((__PCLK__) / ((__SPEED__) * 25U))))
346 * @brief Get the Least significant bits of a 10-Bits address.
347 * @param __ADDRESS__ This parameter must be a value of a 10-Bits slave address.
348 * @retval Value between Min_Data=0x00 and Max_Data=0xFF
350 #define __LL_I2C_10BIT_ADDRESS(__ADDRESS__) ((uint8_t)((uint16_t)((__ADDRESS__) & (uint16_t)(0x00FF))))
353 * @brief Convert a 10-Bits address to a 10-Bits header with Write direction.
354 * @param __ADDRESS__ This parameter must be a value of a 10-Bits slave address.
355 * @retval Value between Min_Data=0xF0 and Max_Data=0xF6
357 #define __LL_I2C_10BIT_HEADER_WRITE(__ADDRESS__) ((uint8_t)((uint16_t)((uint16_t)(((uint16_t)((__ADDRESS__) & (uint16_t)(0x0300))) >> 7) | (uint16_t)(0xF0))))
360 * @brief Convert a 10-Bits address to a 10-Bits header with Read direction.
361 * @param __ADDRESS__ This parameter must be a value of a 10-Bits slave address.
362 * @retval Value between Min_Data=0xF1 and Max_Data=0xF7
364 #define __LL_I2C_10BIT_HEADER_READ(__ADDRESS__) ((uint8_t)((uint16_t)((uint16_t)(((uint16_t)((__ADDRESS__) & (uint16_t)(0x0300))) >> 7) | (uint16_t)(0xF1))))
367 * @}
371 * @}
374 /* Exported functions --------------------------------------------------------*/
376 /** @defgroup I2C_LL_Exported_Functions I2C Exported Functions
377 * @{
380 /** @defgroup I2C_LL_EF_Configuration Configuration
381 * @{
385 * @brief Enable I2C peripheral (PE = 1).
386 * @rmtoll CR1 PE LL_I2C_Enable
387 * @param I2Cx I2C Instance.
388 * @retval None
390 __STATIC_INLINE void LL_I2C_Enable(I2C_TypeDef *I2Cx)
392 SET_BIT(I2Cx->CR1, I2C_CR1_PE);
396 * @brief Disable I2C peripheral (PE = 0).
397 * @rmtoll CR1 PE LL_I2C_Disable
398 * @param I2Cx I2C Instance.
399 * @retval None
401 __STATIC_INLINE void LL_I2C_Disable(I2C_TypeDef *I2Cx)
403 CLEAR_BIT(I2Cx->CR1, I2C_CR1_PE);
407 * @brief Check if the I2C peripheral is enabled or disabled.
408 * @rmtoll CR1 PE LL_I2C_IsEnabled
409 * @param I2Cx I2C Instance.
410 * @retval State of bit (1 or 0).
412 __STATIC_INLINE uint32_t LL_I2C_IsEnabled(I2C_TypeDef *I2Cx)
414 return (READ_BIT(I2Cx->CR1, I2C_CR1_PE) == (I2C_CR1_PE));
417 #if defined(I2C_FLTR_ANOFF)&&defined(I2C_FLTR_DNF)
419 * @brief Configure Noise Filters (Analog and Digital).
420 * @note If the analog filter is also enabled, the digital filter is added to analog filter.
421 * The filters can only be programmed when the I2C is disabled (PE = 0).
422 * @rmtoll FLTR ANOFF LL_I2C_ConfigFilters\n
423 * FLTR DNF LL_I2C_ConfigFilters
424 * @param I2Cx I2C Instance.
425 * @param AnalogFilter This parameter can be one of the following values:
426 * @arg @ref LL_I2C_ANALOGFILTER_ENABLE
427 * @arg @ref LL_I2C_ANALOGFILTER_DISABLE
428 * @param DigitalFilter This parameter must be a value between Min_Data=0x00 (Digital filter disabled) and Max_Data=0x0F (Digital filter enabled and filtering capability up to 15*TPCLK1)
429 * This parameter is used to configure the digital noise filter on SDA and SCL input. The digital filter will suppress the spikes with a length of up to DNF[3:0]*TPCLK1.
430 * @retval None
432 __STATIC_INLINE void LL_I2C_ConfigFilters(I2C_TypeDef *I2Cx, uint32_t AnalogFilter, uint32_t DigitalFilter)
434 MODIFY_REG(I2Cx->FLTR, I2C_FLTR_ANOFF | I2C_FLTR_DNF, AnalogFilter | DigitalFilter);
436 #endif
437 #if defined(I2C_FLTR_DNF)
440 * @brief Configure Digital Noise Filter.
441 * @note If the analog filter is also enabled, the digital filter is added to analog filter.
442 * This filter can only be programmed when the I2C is disabled (PE = 0).
443 * @rmtoll FLTR DNF LL_I2C_SetDigitalFilter
444 * @param I2Cx I2C Instance.
445 * @param DigitalFilter This parameter must be a value between Min_Data=0x00 (Digital filter disabled) and Max_Data=0x0F (Digital filter enabled and filtering capability up to 15*TPCLK1)
446 * This parameter is used to configure the digital noise filter on SDA and SCL input. The digital filter will suppress the spikes with a length of up to DNF[3:0]*TPCLK1.
447 * @retval None
449 __STATIC_INLINE void LL_I2C_SetDigitalFilter(I2C_TypeDef *I2Cx, uint32_t DigitalFilter)
451 MODIFY_REG(I2Cx->FLTR, I2C_FLTR_DNF, DigitalFilter);
455 * @brief Get the current Digital Noise Filter configuration.
456 * @rmtoll FLTR DNF LL_I2C_GetDigitalFilter
457 * @param I2Cx I2C Instance.
458 * @retval Value between Min_Data=0x0 and Max_Data=0xF
460 __STATIC_INLINE uint32_t LL_I2C_GetDigitalFilter(I2C_TypeDef *I2Cx)
462 return (uint32_t)(READ_BIT(I2Cx->FLTR, I2C_FLTR_DNF));
464 #endif
465 #if defined(I2C_FLTR_ANOFF)
468 * @brief Enable Analog Noise Filter.
469 * @note This filter can only be programmed when the I2C is disabled (PE = 0).
470 * @rmtoll FLTR ANOFF LL_I2C_EnableAnalogFilter
471 * @param I2Cx I2C Instance.
472 * @retval None
474 __STATIC_INLINE void LL_I2C_EnableAnalogFilter(I2C_TypeDef *I2Cx)
476 CLEAR_BIT(I2Cx->FLTR, I2C_FLTR_ANOFF);
480 * @brief Disable Analog Noise Filter.
481 * @note This filter can only be programmed when the I2C is disabled (PE = 0).
482 * @rmtoll FLTR ANOFF LL_I2C_DisableAnalogFilter
483 * @param I2Cx I2C Instance.
484 * @retval None
486 __STATIC_INLINE void LL_I2C_DisableAnalogFilter(I2C_TypeDef *I2Cx)
488 SET_BIT(I2Cx->FLTR, I2C_FLTR_ANOFF);
492 * @brief Check if Analog Noise Filter is enabled or disabled.
493 * @rmtoll FLTR ANOFF LL_I2C_IsEnabledAnalogFilter
494 * @param I2Cx I2C Instance.
495 * @retval State of bit (1 or 0).
497 __STATIC_INLINE uint32_t LL_I2C_IsEnabledAnalogFilter(I2C_TypeDef *I2Cx)
499 return (READ_BIT(I2Cx->FLTR, I2C_FLTR_ANOFF) == (I2C_FLTR_ANOFF));
501 #endif
504 * @brief Enable DMA transmission requests.
505 * @rmtoll CR2 DMAEN LL_I2C_EnableDMAReq_TX
506 * @param I2Cx I2C Instance.
507 * @retval None
509 __STATIC_INLINE void LL_I2C_EnableDMAReq_TX(I2C_TypeDef *I2Cx)
511 SET_BIT(I2Cx->CR2, I2C_CR2_DMAEN);
515 * @brief Disable DMA transmission requests.
516 * @rmtoll CR2 DMAEN LL_I2C_DisableDMAReq_TX
517 * @param I2Cx I2C Instance.
518 * @retval None
520 __STATIC_INLINE void LL_I2C_DisableDMAReq_TX(I2C_TypeDef *I2Cx)
522 CLEAR_BIT(I2Cx->CR2, I2C_CR2_DMAEN);
526 * @brief Check if DMA transmission requests are enabled or disabled.
527 * @rmtoll CR2 DMAEN LL_I2C_IsEnabledDMAReq_TX
528 * @param I2Cx I2C Instance.
529 * @retval State of bit (1 or 0).
531 __STATIC_INLINE uint32_t LL_I2C_IsEnabledDMAReq_TX(I2C_TypeDef *I2Cx)
533 return (READ_BIT(I2Cx->CR2, I2C_CR2_DMAEN) == (I2C_CR2_DMAEN));
537 * @brief Enable DMA reception requests.
538 * @rmtoll CR2 DMAEN LL_I2C_EnableDMAReq_RX
539 * @param I2Cx I2C Instance.
540 * @retval None
542 __STATIC_INLINE void LL_I2C_EnableDMAReq_RX(I2C_TypeDef *I2Cx)
544 SET_BIT(I2Cx->CR2, I2C_CR2_DMAEN);
548 * @brief Disable DMA reception requests.
549 * @rmtoll CR2 DMAEN LL_I2C_DisableDMAReq_RX
550 * @param I2Cx I2C Instance.
551 * @retval None
553 __STATIC_INLINE void LL_I2C_DisableDMAReq_RX(I2C_TypeDef *I2Cx)
555 CLEAR_BIT(I2Cx->CR2, I2C_CR2_DMAEN);
559 * @brief Check if DMA reception requests are enabled or disabled.
560 * @rmtoll CR2 DMAEN LL_I2C_IsEnabledDMAReq_RX
561 * @param I2Cx I2C Instance.
562 * @retval State of bit (1 or 0).
564 __STATIC_INLINE uint32_t LL_I2C_IsEnabledDMAReq_RX(I2C_TypeDef *I2Cx)
566 return (READ_BIT(I2Cx->CR2, I2C_CR2_DMAEN) == (I2C_CR2_DMAEN));
570 * @brief Get the data register address used for DMA transfer.
571 * @rmtoll DR DR LL_I2C_DMA_GetRegAddr
572 * @param I2Cx I2C Instance.
573 * @retval Address of data register
575 __STATIC_INLINE uint32_t LL_I2C_DMA_GetRegAddr(I2C_TypeDef *I2Cx)
577 return (uint32_t) & (I2Cx->DR);
581 * @brief Enable Clock stretching.
582 * @note This bit can only be programmed when the I2C is disabled (PE = 0).
583 * @rmtoll CR1 NOSTRETCH LL_I2C_EnableClockStretching
584 * @param I2Cx I2C Instance.
585 * @retval None
587 __STATIC_INLINE void LL_I2C_EnableClockStretching(I2C_TypeDef *I2Cx)
589 CLEAR_BIT(I2Cx->CR1, I2C_CR1_NOSTRETCH);
593 * @brief Disable Clock stretching.
594 * @note This bit can only be programmed when the I2C is disabled (PE = 0).
595 * @rmtoll CR1 NOSTRETCH LL_I2C_DisableClockStretching
596 * @param I2Cx I2C Instance.
597 * @retval None
599 __STATIC_INLINE void LL_I2C_DisableClockStretching(I2C_TypeDef *I2Cx)
601 SET_BIT(I2Cx->CR1, I2C_CR1_NOSTRETCH);
605 * @brief Check if Clock stretching is enabled or disabled.
606 * @rmtoll CR1 NOSTRETCH LL_I2C_IsEnabledClockStretching
607 * @param I2Cx I2C Instance.
608 * @retval State of bit (1 or 0).
610 __STATIC_INLINE uint32_t LL_I2C_IsEnabledClockStretching(I2C_TypeDef *I2Cx)
612 return (READ_BIT(I2Cx->CR1, I2C_CR1_NOSTRETCH) != (I2C_CR1_NOSTRETCH));
616 * @brief Enable General Call.
617 * @note When enabled the Address 0x00 is ACKed.
618 * @rmtoll CR1 ENGC LL_I2C_EnableGeneralCall
619 * @param I2Cx I2C Instance.
620 * @retval None
622 __STATIC_INLINE void LL_I2C_EnableGeneralCall(I2C_TypeDef *I2Cx)
624 SET_BIT(I2Cx->CR1, I2C_CR1_ENGC);
628 * @brief Disable General Call.
629 * @note When disabled the Address 0x00 is NACKed.
630 * @rmtoll CR1 ENGC LL_I2C_DisableGeneralCall
631 * @param I2Cx I2C Instance.
632 * @retval None
634 __STATIC_INLINE void LL_I2C_DisableGeneralCall(I2C_TypeDef *I2Cx)
636 CLEAR_BIT(I2Cx->CR1, I2C_CR1_ENGC);
640 * @brief Check if General Call is enabled or disabled.
641 * @rmtoll CR1 ENGC LL_I2C_IsEnabledGeneralCall
642 * @param I2Cx I2C Instance.
643 * @retval State of bit (1 or 0).
645 __STATIC_INLINE uint32_t LL_I2C_IsEnabledGeneralCall(I2C_TypeDef *I2Cx)
647 return (READ_BIT(I2Cx->CR1, I2C_CR1_ENGC) == (I2C_CR1_ENGC));
651 * @brief Set the Own Address1.
652 * @rmtoll OAR1 ADD0 LL_I2C_SetOwnAddress1\n
653 * OAR1 ADD1_7 LL_I2C_SetOwnAddress1\n
654 * OAR1 ADD8_9 LL_I2C_SetOwnAddress1\n
655 * OAR1 ADDMODE LL_I2C_SetOwnAddress1
656 * @param I2Cx I2C Instance.
657 * @param OwnAddress1 This parameter must be a value between Min_Data=0 and Max_Data=0x3FF.
658 * @param OwnAddrSize This parameter can be one of the following values:
659 * @arg @ref LL_I2C_OWNADDRESS1_7BIT
660 * @arg @ref LL_I2C_OWNADDRESS1_10BIT
661 * @retval None
663 __STATIC_INLINE void LL_I2C_SetOwnAddress1(I2C_TypeDef *I2Cx, uint32_t OwnAddress1, uint32_t OwnAddrSize)
665 MODIFY_REG(I2Cx->OAR1, I2C_OAR1_ADD0 | I2C_OAR1_ADD1_7 | I2C_OAR1_ADD8_9 | I2C_OAR1_ADDMODE, OwnAddress1 | OwnAddrSize);
669 * @brief Set the 7bits Own Address2.
670 * @note This action has no effect if own address2 is enabled.
671 * @rmtoll OAR2 ADD2 LL_I2C_SetOwnAddress2
672 * @param I2Cx I2C Instance.
673 * @param OwnAddress2 This parameter must be a value between Min_Data=0 and Max_Data=0x7F.
674 * @retval None
676 __STATIC_INLINE void LL_I2C_SetOwnAddress2(I2C_TypeDef *I2Cx, uint32_t OwnAddress2)
678 MODIFY_REG(I2Cx->OAR2, I2C_OAR2_ADD2, OwnAddress2);
682 * @brief Enable acknowledge on Own Address2 match address.
683 * @rmtoll OAR2 ENDUAL LL_I2C_EnableOwnAddress2
684 * @param I2Cx I2C Instance.
685 * @retval None
687 __STATIC_INLINE void LL_I2C_EnableOwnAddress2(I2C_TypeDef *I2Cx)
689 SET_BIT(I2Cx->OAR2, I2C_OAR2_ENDUAL);
693 * @brief Disable acknowledge on Own Address2 match address.
694 * @rmtoll OAR2 ENDUAL LL_I2C_DisableOwnAddress2
695 * @param I2Cx I2C Instance.
696 * @retval None
698 __STATIC_INLINE void LL_I2C_DisableOwnAddress2(I2C_TypeDef *I2Cx)
700 CLEAR_BIT(I2Cx->OAR2, I2C_OAR2_ENDUAL);
704 * @brief Check if Own Address1 acknowledge is enabled or disabled.
705 * @rmtoll OAR2 ENDUAL LL_I2C_IsEnabledOwnAddress2
706 * @param I2Cx I2C Instance.
707 * @retval State of bit (1 or 0).
709 __STATIC_INLINE uint32_t LL_I2C_IsEnabledOwnAddress2(I2C_TypeDef *I2Cx)
711 return (READ_BIT(I2Cx->OAR2, I2C_OAR2_ENDUAL) == (I2C_OAR2_ENDUAL));
715 * @brief Configure the Peripheral clock frequency.
716 * @rmtoll CR2 FREQ LL_I2C_SetPeriphClock
717 * @param I2Cx I2C Instance.
718 * @param PeriphClock Peripheral Clock (in Hz)
719 * @retval None
721 __STATIC_INLINE void LL_I2C_SetPeriphClock(I2C_TypeDef *I2Cx, uint32_t PeriphClock)
723 MODIFY_REG(I2Cx->CR2, I2C_CR2_FREQ, __LL_I2C_FREQ_HZ_TO_MHZ(PeriphClock));
727 * @brief Get the Peripheral clock frequency.
728 * @rmtoll CR2 FREQ LL_I2C_GetPeriphClock
729 * @param I2Cx I2C Instance.
730 * @retval Value of Peripheral Clock (in Hz)
732 __STATIC_INLINE uint32_t LL_I2C_GetPeriphClock(I2C_TypeDef *I2Cx)
734 return (uint32_t)(__LL_I2C_FREQ_MHZ_TO_HZ(READ_BIT(I2Cx->CR2, I2C_CR2_FREQ)));
738 * @brief Configure the Duty cycle (Fast mode only).
739 * @rmtoll CCR DUTY LL_I2C_SetDutyCycle
740 * @param I2Cx I2C Instance.
741 * @param DutyCycle This parameter can be one of the following values:
742 * @arg @ref LL_I2C_DUTYCYCLE_2
743 * @arg @ref LL_I2C_DUTYCYCLE_16_9
744 * @retval None
746 __STATIC_INLINE void LL_I2C_SetDutyCycle(I2C_TypeDef *I2Cx, uint32_t DutyCycle)
748 MODIFY_REG(I2Cx->CCR, I2C_CCR_DUTY, DutyCycle);
752 * @brief Get the Duty cycle (Fast mode only).
753 * @rmtoll CCR DUTY LL_I2C_GetDutyCycle
754 * @param I2Cx I2C Instance.
755 * @retval Returned value can be one of the following values:
756 * @arg @ref LL_I2C_DUTYCYCLE_2
757 * @arg @ref LL_I2C_DUTYCYCLE_16_9
759 __STATIC_INLINE uint32_t LL_I2C_GetDutyCycle(I2C_TypeDef *I2Cx)
761 return (uint32_t)(READ_BIT(I2Cx->CCR, I2C_CCR_DUTY));
765 * @brief Configure the I2C master clock speed mode.
766 * @rmtoll CCR FS LL_I2C_SetClockSpeedMode
767 * @param I2Cx I2C Instance.
768 * @param ClockSpeedMode This parameter can be one of the following values:
769 * @arg @ref LL_I2C_CLOCK_SPEED_STANDARD_MODE
770 * @arg @ref LL_I2C_CLOCK_SPEED_FAST_MODE
771 * @retval None
773 __STATIC_INLINE void LL_I2C_SetClockSpeedMode(I2C_TypeDef *I2Cx, uint32_t ClockSpeedMode)
775 MODIFY_REG(I2Cx->CCR, I2C_CCR_FS, ClockSpeedMode);
779 * @brief Get the the I2C master speed mode.
780 * @rmtoll CCR FS LL_I2C_GetClockSpeedMode
781 * @param I2Cx I2C Instance.
782 * @retval Returned value can be one of the following values:
783 * @arg @ref LL_I2C_CLOCK_SPEED_STANDARD_MODE
784 * @arg @ref LL_I2C_CLOCK_SPEED_FAST_MODE
786 __STATIC_INLINE uint32_t LL_I2C_GetClockSpeedMode(I2C_TypeDef *I2Cx)
788 return (uint32_t)(READ_BIT(I2Cx->CCR, I2C_CCR_FS));
792 * @brief Configure the SCL, SDA rising time.
793 * @note This bit can only be programmed when the I2C is disabled (PE = 0).
794 * @rmtoll TRISE TRISE LL_I2C_SetRiseTime
795 * @param I2Cx I2C Instance.
796 * @param RiseTime This parameter must be a value between Min_Data=0x02 and Max_Data=0x3F.
797 * @retval None
799 __STATIC_INLINE void LL_I2C_SetRiseTime(I2C_TypeDef *I2Cx, uint32_t RiseTime)
801 MODIFY_REG(I2Cx->TRISE, I2C_TRISE_TRISE, RiseTime);
805 * @brief Get the SCL, SDA rising time.
806 * @rmtoll TRISE TRISE LL_I2C_GetRiseTime
807 * @param I2Cx I2C Instance.
808 * @retval Value between Min_Data=0x02 and Max_Data=0x3F
810 __STATIC_INLINE uint32_t LL_I2C_GetRiseTime(I2C_TypeDef *I2Cx)
812 return (uint32_t)(READ_BIT(I2Cx->TRISE, I2C_TRISE_TRISE));
816 * @brief Configure the SCL high and low period.
817 * @note This bit can only be programmed when the I2C is disabled (PE = 0).
818 * @rmtoll CCR CCR LL_I2C_SetClockPeriod
819 * @param I2Cx I2C Instance.
820 * @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.
821 * @retval None
823 __STATIC_INLINE void LL_I2C_SetClockPeriod(I2C_TypeDef *I2Cx, uint32_t ClockPeriod)
825 MODIFY_REG(I2Cx->CCR, I2C_CCR_CCR, ClockPeriod);
829 * @brief Get the SCL high and low period.
830 * @rmtoll CCR CCR LL_I2C_GetClockPeriod
831 * @param I2Cx I2C Instance.
832 * @retval Value between Min_Data=0x004 and Max_Data=0xFFF, except in FAST DUTY mode where Min_Data=0x001.
834 __STATIC_INLINE uint32_t LL_I2C_GetClockPeriod(I2C_TypeDef *I2Cx)
836 return (uint32_t)(READ_BIT(I2Cx->CCR, I2C_CCR_CCR));
840 * @brief Configure the SCL speed.
841 * @note This bit can only be programmed when the I2C is disabled (PE = 0).
842 * @rmtoll CR2 FREQ LL_I2C_ConfigSpeed\n
843 * TRISE TRISE LL_I2C_ConfigSpeed\n
844 * CCR FS LL_I2C_ConfigSpeed\n
845 * CCR DUTY LL_I2C_ConfigSpeed\n
846 * CCR CCR LL_I2C_ConfigSpeed
847 * @param I2Cx I2C Instance.
848 * @param PeriphClock Peripheral Clock (in Hz)
849 * @param ClockSpeed This parameter must be a value lower than 400kHz (in Hz).
850 * @param DutyCycle This parameter can be one of the following values:
851 * @arg @ref LL_I2C_DUTYCYCLE_2
852 * @arg @ref LL_I2C_DUTYCYCLE_16_9
853 * @retval None
855 __STATIC_INLINE void LL_I2C_ConfigSpeed(I2C_TypeDef *I2Cx, uint32_t PeriphClock, uint32_t ClockSpeed,
856 uint32_t DutyCycle)
858 register uint32_t freqrange = 0x0U;
859 register uint32_t clockconfig = 0x0U;
861 /* Compute frequency range */
862 freqrange = __LL_I2C_FREQ_HZ_TO_MHZ(PeriphClock);
864 /* Configure I2Cx: Frequency range register */
865 MODIFY_REG(I2Cx->CR2, I2C_CR2_FREQ, freqrange);
867 /* Configure I2Cx: Rise Time register */
868 MODIFY_REG(I2Cx->TRISE, I2C_TRISE_TRISE, __LL_I2C_RISE_TIME(freqrange, ClockSpeed));
870 /* Configure Speed mode, Duty Cycle and Clock control register value */
871 if (ClockSpeed > LL_I2C_MAX_SPEED_STANDARD)
873 /* Set Speed mode at fast and duty cycle for Clock Speed request in fast clock range */
874 clockconfig = LL_I2C_CLOCK_SPEED_FAST_MODE | \
875 __LL_I2C_SPEED_FAST_TO_CCR(PeriphClock, ClockSpeed, DutyCycle) | \
876 DutyCycle;
878 else
880 /* Set Speed mode at standard for Clock Speed request in standard clock range */
881 clockconfig = LL_I2C_CLOCK_SPEED_STANDARD_MODE | \
882 __LL_I2C_SPEED_STANDARD_TO_CCR(PeriphClock, ClockSpeed);
885 /* Configure I2Cx: Clock control register */
886 MODIFY_REG(I2Cx->CCR, (I2C_CCR_FS | I2C_CCR_DUTY | I2C_CCR_CCR), clockconfig);
890 * @brief Configure peripheral mode.
891 * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not
892 * SMBus feature is supported by the I2Cx Instance.
893 * @rmtoll CR1 SMBUS LL_I2C_SetMode\n
894 * CR1 SMBTYPE LL_I2C_SetMode\n
895 * CR1 ENARP LL_I2C_SetMode
896 * @param I2Cx I2C Instance.
897 * @param PeripheralMode This parameter can be one of the following values:
898 * @arg @ref LL_I2C_MODE_I2C
899 * @arg @ref LL_I2C_MODE_SMBUS_HOST
900 * @arg @ref LL_I2C_MODE_SMBUS_DEVICE
901 * @arg @ref LL_I2C_MODE_SMBUS_DEVICE_ARP
902 * @retval None
904 __STATIC_INLINE void LL_I2C_SetMode(I2C_TypeDef *I2Cx, uint32_t PeripheralMode)
906 MODIFY_REG(I2Cx->CR1, I2C_CR1_SMBUS | I2C_CR1_SMBTYPE | I2C_CR1_ENARP, PeripheralMode);
910 * @brief Get peripheral mode.
911 * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not
912 * SMBus feature is supported by the I2Cx Instance.
913 * @rmtoll CR1 SMBUS LL_I2C_GetMode\n
914 * CR1 SMBTYPE LL_I2C_GetMode\n
915 * CR1 ENARP LL_I2C_GetMode
916 * @param I2Cx I2C Instance.
917 * @retval Returned value can be one of the following values:
918 * @arg @ref LL_I2C_MODE_I2C
919 * @arg @ref LL_I2C_MODE_SMBUS_HOST
920 * @arg @ref LL_I2C_MODE_SMBUS_DEVICE
921 * @arg @ref LL_I2C_MODE_SMBUS_DEVICE_ARP
923 __STATIC_INLINE uint32_t LL_I2C_GetMode(I2C_TypeDef *I2Cx)
925 return (uint32_t)(READ_BIT(I2Cx->CR1, I2C_CR1_SMBUS | I2C_CR1_SMBTYPE | I2C_CR1_ENARP));
929 * @brief Enable SMBus alert (Host or Device mode)
930 * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not
931 * SMBus feature is supported by the I2Cx Instance.
932 * @note SMBus Device mode:
933 * - SMBus Alert pin is drived low and
934 * Alert Response Address Header acknowledge is enabled.
935 * SMBus Host mode:
936 * - SMBus Alert pin management is supported.
937 * @rmtoll CR1 ALERT LL_I2C_EnableSMBusAlert
938 * @param I2Cx I2C Instance.
939 * @retval None
941 __STATIC_INLINE void LL_I2C_EnableSMBusAlert(I2C_TypeDef *I2Cx)
943 SET_BIT(I2Cx->CR1, I2C_CR1_ALERT);
947 * @brief Disable SMBus alert (Host or Device mode)
948 * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not
949 * SMBus feature is supported by the I2Cx Instance.
950 * @note SMBus Device mode:
951 * - SMBus Alert pin is not drived (can be used as a standard GPIO) and
952 * Alert Response Address Header acknowledge is disabled.
953 * SMBus Host mode:
954 * - SMBus Alert pin management is not supported.
955 * @rmtoll CR1 ALERT LL_I2C_DisableSMBusAlert
956 * @param I2Cx I2C Instance.
957 * @retval None
959 __STATIC_INLINE void LL_I2C_DisableSMBusAlert(I2C_TypeDef *I2Cx)
961 CLEAR_BIT(I2Cx->CR1, I2C_CR1_ALERT);
965 * @brief Check if SMBus alert (Host or Device mode) is enabled or disabled.
966 * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not
967 * SMBus feature is supported by the I2Cx Instance.
968 * @rmtoll CR1 ALERT LL_I2C_IsEnabledSMBusAlert
969 * @param I2Cx I2C Instance.
970 * @retval State of bit (1 or 0).
972 __STATIC_INLINE uint32_t LL_I2C_IsEnabledSMBusAlert(I2C_TypeDef *I2Cx)
974 return (READ_BIT(I2Cx->CR1, I2C_CR1_ALERT) == (I2C_CR1_ALERT));
978 * @brief Enable SMBus Packet Error Calculation (PEC).
979 * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not
980 * SMBus feature is supported by the I2Cx Instance.
981 * @rmtoll CR1 ENPEC LL_I2C_EnableSMBusPEC
982 * @param I2Cx I2C Instance.
983 * @retval None
985 __STATIC_INLINE void LL_I2C_EnableSMBusPEC(I2C_TypeDef *I2Cx)
987 SET_BIT(I2Cx->CR1, I2C_CR1_ENPEC);
991 * @brief Disable SMBus Packet Error Calculation (PEC).
992 * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not
993 * SMBus feature is supported by the I2Cx Instance.
994 * @rmtoll CR1 ENPEC LL_I2C_DisableSMBusPEC
995 * @param I2Cx I2C Instance.
996 * @retval None
998 __STATIC_INLINE void LL_I2C_DisableSMBusPEC(I2C_TypeDef *I2Cx)
1000 CLEAR_BIT(I2Cx->CR1, I2C_CR1_ENPEC);
1004 * @brief Check if SMBus Packet Error Calculation (PEC) is enabled or disabled.
1005 * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not
1006 * SMBus feature is supported by the I2Cx Instance.
1007 * @rmtoll CR1 ENPEC LL_I2C_IsEnabledSMBusPEC
1008 * @param I2Cx I2C Instance.
1009 * @retval State of bit (1 or 0).
1011 __STATIC_INLINE uint32_t LL_I2C_IsEnabledSMBusPEC(I2C_TypeDef *I2Cx)
1013 return (READ_BIT(I2Cx->CR1, I2C_CR1_ENPEC) == (I2C_CR1_ENPEC));
1017 * @}
1020 /** @defgroup I2C_LL_EF_IT_Management IT_Management
1021 * @{
1025 * @brief Enable TXE interrupt.
1026 * @rmtoll CR2 ITEVTEN LL_I2C_EnableIT_TX\n
1027 * CR2 ITBUFEN LL_I2C_EnableIT_TX
1028 * @param I2Cx I2C Instance.
1029 * @retval None
1031 __STATIC_INLINE void LL_I2C_EnableIT_TX(I2C_TypeDef *I2Cx)
1033 SET_BIT(I2Cx->CR2, I2C_CR2_ITEVTEN | I2C_CR2_ITBUFEN);
1037 * @brief Disable TXE interrupt.
1038 * @rmtoll CR2 ITEVTEN LL_I2C_DisableIT_TX\n
1039 * CR2 ITBUFEN LL_I2C_DisableIT_TX
1040 * @param I2Cx I2C Instance.
1041 * @retval None
1043 __STATIC_INLINE void LL_I2C_DisableIT_TX(I2C_TypeDef *I2Cx)
1045 CLEAR_BIT(I2Cx->CR2, I2C_CR2_ITEVTEN | I2C_CR2_ITBUFEN);
1049 * @brief Check if the TXE Interrupt is enabled or disabled.
1050 * @rmtoll CR2 ITEVTEN LL_I2C_IsEnabledIT_TX\n
1051 * CR2 ITBUFEN LL_I2C_IsEnabledIT_TX
1052 * @param I2Cx I2C Instance.
1053 * @retval State of bit (1 or 0).
1055 __STATIC_INLINE uint32_t LL_I2C_IsEnabledIT_TX(I2C_TypeDef *I2Cx)
1057 return (READ_BIT(I2Cx->CR2, I2C_CR2_ITEVTEN | I2C_CR2_ITBUFEN) == (I2C_CR2_ITEVTEN | I2C_CR2_ITBUFEN));
1061 * @brief Enable RXNE interrupt.
1062 * @rmtoll CR2 ITEVTEN LL_I2C_EnableIT_RX\n
1063 * CR2 ITBUFEN LL_I2C_EnableIT_RX
1064 * @param I2Cx I2C Instance.
1065 * @retval None
1067 __STATIC_INLINE void LL_I2C_EnableIT_RX(I2C_TypeDef *I2Cx)
1069 SET_BIT(I2Cx->CR2, I2C_CR2_ITEVTEN | I2C_CR2_ITBUFEN);
1073 * @brief Disable RXNE interrupt.
1074 * @rmtoll CR2 ITEVTEN LL_I2C_DisableIT_RX\n
1075 * CR2 ITBUFEN LL_I2C_DisableIT_RX
1076 * @param I2Cx I2C Instance.
1077 * @retval None
1079 __STATIC_INLINE void LL_I2C_DisableIT_RX(I2C_TypeDef *I2Cx)
1081 CLEAR_BIT(I2Cx->CR2, I2C_CR2_ITEVTEN | I2C_CR2_ITBUFEN);
1085 * @brief Check if the RXNE Interrupt is enabled or disabled.
1086 * @rmtoll CR2 ITEVTEN LL_I2C_IsEnabledIT_RX\n
1087 * CR2 ITBUFEN LL_I2C_IsEnabledIT_RX
1088 * @param I2Cx I2C Instance.
1089 * @retval State of bit (1 or 0).
1091 __STATIC_INLINE uint32_t LL_I2C_IsEnabledIT_RX(I2C_TypeDef *I2Cx)
1093 return (READ_BIT(I2Cx->CR2, I2C_CR2_ITEVTEN | I2C_CR2_ITBUFEN) == (I2C_CR2_ITEVTEN | I2C_CR2_ITBUFEN));
1097 * @brief Enable Events interrupts.
1098 * @note Any of these events will generate interrupt :
1099 * Start Bit (SB)
1100 * Address sent, Address matched (ADDR)
1101 * 10-bit header sent (ADD10)
1102 * Stop detection (STOPF)
1103 * Byte transfer finished (BTF)
1105 * @note Any of these events will generate interrupt if Buffer interrupts are enabled too(using unitary function @ref LL_I2C_EnableIT_BUF()) :
1106 * Receive buffer not empty (RXNE)
1107 * Transmit buffer empty (TXE)
1108 * @rmtoll CR2 ITEVTEN LL_I2C_EnableIT_EVT
1109 * @param I2Cx I2C Instance.
1110 * @retval None
1112 __STATIC_INLINE void LL_I2C_EnableIT_EVT(I2C_TypeDef *I2Cx)
1114 SET_BIT(I2Cx->CR2, I2C_CR2_ITEVTEN);
1118 * @brief Disable Events interrupts.
1119 * @note Any of these events will generate interrupt :
1120 * Start Bit (SB)
1121 * Address sent, Address matched (ADDR)
1122 * 10-bit header sent (ADD10)
1123 * Stop detection (STOPF)
1124 * Byte transfer finished (BTF)
1125 * Receive buffer not empty (RXNE)
1126 * Transmit buffer empty (TXE)
1127 * @rmtoll CR2 ITEVTEN LL_I2C_DisableIT_EVT
1128 * @param I2Cx I2C Instance.
1129 * @retval None
1131 __STATIC_INLINE void LL_I2C_DisableIT_EVT(I2C_TypeDef *I2Cx)
1133 CLEAR_BIT(I2Cx->CR2, I2C_CR2_ITEVTEN);
1137 * @brief Check if Events interrupts are enabled or disabled.
1138 * @rmtoll CR2 ITEVTEN LL_I2C_IsEnabledIT_EVT
1139 * @param I2Cx I2C Instance.
1140 * @retval State of bit (1 or 0).
1142 __STATIC_INLINE uint32_t LL_I2C_IsEnabledIT_EVT(I2C_TypeDef *I2Cx)
1144 return (READ_BIT(I2Cx->CR2, I2C_CR2_ITEVTEN) == (I2C_CR2_ITEVTEN));
1148 * @brief Enable Buffer interrupts.
1149 * @note Any of these Buffer events will generate interrupt if Events interrupts are enabled too(using unitary function @ref LL_I2C_EnableIT_EVT()) :
1150 * Receive buffer not empty (RXNE)
1151 * Transmit buffer empty (TXE)
1152 * @rmtoll CR2 ITBUFEN LL_I2C_EnableIT_BUF
1153 * @param I2Cx I2C Instance.
1154 * @retval None
1156 __STATIC_INLINE void LL_I2C_EnableIT_BUF(I2C_TypeDef *I2Cx)
1158 SET_BIT(I2Cx->CR2, I2C_CR2_ITBUFEN);
1162 * @brief Disable Buffer interrupts.
1163 * @note Any of these Buffer events will generate interrupt :
1164 * Receive buffer not empty (RXNE)
1165 * Transmit buffer empty (TXE)
1166 * @rmtoll CR2 ITBUFEN LL_I2C_DisableIT_BUF
1167 * @param I2Cx I2C Instance.
1168 * @retval None
1170 __STATIC_INLINE void LL_I2C_DisableIT_BUF(I2C_TypeDef *I2Cx)
1172 CLEAR_BIT(I2Cx->CR2, I2C_CR2_ITBUFEN);
1176 * @brief Check if Buffer interrupts are enabled or disabled.
1177 * @rmtoll CR2 ITBUFEN LL_I2C_IsEnabledIT_BUF
1178 * @param I2Cx I2C Instance.
1179 * @retval State of bit (1 or 0).
1181 __STATIC_INLINE uint32_t LL_I2C_IsEnabledIT_BUF(I2C_TypeDef *I2Cx)
1183 return (READ_BIT(I2Cx->CR2, I2C_CR2_ITBUFEN) == (I2C_CR2_ITBUFEN));
1187 * @brief Enable Error interrupts.
1188 * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not
1189 * SMBus feature is supported by the I2Cx Instance.
1190 * @note Any of these errors will generate interrupt :
1191 * Bus Error detection (BERR)
1192 * Arbitration Loss (ARLO)
1193 * Acknowledge Failure(AF)
1194 * Overrun/Underrun (OVR)
1195 * SMBus Timeout detection (TIMEOUT)
1196 * SMBus PEC error detection (PECERR)
1197 * SMBus Alert pin event detection (SMBALERT)
1198 * @rmtoll CR2 ITERREN LL_I2C_EnableIT_ERR
1199 * @param I2Cx I2C Instance.
1200 * @retval None
1202 __STATIC_INLINE void LL_I2C_EnableIT_ERR(I2C_TypeDef *I2Cx)
1204 SET_BIT(I2Cx->CR2, I2C_CR2_ITERREN);
1208 * @brief Disable Error interrupts.
1209 * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not
1210 * SMBus feature is supported by the I2Cx Instance.
1211 * @note Any of these errors will generate interrupt :
1212 * Bus Error detection (BERR)
1213 * Arbitration Loss (ARLO)
1214 * Acknowledge Failure(AF)
1215 * Overrun/Underrun (OVR)
1216 * SMBus Timeout detection (TIMEOUT)
1217 * SMBus PEC error detection (PECERR)
1218 * SMBus Alert pin event detection (SMBALERT)
1219 * @rmtoll CR2 ITERREN LL_I2C_DisableIT_ERR
1220 * @param I2Cx I2C Instance.
1221 * @retval None
1223 __STATIC_INLINE void LL_I2C_DisableIT_ERR(I2C_TypeDef *I2Cx)
1225 CLEAR_BIT(I2Cx->CR2, I2C_CR2_ITERREN);
1229 * @brief Check if Error interrupts are enabled or disabled.
1230 * @rmtoll CR2 ITERREN LL_I2C_IsEnabledIT_ERR
1231 * @param I2Cx I2C Instance.
1232 * @retval State of bit (1 or 0).
1234 __STATIC_INLINE uint32_t LL_I2C_IsEnabledIT_ERR(I2C_TypeDef *I2Cx)
1236 return (READ_BIT(I2Cx->CR2, I2C_CR2_ITERREN) == (I2C_CR2_ITERREN));
1240 * @}
1243 /** @defgroup I2C_LL_EF_FLAG_management FLAG_management
1244 * @{
1248 * @brief Indicate the status of Transmit data register empty flag.
1249 * @note RESET: When next data is written in Transmit data register.
1250 * SET: When Transmit data register is empty.
1251 * @rmtoll SR1 TXE LL_I2C_IsActiveFlag_TXE
1252 * @param I2Cx I2C Instance.
1253 * @retval State of bit (1 or 0).
1255 __STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_TXE(I2C_TypeDef *I2Cx)
1257 return (READ_BIT(I2Cx->SR1, I2C_SR1_TXE) == (I2C_SR1_TXE));
1261 * @brief Indicate the status of Byte Transfer Finished flag.
1262 * RESET: When Data byte transfer not done.
1263 * SET: When Data byte transfer succeeded.
1264 * @rmtoll SR1 BTF LL_I2C_IsActiveFlag_BTF
1265 * @param I2Cx I2C Instance.
1266 * @retval State of bit (1 or 0).
1268 __STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_BTF(I2C_TypeDef *I2Cx)
1270 return (READ_BIT(I2Cx->SR1, I2C_SR1_BTF) == (I2C_SR1_BTF));
1274 * @brief Indicate the status of Receive data register not empty flag.
1275 * @note RESET: When Receive data register is read.
1276 * SET: When the received data is copied in Receive data register.
1277 * @rmtoll SR1 RXNE LL_I2C_IsActiveFlag_RXNE
1278 * @param I2Cx I2C Instance.
1279 * @retval State of bit (1 or 0).
1281 __STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_RXNE(I2C_TypeDef *I2Cx)
1283 return (READ_BIT(I2Cx->SR1, I2C_SR1_RXNE) == (I2C_SR1_RXNE));
1287 * @brief Indicate the status of Start Bit (master mode).
1288 * @note RESET: When No Start condition.
1289 * SET: When Start condition is generated.
1290 * @rmtoll SR1 SB LL_I2C_IsActiveFlag_SB
1291 * @param I2Cx I2C Instance.
1292 * @retval State of bit (1 or 0).
1294 __STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_SB(I2C_TypeDef *I2Cx)
1296 return (READ_BIT(I2Cx->SR1, I2C_SR1_SB) == (I2C_SR1_SB));
1300 * @brief Indicate the status of Address sent (master mode) or Address matched flag (slave mode).
1301 * @note RESET: Clear default value.
1302 * 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).
1303 * @rmtoll SR1 ADDR LL_I2C_IsActiveFlag_ADDR
1304 * @param I2Cx I2C Instance.
1305 * @retval State of bit (1 or 0).
1307 __STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_ADDR(I2C_TypeDef *I2Cx)
1309 return (READ_BIT(I2Cx->SR1, I2C_SR1_ADDR) == (I2C_SR1_ADDR));
1313 * @brief Indicate the status of 10-bit header sent (master mode).
1314 * @note RESET: When no ADD10 event occured.
1315 * SET: When the master has sent the first address byte (header).
1316 * @rmtoll SR1 ADD10 LL_I2C_IsActiveFlag_ADD10
1317 * @param I2Cx I2C Instance.
1318 * @retval State of bit (1 or 0).
1320 __STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_ADD10(I2C_TypeDef *I2Cx)
1322 return (READ_BIT(I2Cx->SR1, I2C_SR1_ADD10) == (I2C_SR1_ADD10));
1326 * @brief Indicate the status of Acknowledge failure flag.
1327 * @note RESET: No acknowledge failure.
1328 * SET: When an acknowledge failure is received after a byte transmission.
1329 * @rmtoll SR1 AF LL_I2C_IsActiveFlag_AF
1330 * @param I2Cx I2C Instance.
1331 * @retval State of bit (1 or 0).
1333 __STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_AF(I2C_TypeDef *I2Cx)
1335 return (READ_BIT(I2Cx->SR1, I2C_SR1_AF) == (I2C_SR1_AF));
1339 * @brief Indicate the status of Stop detection flag (slave mode).
1340 * @note RESET: Clear default value.
1341 * SET: When a Stop condition is detected.
1342 * @rmtoll SR1 STOPF LL_I2C_IsActiveFlag_STOP
1343 * @param I2Cx I2C Instance.
1344 * @retval State of bit (1 or 0).
1346 __STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_STOP(I2C_TypeDef *I2Cx)
1348 return (READ_BIT(I2Cx->SR1, I2C_SR1_STOPF) == (I2C_SR1_STOPF));
1352 * @brief Indicate the status of Bus error flag.
1353 * @note RESET: Clear default value.
1354 * SET: When a misplaced Start or Stop condition is detected.
1355 * @rmtoll SR1 BERR LL_I2C_IsActiveFlag_BERR
1356 * @param I2Cx I2C Instance.
1357 * @retval State of bit (1 or 0).
1359 __STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_BERR(I2C_TypeDef *I2Cx)
1361 return (READ_BIT(I2Cx->SR1, I2C_SR1_BERR) == (I2C_SR1_BERR));
1365 * @brief Indicate the status of Arbitration lost flag.
1366 * @note RESET: Clear default value.
1367 * SET: When arbitration lost.
1368 * @rmtoll SR1 ARLO LL_I2C_IsActiveFlag_ARLO
1369 * @param I2Cx I2C Instance.
1370 * @retval State of bit (1 or 0).
1372 __STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_ARLO(I2C_TypeDef *I2Cx)
1374 return (READ_BIT(I2Cx->SR1, I2C_SR1_ARLO) == (I2C_SR1_ARLO));
1378 * @brief Indicate the status of Overrun/Underrun flag.
1379 * @note RESET: Clear default value.
1380 * SET: When an overrun/underrun error occurs (Clock Stretching Disabled).
1381 * @rmtoll SR1 OVR LL_I2C_IsActiveFlag_OVR
1382 * @param I2Cx I2C Instance.
1383 * @retval State of bit (1 or 0).
1385 __STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_OVR(I2C_TypeDef *I2Cx)
1387 return (READ_BIT(I2Cx->SR1, I2C_SR1_OVR) == (I2C_SR1_OVR));
1391 * @brief Indicate the status of SMBus PEC error flag in reception.
1392 * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not
1393 * SMBus feature is supported by the I2Cx Instance.
1394 * @rmtoll SR1 PECERR LL_I2C_IsActiveSMBusFlag_PECERR
1395 * @param I2Cx I2C Instance.
1396 * @retval State of bit (1 or 0).
1398 __STATIC_INLINE uint32_t LL_I2C_IsActiveSMBusFlag_PECERR(I2C_TypeDef *I2Cx)
1400 return (READ_BIT(I2Cx->SR1, I2C_SR1_PECERR) == (I2C_SR1_PECERR));
1404 * @brief Indicate the status of SMBus Timeout detection flag.
1405 * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not
1406 * SMBus feature is supported by the I2Cx Instance.
1407 * @rmtoll SR1 TIMEOUT LL_I2C_IsActiveSMBusFlag_TIMEOUT
1408 * @param I2Cx I2C Instance.
1409 * @retval State of bit (1 or 0).
1411 __STATIC_INLINE uint32_t LL_I2C_IsActiveSMBusFlag_TIMEOUT(I2C_TypeDef *I2Cx)
1413 return (READ_BIT(I2Cx->SR1, I2C_SR1_TIMEOUT) == (I2C_SR1_TIMEOUT));
1417 * @brief Indicate the status of SMBus alert flag.
1418 * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not
1419 * SMBus feature is supported by the I2Cx Instance.
1420 * @rmtoll SR1 SMBALERT LL_I2C_IsActiveSMBusFlag_ALERT
1421 * @param I2Cx I2C Instance.
1422 * @retval State of bit (1 or 0).
1424 __STATIC_INLINE uint32_t LL_I2C_IsActiveSMBusFlag_ALERT(I2C_TypeDef *I2Cx)
1426 return (READ_BIT(I2Cx->SR1, I2C_SR1_SMBALERT) == (I2C_SR1_SMBALERT));
1430 * @brief Indicate the status of Bus Busy flag.
1431 * @note RESET: Clear default value.
1432 * SET: When a Start condition is detected.
1433 * @rmtoll SR2 BUSY LL_I2C_IsActiveFlag_BUSY
1434 * @param I2Cx I2C Instance.
1435 * @retval State of bit (1 or 0).
1437 __STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_BUSY(I2C_TypeDef *I2Cx)
1439 return (READ_BIT(I2Cx->SR2, I2C_SR2_BUSY) == (I2C_SR2_BUSY));
1443 * @brief Indicate the status of Dual flag.
1444 * @note RESET: Received address matched with OAR1.
1445 * SET: Received address matched with OAR2.
1446 * @rmtoll SR2 DUALF LL_I2C_IsActiveFlag_DUAL
1447 * @param I2Cx I2C Instance.
1448 * @retval State of bit (1 or 0).
1450 __STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_DUAL(I2C_TypeDef *I2Cx)
1452 return (READ_BIT(I2Cx->SR2, I2C_SR2_DUALF) == (I2C_SR2_DUALF));
1456 * @brief Indicate the status of SMBus Host address reception (Slave mode).
1457 * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not
1458 * SMBus feature is supported by the I2Cx Instance.
1459 * @note RESET: No SMBus Host address
1460 * SET: SMBus Host address received.
1461 * @note This status is cleared by hardware after a STOP condition or repeated START condition.
1462 * @rmtoll SR2 SMBHOST LL_I2C_IsActiveSMBusFlag_SMBHOST
1463 * @param I2Cx I2C Instance.
1464 * @retval State of bit (1 or 0).
1466 __STATIC_INLINE uint32_t LL_I2C_IsActiveSMBusFlag_SMBHOST(I2C_TypeDef *I2Cx)
1468 return (READ_BIT(I2Cx->SR2, I2C_SR2_SMBHOST) == (I2C_SR2_SMBHOST));
1472 * @brief Indicate the status of SMBus Device default address reception (Slave mode).
1473 * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not
1474 * SMBus feature is supported by the I2Cx Instance.
1475 * @note RESET: No SMBus Device default address
1476 * SET: SMBus Device default address received.
1477 * @note This status is cleared by hardware after a STOP condition or repeated START condition.
1478 * @rmtoll SR2 SMBDEFAULT LL_I2C_IsActiveSMBusFlag_SMBDEFAULT
1479 * @param I2Cx I2C Instance.
1480 * @retval State of bit (1 or 0).
1482 __STATIC_INLINE uint32_t LL_I2C_IsActiveSMBusFlag_SMBDEFAULT(I2C_TypeDef *I2Cx)
1484 return (READ_BIT(I2Cx->SR2, I2C_SR2_SMBDEFAULT) == (I2C_SR2_SMBDEFAULT));
1488 * @brief Indicate the status of General call address reception (Slave mode).
1489 * @note RESET: No Generall call address
1490 * SET: General call address received.
1491 * @note This status is cleared by hardware after a STOP condition or repeated START condition.
1492 * @rmtoll SR2 GENCALL LL_I2C_IsActiveFlag_GENCALL
1493 * @param I2Cx I2C Instance.
1494 * @retval State of bit (1 or 0).
1496 __STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_GENCALL(I2C_TypeDef *I2Cx)
1498 return (READ_BIT(I2Cx->SR2, I2C_SR2_GENCALL) == (I2C_SR2_GENCALL));
1502 * @brief Indicate the status of Master/Slave flag.
1503 * @note RESET: Slave Mode.
1504 * SET: Master Mode.
1505 * @rmtoll SR2 MSL LL_I2C_IsActiveFlag_MSL
1506 * @param I2Cx I2C Instance.
1507 * @retval State of bit (1 or 0).
1509 __STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_MSL(I2C_TypeDef *I2Cx)
1511 return (READ_BIT(I2Cx->SR2, I2C_SR2_MSL) == (I2C_SR2_MSL));
1515 * @brief Clear Address Matched flag.
1516 * @note Clearing this flag is done by a read access to the I2Cx_SR1
1517 * register followed by a read access to the I2Cx_SR2 register.
1518 * @rmtoll SR1 ADDR LL_I2C_ClearFlag_ADDR
1519 * @param I2Cx I2C Instance.
1520 * @retval None
1522 __STATIC_INLINE void LL_I2C_ClearFlag_ADDR(I2C_TypeDef *I2Cx)
1524 __IO uint32_t tmpreg;
1525 tmpreg = I2Cx->SR1;
1526 (void) tmpreg;
1527 tmpreg = I2Cx->SR2;
1528 (void) tmpreg;
1532 * @brief Clear Acknowledge failure flag.
1533 * @rmtoll SR1 AF LL_I2C_ClearFlag_AF
1534 * @param I2Cx I2C Instance.
1535 * @retval None
1537 __STATIC_INLINE void LL_I2C_ClearFlag_AF(I2C_TypeDef *I2Cx)
1539 CLEAR_BIT(I2Cx->SR1, I2C_SR1_AF);
1543 * @brief Clear Stop detection flag.
1544 * @note Clearing this flag is done by a read access to the I2Cx_SR1
1545 * register followed by a write access to I2Cx_CR1 register.
1546 * @rmtoll SR1 STOPF LL_I2C_ClearFlag_STOP\n
1547 * CR1 PE LL_I2C_ClearFlag_STOP
1548 * @param I2Cx I2C Instance.
1549 * @retval None
1551 __STATIC_INLINE void LL_I2C_ClearFlag_STOP(I2C_TypeDef *I2Cx)
1553 __IO uint32_t tmpreg;
1554 tmpreg = I2Cx->SR1;
1555 (void) tmpreg;
1556 SET_BIT(I2Cx->CR1, I2C_CR1_PE);
1560 * @brief Clear Bus error flag.
1561 * @rmtoll SR1 BERR LL_I2C_ClearFlag_BERR
1562 * @param I2Cx I2C Instance.
1563 * @retval None
1565 __STATIC_INLINE void LL_I2C_ClearFlag_BERR(I2C_TypeDef *I2Cx)
1567 CLEAR_BIT(I2Cx->SR1, I2C_SR1_BERR);
1571 * @brief Clear Arbitration lost flag.
1572 * @rmtoll SR1 ARLO LL_I2C_ClearFlag_ARLO
1573 * @param I2Cx I2C Instance.
1574 * @retval None
1576 __STATIC_INLINE void LL_I2C_ClearFlag_ARLO(I2C_TypeDef *I2Cx)
1578 CLEAR_BIT(I2Cx->SR1, I2C_SR1_ARLO);
1582 * @brief Clear Overrun/Underrun flag.
1583 * @rmtoll SR1 OVR LL_I2C_ClearFlag_OVR
1584 * @param I2Cx I2C Instance.
1585 * @retval None
1587 __STATIC_INLINE void LL_I2C_ClearFlag_OVR(I2C_TypeDef *I2Cx)
1589 CLEAR_BIT(I2Cx->SR1, I2C_SR1_OVR);
1593 * @brief Clear SMBus PEC error flag.
1594 * @rmtoll SR1 PECERR LL_I2C_ClearSMBusFlag_PECERR
1595 * @param I2Cx I2C Instance.
1596 * @retval None
1598 __STATIC_INLINE void LL_I2C_ClearSMBusFlag_PECERR(I2C_TypeDef *I2Cx)
1600 CLEAR_BIT(I2Cx->SR1, I2C_SR1_PECERR);
1604 * @brief Clear SMBus Timeout detection flag.
1605 * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not
1606 * SMBus feature is supported by the I2Cx Instance.
1607 * @rmtoll SR1 TIMEOUT LL_I2C_ClearSMBusFlag_TIMEOUT
1608 * @param I2Cx I2C Instance.
1609 * @retval None
1611 __STATIC_INLINE void LL_I2C_ClearSMBusFlag_TIMEOUT(I2C_TypeDef *I2Cx)
1613 CLEAR_BIT(I2Cx->SR1, I2C_SR1_TIMEOUT);
1617 * @brief Clear SMBus Alert flag.
1618 * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not
1619 * SMBus feature is supported by the I2Cx Instance.
1620 * @rmtoll SR1 SMBALERT LL_I2C_ClearSMBusFlag_ALERT
1621 * @param I2Cx I2C Instance.
1622 * @retval None
1624 __STATIC_INLINE void LL_I2C_ClearSMBusFlag_ALERT(I2C_TypeDef *I2Cx)
1626 CLEAR_BIT(I2Cx->SR1, I2C_SR1_SMBALERT);
1630 * @}
1633 /** @defgroup I2C_LL_EF_Data_Management Data_Management
1634 * @{
1638 * @brief Enable Reset of I2C peripheral.
1639 * @rmtoll CR1 SWRST LL_I2C_EnableReset
1640 * @param I2Cx I2C Instance.
1641 * @retval None
1643 __STATIC_INLINE void LL_I2C_EnableReset(I2C_TypeDef *I2Cx)
1645 SET_BIT(I2Cx->CR1, I2C_CR1_SWRST);
1649 * @brief Disable Reset of I2C peripheral.
1650 * @rmtoll CR1 SWRST LL_I2C_DisableReset
1651 * @param I2Cx I2C Instance.
1652 * @retval None
1654 __STATIC_INLINE void LL_I2C_DisableReset(I2C_TypeDef *I2Cx)
1656 CLEAR_BIT(I2Cx->CR1, I2C_CR1_SWRST);
1660 * @brief Check if the I2C peripheral is under reset state or not.
1661 * @rmtoll CR1 SWRST LL_I2C_IsResetEnabled
1662 * @param I2Cx I2C Instance.
1663 * @retval State of bit (1 or 0).
1665 __STATIC_INLINE uint32_t LL_I2C_IsResetEnabled(I2C_TypeDef *I2Cx)
1667 return (READ_BIT(I2Cx->CR1, I2C_CR1_SWRST) == (I2C_CR1_SWRST));
1671 * @brief Prepare the generation of a ACKnowledge or Non ACKnowledge condition after the address receive match code or next received byte.
1672 * @note Usage in Slave or Master mode.
1673 * @rmtoll CR1 ACK LL_I2C_AcknowledgeNextData
1674 * @param I2Cx I2C Instance.
1675 * @param TypeAcknowledge This parameter can be one of the following values:
1676 * @arg @ref LL_I2C_ACK
1677 * @arg @ref LL_I2C_NACK
1678 * @retval None
1680 __STATIC_INLINE void LL_I2C_AcknowledgeNextData(I2C_TypeDef *I2Cx, uint32_t TypeAcknowledge)
1682 MODIFY_REG(I2Cx->CR1, I2C_CR1_ACK, TypeAcknowledge);
1686 * @brief Generate a START or RESTART condition
1687 * @note The START bit can be set even if bus is BUSY or I2C is in slave mode.
1688 * This action has no effect when RELOAD is set.
1689 * @rmtoll CR1 START LL_I2C_GenerateStartCondition
1690 * @param I2Cx I2C Instance.
1691 * @retval None
1693 __STATIC_INLINE void LL_I2C_GenerateStartCondition(I2C_TypeDef *I2Cx)
1695 SET_BIT(I2Cx->CR1, I2C_CR1_START);
1699 * @brief Generate a STOP condition after the current byte transfer (master mode).
1700 * @rmtoll CR1 STOP LL_I2C_GenerateStopCondition
1701 * @param I2Cx I2C Instance.
1702 * @retval None
1704 __STATIC_INLINE void LL_I2C_GenerateStopCondition(I2C_TypeDef *I2Cx)
1706 SET_BIT(I2Cx->CR1, I2C_CR1_STOP);
1710 * @brief Enable bit POS (master/host mode).
1711 * @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.
1712 * @rmtoll CR1 POS LL_I2C_EnableBitPOS
1713 * @param I2Cx I2C Instance.
1714 * @retval None
1716 __STATIC_INLINE void LL_I2C_EnableBitPOS(I2C_TypeDef *I2Cx)
1718 SET_BIT(I2Cx->CR1, I2C_CR1_POS);
1722 * @brief Disable bit POS (master/host mode).
1723 * @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.
1724 * @rmtoll CR1 POS LL_I2C_DisableBitPOS
1725 * @param I2Cx I2C Instance.
1726 * @retval None
1728 __STATIC_INLINE void LL_I2C_DisableBitPOS(I2C_TypeDef *I2Cx)
1730 CLEAR_BIT(I2Cx->CR1, I2C_CR1_POS);
1734 * @brief Check if bit POS is enabled or disabled.
1735 * @rmtoll CR1 POS LL_I2C_IsEnabledBitPOS
1736 * @param I2Cx I2C Instance.
1737 * @retval State of bit (1 or 0).
1739 __STATIC_INLINE uint32_t LL_I2C_IsEnabledBitPOS(I2C_TypeDef *I2Cx)
1741 return (READ_BIT(I2Cx->CR1, I2C_CR1_POS) == (I2C_CR1_POS));
1745 * @brief Indicate the value of transfer direction.
1746 * @note RESET: Bus is in read transfer (peripheral point of view).
1747 * SET: Bus is in write transfer (peripheral point of view).
1748 * @rmtoll SR2 TRA LL_I2C_GetTransferDirection
1749 * @param I2Cx I2C Instance.
1750 * @retval Returned value can be one of the following values:
1751 * @arg @ref LL_I2C_DIRECTION_WRITE
1752 * @arg @ref LL_I2C_DIRECTION_READ
1754 __STATIC_INLINE uint32_t LL_I2C_GetTransferDirection(I2C_TypeDef *I2Cx)
1756 return (uint32_t)(READ_BIT(I2Cx->SR2, I2C_SR2_TRA));
1760 * @brief Enable DMA last transfer.
1761 * @note This action mean that next DMA EOT is the last transfer.
1762 * @rmtoll CR2 LAST LL_I2C_EnableLastDMA
1763 * @param I2Cx I2C Instance.
1764 * @retval None
1766 __STATIC_INLINE void LL_I2C_EnableLastDMA(I2C_TypeDef *I2Cx)
1768 SET_BIT(I2Cx->CR2, I2C_CR2_LAST);
1772 * @brief Disable DMA last transfer.
1773 * @note This action mean that next DMA EOT is not the last transfer.
1774 * @rmtoll CR2 LAST LL_I2C_DisableLastDMA
1775 * @param I2Cx I2C Instance.
1776 * @retval None
1778 __STATIC_INLINE void LL_I2C_DisableLastDMA(I2C_TypeDef *I2Cx)
1780 CLEAR_BIT(I2Cx->CR2, I2C_CR2_LAST);
1784 * @brief Check if DMA last transfer is enabled or disabled.
1785 * @rmtoll CR2 LAST LL_I2C_IsEnabledLastDMA
1786 * @param I2Cx I2C Instance.
1787 * @retval State of bit (1 or 0).
1789 __STATIC_INLINE uint32_t LL_I2C_IsEnabledLastDMA(I2C_TypeDef *I2Cx)
1791 return (READ_BIT(I2Cx->CR2, I2C_CR2_LAST) == (I2C_CR2_LAST));
1795 * @brief Enable transfer or internal comparison of the SMBus Packet Error byte (transmission or reception mode).
1796 * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not
1797 * SMBus feature is supported by the I2Cx Instance.
1798 * @note This feature is cleared by hardware when the PEC byte is transferred or compared,
1799 * or by a START or STOP condition, it is also cleared by software.
1800 * @rmtoll CR1 PEC LL_I2C_EnableSMBusPECCompare
1801 * @param I2Cx I2C Instance.
1802 * @retval None
1804 __STATIC_INLINE void LL_I2C_EnableSMBusPECCompare(I2C_TypeDef *I2Cx)
1806 SET_BIT(I2Cx->CR1, I2C_CR1_PEC);
1810 * @brief Disable transfer or internal comparison of the SMBus Packet Error byte (transmission or reception mode).
1811 * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not
1812 * SMBus feature is supported by the I2Cx Instance.
1813 * @rmtoll CR1 PEC LL_I2C_DisableSMBusPECCompare
1814 * @param I2Cx I2C Instance.
1815 * @retval None
1817 __STATIC_INLINE void LL_I2C_DisableSMBusPECCompare(I2C_TypeDef *I2Cx)
1819 CLEAR_BIT(I2Cx->CR1, I2C_CR1_PEC);
1823 * @brief Check if the SMBus Packet Error byte transfer or internal comparison is requested or not.
1824 * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not
1825 * SMBus feature is supported by the I2Cx Instance.
1826 * @rmtoll CR1 PEC LL_I2C_IsEnabledSMBusPECCompare
1827 * @param I2Cx I2C Instance.
1828 * @retval State of bit (1 or 0).
1830 __STATIC_INLINE uint32_t LL_I2C_IsEnabledSMBusPECCompare(I2C_TypeDef *I2Cx)
1832 return (READ_BIT(I2Cx->CR1, I2C_CR1_PEC) == (I2C_CR1_PEC));
1836 * @brief Get the SMBus Packet Error byte calculated.
1837 * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not
1838 * SMBus feature is supported by the I2Cx Instance.
1839 * @rmtoll SR2 PEC LL_I2C_GetSMBusPEC
1840 * @param I2Cx I2C Instance.
1841 * @retval Value between Min_Data=0x00 and Max_Data=0xFF
1843 __STATIC_INLINE uint32_t LL_I2C_GetSMBusPEC(I2C_TypeDef *I2Cx)
1845 return (uint32_t)(READ_BIT(I2Cx->SR2, I2C_SR2_PEC) >> I2C_SR2_PEC_Pos);
1849 * @brief Read Receive Data register.
1850 * @rmtoll DR DR LL_I2C_ReceiveData8
1851 * @param I2Cx I2C Instance.
1852 * @retval Value between Min_Data=0x0 and Max_Data=0xFF
1854 __STATIC_INLINE uint8_t LL_I2C_ReceiveData8(I2C_TypeDef *I2Cx)
1856 return (uint8_t)(READ_BIT(I2Cx->DR, I2C_DR_DR));
1860 * @brief Write in Transmit Data Register .
1861 * @rmtoll DR DR LL_I2C_TransmitData8
1862 * @param I2Cx I2C Instance.
1863 * @param Data Value between Min_Data=0x0 and Max_Data=0xFF
1864 * @retval None
1866 __STATIC_INLINE void LL_I2C_TransmitData8(I2C_TypeDef *I2Cx, uint8_t Data)
1868 MODIFY_REG(I2Cx->DR, I2C_DR_DR, Data);
1872 * @}
1875 #if defined(USE_FULL_LL_DRIVER)
1876 /** @defgroup I2C_LL_EF_Init Initialization and de-initialization functions
1877 * @{
1880 uint32_t LL_I2C_Init(I2C_TypeDef *I2Cx, LL_I2C_InitTypeDef *I2C_InitStruct);
1881 uint32_t LL_I2C_DeInit(I2C_TypeDef *I2Cx);
1882 void LL_I2C_StructInit(LL_I2C_InitTypeDef *I2C_InitStruct);
1886 * @}
1888 #endif /* USE_FULL_LL_DRIVER */
1891 * @}
1895 * @}
1898 #endif /* I2C1 || I2C2 || I2C3 */
1901 * @}
1904 #ifdef __cplusplus
1906 #endif
1908 #endif /* __STM32F4xx_LL_I2C_H */
1910 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/