F1 and F3 HAL / LL libraries
[betaflight.git] / lib / main / STM32F3 / Drivers / STM32F3xx_HAL_Driver / Src / stm32f3xx_hal_i2c.c
blob82e59e74204273d31dcd1e5799547b4c3348e720
1 /**
2 ******************************************************************************
3 * @file stm32f3xx_hal_i2c.c
4 * @author MCD Application Team
5 * @brief I2C HAL module driver.
6 * This file provides firmware functions to manage the following
7 * functionalities of the Inter Integrated Circuit (I2C) peripheral:
8 * + Initialization and de-initialization functions
9 * + IO operation functions
10 * + Peripheral State and Errors functions
12 @verbatim
13 ==============================================================================
14 ##### How to use this driver #####
15 ==============================================================================
16 [..]
17 The I2C HAL driver can be used as follows:
19 (#) Declare a I2C_HandleTypeDef handle structure, for example:
20 I2C_HandleTypeDef hi2c;
22 (#)Initialize the I2C low level resources by implementing the HAL_I2C_MspInit() API:
23 (##) Enable the I2Cx interface clock
24 (##) I2C pins configuration
25 (+++) Enable the clock for the I2C GPIOs
26 (+++) Configure I2C pins as alternate function open-drain
27 (##) NVIC configuration if you need to use interrupt process
28 (+++) Configure the I2Cx interrupt priority
29 (+++) Enable the NVIC I2C IRQ Channel
30 (##) DMA Configuration if you need to use DMA process
31 (+++) Declare a DMA_HandleTypeDef handle structure for the transmit or receive channel
32 (+++) Enable the DMAx interface clock using
33 (+++) Configure the DMA handle parameters
34 (+++) Configure the DMA Tx or Rx channel
35 (+++) Associate the initialized DMA handle to the hi2c DMA Tx or Rx handle
36 (+++) Configure the priority and enable the NVIC for the transfer complete interrupt on
37 the DMA Tx or Rx channel
39 (#) Configure the Communication Clock Timing, Own Address1, Master Addressing mode, Dual Addressing mode,
40 Own Address2, Own Address2 Mask, General call and Nostretch mode in the hi2c Init structure.
42 (#) Initialize the I2C registers by calling the HAL_I2C_Init(), configures also the low level Hardware
43 (GPIO, CLOCK, NVIC...etc) by calling the customized HAL_I2C_MspInit(&hi2c) API.
45 (#) To check if target device is ready for communication, use the function HAL_I2C_IsDeviceReady()
47 (#) For I2C IO and IO MEM operations, three operation modes are available within this driver :
49 *** Polling mode IO operation ***
50 =================================
51 [..]
52 (+) Transmit in master mode an amount of data in blocking mode using HAL_I2C_Master_Transmit()
53 (+) Receive in master mode an amount of data in blocking mode using HAL_I2C_Master_Receive()
54 (+) Transmit in slave mode an amount of data in blocking mode using HAL_I2C_Slave_Transmit()
55 (+) Receive in slave mode an amount of data in blocking mode using HAL_I2C_Slave_Receive()
57 *** Polling mode IO MEM operation ***
58 =====================================
59 [..]
60 (+) Write an amount of data in blocking mode to a specific memory address using HAL_I2C_Mem_Write()
61 (+) Read an amount of data in blocking mode from a specific memory address using HAL_I2C_Mem_Read()
64 *** Interrupt mode IO operation ***
65 ===================================
66 [..]
67 (+) Transmit in master mode an amount of data in non-blocking mode using HAL_I2C_Master_Transmit_IT()
68 (+) At transmission end of transfer, HAL_I2C_MasterTxCpltCallback() is executed and user can
69 add his own code by customization of function pointer HAL_I2C_MasterTxCpltCallback()
70 (+) Receive in master mode an amount of data in non-blocking mode using HAL_I2C_Master_Receive_IT()
71 (+) At reception end of transfer, HAL_I2C_MasterRxCpltCallback() is executed and user can
72 add his own code by customization of function pointer HAL_I2C_MasterRxCpltCallback()
73 (+) Transmit in slave mode an amount of data in non-blocking mode using HAL_I2C_Slave_Transmit_IT()
74 (+) At transmission end of transfer, HAL_I2C_SlaveTxCpltCallback() is executed and user can
75 add his own code by customization of function pointer HAL_I2C_SlaveTxCpltCallback()
76 (+) Receive in slave mode an amount of data in non-blocking mode using HAL_I2C_Slave_Receive_IT()
77 (+) At reception end of transfer, HAL_I2C_SlaveRxCpltCallback() is executed and user can
78 add his own code by customization of function pointer HAL_I2C_SlaveRxCpltCallback()
79 (+) In case of transfer Error, HAL_I2C_ErrorCallback() function is executed and user can
80 add his own code by customization of function pointer HAL_I2C_ErrorCallback()
81 (+) Abort a master I2C process communication with Interrupt using HAL_I2C_Master_Abort_IT()
82 (+) End of abort process, HAL_I2C_AbortCpltCallback() is executed and user can
83 add his own code by customization of function pointer HAL_I2C_AbortCpltCallback()
84 (+) Discard a slave I2C process communication using __HAL_I2C_GENERATE_NACK() macro.
85 This action will inform Master to generate a Stop condition to discard the communication.
88 *** Interrupt mode IO sequential operation ***
89 ==============================================
90 [..]
91 (@) These interfaces allow to manage a sequential transfer with a repeated start condition
92 when a direction change during transfer
93 [..]
94 (+) A specific option field manage the different steps of a sequential transfer
95 (+) Option field values are defined through @ref I2C_XFEROPTIONS and are listed below:
96 (++) I2C_FIRST_AND_LAST_FRAME: No sequential usage, functionnal is same as associated interfaces in no sequential mode
97 (++) I2C_FIRST_FRAME: Sequential usage, this option allow to manage a sequence with start condition, address
98 and data to transfer without a final stop condition
99 (++) I2C_FIRST_AND_NEXT_FRAME: Sequential usage (Master only), this option allow to manage a sequence with start condition, address
100 and data to transfer without a final stop condition, an then permit a call the same master sequential interface
101 several times (like HAL_I2C_Master_Sequential_Transmit_IT() then HAL_I2C_Master_Sequential_Transmit_IT())
102 (++) I2C_NEXT_FRAME: Sequential usage, this option allow to manage a sequence with a restart condition, address
103 and with new data to transfer if the direction change or manage only the new data to transfer
104 if no direction change and without a final stop condition in both cases
105 (++) I2C_LAST_FRAME: Sequential usage, this option allow to manage a sequance with a restart condition, address
106 and with new data to transfer if the direction change or manage only the new data to transfer
107 if no direction change and with a final stop condition in both cases
109 (+) Differents sequential I2C interfaces are listed below:
110 (++) Sequential transmit in master I2C mode an amount of data in non-blocking mode using HAL_I2C_Master_Sequential_Transmit_IT()
111 (+++) At transmission end of current frame transfer, HAL_I2C_MasterTxCpltCallback() is executed and user can
112 add his own code by customization of function pointer HAL_I2C_MasterTxCpltCallback()
113 (++) Sequential receive in master I2C mode an amount of data in non-blocking mode using HAL_I2C_Master_Sequential_Receive_IT()
114 (+++) At reception end of current frame transfer, HAL_I2C_MasterRxCpltCallback() is executed and user can
115 add his own code by customization of function pointer HAL_I2C_MasterRxCpltCallback()
116 (++) Abort a master I2C process communication with Interrupt using HAL_I2C_Master_Abort_IT()
117 (+++) End of abort process, HAL_I2C_AbortCpltCallback() is executed and user can
118 add his own code by customization of function pointer HAL_I2C_AbortCpltCallback()
119 (++) Enable/disable the Address listen mode in slave I2C mode using HAL_I2C_EnableListen_IT() HAL_I2C_DisableListen_IT()
120 (+++) When address slave I2C match, HAL_I2C_AddrCallback() is executed and user can
121 add his own code to check the Address Match Code and the transmission direction request by master (Write/Read).
122 (+++) At Listen mode end HAL_I2C_ListenCpltCallback() is executed and user can
123 add his own code by customization of function pointer HAL_I2C_ListenCpltCallback()
124 (++) Sequential transmit in slave I2C mode an amount of data in non-blocking mode using HAL_I2C_Slave_Sequential_Transmit_IT()
125 (+++) At transmission end of current frame transfer, HAL_I2C_SlaveTxCpltCallback() is executed and user can
126 add his own code by customization of function pointer HAL_I2C_SlaveTxCpltCallback()
127 (++) Sequential receive in slave I2C mode an amount of data in non-blocking mode using HAL_I2C_Slave_Sequential_Receive_IT()
128 (+++) At reception end of current frame transfer, HAL_I2C_SlaveRxCpltCallback() is executed and user can
129 add his own code by customization of function pointer HAL_I2C_SlaveRxCpltCallback()
130 (++) In case of transfer Error, HAL_I2C_ErrorCallback() function is executed and user can
131 add his own code by customization of function pointer HAL_I2C_ErrorCallback()
132 (++) Abort a master I2C process communication with Interrupt using HAL_I2C_Master_Abort_IT()
133 (++) End of abort process, HAL_I2C_AbortCpltCallback() is executed and user can
134 add his own code by customization of function pointer HAL_I2C_AbortCpltCallback()
135 (++) Discard a slave I2C process communication using __HAL_I2C_GENERATE_NACK() macro.
136 This action will inform Master to generate a Stop condition to discard the communication.
138 *** Interrupt mode IO MEM operation ***
139 =======================================
140 [..]
141 (+) Write an amount of data in non-blocking mode with Interrupt to a specific memory address using
142 HAL_I2C_Mem_Write_IT()
143 (+) At Memory end of write transfer, HAL_I2C_MemTxCpltCallback() is executed and user can
144 add his own code by customization of function pointer HAL_I2C_MemTxCpltCallback()
145 (+) Read an amount of data in non-blocking mode with Interrupt from a specific memory address using
146 HAL_I2C_Mem_Read_IT()
147 (+) At Memory end of read transfer, HAL_I2C_MemRxCpltCallback() is executed and user can
148 add his own code by customization of function pointer HAL_I2C_MemRxCpltCallback()
149 (+) In case of transfer Error, HAL_I2C_ErrorCallback() function is executed and user can
150 add his own code by customization of function pointer HAL_I2C_ErrorCallback()
152 *** DMA mode IO operation ***
153 ==============================
154 [..]
155 (+) Transmit in master mode an amount of data in non-blocking mode (DMA) using
156 HAL_I2C_Master_Transmit_DMA()
157 (+) At transmission end of transfer, HAL_I2C_MasterTxCpltCallback() is executed and user can
158 add his own code by customization of function pointer HAL_I2C_MasterTxCpltCallback()
159 (+) Receive in master mode an amount of data in non-blocking mode (DMA) using
160 HAL_I2C_Master_Receive_DMA()
161 (+) At reception end of transfer, HAL_I2C_MasterRxCpltCallback() is executed and user can
162 add his own code by customization of function pointer HAL_I2C_MasterRxCpltCallback()
163 (+) Transmit in slave mode an amount of data in non-blocking mode (DMA) using
164 HAL_I2C_Slave_Transmit_DMA()
165 (+) At transmission end of transfer, HAL_I2C_SlaveTxCpltCallback() is executed and user can
166 add his own code by customization of function pointer HAL_I2C_SlaveTxCpltCallback()
167 (+) Receive in slave mode an amount of data in non-blocking mode (DMA) using
168 HAL_I2C_Slave_Receive_DMA()
169 (+) At reception end of transfer, HAL_I2C_SlaveRxCpltCallback() is executed and user can
170 add his own code by customization of function pointer HAL_I2C_SlaveRxCpltCallback()
171 (+) In case of transfer Error, HAL_I2C_ErrorCallback() function is executed and user can
172 add his own code by customization of function pointer HAL_I2C_ErrorCallback()
173 (+) Abort a master I2C process communication with Interrupt using HAL_I2C_Master_Abort_IT()
174 (+) End of abort process, HAL_I2C_AbortCpltCallback() is executed and user can
175 add his own code by customization of function pointer HAL_I2C_AbortCpltCallback()
176 (+) Discard a slave I2C process communication using __HAL_I2C_GENERATE_NACK() macro.
177 This action will inform Master to generate a Stop condition to discard the communication.
179 *** DMA mode IO MEM operation ***
180 =================================
181 [..]
182 (+) Write an amount of data in non-blocking mode with DMA to a specific memory address using
183 HAL_I2C_Mem_Write_DMA()
184 (+) At Memory end of write transfer, HAL_I2C_MemTxCpltCallback() is executed and user can
185 add his own code by customization of function pointer HAL_I2C_MemTxCpltCallback()
186 (+) Read an amount of data in non-blocking mode with DMA from a specific memory address using
187 HAL_I2C_Mem_Read_DMA()
188 (+) At Memory end of read transfer, HAL_I2C_MemRxCpltCallback() is executed and user can
189 add his own code by customization of function pointer HAL_I2C_MemRxCpltCallback()
190 (+) In case of transfer Error, HAL_I2C_ErrorCallback() function is executed and user can
191 add his own code by customization of function pointer HAL_I2C_ErrorCallback()
194 *** I2C HAL driver macros list ***
195 ==================================
196 [..]
197 Below the list of most used macros in I2C HAL driver.
199 (+) __HAL_I2C_ENABLE: Enable the I2C peripheral
200 (+) __HAL_I2C_DISABLE: Disable the I2C peripheral
201 (+) __HAL_I2C_GENERATE_NACK: Generate a Non-Acknowledge I2C peripheral in Slave mode
202 (+) __HAL_I2C_GET_FLAG: Check whether the specified I2C flag is set or not
203 (+) __HAL_I2C_CLEAR_FLAG: Clear the specified I2C pending flag
204 (+) __HAL_I2C_ENABLE_IT: Enable the specified I2C interrupt
205 (+) __HAL_I2C_DISABLE_IT: Disable the specified I2C interrupt
207 [..]
208 (@) You can refer to the I2C HAL driver header file for more useful macros
210 @endverbatim
211 ******************************************************************************
212 * @attention
214 * <h2><center>&copy; COPYRIGHT(c) 2016 STMicroelectronics</center></h2>
216 * Redistribution and use in source and binary forms, with or without modification,
217 * are permitted provided that the following conditions are met:
218 * 1. Redistributions of source code must retain the above copyright notice,
219 * this list of conditions and the following disclaimer.
220 * 2. Redistributions in binary form must reproduce the above copyright notice,
221 * this list of conditions and the following disclaimer in the documentation
222 * and/or other materials provided with the distribution.
223 * 3. Neither the name of STMicroelectronics nor the names of its contributors
224 * may be used to endorse or promote products derived from this software
225 * without specific prior written permission.
227 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
228 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
229 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
230 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
231 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
232 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
233 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
234 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
235 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
236 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
238 ******************************************************************************
241 /* Includes ------------------------------------------------------------------*/
242 #include "stm32f3xx_hal.h"
244 /** @addtogroup STM32F3xx_HAL_Driver
245 * @{
248 /** @defgroup I2C I2C
249 * @brief I2C HAL module driver
250 * @{
253 #ifdef HAL_I2C_MODULE_ENABLED
255 /* Private typedef -----------------------------------------------------------*/
256 /* Private define ------------------------------------------------------------*/
258 /** @defgroup I2C_Private_Define I2C Private Define
259 * @{
261 #define TIMING_CLEAR_MASK (0xF0FFFFFFU) /*!< I2C TIMING clear register Mask */
262 #define I2C_TIMEOUT_ADDR (10000U) /*!< 10 s */
263 #define I2C_TIMEOUT_BUSY (25U) /*!< 25 ms */
264 #define I2C_TIMEOUT_DIR (25U) /*!< 25 ms */
265 #define I2C_TIMEOUT_RXNE (25U) /*!< 25 ms */
266 #define I2C_TIMEOUT_STOPF (25U) /*!< 25 ms */
267 #define I2C_TIMEOUT_TC (25U) /*!< 25 ms */
268 #define I2C_TIMEOUT_TCR (25U) /*!< 25 ms */
269 #define I2C_TIMEOUT_TXIS (25U) /*!< 25 ms */
270 #define I2C_TIMEOUT_FLAG (25U) /*!< 25 ms */
272 #define MAX_NBYTE_SIZE 255U
273 #define SlaveAddr_SHIFT 7U
274 #define SlaveAddr_MSK 0x06U
276 /* Private define for @ref PreviousState usage */
277 #define I2C_STATE_MSK ((uint32_t)((HAL_I2C_STATE_BUSY_TX | HAL_I2C_STATE_BUSY_RX) & (~((uint32_t)HAL_I2C_STATE_READY)))) /*!< Mask State define, keep only RX and TX bits */
278 #define I2C_STATE_NONE ((uint32_t)(HAL_I2C_MODE_NONE)) /*!< Default Value */
279 #define I2C_STATE_MASTER_BUSY_TX ((uint32_t)((HAL_I2C_STATE_BUSY_TX & I2C_STATE_MSK) | HAL_I2C_MODE_MASTER)) /*!< Master Busy TX, combinaison of State LSB and Mode enum */
280 #define I2C_STATE_MASTER_BUSY_RX ((uint32_t)((HAL_I2C_STATE_BUSY_RX & I2C_STATE_MSK) | HAL_I2C_MODE_MASTER)) /*!< Master Busy RX, combinaison of State LSB and Mode enum */
281 #define I2C_STATE_SLAVE_BUSY_TX ((uint32_t)((HAL_I2C_STATE_BUSY_TX & I2C_STATE_MSK) | HAL_I2C_MODE_SLAVE)) /*!< Slave Busy TX, combinaison of State LSB and Mode enum */
282 #define I2C_STATE_SLAVE_BUSY_RX ((uint32_t)((HAL_I2C_STATE_BUSY_RX & I2C_STATE_MSK) | HAL_I2C_MODE_SLAVE)) /*!< Slave Busy RX, combinaison of State LSB and Mode enum */
283 #define I2C_STATE_MEM_BUSY_TX ((uint32_t)((HAL_I2C_STATE_BUSY_TX & I2C_STATE_MSK) | HAL_I2C_MODE_MEM)) /*!< Memory Busy TX, combinaison of State LSB and Mode enum */
284 #define I2C_STATE_MEM_BUSY_RX ((uint32_t)((HAL_I2C_STATE_BUSY_RX & I2C_STATE_MSK) | HAL_I2C_MODE_MEM)) /*!< Memory Busy RX, combinaison of State LSB and Mode enum */
287 /* Private define to centralize the enable/disable of Interrupts */
288 #define I2C_XFER_TX_IT (0x00000001U)
289 #define I2C_XFER_RX_IT (0x00000002U)
290 #define I2C_XFER_LISTEN_IT (0x00000004U)
292 #define I2C_XFER_ERROR_IT (0x00000011U)
293 #define I2C_XFER_CPLT_IT (0x00000012U)
294 #define I2C_XFER_RELOAD_IT (0x00000012U)
296 /* Private define Sequential Transfer Options default/reset value */
297 #define I2C_NO_OPTION_FRAME (0xFFFF0000U)
299 * @}
302 /* Private macro -------------------------------------------------------------*/
303 #define I2C_GET_DMA_REMAIN_DATA(__HANDLE__) ((((__HANDLE__)->State) == HAL_I2C_STATE_BUSY_TX) ? \
304 ((uint32_t)((__HANDLE__)->hdmatx->Instance->CNDTR)) : \
305 ((uint32_t)((__HANDLE__)->hdmarx->Instance->CNDTR)))
307 /* Private variables ---------------------------------------------------------*/
308 /* Private function prototypes -----------------------------------------------*/
310 /** @defgroup I2C_Private_Functions I2C Private Functions
311 * @{
313 /* Private functions to handle DMA transfer */
314 static void I2C_DMAMasterTransmitCplt(DMA_HandleTypeDef *hdma);
315 static void I2C_DMAMasterReceiveCplt(DMA_HandleTypeDef *hdma);
316 static void I2C_DMASlaveTransmitCplt(DMA_HandleTypeDef *hdma);
317 static void I2C_DMASlaveReceiveCplt(DMA_HandleTypeDef *hdma);
318 static void I2C_DMAError(DMA_HandleTypeDef *hdma);
319 static void I2C_DMAAbort(DMA_HandleTypeDef *hdma);
321 /* Private functions to handle IT transfer */
322 static void I2C_ITAddrCplt(I2C_HandleTypeDef *hi2c, uint32_t ITFlags);
323 static void I2C_ITMasterSequentialCplt(I2C_HandleTypeDef *hi2c);
324 static void I2C_ITSlaveSequentialCplt(I2C_HandleTypeDef *hi2c);
325 static void I2C_ITMasterCplt(I2C_HandleTypeDef *hi2c, uint32_t ITFlags);
326 static void I2C_ITSlaveCplt(I2C_HandleTypeDef *hi2c, uint32_t ITFlags);
327 static void I2C_ITListenCplt(I2C_HandleTypeDef *hi2c, uint32_t ITFlags);
328 static void I2C_ITError(I2C_HandleTypeDef *hi2c, uint32_t ErrorCode);
330 /* Private functions to handle IT transfer */
331 static HAL_StatusTypeDef I2C_RequestMemoryWrite(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint32_t Timeout, uint32_t Tickstart);
332 static HAL_StatusTypeDef I2C_RequestMemoryRead(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint32_t Timeout, uint32_t Tickstart);
334 /* Private functions for I2C transfer IRQ handler */
335 static HAL_StatusTypeDef I2C_Master_ISR_IT(struct __I2C_HandleTypeDef *hi2c, uint32_t ITFlags, uint32_t ITSources);
336 static HAL_StatusTypeDef I2C_Slave_ISR_IT(struct __I2C_HandleTypeDef *hi2c, uint32_t ITFlags, uint32_t ITSources);
337 static HAL_StatusTypeDef I2C_Master_ISR_DMA(struct __I2C_HandleTypeDef *hi2c, uint32_t ITFlags, uint32_t ITSources);
338 static HAL_StatusTypeDef I2C_Slave_ISR_DMA(struct __I2C_HandleTypeDef *hi2c, uint32_t ITFlags, uint32_t ITSources);
340 /* Private functions to handle flags during polling transfer */
341 static HAL_StatusTypeDef I2C_WaitOnFlagUntilTimeout(I2C_HandleTypeDef *hi2c, uint32_t Flag, FlagStatus Status, uint32_t Timeout, uint32_t Tickstart);
342 static HAL_StatusTypeDef I2C_WaitOnTXISFlagUntilTimeout(I2C_HandleTypeDef *hi2c, uint32_t Timeout, uint32_t Tickstart);
343 static HAL_StatusTypeDef I2C_WaitOnRXNEFlagUntilTimeout(I2C_HandleTypeDef *hi2c, uint32_t Timeout, uint32_t Tickstart);
344 static HAL_StatusTypeDef I2C_WaitOnSTOPFlagUntilTimeout(I2C_HandleTypeDef *hi2c, uint32_t Timeout, uint32_t Tickstart);
345 static HAL_StatusTypeDef I2C_IsAcknowledgeFailed(I2C_HandleTypeDef *hi2c, uint32_t Timeout, uint32_t Tickstart);
347 /* Private functions to centralize the enable/disable of Interrupts */
348 static HAL_StatusTypeDef I2C_Enable_IRQ(I2C_HandleTypeDef *hi2c, uint16_t InterruptRequest);
349 static HAL_StatusTypeDef I2C_Disable_IRQ(I2C_HandleTypeDef *hi2c, uint16_t InterruptRequest);
351 /* Private functions to flush TXDR register */
352 static void I2C_Flush_TXDR(I2C_HandleTypeDef *hi2c);
354 /* Private functions to handle start, restart or stop a transfer */
355 static void I2C_TransferConfig(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t Size, uint32_t Mode, uint32_t Request);
357 * @}
360 /* Exported functions --------------------------------------------------------*/
362 /** @defgroup I2C_Exported_Functions I2C Exported Functions
363 * @{
366 /** @defgroup I2C_Exported_Functions_Group1 Initialization and de-initialization functions
367 * @brief Initialization and Configuration functions
369 @verbatim
370 ===============================================================================
371 ##### Initialization and de-initialization functions #####
372 ===============================================================================
373 [..] This subsection provides a set of functions allowing to initialize and
374 deinitialize the I2Cx peripheral:
376 (+) User must Implement HAL_I2C_MspInit() function in which he configures
377 all related peripherals resources (CLOCK, GPIO, DMA, IT and NVIC ).
379 (+) Call the function HAL_I2C_Init() to configure the selected device with
380 the selected configuration:
381 (++) Clock Timing
382 (++) Own Address 1
383 (++) Addressing mode (Master, Slave)
384 (++) Dual Addressing mode
385 (++) Own Address 2
386 (++) Own Address 2 Mask
387 (++) General call mode
388 (++) Nostretch mode
390 (+) Call the function HAL_I2C_DeInit() to restore the default configuration
391 of the selected I2Cx peripheral.
393 @endverbatim
394 * @{
398 * @brief Initializes the I2C according to the specified parameters
399 * in the I2C_InitTypeDef and initialize the associated handle.
400 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
401 * the configuration information for the specified I2C.
402 * @retval HAL status
404 HAL_StatusTypeDef HAL_I2C_Init(I2C_HandleTypeDef *hi2c)
406 /* Check the I2C handle allocation */
407 if (hi2c == NULL)
409 return HAL_ERROR;
412 /* Check the parameters */
413 assert_param(IS_I2C_ALL_INSTANCE(hi2c->Instance));
414 assert_param(IS_I2C_OWN_ADDRESS1(hi2c->Init.OwnAddress1));
415 assert_param(IS_I2C_ADDRESSING_MODE(hi2c->Init.AddressingMode));
416 assert_param(IS_I2C_DUAL_ADDRESS(hi2c->Init.DualAddressMode));
417 assert_param(IS_I2C_OWN_ADDRESS2(hi2c->Init.OwnAddress2));
418 assert_param(IS_I2C_OWN_ADDRESS2_MASK(hi2c->Init.OwnAddress2Masks));
419 assert_param(IS_I2C_GENERAL_CALL(hi2c->Init.GeneralCallMode));
420 assert_param(IS_I2C_NO_STRETCH(hi2c->Init.NoStretchMode));
422 if (hi2c->State == HAL_I2C_STATE_RESET)
424 /* Allocate lock resource and initialize it */
425 hi2c->Lock = HAL_UNLOCKED;
427 /* Init the low level hardware : GPIO, CLOCK, CORTEX...etc */
428 HAL_I2C_MspInit(hi2c);
431 hi2c->State = HAL_I2C_STATE_BUSY;
433 /* Disable the selected I2C peripheral */
434 __HAL_I2C_DISABLE(hi2c);
436 /*---------------------------- I2Cx TIMINGR Configuration ------------------*/
437 /* Configure I2Cx: Frequency range */
438 hi2c->Instance->TIMINGR = hi2c->Init.Timing & TIMING_CLEAR_MASK;
440 /*---------------------------- I2Cx OAR1 Configuration ---------------------*/
441 /* Disable Own Address1 before set the Own Address1 configuration */
442 hi2c->Instance->OAR1 &= ~I2C_OAR1_OA1EN;
444 /* Configure I2Cx: Own Address1 and ack own address1 mode */
445 if (hi2c->Init.AddressingMode == I2C_ADDRESSINGMODE_7BIT)
447 hi2c->Instance->OAR1 = (I2C_OAR1_OA1EN | hi2c->Init.OwnAddress1);
449 else /* I2C_ADDRESSINGMODE_10BIT */
451 hi2c->Instance->OAR1 = (I2C_OAR1_OA1EN | I2C_OAR1_OA1MODE | hi2c->Init.OwnAddress1);
454 /*---------------------------- I2Cx CR2 Configuration ----------------------*/
455 /* Configure I2Cx: Addressing Master mode */
456 if (hi2c->Init.AddressingMode == I2C_ADDRESSINGMODE_10BIT)
458 hi2c->Instance->CR2 = (I2C_CR2_ADD10);
460 /* Enable the AUTOEND by default, and enable NACK (should be disable only during Slave process */
461 hi2c->Instance->CR2 |= (I2C_CR2_AUTOEND | I2C_CR2_NACK);
463 /*---------------------------- I2Cx OAR2 Configuration ---------------------*/
464 /* Disable Own Address2 before set the Own Address2 configuration */
465 hi2c->Instance->OAR2 &= ~I2C_DUALADDRESS_ENABLE;
467 /* Configure I2Cx: Dual mode and Own Address2 */
468 hi2c->Instance->OAR2 = (hi2c->Init.DualAddressMode | hi2c->Init.OwnAddress2 | (hi2c->Init.OwnAddress2Masks << 8));
470 /*---------------------------- I2Cx CR1 Configuration ----------------------*/
471 /* Configure I2Cx: Generalcall and NoStretch mode */
472 hi2c->Instance->CR1 = (hi2c->Init.GeneralCallMode | hi2c->Init.NoStretchMode);
474 /* Enable the selected I2C peripheral */
475 __HAL_I2C_ENABLE(hi2c);
477 hi2c->ErrorCode = HAL_I2C_ERROR_NONE;
478 hi2c->State = HAL_I2C_STATE_READY;
479 hi2c->PreviousState = I2C_STATE_NONE;
480 hi2c->Mode = HAL_I2C_MODE_NONE;
482 return HAL_OK;
486 * @brief DeInitialize the I2C peripheral.
487 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
488 * the configuration information for the specified I2C.
489 * @retval HAL status
491 HAL_StatusTypeDef HAL_I2C_DeInit(I2C_HandleTypeDef *hi2c)
493 /* Check the I2C handle allocation */
494 if (hi2c == NULL)
496 return HAL_ERROR;
499 /* Check the parameters */
500 assert_param(IS_I2C_ALL_INSTANCE(hi2c->Instance));
502 hi2c->State = HAL_I2C_STATE_BUSY;
504 /* Disable the I2C Peripheral Clock */
505 __HAL_I2C_DISABLE(hi2c);
507 /* DeInit the low level hardware: GPIO, CLOCK, NVIC */
508 HAL_I2C_MspDeInit(hi2c);
510 hi2c->ErrorCode = HAL_I2C_ERROR_NONE;
511 hi2c->State = HAL_I2C_STATE_RESET;
512 hi2c->PreviousState = I2C_STATE_NONE;
513 hi2c->Mode = HAL_I2C_MODE_NONE;
515 /* Release Lock */
516 __HAL_UNLOCK(hi2c);
518 return HAL_OK;
522 * @brief Initialize the I2C MSP.
523 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
524 * the configuration information for the specified I2C.
525 * @retval None
527 __weak void HAL_I2C_MspInit(I2C_HandleTypeDef *hi2c)
529 /* Prevent unused argument(s) compilation warning */
530 UNUSED(hi2c);
532 /* NOTE : This function should not be modified, when the callback is needed,
533 the HAL_I2C_MspInit could be implemented in the user file
538 * @brief DeInitialize the I2C MSP.
539 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
540 * the configuration information for the specified I2C.
541 * @retval None
543 __weak void HAL_I2C_MspDeInit(I2C_HandleTypeDef *hi2c)
545 /* Prevent unused argument(s) compilation warning */
546 UNUSED(hi2c);
548 /* NOTE : This function should not be modified, when the callback is needed,
549 the HAL_I2C_MspDeInit could be implemented in the user file
554 * @}
557 /** @defgroup I2C_Exported_Functions_Group2 Input and Output operation functions
558 * @brief Data transfers functions
560 @verbatim
561 ===============================================================================
562 ##### IO operation functions #####
563 ===============================================================================
564 [..]
565 This subsection provides a set of functions allowing to manage the I2C data
566 transfers.
568 (#) There are two modes of transfer:
569 (++) Blocking mode : The communication is performed in the polling mode.
570 The status of all data processing is returned by the same function
571 after finishing transfer.
572 (++) No-Blocking mode : The communication is performed using Interrupts
573 or DMA. These functions return the status of the transfer startup.
574 The end of the data processing will be indicated through the
575 dedicated I2C IRQ when using Interrupt mode or the DMA IRQ when
576 using DMA mode.
578 (#) Blocking mode functions are :
579 (++) HAL_I2C_Master_Transmit()
580 (++) HAL_I2C_Master_Receive()
581 (++) HAL_I2C_Slave_Transmit()
582 (++) HAL_I2C_Slave_Receive()
583 (++) HAL_I2C_Mem_Write()
584 (++) HAL_I2C_Mem_Read()
585 (++) HAL_I2C_IsDeviceReady()
587 (#) No-Blocking mode functions with Interrupt are :
588 (++) HAL_I2C_Master_Transmit_IT()
589 (++) HAL_I2C_Master_Receive_IT()
590 (++) HAL_I2C_Slave_Transmit_IT()
591 (++) HAL_I2C_Slave_Receive_IT()
592 (++) HAL_I2C_Mem_Write_IT()
593 (++) HAL_I2C_Mem_Read_IT()
595 (#) No-Blocking mode functions with DMA are :
596 (++) HAL_I2C_Master_Transmit_DMA()
597 (++) HAL_I2C_Master_Receive_DMA()
598 (++) HAL_I2C_Slave_Transmit_DMA()
599 (++) HAL_I2C_Slave_Receive_DMA()
600 (++) HAL_I2C_Mem_Write_DMA()
601 (++) HAL_I2C_Mem_Read_DMA()
603 (#) A set of Transfer Complete Callbacks are provided in non Blocking mode:
604 (++) HAL_I2C_MemTxCpltCallback()
605 (++) HAL_I2C_MemRxCpltCallback()
606 (++) HAL_I2C_MasterTxCpltCallback()
607 (++) HAL_I2C_MasterRxCpltCallback()
608 (++) HAL_I2C_SlaveTxCpltCallback()
609 (++) HAL_I2C_SlaveRxCpltCallback()
610 (++) HAL_I2C_ErrorCallback()
612 @endverbatim
613 * @{
617 * @brief Transmits in master mode an amount of data in blocking mode.
618 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
619 * the configuration information for the specified I2C.
620 * @param DevAddress Target device address: The device 7 bits address value
621 * in datasheet must be shift at right before call interface
622 * @param pData Pointer to data buffer
623 * @param Size Amount of data to be sent
624 * @param Timeout Timeout duration
625 * @retval HAL status
627 HAL_StatusTypeDef HAL_I2C_Master_Transmit(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size, uint32_t Timeout)
629 uint32_t tickstart = 0U;
631 if (hi2c->State == HAL_I2C_STATE_READY)
633 /* Process Locked */
634 __HAL_LOCK(hi2c);
636 /* Init tickstart for timeout management*/
637 tickstart = HAL_GetTick();
639 if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_BUSY, SET, I2C_TIMEOUT_BUSY, tickstart) != HAL_OK)
641 return HAL_TIMEOUT;
644 hi2c->State = HAL_I2C_STATE_BUSY_TX;
645 hi2c->Mode = HAL_I2C_MODE_MASTER;
646 hi2c->ErrorCode = HAL_I2C_ERROR_NONE;
648 /* Prepare transfer parameters */
649 hi2c->pBuffPtr = pData;
650 hi2c->XferCount = Size;
651 hi2c->XferISR = NULL;
653 /* Send Slave Address */
654 /* Set NBYTES to write and reload if hi2c->XferCount > MAX_NBYTE_SIZE and generate RESTART */
655 if (hi2c->XferCount > MAX_NBYTE_SIZE)
657 hi2c->XferSize = MAX_NBYTE_SIZE;
658 I2C_TransferConfig(hi2c, DevAddress, hi2c->XferSize, I2C_RELOAD_MODE, I2C_GENERATE_START_WRITE);
660 else
662 hi2c->XferSize = hi2c->XferCount;
663 I2C_TransferConfig(hi2c, DevAddress, hi2c->XferSize, I2C_AUTOEND_MODE, I2C_GENERATE_START_WRITE);
666 while (hi2c->XferCount > 0U)
668 /* Wait until TXIS flag is set */
669 if (I2C_WaitOnTXISFlagUntilTimeout(hi2c, Timeout, tickstart) != HAL_OK)
671 if (hi2c->ErrorCode == HAL_I2C_ERROR_AF)
673 return HAL_ERROR;
675 else
677 return HAL_TIMEOUT;
680 /* Write data to TXDR */
681 hi2c->Instance->TXDR = (*hi2c->pBuffPtr++);
682 hi2c->XferCount--;
683 hi2c->XferSize--;
685 if ((hi2c->XferSize == 0U) && (hi2c->XferCount != 0U))
687 /* Wait until TCR flag is set */
688 if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_TCR, RESET, Timeout, tickstart) != HAL_OK)
690 return HAL_TIMEOUT;
693 if (hi2c->XferCount > MAX_NBYTE_SIZE)
695 hi2c->XferSize = MAX_NBYTE_SIZE;
696 I2C_TransferConfig(hi2c, DevAddress, hi2c->XferSize, I2C_RELOAD_MODE, I2C_NO_STARTSTOP);
698 else
700 hi2c->XferSize = hi2c->XferCount;
701 I2C_TransferConfig(hi2c, DevAddress, hi2c->XferSize, I2C_AUTOEND_MODE, I2C_NO_STARTSTOP);
706 /* No need to Check TC flag, with AUTOEND mode the stop is automatically generated */
707 /* Wait until STOPF flag is set */
708 if (I2C_WaitOnSTOPFlagUntilTimeout(hi2c, Timeout, tickstart) != HAL_OK)
710 if (hi2c->ErrorCode == HAL_I2C_ERROR_AF)
712 return HAL_ERROR;
714 else
716 return HAL_TIMEOUT;
720 /* Clear STOP Flag */
721 __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_STOPF);
723 /* Clear Configuration Register 2 */
724 I2C_RESET_CR2(hi2c);
726 hi2c->State = HAL_I2C_STATE_READY;
727 hi2c->Mode = HAL_I2C_MODE_NONE;
729 /* Process Unlocked */
730 __HAL_UNLOCK(hi2c);
732 return HAL_OK;
734 else
736 return HAL_BUSY;
741 * @brief Receives in master mode an amount of data in blocking mode.
742 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
743 * the configuration information for the specified I2C.
744 * @param DevAddress Target device address: The device 7 bits address value
745 * in datasheet must be shift at right before call interface
746 * @param pData Pointer to data buffer
747 * @param Size Amount of data to be sent
748 * @param Timeout Timeout duration
749 * @retval HAL status
751 HAL_StatusTypeDef HAL_I2C_Master_Receive(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size, uint32_t Timeout)
753 uint32_t tickstart = 0U;
755 if (hi2c->State == HAL_I2C_STATE_READY)
757 /* Process Locked */
758 __HAL_LOCK(hi2c);
760 /* Init tickstart for timeout management*/
761 tickstart = HAL_GetTick();
763 if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_BUSY, SET, I2C_TIMEOUT_BUSY, tickstart) != HAL_OK)
765 return HAL_TIMEOUT;
768 hi2c->State = HAL_I2C_STATE_BUSY_RX;
769 hi2c->Mode = HAL_I2C_MODE_MASTER;
770 hi2c->ErrorCode = HAL_I2C_ERROR_NONE;
772 /* Prepare transfer parameters */
773 hi2c->pBuffPtr = pData;
774 hi2c->XferCount = Size;
775 hi2c->XferISR = NULL;
777 /* Send Slave Address */
778 /* Set NBYTES to write and reload if hi2c->XferCount > MAX_NBYTE_SIZE and generate RESTART */
779 if (hi2c->XferCount > MAX_NBYTE_SIZE)
781 hi2c->XferSize = MAX_NBYTE_SIZE;
782 I2C_TransferConfig(hi2c, DevAddress, hi2c->XferSize, I2C_RELOAD_MODE, I2C_GENERATE_START_READ);
784 else
786 hi2c->XferSize = hi2c->XferCount;
787 I2C_TransferConfig(hi2c, DevAddress, hi2c->XferSize, I2C_AUTOEND_MODE, I2C_GENERATE_START_READ);
790 while (hi2c->XferCount > 0U)
792 /* Wait until RXNE flag is set */
793 if (I2C_WaitOnRXNEFlagUntilTimeout(hi2c, Timeout, tickstart) != HAL_OK)
795 if (hi2c->ErrorCode == HAL_I2C_ERROR_AF)
797 return HAL_ERROR;
799 else
801 return HAL_TIMEOUT;
805 /* Read data from RXDR */
806 (*hi2c->pBuffPtr++) = hi2c->Instance->RXDR;
807 hi2c->XferSize--;
808 hi2c->XferCount--;
810 if ((hi2c->XferSize == 0U) && (hi2c->XferCount != 0U))
812 /* Wait until TCR flag is set */
813 if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_TCR, RESET, Timeout, tickstart) != HAL_OK)
815 return HAL_TIMEOUT;
818 if (hi2c->XferCount > MAX_NBYTE_SIZE)
820 hi2c->XferSize = MAX_NBYTE_SIZE;
821 I2C_TransferConfig(hi2c, DevAddress, hi2c->XferSize, I2C_RELOAD_MODE, I2C_NO_STARTSTOP);
823 else
825 hi2c->XferSize = hi2c->XferCount;
826 I2C_TransferConfig(hi2c, DevAddress, hi2c->XferSize, I2C_AUTOEND_MODE, I2C_NO_STARTSTOP);
831 /* No need to Check TC flag, with AUTOEND mode the stop is automatically generated */
832 /* Wait until STOPF flag is set */
833 if (I2C_WaitOnSTOPFlagUntilTimeout(hi2c, Timeout, tickstart) != HAL_OK)
835 if (hi2c->ErrorCode == HAL_I2C_ERROR_AF)
837 return HAL_ERROR;
839 else
841 return HAL_TIMEOUT;
845 /* Clear STOP Flag */
846 __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_STOPF);
848 /* Clear Configuration Register 2 */
849 I2C_RESET_CR2(hi2c);
851 hi2c->State = HAL_I2C_STATE_READY;
852 hi2c->Mode = HAL_I2C_MODE_NONE;
854 /* Process Unlocked */
855 __HAL_UNLOCK(hi2c);
857 return HAL_OK;
859 else
861 return HAL_BUSY;
866 * @brief Transmits in slave mode an amount of data in blocking mode.
867 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
868 * the configuration information for the specified I2C.
869 * @param pData Pointer to data buffer
870 * @param Size Amount of data to be sent
871 * @param Timeout Timeout duration
872 * @retval HAL status
874 HAL_StatusTypeDef HAL_I2C_Slave_Transmit(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size, uint32_t Timeout)
876 uint32_t tickstart = 0U;
878 if (hi2c->State == HAL_I2C_STATE_READY)
880 if ((pData == NULL) || (Size == 0U))
882 return HAL_ERROR;
884 /* Process Locked */
885 __HAL_LOCK(hi2c);
887 /* Init tickstart for timeout management*/
888 tickstart = HAL_GetTick();
890 hi2c->State = HAL_I2C_STATE_BUSY_TX;
891 hi2c->Mode = HAL_I2C_MODE_SLAVE;
892 hi2c->ErrorCode = HAL_I2C_ERROR_NONE;
894 /* Prepare transfer parameters */
895 hi2c->pBuffPtr = pData;
896 hi2c->XferCount = Size;
897 hi2c->XferISR = NULL;
899 /* Enable Address Acknowledge */
900 hi2c->Instance->CR2 &= ~I2C_CR2_NACK;
902 /* Wait until ADDR flag is set */
903 if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_ADDR, RESET, Timeout, tickstart) != HAL_OK)
905 /* Disable Address Acknowledge */
906 hi2c->Instance->CR2 |= I2C_CR2_NACK;
907 return HAL_TIMEOUT;
910 /* Clear ADDR flag */
911 __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_ADDR);
913 /* If 10bit addressing mode is selected */
914 if (hi2c->Init.AddressingMode == I2C_ADDRESSINGMODE_10BIT)
916 /* Wait until ADDR flag is set */
917 if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_ADDR, RESET, Timeout, tickstart) != HAL_OK)
919 /* Disable Address Acknowledge */
920 hi2c->Instance->CR2 |= I2C_CR2_NACK;
921 return HAL_TIMEOUT;
924 /* Clear ADDR flag */
925 __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_ADDR);
928 /* Wait until DIR flag is set Transmitter mode */
929 if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_DIR, RESET, Timeout, tickstart) != HAL_OK)
931 /* Disable Address Acknowledge */
932 hi2c->Instance->CR2 |= I2C_CR2_NACK;
933 return HAL_TIMEOUT;
936 while (hi2c->XferCount > 0U)
938 /* Wait until TXIS flag is set */
939 if (I2C_WaitOnTXISFlagUntilTimeout(hi2c, Timeout, tickstart) != HAL_OK)
941 /* Disable Address Acknowledge */
942 hi2c->Instance->CR2 |= I2C_CR2_NACK;
944 if (hi2c->ErrorCode == HAL_I2C_ERROR_AF)
946 return HAL_ERROR;
948 else
950 return HAL_TIMEOUT;
954 /* Write data to TXDR */
955 hi2c->Instance->TXDR = (*hi2c->pBuffPtr++);
956 hi2c->XferCount--;
959 /* Wait until STOP flag is set */
960 if (I2C_WaitOnSTOPFlagUntilTimeout(hi2c, Timeout, tickstart) != HAL_OK)
962 /* Disable Address Acknowledge */
963 hi2c->Instance->CR2 |= I2C_CR2_NACK;
965 if (hi2c->ErrorCode == HAL_I2C_ERROR_AF)
967 /* Normal use case for Transmitter mode */
968 /* A NACK is generated to confirm the end of transfer */
969 hi2c->ErrorCode = HAL_I2C_ERROR_NONE;
971 else
973 return HAL_TIMEOUT;
977 /* Clear STOP flag */
978 __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_STOPF);
980 /* Wait until BUSY flag is reset */
981 if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_BUSY, SET, Timeout, tickstart) != HAL_OK)
983 /* Disable Address Acknowledge */
984 hi2c->Instance->CR2 |= I2C_CR2_NACK;
985 return HAL_TIMEOUT;
988 /* Disable Address Acknowledge */
989 hi2c->Instance->CR2 |= I2C_CR2_NACK;
991 hi2c->State = HAL_I2C_STATE_READY;
992 hi2c->Mode = HAL_I2C_MODE_NONE;
994 /* Process Unlocked */
995 __HAL_UNLOCK(hi2c);
997 return HAL_OK;
999 else
1001 return HAL_BUSY;
1006 * @brief Receive in slave mode an amount of data in blocking mode
1007 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
1008 * the configuration information for the specified I2C.
1009 * @param pData Pointer to data buffer
1010 * @param Size Amount of data to be sent
1011 * @param Timeout Timeout duration
1012 * @retval HAL status
1014 HAL_StatusTypeDef HAL_I2C_Slave_Receive(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size, uint32_t Timeout)
1016 uint32_t tickstart = 0U;
1018 if (hi2c->State == HAL_I2C_STATE_READY)
1020 if ((pData == NULL) || (Size == 0U))
1022 return HAL_ERROR;
1024 /* Process Locked */
1025 __HAL_LOCK(hi2c);
1027 /* Init tickstart for timeout management*/
1028 tickstart = HAL_GetTick();
1030 hi2c->State = HAL_I2C_STATE_BUSY_RX;
1031 hi2c->Mode = HAL_I2C_MODE_SLAVE;
1032 hi2c->ErrorCode = HAL_I2C_ERROR_NONE;
1034 /* Prepare transfer parameters */
1035 hi2c->pBuffPtr = pData;
1036 hi2c->XferCount = Size;
1037 hi2c->XferISR = NULL;
1039 /* Enable Address Acknowledge */
1040 hi2c->Instance->CR2 &= ~I2C_CR2_NACK;
1042 /* Wait until ADDR flag is set */
1043 if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_ADDR, RESET, Timeout, tickstart) != HAL_OK)
1045 /* Disable Address Acknowledge */
1046 hi2c->Instance->CR2 |= I2C_CR2_NACK;
1047 return HAL_TIMEOUT;
1050 /* Clear ADDR flag */
1051 __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_ADDR);
1053 /* Wait until DIR flag is reset Receiver mode */
1054 if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_DIR, SET, Timeout, tickstart) != HAL_OK)
1056 /* Disable Address Acknowledge */
1057 hi2c->Instance->CR2 |= I2C_CR2_NACK;
1058 return HAL_TIMEOUT;
1061 while (hi2c->XferCount > 0U)
1063 /* Wait until RXNE flag is set */
1064 if (I2C_WaitOnRXNEFlagUntilTimeout(hi2c, Timeout, tickstart) != HAL_OK)
1066 /* Disable Address Acknowledge */
1067 hi2c->Instance->CR2 |= I2C_CR2_NACK;
1069 /* Store Last receive data if any */
1070 if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_RXNE) == SET)
1072 /* Read data from RXDR */
1073 (*hi2c->pBuffPtr++) = hi2c->Instance->RXDR;
1074 hi2c->XferCount--;
1077 if (hi2c->ErrorCode == HAL_I2C_ERROR_TIMEOUT)
1079 return HAL_TIMEOUT;
1081 else
1083 return HAL_ERROR;
1087 /* Read data from RXDR */
1088 (*hi2c->pBuffPtr++) = hi2c->Instance->RXDR;
1089 hi2c->XferCount--;
1092 /* Wait until STOP flag is set */
1093 if (I2C_WaitOnSTOPFlagUntilTimeout(hi2c, Timeout, tickstart) != HAL_OK)
1095 /* Disable Address Acknowledge */
1096 hi2c->Instance->CR2 |= I2C_CR2_NACK;
1098 if (hi2c->ErrorCode == HAL_I2C_ERROR_AF)
1100 return HAL_ERROR;
1102 else
1104 return HAL_TIMEOUT;
1108 /* Clear STOP flag */
1109 __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_STOPF);
1111 /* Wait until BUSY flag is reset */
1112 if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_BUSY, SET, Timeout, tickstart) != HAL_OK)
1114 /* Disable Address Acknowledge */
1115 hi2c->Instance->CR2 |= I2C_CR2_NACK;
1116 return HAL_TIMEOUT;
1119 /* Disable Address Acknowledge */
1120 hi2c->Instance->CR2 |= I2C_CR2_NACK;
1122 hi2c->State = HAL_I2C_STATE_READY;
1123 hi2c->Mode = HAL_I2C_MODE_NONE;
1125 /* Process Unlocked */
1126 __HAL_UNLOCK(hi2c);
1128 return HAL_OK;
1130 else
1132 return HAL_BUSY;
1137 * @brief Transmit in master mode an amount of data in non-blocking mode with Interrupt
1138 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
1139 * the configuration information for the specified I2C.
1140 * @param DevAddress Target device address: The device 7 bits address value
1141 * in datasheet must be shift at right before call interface
1142 * @param pData Pointer to data buffer
1143 * @param Size Amount of data to be sent
1144 * @retval HAL status
1146 HAL_StatusTypeDef HAL_I2C_Master_Transmit_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size)
1148 uint32_t xfermode = 0U;
1150 if (hi2c->State == HAL_I2C_STATE_READY)
1152 if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BUSY) == SET)
1154 return HAL_BUSY;
1157 /* Process Locked */
1158 __HAL_LOCK(hi2c);
1160 hi2c->State = HAL_I2C_STATE_BUSY_TX;
1161 hi2c->Mode = HAL_I2C_MODE_MASTER;
1162 hi2c->ErrorCode = HAL_I2C_ERROR_NONE;
1164 /* Prepare transfer parameters */
1165 hi2c->pBuffPtr = pData;
1166 hi2c->XferCount = Size;
1167 hi2c->XferOptions = I2C_NO_OPTION_FRAME;
1168 hi2c->XferISR = I2C_Master_ISR_IT;
1170 if (hi2c->XferCount > MAX_NBYTE_SIZE)
1172 hi2c->XferSize = MAX_NBYTE_SIZE;
1173 xfermode = I2C_RELOAD_MODE;
1175 else
1177 hi2c->XferSize = hi2c->XferCount;
1178 xfermode = I2C_AUTOEND_MODE;
1181 /* Send Slave Address */
1182 /* Set NBYTES to write and reload if hi2c->XferCount > MAX_NBYTE_SIZE */
1183 I2C_TransferConfig(hi2c, DevAddress, hi2c->XferSize, xfermode, I2C_GENERATE_START_WRITE);
1185 /* Process Unlocked */
1186 __HAL_UNLOCK(hi2c);
1188 /* Note : The I2C interrupts must be enabled after unlocking current process
1189 to avoid the risk of I2C interrupt handle execution before current
1190 process unlock */
1192 /* Enable ERR, TC, STOP, NACK, TXI interrupt */
1193 /* possible to enable all of these */
1194 /* I2C_IT_ERRI | I2C_IT_TCI| I2C_IT_STOPI| I2C_IT_NACKI | I2C_IT_ADDRI | I2C_IT_RXI | I2C_IT_TXI */
1195 I2C_Enable_IRQ(hi2c, I2C_XFER_TX_IT);
1197 return HAL_OK;
1199 else
1201 return HAL_BUSY;
1206 * @brief Receive in master mode an amount of data in non-blocking mode with Interrupt
1207 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
1208 * the configuration information for the specified I2C.
1209 * @param DevAddress Target device address: The device 7 bits address value
1210 * in datasheet must be shift at right before call interface
1211 * @param pData Pointer to data buffer
1212 * @param Size Amount of data to be sent
1213 * @retval HAL status
1215 HAL_StatusTypeDef HAL_I2C_Master_Receive_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size)
1217 uint32_t xfermode = 0U;
1219 if (hi2c->State == HAL_I2C_STATE_READY)
1221 if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BUSY) == SET)
1223 return HAL_BUSY;
1226 /* Process Locked */
1227 __HAL_LOCK(hi2c);
1229 hi2c->State = HAL_I2C_STATE_BUSY_RX;
1230 hi2c->Mode = HAL_I2C_MODE_MASTER;
1231 hi2c->ErrorCode = HAL_I2C_ERROR_NONE;
1233 /* Prepare transfer parameters */
1234 hi2c->pBuffPtr = pData;
1235 hi2c->XferCount = Size;
1236 hi2c->XferOptions = I2C_NO_OPTION_FRAME;
1237 hi2c->XferISR = I2C_Master_ISR_IT;
1239 if (hi2c->XferCount > MAX_NBYTE_SIZE)
1241 hi2c->XferSize = MAX_NBYTE_SIZE;
1242 xfermode = I2C_RELOAD_MODE;
1244 else
1246 hi2c->XferSize = hi2c->XferCount;
1247 xfermode = I2C_AUTOEND_MODE;
1250 /* Send Slave Address */
1251 /* Set NBYTES to write and reload if hi2c->XferCount > MAX_NBYTE_SIZE */
1252 I2C_TransferConfig(hi2c, DevAddress, hi2c->XferSize, xfermode, I2C_GENERATE_START_READ);
1254 /* Process Unlocked */
1255 __HAL_UNLOCK(hi2c);
1257 /* Note : The I2C interrupts must be enabled after unlocking current process
1258 to avoid the risk of I2C interrupt handle execution before current
1259 process unlock */
1261 /* Enable ERR, TC, STOP, NACK, RXI interrupt */
1262 /* possible to enable all of these */
1263 /* I2C_IT_ERRI | I2C_IT_TCI| I2C_IT_STOPI| I2C_IT_NACKI | I2C_IT_ADDRI | I2C_IT_RXI | I2C_IT_TXI */
1264 I2C_Enable_IRQ(hi2c, I2C_XFER_RX_IT);
1266 return HAL_OK;
1268 else
1270 return HAL_BUSY;
1275 * @brief Transmit in slave mode an amount of data in non-blocking mode with Interrupt
1276 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
1277 * the configuration information for the specified I2C.
1278 * @param pData Pointer to data buffer
1279 * @param Size Amount of data to be sent
1280 * @retval HAL status
1282 HAL_StatusTypeDef HAL_I2C_Slave_Transmit_IT(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size)
1284 if (hi2c->State == HAL_I2C_STATE_READY)
1286 /* Process Locked */
1287 __HAL_LOCK(hi2c);
1289 hi2c->State = HAL_I2C_STATE_BUSY_TX;
1290 hi2c->Mode = HAL_I2C_MODE_SLAVE;
1291 hi2c->ErrorCode = HAL_I2C_ERROR_NONE;
1293 /* Enable Address Acknowledge */
1294 hi2c->Instance->CR2 &= ~I2C_CR2_NACK;
1296 /* Prepare transfer parameters */
1297 hi2c->pBuffPtr = pData;
1298 hi2c->XferCount = Size;
1299 hi2c->XferSize = hi2c->XferCount;
1300 hi2c->XferOptions = I2C_NO_OPTION_FRAME;
1301 hi2c->XferISR = I2C_Slave_ISR_IT;
1303 /* Process Unlocked */
1304 __HAL_UNLOCK(hi2c);
1306 /* Note : The I2C interrupts must be enabled after unlocking current process
1307 to avoid the risk of I2C interrupt handle execution before current
1308 process unlock */
1310 /* Enable ERR, TC, STOP, NACK, TXI interrupt */
1311 /* possible to enable all of these */
1312 /* I2C_IT_ERRI | I2C_IT_TCI| I2C_IT_STOPI| I2C_IT_NACKI | I2C_IT_ADDRI | I2C_IT_RXI | I2C_IT_TXI */
1313 I2C_Enable_IRQ(hi2c, I2C_XFER_TX_IT | I2C_XFER_LISTEN_IT);
1315 return HAL_OK;
1317 else
1319 return HAL_BUSY;
1324 * @brief Receive in slave mode an amount of data in non-blocking mode with Interrupt
1325 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
1326 * the configuration information for the specified I2C.
1327 * @param pData Pointer to data buffer
1328 * @param Size Amount of data to be sent
1329 * @retval HAL status
1331 HAL_StatusTypeDef HAL_I2C_Slave_Receive_IT(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size)
1333 if (hi2c->State == HAL_I2C_STATE_READY)
1335 /* Process Locked */
1336 __HAL_LOCK(hi2c);
1338 hi2c->State = HAL_I2C_STATE_BUSY_RX;
1339 hi2c->Mode = HAL_I2C_MODE_SLAVE;
1340 hi2c->ErrorCode = HAL_I2C_ERROR_NONE;
1342 /* Enable Address Acknowledge */
1343 hi2c->Instance->CR2 &= ~I2C_CR2_NACK;
1345 /* Prepare transfer parameters */
1346 hi2c->pBuffPtr = pData;
1347 hi2c->XferCount = Size;
1348 hi2c->XferSize = hi2c->XferCount;
1349 hi2c->XferOptions = I2C_NO_OPTION_FRAME;
1350 hi2c->XferISR = I2C_Slave_ISR_IT;
1352 /* Process Unlocked */
1353 __HAL_UNLOCK(hi2c);
1355 /* Note : The I2C interrupts must be enabled after unlocking current process
1356 to avoid the risk of I2C interrupt handle execution before current
1357 process unlock */
1359 /* Enable ERR, TC, STOP, NACK, RXI interrupt */
1360 /* possible to enable all of these */
1361 /* I2C_IT_ERRI | I2C_IT_TCI| I2C_IT_STOPI| I2C_IT_NACKI | I2C_IT_ADDRI | I2C_IT_RXI | I2C_IT_TXI */
1362 I2C_Enable_IRQ(hi2c, I2C_XFER_RX_IT | I2C_XFER_LISTEN_IT);
1364 return HAL_OK;
1366 else
1368 return HAL_BUSY;
1373 * @brief Transmit in master mode an amount of data in non-blocking mode with DMA
1374 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
1375 * the configuration information for the specified I2C.
1376 * @param DevAddress Target device address: The device 7 bits address value
1377 * in datasheet must be shift at right before call interface
1378 * @param pData Pointer to data buffer
1379 * @param Size Amount of data to be sent
1380 * @retval HAL status
1382 HAL_StatusTypeDef HAL_I2C_Master_Transmit_DMA(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size)
1384 uint32_t xfermode = 0U;
1386 if (hi2c->State == HAL_I2C_STATE_READY)
1388 if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BUSY) == SET)
1390 return HAL_BUSY;
1393 /* Process Locked */
1394 __HAL_LOCK(hi2c);
1396 hi2c->State = HAL_I2C_STATE_BUSY_TX;
1397 hi2c->Mode = HAL_I2C_MODE_MASTER;
1398 hi2c->ErrorCode = HAL_I2C_ERROR_NONE;
1400 /* Prepare transfer parameters */
1401 hi2c->pBuffPtr = pData;
1402 hi2c->XferCount = Size;
1403 hi2c->XferOptions = I2C_NO_OPTION_FRAME;
1404 hi2c->XferISR = I2C_Master_ISR_DMA;
1406 if (hi2c->XferCount > MAX_NBYTE_SIZE)
1408 hi2c->XferSize = MAX_NBYTE_SIZE;
1409 xfermode = I2C_RELOAD_MODE;
1411 else
1413 hi2c->XferSize = hi2c->XferCount;
1414 xfermode = I2C_AUTOEND_MODE;
1417 if (hi2c->XferSize > 0U)
1419 /* Set the I2C DMA transfer complete callback */
1420 hi2c->hdmatx->XferCpltCallback = I2C_DMAMasterTransmitCplt;
1422 /* Set the DMA error callback */
1423 hi2c->hdmatx->XferErrorCallback = I2C_DMAError;
1425 /* Set the unused DMA callbacks to NULL */
1426 hi2c->hdmatx->XferHalfCpltCallback = NULL;
1427 hi2c->hdmatx->XferAbortCallback = NULL;
1429 /* Enable the DMA channel */
1430 HAL_DMA_Start_IT(hi2c->hdmatx, (uint32_t)pData, (uint32_t)&hi2c->Instance->TXDR, hi2c->XferSize);
1432 /* Send Slave Address */
1433 /* Set NBYTES to write and reload if hi2c->XferCount > MAX_NBYTE_SIZE and generate RESTART */
1434 I2C_TransferConfig(hi2c, DevAddress, hi2c->XferSize, xfermode, I2C_GENERATE_START_WRITE);
1436 /* Update XferCount value */
1437 hi2c->XferCount -= hi2c->XferSize;
1439 /* Process Unlocked */
1440 __HAL_UNLOCK(hi2c);
1442 /* Note : The I2C interrupts must be enabled after unlocking current process
1443 to avoid the risk of I2C interrupt handle execution before current
1444 process unlock */
1445 /* Enable ERR and NACK interrupts */
1446 I2C_Enable_IRQ(hi2c, I2C_XFER_ERROR_IT);
1448 /* Enable DMA Request */
1449 hi2c->Instance->CR1 |= I2C_CR1_TXDMAEN;
1451 else
1453 /* Update Transfer ISR function pointer */
1454 hi2c->XferISR = I2C_Master_ISR_IT;
1456 /* Send Slave Address */
1457 /* Set NBYTES to write and generate START condition */
1458 I2C_TransferConfig(hi2c, DevAddress, hi2c->XferSize, I2C_AUTOEND_MODE, I2C_GENERATE_START_WRITE);
1460 /* Process Unlocked */
1461 __HAL_UNLOCK(hi2c);
1463 /* Note : The I2C interrupts must be enabled after unlocking current process
1464 to avoid the risk of I2C interrupt handle execution before current
1465 process unlock */
1466 /* Enable ERR, TC, STOP, NACK, TXI interrupt */
1467 /* possible to enable all of these */
1468 /* I2C_IT_ERRI | I2C_IT_TCI| I2C_IT_STOPI| I2C_IT_NACKI | I2C_IT_ADDRI | I2C_IT_RXI | I2C_IT_TXI */
1469 I2C_Enable_IRQ(hi2c, I2C_XFER_TX_IT);
1472 return HAL_OK;
1474 else
1476 return HAL_BUSY;
1481 * @brief Receive in master mode an amount of data in non-blocking mode with DMA
1482 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
1483 * the configuration information for the specified I2C.
1484 * @param DevAddress Target device address: The device 7 bits address value
1485 * in datasheet must be shift at right before call interface
1486 * @param pData Pointer to data buffer
1487 * @param Size Amount of data to be sent
1488 * @retval HAL status
1490 HAL_StatusTypeDef HAL_I2C_Master_Receive_DMA(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size)
1492 uint32_t xfermode = 0U;
1494 if (hi2c->State == HAL_I2C_STATE_READY)
1496 if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BUSY) == SET)
1498 return HAL_BUSY;
1501 /* Process Locked */
1502 __HAL_LOCK(hi2c);
1504 hi2c->State = HAL_I2C_STATE_BUSY_RX;
1505 hi2c->Mode = HAL_I2C_MODE_MASTER;
1506 hi2c->ErrorCode = HAL_I2C_ERROR_NONE;
1508 /* Prepare transfer parameters */
1509 hi2c->pBuffPtr = pData;
1510 hi2c->XferCount = Size;
1511 hi2c->XferOptions = I2C_NO_OPTION_FRAME;
1512 hi2c->XferISR = I2C_Master_ISR_DMA;
1514 if (hi2c->XferCount > MAX_NBYTE_SIZE)
1516 hi2c->XferSize = MAX_NBYTE_SIZE;
1517 xfermode = I2C_RELOAD_MODE;
1519 else
1521 hi2c->XferSize = hi2c->XferCount;
1522 xfermode = I2C_AUTOEND_MODE;
1525 if (hi2c->XferSize > 0U)
1527 /* Set the I2C DMA transfer complete callback */
1528 hi2c->hdmarx->XferCpltCallback = I2C_DMAMasterReceiveCplt;
1530 /* Set the DMA error callback */
1531 hi2c->hdmarx->XferErrorCallback = I2C_DMAError;
1533 /* Set the unused DMA callbacks to NULL */
1534 hi2c->hdmarx->XferHalfCpltCallback = NULL;
1535 hi2c->hdmarx->XferAbortCallback = NULL;
1537 /* Enable the DMA channel */
1538 HAL_DMA_Start_IT(hi2c->hdmarx, (uint32_t)&hi2c->Instance->RXDR, (uint32_t)pData, hi2c->XferSize);
1540 /* Send Slave Address */
1541 /* Set NBYTES to read and reload if hi2c->XferCount > MAX_NBYTE_SIZE and generate RESTART */
1542 I2C_TransferConfig(hi2c, DevAddress, hi2c->XferSize, xfermode, I2C_GENERATE_START_READ);
1544 /* Update XferCount value */
1545 hi2c->XferCount -= hi2c->XferSize;
1547 /* Process Unlocked */
1548 __HAL_UNLOCK(hi2c);
1550 /* Note : The I2C interrupts must be enabled after unlocking current process
1551 to avoid the risk of I2C interrupt handle execution before current
1552 process unlock */
1553 /* Enable ERR and NACK interrupts */
1554 I2C_Enable_IRQ(hi2c, I2C_XFER_ERROR_IT);
1556 /* Enable DMA Request */
1557 hi2c->Instance->CR1 |= I2C_CR1_RXDMAEN;
1559 else
1561 /* Update Transfer ISR function pointer */
1562 hi2c->XferISR = I2C_Master_ISR_IT;
1564 /* Send Slave Address */
1565 /* Set NBYTES to read and generate START condition */
1566 I2C_TransferConfig(hi2c, DevAddress, hi2c->XferSize, I2C_AUTOEND_MODE, I2C_GENERATE_START_READ);
1568 /* Process Unlocked */
1569 __HAL_UNLOCK(hi2c);
1571 /* Note : The I2C interrupts must be enabled after unlocking current process
1572 to avoid the risk of I2C interrupt handle execution before current
1573 process unlock */
1574 /* Enable ERR, TC, STOP, NACK, TXI interrupt */
1575 /* possible to enable all of these */
1576 /* I2C_IT_ERRI | I2C_IT_TCI| I2C_IT_STOPI| I2C_IT_NACKI | I2C_IT_ADDRI | I2C_IT_RXI | I2C_IT_TXI */
1577 I2C_Enable_IRQ(hi2c, I2C_XFER_TX_IT);
1579 return HAL_OK;
1581 else
1583 return HAL_BUSY;
1588 * @brief Transmit in slave mode an amount of data in non-blocking mode with DMA
1589 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
1590 * the configuration information for the specified I2C.
1591 * @param pData Pointer to data buffer
1592 * @param Size Amount of data to be sent
1593 * @retval HAL status
1595 HAL_StatusTypeDef HAL_I2C_Slave_Transmit_DMA(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size)
1597 if (hi2c->State == HAL_I2C_STATE_READY)
1599 if ((pData == NULL) || (Size == 0U))
1601 return HAL_ERROR;
1603 /* Process Locked */
1604 __HAL_LOCK(hi2c);
1606 hi2c->State = HAL_I2C_STATE_BUSY_TX;
1607 hi2c->Mode = HAL_I2C_MODE_SLAVE;
1608 hi2c->ErrorCode = HAL_I2C_ERROR_NONE;
1610 /* Prepare transfer parameters */
1611 hi2c->pBuffPtr = pData;
1612 hi2c->XferCount = Size;
1613 hi2c->XferSize = hi2c->XferCount;
1614 hi2c->XferOptions = I2C_NO_OPTION_FRAME;
1615 hi2c->XferISR = I2C_Slave_ISR_DMA;
1617 /* Set the I2C DMA transfer complete callback */
1618 hi2c->hdmatx->XferCpltCallback = I2C_DMASlaveTransmitCplt;
1620 /* Set the DMA error callback */
1621 hi2c->hdmatx->XferErrorCallback = I2C_DMAError;
1623 /* Set the unused DMA callbacks to NULL */
1624 hi2c->hdmatx->XferHalfCpltCallback = NULL;
1625 hi2c->hdmatx->XferAbortCallback = NULL;
1627 /* Enable the DMA channel */
1628 HAL_DMA_Start_IT(hi2c->hdmatx, (uint32_t)pData, (uint32_t)&hi2c->Instance->TXDR, hi2c->XferSize);
1630 /* Enable Address Acknowledge */
1631 hi2c->Instance->CR2 &= ~I2C_CR2_NACK;
1633 /* Process Unlocked */
1634 __HAL_UNLOCK(hi2c);
1636 /* Note : The I2C interrupts must be enabled after unlocking current process
1637 to avoid the risk of I2C interrupt handle execution before current
1638 process unlock */
1639 /* Enable ERR, STOP, NACK, ADDR interrupts */
1640 I2C_Enable_IRQ(hi2c, I2C_XFER_LISTEN_IT);
1642 /* Enable DMA Request */
1643 hi2c->Instance->CR1 |= I2C_CR1_TXDMAEN;
1645 return HAL_OK;
1647 else
1649 return HAL_BUSY;
1654 * @brief Receive in slave mode an amount of data in non-blocking mode with DMA
1655 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
1656 * the configuration information for the specified I2C.
1657 * @param pData Pointer to data buffer
1658 * @param Size Amount of data to be sent
1659 * @retval HAL status
1661 HAL_StatusTypeDef HAL_I2C_Slave_Receive_DMA(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size)
1663 if (hi2c->State == HAL_I2C_STATE_READY)
1665 if ((pData == NULL) || (Size == 0U))
1667 return HAL_ERROR;
1669 /* Process Locked */
1670 __HAL_LOCK(hi2c);
1672 hi2c->State = HAL_I2C_STATE_BUSY_RX;
1673 hi2c->Mode = HAL_I2C_MODE_SLAVE;
1674 hi2c->ErrorCode = HAL_I2C_ERROR_NONE;
1676 /* Prepare transfer parameters */
1677 hi2c->pBuffPtr = pData;
1678 hi2c->XferCount = Size;
1679 hi2c->XferSize = hi2c->XferCount;
1680 hi2c->XferOptions = I2C_NO_OPTION_FRAME;
1681 hi2c->XferISR = I2C_Slave_ISR_DMA;
1683 /* Set the I2C DMA transfer complete callback */
1684 hi2c->hdmarx->XferCpltCallback = I2C_DMASlaveReceiveCplt;
1686 /* Set the DMA error callback */
1687 hi2c->hdmarx->XferErrorCallback = I2C_DMAError;
1689 /* Set the unused DMA callbacks to NULL */
1690 hi2c->hdmarx->XferHalfCpltCallback = NULL;
1691 hi2c->hdmarx->XferAbortCallback = NULL;
1693 /* Enable the DMA channel */
1694 HAL_DMA_Start_IT(hi2c->hdmarx, (uint32_t)&hi2c->Instance->RXDR, (uint32_t)pData, hi2c->XferSize);
1696 /* Enable Address Acknowledge */
1697 hi2c->Instance->CR2 &= ~I2C_CR2_NACK;
1699 /* Process Unlocked */
1700 __HAL_UNLOCK(hi2c);
1702 /* Note : The I2C interrupts must be enabled after unlocking current process
1703 to avoid the risk of I2C interrupt handle execution before current
1704 process unlock */
1705 /* Enable ERR, STOP, NACK, ADDR interrupts */
1706 I2C_Enable_IRQ(hi2c, I2C_XFER_LISTEN_IT);
1708 /* Enable DMA Request */
1709 hi2c->Instance->CR1 |= I2C_CR1_RXDMAEN;
1711 return HAL_OK;
1713 else
1715 return HAL_BUSY;
1719 * @brief Write an amount of data in blocking mode to a specific memory address
1720 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
1721 * the configuration information for the specified I2C.
1722 * @param DevAddress Target device address: The device 7 bits address value
1723 * in datasheet must be shift at right before call interface
1724 * @param MemAddress Internal memory address
1725 * @param MemAddSize Size of internal memory address
1726 * @param pData Pointer to data buffer
1727 * @param Size Amount of data to be sent
1728 * @param Timeout Timeout duration
1729 * @retval HAL status
1731 HAL_StatusTypeDef HAL_I2C_Mem_Write(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint8_t *pData, uint16_t Size, uint32_t Timeout)
1733 uint32_t tickstart = 0U;
1735 /* Check the parameters */
1736 assert_param(IS_I2C_MEMADD_SIZE(MemAddSize));
1738 if (hi2c->State == HAL_I2C_STATE_READY)
1740 if ((pData == NULL) || (Size == 0U))
1742 return HAL_ERROR;
1745 /* Process Locked */
1746 __HAL_LOCK(hi2c);
1748 /* Init tickstart for timeout management*/
1749 tickstart = HAL_GetTick();
1751 if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_BUSY, SET, I2C_TIMEOUT_BUSY, tickstart) != HAL_OK)
1753 return HAL_TIMEOUT;
1756 hi2c->State = HAL_I2C_STATE_BUSY_TX;
1757 hi2c->Mode = HAL_I2C_MODE_MEM;
1758 hi2c->ErrorCode = HAL_I2C_ERROR_NONE;
1760 /* Prepare transfer parameters */
1761 hi2c->pBuffPtr = pData;
1762 hi2c->XferCount = Size;
1763 hi2c->XferISR = NULL;
1765 /* Send Slave Address and Memory Address */
1766 if (I2C_RequestMemoryWrite(hi2c, DevAddress, MemAddress, MemAddSize, Timeout, tickstart) != HAL_OK)
1768 if (hi2c->ErrorCode == HAL_I2C_ERROR_AF)
1770 /* Process Unlocked */
1771 __HAL_UNLOCK(hi2c);
1772 return HAL_ERROR;
1774 else
1776 /* Process Unlocked */
1777 __HAL_UNLOCK(hi2c);
1778 return HAL_TIMEOUT;
1782 /* Set NBYTES to write and reload if hi2c->XferCount > MAX_NBYTE_SIZE */
1783 if (hi2c->XferCount > MAX_NBYTE_SIZE)
1785 hi2c->XferSize = MAX_NBYTE_SIZE;
1786 I2C_TransferConfig(hi2c, DevAddress, hi2c->XferSize, I2C_RELOAD_MODE, I2C_NO_STARTSTOP);
1788 else
1790 hi2c->XferSize = hi2c->XferCount;
1791 I2C_TransferConfig(hi2c, DevAddress, hi2c->XferSize, I2C_AUTOEND_MODE, I2C_NO_STARTSTOP);
1796 /* Wait until TXIS flag is set */
1797 if (I2C_WaitOnTXISFlagUntilTimeout(hi2c, Timeout, tickstart) != HAL_OK)
1799 if (hi2c->ErrorCode == HAL_I2C_ERROR_AF)
1801 return HAL_ERROR;
1803 else
1805 return HAL_TIMEOUT;
1809 /* Write data to TXDR */
1810 hi2c->Instance->TXDR = (*hi2c->pBuffPtr++);
1811 hi2c->XferCount--;
1812 hi2c->XferSize--;
1814 if ((hi2c->XferSize == 0U) && (hi2c->XferCount != 0U))
1816 /* Wait until TCR flag is set */
1817 if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_TCR, RESET, Timeout, tickstart) != HAL_OK)
1819 return HAL_TIMEOUT;
1822 if (hi2c->XferCount > MAX_NBYTE_SIZE)
1824 hi2c->XferSize = MAX_NBYTE_SIZE;
1825 I2C_TransferConfig(hi2c, DevAddress, hi2c->XferSize, I2C_RELOAD_MODE, I2C_NO_STARTSTOP);
1827 else
1829 hi2c->XferSize = hi2c->XferCount;
1830 I2C_TransferConfig(hi2c, DevAddress, hi2c->XferSize, I2C_AUTOEND_MODE, I2C_NO_STARTSTOP);
1835 while (hi2c->XferCount > 0U);
1837 /* No need to Check TC flag, with AUTOEND mode the stop is automatically generated */
1838 /* Wait until STOPF flag is reset */
1839 if (I2C_WaitOnSTOPFlagUntilTimeout(hi2c, Timeout, tickstart) != HAL_OK)
1841 if (hi2c->ErrorCode == HAL_I2C_ERROR_AF)
1843 return HAL_ERROR;
1845 else
1847 return HAL_TIMEOUT;
1851 /* Clear STOP Flag */
1852 __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_STOPF);
1854 /* Clear Configuration Register 2 */
1855 I2C_RESET_CR2(hi2c);
1857 hi2c->State = HAL_I2C_STATE_READY;
1858 hi2c->Mode = HAL_I2C_MODE_NONE;
1860 /* Process Unlocked */
1861 __HAL_UNLOCK(hi2c);
1863 return HAL_OK;
1865 else
1867 return HAL_BUSY;
1872 * @brief Read an amount of data in blocking mode from a specific memory address
1873 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
1874 * the configuration information for the specified I2C.
1875 * @param DevAddress Target device address: The device 7 bits address value
1876 * in datasheet must be shift at right before call interface
1877 * @param MemAddress Internal memory address
1878 * @param MemAddSize Size of internal memory address
1879 * @param pData Pointer to data buffer
1880 * @param Size Amount of data to be sent
1881 * @param Timeout Timeout duration
1882 * @retval HAL status
1884 HAL_StatusTypeDef HAL_I2C_Mem_Read(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint8_t *pData, uint16_t Size, uint32_t Timeout)
1886 uint32_t tickstart = 0U;
1888 /* Check the parameters */
1889 assert_param(IS_I2C_MEMADD_SIZE(MemAddSize));
1891 if (hi2c->State == HAL_I2C_STATE_READY)
1893 if ((pData == NULL) || (Size == 0U))
1895 return HAL_ERROR;
1898 /* Process Locked */
1899 __HAL_LOCK(hi2c);
1901 /* Init tickstart for timeout management*/
1902 tickstart = HAL_GetTick();
1904 if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_BUSY, SET, I2C_TIMEOUT_BUSY, tickstart) != HAL_OK)
1906 return HAL_TIMEOUT;
1909 hi2c->State = HAL_I2C_STATE_BUSY_RX;
1910 hi2c->Mode = HAL_I2C_MODE_MEM;
1911 hi2c->ErrorCode = HAL_I2C_ERROR_NONE;
1913 /* Prepare transfer parameters */
1914 hi2c->pBuffPtr = pData;
1915 hi2c->XferCount = Size;
1916 hi2c->XferISR = NULL;
1918 /* Send Slave Address and Memory Address */
1919 if (I2C_RequestMemoryRead(hi2c, DevAddress, MemAddress, MemAddSize, Timeout, tickstart) != HAL_OK)
1921 if (hi2c->ErrorCode == HAL_I2C_ERROR_AF)
1923 /* Process Unlocked */
1924 __HAL_UNLOCK(hi2c);
1925 return HAL_ERROR;
1927 else
1929 /* Process Unlocked */
1930 __HAL_UNLOCK(hi2c);
1931 return HAL_TIMEOUT;
1935 /* Send Slave Address */
1936 /* Set NBYTES to write and reload if hi2c->XferCount > MAX_NBYTE_SIZE and generate RESTART */
1937 if (hi2c->XferCount > MAX_NBYTE_SIZE)
1939 hi2c->XferSize = MAX_NBYTE_SIZE;
1940 I2C_TransferConfig(hi2c, DevAddress, hi2c->XferSize, I2C_RELOAD_MODE, I2C_GENERATE_START_READ);
1942 else
1944 hi2c->XferSize = hi2c->XferCount;
1945 I2C_TransferConfig(hi2c, DevAddress, hi2c->XferSize, I2C_AUTOEND_MODE, I2C_GENERATE_START_READ);
1950 /* Wait until RXNE flag is set */
1951 if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_RXNE, RESET, Timeout, tickstart) != HAL_OK)
1953 return HAL_TIMEOUT;
1956 /* Read data from RXDR */
1957 (*hi2c->pBuffPtr++) = hi2c->Instance->RXDR;
1958 hi2c->XferSize--;
1959 hi2c->XferCount--;
1961 if ((hi2c->XferSize == 0U) && (hi2c->XferCount != 0U))
1963 /* Wait until TCR flag is set */
1964 if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_TCR, RESET, Timeout, tickstart) != HAL_OK)
1966 return HAL_TIMEOUT;
1969 if (hi2c->XferCount > MAX_NBYTE_SIZE)
1971 hi2c->XferSize = MAX_NBYTE_SIZE;
1972 I2C_TransferConfig(hi2c, DevAddress, hi2c->XferSize, I2C_RELOAD_MODE, I2C_NO_STARTSTOP);
1974 else
1976 hi2c->XferSize = hi2c->XferCount;
1977 I2C_TransferConfig(hi2c, DevAddress, hi2c->XferSize, I2C_AUTOEND_MODE, I2C_NO_STARTSTOP);
1981 while (hi2c->XferCount > 0U);
1983 /* No need to Check TC flag, with AUTOEND mode the stop is automatically generated */
1984 /* Wait until STOPF flag is reset */
1985 if (I2C_WaitOnSTOPFlagUntilTimeout(hi2c, Timeout, tickstart) != HAL_OK)
1987 if (hi2c->ErrorCode == HAL_I2C_ERROR_AF)
1989 return HAL_ERROR;
1991 else
1993 return HAL_TIMEOUT;
1997 /* Clear STOP Flag */
1998 __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_STOPF);
2000 /* Clear Configuration Register 2 */
2001 I2C_RESET_CR2(hi2c);
2003 hi2c->State = HAL_I2C_STATE_READY;
2004 hi2c->Mode = HAL_I2C_MODE_NONE;
2006 /* Process Unlocked */
2007 __HAL_UNLOCK(hi2c);
2009 return HAL_OK;
2011 else
2013 return HAL_BUSY;
2017 * @brief Write an amount of data in non-blocking mode with Interrupt to a specific memory address
2018 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
2019 * the configuration information for the specified I2C.
2020 * @param DevAddress Target device address: The device 7 bits address value
2021 * in datasheet must be shift at right before call interface
2022 * @param MemAddress Internal memory address
2023 * @param MemAddSize Size of internal memory address
2024 * @param pData Pointer to data buffer
2025 * @param Size Amount of data to be sent
2026 * @retval HAL status
2028 HAL_StatusTypeDef HAL_I2C_Mem_Write_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint8_t *pData, uint16_t Size)
2030 uint32_t tickstart = 0U;
2031 uint32_t xfermode = 0U;
2033 /* Check the parameters */
2034 assert_param(IS_I2C_MEMADD_SIZE(MemAddSize));
2036 if (hi2c->State == HAL_I2C_STATE_READY)
2038 if ((pData == NULL) || (Size == 0U))
2040 return HAL_ERROR;
2043 if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BUSY) == SET)
2045 return HAL_BUSY;
2048 /* Process Locked */
2049 __HAL_LOCK(hi2c);
2051 /* Init tickstart for timeout management*/
2052 tickstart = HAL_GetTick();
2054 hi2c->State = HAL_I2C_STATE_BUSY_TX;
2055 hi2c->Mode = HAL_I2C_MODE_MEM;
2056 hi2c->ErrorCode = HAL_I2C_ERROR_NONE;
2058 /* Prepare transfer parameters */
2059 hi2c->pBuffPtr = pData;
2060 hi2c->XferCount = Size;
2061 hi2c->XferOptions = I2C_NO_OPTION_FRAME;
2062 hi2c->XferISR = I2C_Master_ISR_IT;
2064 if (hi2c->XferCount > MAX_NBYTE_SIZE)
2066 hi2c->XferSize = MAX_NBYTE_SIZE;
2067 xfermode = I2C_RELOAD_MODE;
2069 else
2071 hi2c->XferSize = hi2c->XferCount;
2072 xfermode = I2C_AUTOEND_MODE;
2075 /* Send Slave Address and Memory Address */
2076 if (I2C_RequestMemoryWrite(hi2c, DevAddress, MemAddress, MemAddSize, I2C_TIMEOUT_FLAG, tickstart) != HAL_OK)
2078 if (hi2c->ErrorCode == HAL_I2C_ERROR_AF)
2080 /* Process Unlocked */
2081 __HAL_UNLOCK(hi2c);
2082 return HAL_ERROR;
2084 else
2086 /* Process Unlocked */
2087 __HAL_UNLOCK(hi2c);
2088 return HAL_TIMEOUT;
2092 /* Set NBYTES to write and reload if hi2c->XferCount > MAX_NBYTE_SIZE and generate RESTART */
2093 I2C_TransferConfig(hi2c, DevAddress, hi2c->XferSize, xfermode, I2C_NO_STARTSTOP);
2095 /* Process Unlocked */
2096 __HAL_UNLOCK(hi2c);
2098 /* Note : The I2C interrupts must be enabled after unlocking current process
2099 to avoid the risk of I2C interrupt handle execution before current
2100 process unlock */
2102 /* Enable ERR, TC, STOP, NACK, TXI interrupt */
2103 /* possible to enable all of these */
2104 /* I2C_IT_ERRI | I2C_IT_TCI| I2C_IT_STOPI| I2C_IT_NACKI | I2C_IT_ADDRI | I2C_IT_RXI | I2C_IT_TXI */
2105 I2C_Enable_IRQ(hi2c, I2C_XFER_TX_IT);
2107 return HAL_OK;
2109 else
2111 return HAL_BUSY;
2116 * @brief Read an amount of data in non-blocking mode with Interrupt from a specific memory address
2117 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
2118 * the configuration information for the specified I2C.
2119 * @param DevAddress Target device address: The device 7 bits address value
2120 * in datasheet must be shift at right before call interface
2121 * @param MemAddress Internal memory address
2122 * @param MemAddSize Size of internal memory address
2123 * @param pData Pointer to data buffer
2124 * @param Size Amount of data to be sent
2125 * @retval HAL status
2127 HAL_StatusTypeDef HAL_I2C_Mem_Read_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint8_t *pData, uint16_t Size)
2129 uint32_t tickstart = 0U;
2130 uint32_t xfermode = 0U;
2132 /* Check the parameters */
2133 assert_param(IS_I2C_MEMADD_SIZE(MemAddSize));
2135 if (hi2c->State == HAL_I2C_STATE_READY)
2137 if ((pData == NULL) || (Size == 0U))
2139 return HAL_ERROR;
2142 if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BUSY) == SET)
2144 return HAL_BUSY;
2147 /* Process Locked */
2148 __HAL_LOCK(hi2c);
2150 /* Init tickstart for timeout management*/
2151 tickstart = HAL_GetTick();
2153 hi2c->State = HAL_I2C_STATE_BUSY_RX;
2154 hi2c->Mode = HAL_I2C_MODE_MEM;
2155 hi2c->ErrorCode = HAL_I2C_ERROR_NONE;
2157 /* Prepare transfer parameters */
2158 hi2c->pBuffPtr = pData;
2159 hi2c->XferCount = Size;
2160 hi2c->XferOptions = I2C_NO_OPTION_FRAME;
2161 hi2c->XferISR = I2C_Master_ISR_IT;
2163 if (hi2c->XferCount > MAX_NBYTE_SIZE)
2165 hi2c->XferSize = MAX_NBYTE_SIZE;
2166 xfermode = I2C_RELOAD_MODE;
2168 else
2170 hi2c->XferSize = hi2c->XferCount;
2171 xfermode = I2C_AUTOEND_MODE;
2174 /* Send Slave Address and Memory Address */
2175 if (I2C_RequestMemoryRead(hi2c, DevAddress, MemAddress, MemAddSize, I2C_TIMEOUT_FLAG, tickstart) != HAL_OK)
2177 if (hi2c->ErrorCode == HAL_I2C_ERROR_AF)
2179 /* Process Unlocked */
2180 __HAL_UNLOCK(hi2c);
2181 return HAL_ERROR;
2183 else
2185 /* Process Unlocked */
2186 __HAL_UNLOCK(hi2c);
2187 return HAL_TIMEOUT;
2191 /* Set NBYTES to write and reload if hi2c->XferCount > MAX_NBYTE_SIZE and generate RESTART */
2192 I2C_TransferConfig(hi2c, DevAddress, hi2c->XferSize, xfermode, I2C_GENERATE_START_READ);
2194 /* Process Unlocked */
2195 __HAL_UNLOCK(hi2c);
2197 /* Note : The I2C interrupts must be enabled after unlocking current process
2198 to avoid the risk of I2C interrupt handle execution before current
2199 process unlock */
2201 /* Enable ERR, TC, STOP, NACK, RXI interrupt */
2202 /* possible to enable all of these */
2203 /* I2C_IT_ERRI | I2C_IT_TCI| I2C_IT_STOPI| I2C_IT_NACKI | I2C_IT_ADDRI | I2C_IT_RXI | I2C_IT_TXI */
2204 I2C_Enable_IRQ(hi2c, I2C_XFER_RX_IT);
2206 return HAL_OK;
2208 else
2210 return HAL_BUSY;
2214 * @brief Write an amount of data in non-blocking mode with DMA to a specific memory address
2215 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
2216 * the configuration information for the specified I2C.
2217 * @param DevAddress Target device address: The device 7 bits address value
2218 * in datasheet must be shift at right before call interface
2219 * @param MemAddress Internal memory address
2220 * @param MemAddSize Size of internal memory address
2221 * @param pData Pointer to data buffer
2222 * @param Size Amount of data to be sent
2223 * @retval HAL status
2225 HAL_StatusTypeDef HAL_I2C_Mem_Write_DMA(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint8_t *pData, uint16_t Size)
2227 uint32_t tickstart = 0U;
2228 uint32_t xfermode = 0U;
2230 /* Check the parameters */
2231 assert_param(IS_I2C_MEMADD_SIZE(MemAddSize));
2233 if (hi2c->State == HAL_I2C_STATE_READY)
2235 if ((pData == NULL) || (Size == 0U))
2237 return HAL_ERROR;
2240 if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BUSY) == SET)
2242 return HAL_BUSY;
2245 /* Process Locked */
2246 __HAL_LOCK(hi2c);
2248 /* Init tickstart for timeout management*/
2249 tickstart = HAL_GetTick();
2251 hi2c->State = HAL_I2C_STATE_BUSY_TX;
2252 hi2c->Mode = HAL_I2C_MODE_MEM;
2253 hi2c->ErrorCode = HAL_I2C_ERROR_NONE;
2255 /* Prepare transfer parameters */
2256 hi2c->pBuffPtr = pData;
2257 hi2c->XferCount = Size;
2258 hi2c->XferOptions = I2C_NO_OPTION_FRAME;
2259 hi2c->XferISR = I2C_Master_ISR_DMA;
2261 if (hi2c->XferCount > MAX_NBYTE_SIZE)
2263 hi2c->XferSize = MAX_NBYTE_SIZE;
2264 xfermode = I2C_RELOAD_MODE;
2266 else
2268 hi2c->XferSize = hi2c->XferCount;
2269 xfermode = I2C_AUTOEND_MODE;
2272 /* Send Slave Address and Memory Address */
2273 if (I2C_RequestMemoryWrite(hi2c, DevAddress, MemAddress, MemAddSize, I2C_TIMEOUT_FLAG, tickstart) != HAL_OK)
2275 if (hi2c->ErrorCode == HAL_I2C_ERROR_AF)
2277 /* Process Unlocked */
2278 __HAL_UNLOCK(hi2c);
2279 return HAL_ERROR;
2281 else
2283 /* Process Unlocked */
2284 __HAL_UNLOCK(hi2c);
2285 return HAL_TIMEOUT;
2289 /* Set the I2C DMA transfer complete callback */
2290 hi2c->hdmatx->XferCpltCallback = I2C_DMAMasterTransmitCplt;
2292 /* Set the DMA error callback */
2293 hi2c->hdmatx->XferErrorCallback = I2C_DMAError;
2295 /* Set the unused DMA callbacks to NULL */
2296 hi2c->hdmatx->XferHalfCpltCallback = NULL;
2297 hi2c->hdmatx->XferAbortCallback = NULL;
2299 /* Enable the DMA channel */
2300 HAL_DMA_Start_IT(hi2c->hdmatx, (uint32_t)pData, (uint32_t)&hi2c->Instance->TXDR, hi2c->XferSize);
2302 /* Send Slave Address */
2303 /* Set NBYTES to write and reload if hi2c->XferCount > MAX_NBYTE_SIZE and generate RESTART */
2304 I2C_TransferConfig(hi2c, DevAddress, hi2c->XferSize, xfermode, I2C_NO_STARTSTOP);
2306 /* Update XferCount value */
2307 hi2c->XferCount -= hi2c->XferSize;
2309 /* Process Unlocked */
2310 __HAL_UNLOCK(hi2c);
2312 /* Note : The I2C interrupts must be enabled after unlocking current process
2313 to avoid the risk of I2C interrupt handle execution before current
2314 process unlock */
2315 /* Enable ERR and NACK interrupts */
2316 I2C_Enable_IRQ(hi2c, I2C_XFER_ERROR_IT);
2318 /* Enable DMA Request */
2319 hi2c->Instance->CR1 |= I2C_CR1_TXDMAEN;
2321 return HAL_OK;
2323 else
2325 return HAL_BUSY;
2330 * @brief Reads an amount of data in non-blocking mode with DMA from a specific memory address.
2331 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
2332 * the configuration information for the specified I2C.
2333 * @param DevAddress Target device address: The device 7 bits address value
2334 * in datasheet must be shift at right before call interface
2335 * @param MemAddress Internal memory address
2336 * @param MemAddSize Size of internal memory address
2337 * @param pData Pointer to data buffer
2338 * @param Size Amount of data to be read
2339 * @retval HAL status
2341 HAL_StatusTypeDef HAL_I2C_Mem_Read_DMA(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint8_t *pData, uint16_t Size)
2343 uint32_t tickstart = 0U;
2344 uint32_t xfermode = 0U;
2346 /* Check the parameters */
2347 assert_param(IS_I2C_MEMADD_SIZE(MemAddSize));
2349 if (hi2c->State == HAL_I2C_STATE_READY)
2351 if ((pData == NULL) || (Size == 0U))
2353 return HAL_ERROR;
2356 if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BUSY) == SET)
2358 return HAL_BUSY;
2361 /* Process Locked */
2362 __HAL_LOCK(hi2c);
2364 /* Init tickstart for timeout management*/
2365 tickstart = HAL_GetTick();
2367 hi2c->State = HAL_I2C_STATE_BUSY_RX;
2368 hi2c->Mode = HAL_I2C_MODE_MEM;
2369 hi2c->ErrorCode = HAL_I2C_ERROR_NONE;
2371 /* Prepare transfer parameters */
2372 hi2c->pBuffPtr = pData;
2373 hi2c->XferCount = Size;
2374 hi2c->XferOptions = I2C_NO_OPTION_FRAME;
2375 hi2c->XferISR = I2C_Master_ISR_DMA;
2377 if (hi2c->XferCount > MAX_NBYTE_SIZE)
2379 hi2c->XferSize = MAX_NBYTE_SIZE;
2380 xfermode = I2C_RELOAD_MODE;
2382 else
2384 hi2c->XferSize = hi2c->XferCount;
2385 xfermode = I2C_AUTOEND_MODE;
2388 /* Send Slave Address and Memory Address */
2389 if (I2C_RequestMemoryRead(hi2c, DevAddress, MemAddress, MemAddSize, I2C_TIMEOUT_FLAG, tickstart) != HAL_OK)
2391 if (hi2c->ErrorCode == HAL_I2C_ERROR_AF)
2393 /* Process Unlocked */
2394 __HAL_UNLOCK(hi2c);
2395 return HAL_ERROR;
2397 else
2399 /* Process Unlocked */
2400 __HAL_UNLOCK(hi2c);
2401 return HAL_TIMEOUT;
2405 /* Set the I2C DMA transfer complete callback */
2406 hi2c->hdmarx->XferCpltCallback = I2C_DMAMasterReceiveCplt;
2408 /* Set the DMA error callback */
2409 hi2c->hdmarx->XferErrorCallback = I2C_DMAError;
2411 /* Set the unused DMA callbacks to NULL */
2412 hi2c->hdmarx->XferHalfCpltCallback = NULL;
2413 hi2c->hdmarx->XferAbortCallback = NULL;
2415 /* Enable the DMA channel */
2416 HAL_DMA_Start_IT(hi2c->hdmarx, (uint32_t)&hi2c->Instance->RXDR, (uint32_t)pData, hi2c->XferSize);
2418 /* Set NBYTES to write and reload if hi2c->XferCount > MAX_NBYTE_SIZE and generate RESTART */
2419 I2C_TransferConfig(hi2c, DevAddress, hi2c->XferSize, xfermode, I2C_GENERATE_START_READ);
2421 /* Update XferCount value */
2422 hi2c->XferCount -= hi2c->XferSize;
2424 /* Process Unlocked */
2425 __HAL_UNLOCK(hi2c);
2427 /* Enable DMA Request */
2428 hi2c->Instance->CR1 |= I2C_CR1_RXDMAEN;
2430 /* Note : The I2C interrupts must be enabled after unlocking current process
2431 to avoid the risk of I2C interrupt handle execution before current
2432 process unlock */
2433 /* Enable ERR and NACK interrupts */
2434 I2C_Enable_IRQ(hi2c, I2C_XFER_ERROR_IT);
2436 return HAL_OK;
2438 else
2440 return HAL_BUSY;
2445 * @brief Checks if target device is ready for communication.
2446 * @note This function is used with Memory devices
2447 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
2448 * the configuration information for the specified I2C.
2449 * @param DevAddress Target device address: The device 7 bits address value
2450 * in datasheet must be shift at right before call interface
2451 * @param Trials Number of trials
2452 * @param Timeout Timeout duration
2453 * @retval HAL status
2455 HAL_StatusTypeDef HAL_I2C_IsDeviceReady(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint32_t Trials, uint32_t Timeout)
2457 uint32_t tickstart = 0U;
2459 __IO uint32_t I2C_Trials = 0U;
2461 if (hi2c->State == HAL_I2C_STATE_READY)
2463 if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BUSY) == SET)
2465 return HAL_BUSY;
2468 /* Process Locked */
2469 __HAL_LOCK(hi2c);
2471 hi2c->State = HAL_I2C_STATE_BUSY;
2472 hi2c->ErrorCode = HAL_I2C_ERROR_NONE;
2476 /* Generate Start */
2477 hi2c->Instance->CR2 = I2C_GENERATE_START(hi2c->Init.AddressingMode, DevAddress);
2479 /* No need to Check TC flag, with AUTOEND mode the stop is automatically generated */
2480 /* Wait until STOPF flag is set or a NACK flag is set*/
2481 tickstart = HAL_GetTick();
2482 while ((__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_STOPF) == RESET) && (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_AF) == RESET) && (hi2c->State != HAL_I2C_STATE_TIMEOUT))
2484 if (Timeout != HAL_MAX_DELAY)
2486 if ((Timeout == 0U) || ((HAL_GetTick() - tickstart) > Timeout))
2488 /* Device is ready */
2489 hi2c->State = HAL_I2C_STATE_READY;
2490 /* Process Unlocked */
2491 __HAL_UNLOCK(hi2c);
2492 return HAL_TIMEOUT;
2497 /* Check if the NACKF flag has not been set */
2498 if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_AF) == RESET)
2500 /* Wait until STOPF flag is reset */
2501 if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_STOPF, RESET, Timeout, tickstart) != HAL_OK)
2503 return HAL_TIMEOUT;
2506 /* Clear STOP Flag */
2507 __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_STOPF);
2509 /* Device is ready */
2510 hi2c->State = HAL_I2C_STATE_READY;
2512 /* Process Unlocked */
2513 __HAL_UNLOCK(hi2c);
2515 return HAL_OK;
2517 else
2519 /* Wait until STOPF flag is reset */
2520 if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_STOPF, RESET, Timeout, tickstart) != HAL_OK)
2522 return HAL_TIMEOUT;
2525 /* Clear NACK Flag */
2526 __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_AF);
2528 /* Clear STOP Flag, auto generated with autoend*/
2529 __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_STOPF);
2532 /* Check if the maximum allowed number of trials has been reached */
2533 if (I2C_Trials++ == Trials)
2535 /* Generate Stop */
2536 hi2c->Instance->CR2 |= I2C_CR2_STOP;
2538 /* Wait until STOPF flag is reset */
2539 if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_STOPF, RESET, Timeout, tickstart) != HAL_OK)
2541 return HAL_TIMEOUT;
2544 /* Clear STOP Flag */
2545 __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_STOPF);
2548 while (I2C_Trials < Trials);
2550 hi2c->State = HAL_I2C_STATE_READY;
2552 /* Process Unlocked */
2553 __HAL_UNLOCK(hi2c);
2555 return HAL_TIMEOUT;
2557 else
2559 return HAL_BUSY;
2564 * @brief Sequential transmit in master I2C mode an amount of data in non-blocking mode with Interrupt.
2565 * @note This interface allow to manage repeated start condition when a direction change during transfer
2566 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
2567 * the configuration information for the specified I2C.
2568 * @param DevAddress Target device address: The device 7 bits address value
2569 * in datasheet must be shift at right before call interface
2570 * @param pData Pointer to data buffer
2571 * @param Size Amount of data to be sent
2572 * @param XferOptions Options of Transfer, value of @ref I2C_XFEROPTIONS
2573 * @retval HAL status
2575 HAL_StatusTypeDef HAL_I2C_Master_Sequential_Transmit_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size, uint32_t XferOptions)
2577 uint32_t xfermode = 0U;
2578 uint32_t xferrequest = I2C_GENERATE_START_WRITE;
2580 /* Check the parameters */
2581 assert_param(IS_I2C_TRANSFER_OPTIONS_REQUEST(XferOptions));
2583 if (hi2c->State == HAL_I2C_STATE_READY)
2585 /* Process Locked */
2586 __HAL_LOCK(hi2c);
2588 hi2c->State = HAL_I2C_STATE_BUSY_TX;
2589 hi2c->Mode = HAL_I2C_MODE_MASTER;
2590 hi2c->ErrorCode = HAL_I2C_ERROR_NONE;
2592 /* Prepare transfer parameters */
2593 hi2c->pBuffPtr = pData;
2594 hi2c->XferCount = Size;
2595 hi2c->XferOptions = XferOptions;
2596 hi2c->XferISR = I2C_Master_ISR_IT;
2598 /* If size > MAX_NBYTE_SIZE, use reload mode */
2599 if (hi2c->XferCount > MAX_NBYTE_SIZE)
2601 hi2c->XferSize = MAX_NBYTE_SIZE;
2602 xfermode = I2C_RELOAD_MODE;
2604 else
2606 hi2c->XferSize = hi2c->XferCount;
2607 xfermode = hi2c->XferOptions;
2610 /* If transfer direction not change, do not generate Restart Condition */
2611 /* Mean Previous state is same as current state */
2612 if (hi2c->PreviousState == I2C_STATE_MASTER_BUSY_TX)
2614 xferrequest = I2C_NO_STARTSTOP;
2617 /* Send Slave Address and set NBYTES to write */
2618 I2C_TransferConfig(hi2c, DevAddress, hi2c->XferSize, xfermode, xferrequest);
2620 /* Process Unlocked */
2621 __HAL_UNLOCK(hi2c);
2623 /* Note : The I2C interrupts must be enabled after unlocking current process
2624 to avoid the risk of I2C interrupt handle execution before current
2625 process unlock */
2626 I2C_Enable_IRQ(hi2c, I2C_XFER_TX_IT);
2628 return HAL_OK;
2630 else
2632 return HAL_BUSY;
2637 * @brief Sequential receive in master I2C mode an amount of data in non-blocking mode with Interrupt
2638 * @note This interface allow to manage repeated start condition when a direction change during transfer
2639 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
2640 * the configuration information for the specified I2C.
2641 * @param DevAddress Target device address: The device 7 bits address value
2642 * in datasheet must be shift at right before call interface
2643 * @param pData Pointer to data buffer
2644 * @param Size Amount of data to be sent
2645 * @param XferOptions Options of Transfer, value of @ref I2C_XFEROPTIONS
2646 * @retval HAL status
2648 HAL_StatusTypeDef HAL_I2C_Master_Sequential_Receive_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size, uint32_t XferOptions)
2650 uint32_t xfermode = 0U;
2651 uint32_t xferrequest = I2C_GENERATE_START_READ;
2653 /* Check the parameters */
2654 assert_param(IS_I2C_TRANSFER_OPTIONS_REQUEST(XferOptions));
2656 if (hi2c->State == HAL_I2C_STATE_READY)
2658 /* Process Locked */
2659 __HAL_LOCK(hi2c);
2661 hi2c->State = HAL_I2C_STATE_BUSY_RX;
2662 hi2c->Mode = HAL_I2C_MODE_MASTER;
2663 hi2c->ErrorCode = HAL_I2C_ERROR_NONE;
2665 /* Prepare transfer parameters */
2666 hi2c->pBuffPtr = pData;
2667 hi2c->XferCount = Size;
2668 hi2c->XferOptions = XferOptions;
2669 hi2c->XferISR = I2C_Master_ISR_IT;
2671 /* If hi2c->XferCount > MAX_NBYTE_SIZE, use reload mode */
2672 if (hi2c->XferCount > MAX_NBYTE_SIZE)
2674 hi2c->XferSize = MAX_NBYTE_SIZE;
2675 xfermode = I2C_RELOAD_MODE;
2677 else
2679 hi2c->XferSize = hi2c->XferCount;
2680 xfermode = hi2c->XferOptions;
2683 /* If transfer direction not change, do not generate Restart Condition */
2684 /* Mean Previous state is same as current state */
2685 if (hi2c->PreviousState == I2C_STATE_MASTER_BUSY_RX)
2687 xferrequest = I2C_NO_STARTSTOP;
2690 /* Send Slave Address and set NBYTES to read */
2691 I2C_TransferConfig(hi2c, DevAddress, hi2c->XferSize, xfermode, xferrequest);
2693 /* Process Unlocked */
2694 __HAL_UNLOCK(hi2c);
2696 /* Note : The I2C interrupts must be enabled after unlocking current process
2697 to avoid the risk of I2C interrupt handle execution before current
2698 process unlock */
2699 I2C_Enable_IRQ(hi2c, I2C_XFER_RX_IT);
2701 return HAL_OK;
2703 else
2705 return HAL_BUSY;
2710 * @brief Sequential transmit in slave/device I2C mode an amount of data in non-blocking mode with Interrupt
2711 * @note This interface allow to manage repeated start condition when a direction change during transfer
2712 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
2713 * the configuration information for the specified I2C.
2714 * @param pData Pointer to data buffer
2715 * @param Size Amount of data to be sent
2716 * @param XferOptions Options of Transfer, value of @ref I2C_XFEROPTIONS
2717 * @retval HAL status
2719 HAL_StatusTypeDef HAL_I2C_Slave_Sequential_Transmit_IT(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size, uint32_t XferOptions)
2721 /* Check the parameters */
2722 assert_param(IS_I2C_TRANSFER_OPTIONS_REQUEST(XferOptions));
2724 if ((hi2c->State & HAL_I2C_STATE_LISTEN) == HAL_I2C_STATE_LISTEN)
2726 if ((pData == NULL) || (Size == 0U))
2728 return HAL_ERROR;
2731 /* Disable Interrupts, to prevent preemption during treatment in case of multicall */
2732 I2C_Disable_IRQ(hi2c, I2C_XFER_LISTEN_IT | I2C_XFER_TX_IT);
2734 /* Process Locked */
2735 __HAL_LOCK(hi2c);
2737 /* I2C cannot manage full duplex exchange so disable previous IT enabled if any */
2738 /* and then toggle the HAL slave RX state to TX state */
2739 if (hi2c->State == HAL_I2C_STATE_BUSY_RX_LISTEN)
2741 /* Disable associated Interrupts */
2742 I2C_Disable_IRQ(hi2c, I2C_XFER_RX_IT);
2745 hi2c->State = HAL_I2C_STATE_BUSY_TX_LISTEN;
2746 hi2c->Mode = HAL_I2C_MODE_SLAVE;
2747 hi2c->ErrorCode = HAL_I2C_ERROR_NONE;
2749 /* Enable Address Acknowledge */
2750 hi2c->Instance->CR2 &= ~I2C_CR2_NACK;
2752 /* Prepare transfer parameters */
2753 hi2c->pBuffPtr = pData;
2754 hi2c->XferCount = Size;
2755 hi2c->XferSize = hi2c->XferCount;
2756 hi2c->XferOptions = XferOptions;
2757 hi2c->XferISR = I2C_Slave_ISR_IT;
2759 if (I2C_GET_DIR(hi2c) == I2C_DIRECTION_RECEIVE)
2761 /* Clear ADDR flag after prepare the transfer parameters */
2762 /* This action will generate an acknowledge to the Master */
2763 __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_ADDR);
2766 /* Process Unlocked */
2767 __HAL_UNLOCK(hi2c);
2769 /* Note : The I2C interrupts must be enabled after unlocking current process
2770 to avoid the risk of I2C interrupt handle execution before current
2771 process unlock */
2772 /* REnable ADDR interrupt */
2773 I2C_Enable_IRQ(hi2c, I2C_XFER_TX_IT | I2C_XFER_LISTEN_IT);
2775 return HAL_OK;
2777 else
2779 return HAL_ERROR;
2784 * @brief Sequential receive in slave/device I2C mode an amount of data in non-blocking mode with Interrupt
2785 * @note This interface allow to manage repeated start condition when a direction change during transfer
2786 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
2787 * the configuration information for the specified I2C.
2788 * @param pData Pointer to data buffer
2789 * @param Size Amount of data to be sent
2790 * @param XferOptions Options of Transfer, value of @ref I2C_XFEROPTIONS
2791 * @retval HAL status
2793 HAL_StatusTypeDef HAL_I2C_Slave_Sequential_Receive_IT(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size, uint32_t XferOptions)
2795 /* Check the parameters */
2796 assert_param(IS_I2C_TRANSFER_OPTIONS_REQUEST(XferOptions));
2798 if ((hi2c->State & HAL_I2C_STATE_LISTEN) == HAL_I2C_STATE_LISTEN)
2800 if ((pData == NULL) || (Size == 0U))
2802 return HAL_ERROR;
2805 /* Disable Interrupts, to prevent preemption during treatment in case of multicall */
2806 I2C_Disable_IRQ(hi2c, I2C_XFER_LISTEN_IT | I2C_XFER_RX_IT);
2808 /* Process Locked */
2809 __HAL_LOCK(hi2c);
2811 /* I2C cannot manage full duplex exchange so disable previous IT enabled if any */
2812 /* and then toggle the HAL slave TX state to RX state */
2813 if (hi2c->State == HAL_I2C_STATE_BUSY_TX_LISTEN)
2815 /* Disable associated Interrupts */
2816 I2C_Disable_IRQ(hi2c, I2C_XFER_TX_IT);
2819 hi2c->State = HAL_I2C_STATE_BUSY_RX_LISTEN;
2820 hi2c->Mode = HAL_I2C_MODE_SLAVE;
2821 hi2c->ErrorCode = HAL_I2C_ERROR_NONE;
2823 /* Enable Address Acknowledge */
2824 hi2c->Instance->CR2 &= ~I2C_CR2_NACK;
2826 /* Prepare transfer parameters */
2827 hi2c->pBuffPtr = pData;
2828 hi2c->XferCount = Size;
2829 hi2c->XferSize = hi2c->XferCount;
2830 hi2c->XferOptions = XferOptions;
2831 hi2c->XferISR = I2C_Slave_ISR_IT;
2833 if (I2C_GET_DIR(hi2c) == I2C_DIRECTION_TRANSMIT)
2835 /* Clear ADDR flag after prepare the transfer parameters */
2836 /* This action will generate an acknowledge to the Master */
2837 __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_ADDR);
2840 /* Process Unlocked */
2841 __HAL_UNLOCK(hi2c);
2843 /* Note : The I2C interrupts must be enabled after unlocking current process
2844 to avoid the risk of I2C interrupt handle execution before current
2845 process unlock */
2846 /* REnable ADDR interrupt */
2847 I2C_Enable_IRQ(hi2c, I2C_XFER_RX_IT | I2C_XFER_LISTEN_IT);
2849 return HAL_OK;
2851 else
2853 return HAL_ERROR;
2858 * @brief Enable the Address listen mode with Interrupt.
2859 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
2860 * the configuration information for the specified I2C.
2861 * @retval HAL status
2863 HAL_StatusTypeDef HAL_I2C_EnableListen_IT(I2C_HandleTypeDef *hi2c)
2865 if (hi2c->State == HAL_I2C_STATE_READY)
2867 hi2c->State = HAL_I2C_STATE_LISTEN;
2868 hi2c->XferISR = I2C_Slave_ISR_IT;
2870 /* Enable the Address Match interrupt */
2871 I2C_Enable_IRQ(hi2c, I2C_XFER_LISTEN_IT);
2873 return HAL_OK;
2875 else
2877 return HAL_BUSY;
2882 * @brief Disable the Address listen mode with Interrupt.
2883 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
2884 * the configuration information for the specified I2C
2885 * @retval HAL status
2887 HAL_StatusTypeDef HAL_I2C_DisableListen_IT(I2C_HandleTypeDef *hi2c)
2889 /* Declaration of tmp to prevent undefined behavior of volatile usage */
2890 uint32_t tmp;
2892 /* Disable Address listen mode only if a transfer is not ongoing */
2893 if (hi2c->State == HAL_I2C_STATE_LISTEN)
2895 tmp = (uint32_t)(hi2c->State) & I2C_STATE_MSK;
2896 hi2c->PreviousState = tmp | (uint32_t)(hi2c->Mode);
2897 hi2c->State = HAL_I2C_STATE_READY;
2898 hi2c->Mode = HAL_I2C_MODE_NONE;
2899 hi2c->XferISR = NULL;
2901 /* Disable the Address Match interrupt */
2902 I2C_Disable_IRQ(hi2c, I2C_XFER_LISTEN_IT);
2904 return HAL_OK;
2906 else
2908 return HAL_BUSY;
2913 * @brief Abort a master I2C IT or DMA process communication with Interrupt.
2914 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
2915 * the configuration information for the specified I2C.
2916 * @param DevAddress Target device address: The device 7 bits address value
2917 * in datasheet must be shift at right before call interface
2918 * @retval HAL status
2920 HAL_StatusTypeDef HAL_I2C_Master_Abort_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress)
2922 if (hi2c->Mode == HAL_I2C_MODE_MASTER)
2924 /* Process Locked */
2925 __HAL_LOCK(hi2c);
2927 /* Disable Interrupts */
2928 I2C_Disable_IRQ(hi2c, I2C_XFER_RX_IT);
2929 I2C_Disable_IRQ(hi2c, I2C_XFER_TX_IT);
2931 /* Set State at HAL_I2C_STATE_ABORT */
2932 hi2c->State = HAL_I2C_STATE_ABORT;
2934 /* Set NBYTES to 1 to generate a dummy read on I2C peripheral */
2935 /* Set AUTOEND mode, this will generate a NACK then STOP condition to abort the current transfer */
2936 I2C_TransferConfig(hi2c, DevAddress, 1, I2C_AUTOEND_MODE, I2C_GENERATE_STOP);
2938 /* Process Unlocked */
2939 __HAL_UNLOCK(hi2c);
2941 /* Note : The I2C interrupts must be enabled after unlocking current process
2942 to avoid the risk of I2C interrupt handle execution before current
2943 process unlock */
2944 I2C_Enable_IRQ(hi2c, I2C_XFER_CPLT_IT);
2946 return HAL_OK;
2948 else
2950 /* Wrong usage of abort function */
2951 /* This function should be used only in case of abort monitored by master device */
2952 return HAL_ERROR;
2957 * @}
2960 /** @defgroup I2C_IRQ_Handler_and_Callbacks IRQ Handler and Callbacks
2961 * @{
2965 * @brief This function handles I2C event interrupt request.
2966 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
2967 * the configuration information for the specified I2C.
2968 * @retval None
2970 void HAL_I2C_EV_IRQHandler(I2C_HandleTypeDef *hi2c)
2972 /* Get current IT Flags and IT sources value */
2973 uint32_t itflags = READ_REG(hi2c->Instance->ISR);
2974 uint32_t itsources = READ_REG(hi2c->Instance->CR1);
2976 /* I2C events treatment -------------------------------------*/
2977 if (hi2c->XferISR != NULL)
2979 hi2c->XferISR(hi2c, itflags, itsources);
2984 * @brief This function handles I2C error interrupt request.
2985 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
2986 * the configuration information for the specified I2C.
2987 * @retval None
2989 void HAL_I2C_ER_IRQHandler(I2C_HandleTypeDef *hi2c)
2991 uint32_t itflags = READ_REG(hi2c->Instance->ISR);
2992 uint32_t itsources = READ_REG(hi2c->Instance->CR1);
2994 /* I2C Bus error interrupt occurred ------------------------------------*/
2995 if (((itflags & I2C_FLAG_BERR) != RESET) && ((itsources & I2C_IT_ERRI) != RESET))
2997 hi2c->ErrorCode |= HAL_I2C_ERROR_BERR;
2999 /* Clear BERR flag */
3000 __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_BERR);
3003 /* I2C Over-Run/Under-Run interrupt occurred ----------------------------------------*/
3004 if (((itflags & I2C_FLAG_OVR) != RESET) && ((itsources & I2C_IT_ERRI) != RESET))
3006 hi2c->ErrorCode |= HAL_I2C_ERROR_OVR;
3008 /* Clear OVR flag */
3009 __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_OVR);
3012 /* I2C Arbitration Loss error interrupt occurred -------------------------------------*/
3013 if (((itflags & I2C_FLAG_ARLO) != RESET) && ((itsources & I2C_IT_ERRI) != RESET))
3015 hi2c->ErrorCode |= HAL_I2C_ERROR_ARLO;
3017 /* Clear ARLO flag */
3018 __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_ARLO);
3021 /* Call the Error Callback in case of Error detected */
3022 if ((hi2c->ErrorCode & (HAL_I2C_ERROR_BERR | HAL_I2C_ERROR_OVR | HAL_I2C_ERROR_ARLO)) != HAL_I2C_ERROR_NONE)
3024 I2C_ITError(hi2c, hi2c->ErrorCode);
3029 * @brief Master Tx Transfer completed callback.
3030 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
3031 * the configuration information for the specified I2C.
3032 * @retval None
3034 __weak void HAL_I2C_MasterTxCpltCallback(I2C_HandleTypeDef *hi2c)
3036 /* Prevent unused argument(s) compilation warning */
3037 UNUSED(hi2c);
3039 /* NOTE : This function should not be modified, when the callback is needed,
3040 the HAL_I2C_MasterTxCpltCallback could be implemented in the user file
3045 * @brief Master Rx Transfer completed callback.
3046 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
3047 * the configuration information for the specified I2C.
3048 * @retval None
3050 __weak void HAL_I2C_MasterRxCpltCallback(I2C_HandleTypeDef *hi2c)
3052 /* Prevent unused argument(s) compilation warning */
3053 UNUSED(hi2c);
3055 /* NOTE : This function should not be modified, when the callback is needed,
3056 the HAL_I2C_MasterRxCpltCallback could be implemented in the user file
3060 /** @brief Slave Tx Transfer completed callback.
3061 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
3062 * the configuration information for the specified I2C.
3063 * @retval None
3065 __weak void HAL_I2C_SlaveTxCpltCallback(I2C_HandleTypeDef *hi2c)
3067 /* Prevent unused argument(s) compilation warning */
3068 UNUSED(hi2c);
3070 /* NOTE : This function should not be modified, when the callback is needed,
3071 the HAL_I2C_SlaveTxCpltCallback could be implemented in the user file
3076 * @brief Slave Rx Transfer completed callback.
3077 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
3078 * the configuration information for the specified I2C.
3079 * @retval None
3081 __weak void HAL_I2C_SlaveRxCpltCallback(I2C_HandleTypeDef *hi2c)
3083 /* Prevent unused argument(s) compilation warning */
3084 UNUSED(hi2c);
3086 /* NOTE : This function should not be modified, when the callback is needed,
3087 the HAL_I2C_SlaveRxCpltCallback could be implemented in the user file
3092 * @brief Slave Address Match callback.
3093 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
3094 * the configuration information for the specified I2C.
3095 * @param TransferDirection Master request Transfer Direction (Write/Read), value of @ref I2C_XFERDIRECTION
3096 * @param AddrMatchCode Address Match Code
3097 * @retval None
3099 __weak void HAL_I2C_AddrCallback(I2C_HandleTypeDef *hi2c, uint8_t TransferDirection, uint16_t AddrMatchCode)
3101 /* Prevent unused argument(s) compilation warning */
3102 UNUSED(hi2c);
3103 UNUSED(TransferDirection);
3104 UNUSED(AddrMatchCode);
3106 /* NOTE : This function should not be modified, when the callback is needed,
3107 the HAL_I2C_AddrCallback() could be implemented in the user file
3112 * @brief Listen Complete callback.
3113 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
3114 * the configuration information for the specified I2C.
3115 * @retval None
3117 __weak void HAL_I2C_ListenCpltCallback(I2C_HandleTypeDef *hi2c)
3119 /* Prevent unused argument(s) compilation warning */
3120 UNUSED(hi2c);
3122 /* NOTE : This function should not be modified, when the callback is needed,
3123 the HAL_I2C_ListenCpltCallback() could be implemented in the user file
3128 * @brief Memory Tx Transfer completed callback.
3129 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
3130 * the configuration information for the specified I2C.
3131 * @retval None
3133 __weak void HAL_I2C_MemTxCpltCallback(I2C_HandleTypeDef *hi2c)
3135 /* Prevent unused argument(s) compilation warning */
3136 UNUSED(hi2c);
3138 /* NOTE : This function should not be modified, when the callback is needed,
3139 the HAL_I2C_MemTxCpltCallback could be implemented in the user file
3144 * @brief Memory Rx Transfer completed callback.
3145 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
3146 * the configuration information for the specified I2C.
3147 * @retval None
3149 __weak void HAL_I2C_MemRxCpltCallback(I2C_HandleTypeDef *hi2c)
3151 /* Prevent unused argument(s) compilation warning */
3152 UNUSED(hi2c);
3154 /* NOTE : This function should not be modified, when the callback is needed,
3155 the HAL_I2C_MemRxCpltCallback could be implemented in the user file
3160 * @brief I2C error callback.
3161 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
3162 * the configuration information for the specified I2C.
3163 * @retval None
3165 __weak void HAL_I2C_ErrorCallback(I2C_HandleTypeDef *hi2c)
3167 /* Prevent unused argument(s) compilation warning */
3168 UNUSED(hi2c);
3170 /* NOTE : This function should not be modified, when the callback is needed,
3171 the HAL_I2C_ErrorCallback could be implemented in the user file
3176 * @brief I2C abort callback.
3177 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
3178 * the configuration information for the specified I2C.
3179 * @retval None
3181 __weak void HAL_I2C_AbortCpltCallback(I2C_HandleTypeDef *hi2c)
3183 /* Prevent unused argument(s) compilation warning */
3184 UNUSED(hi2c);
3186 /* NOTE : This function should not be modified, when the callback is needed,
3187 the HAL_I2C_AbortCpltCallback could be implemented in the user file
3192 * @}
3195 /** @defgroup I2C_Exported_Functions_Group3 Peripheral State, Mode and Error functions
3196 * @brief Peripheral State, Mode and Error functions
3198 @verbatim
3199 ===============================================================================
3200 ##### Peripheral State, Mode and Error functions #####
3201 ===============================================================================
3202 [..]
3203 This subsection permit to get in run-time the status of the peripheral
3204 and the data flow.
3206 @endverbatim
3207 * @{
3211 * @brief Return the I2C handle state.
3212 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
3213 * the configuration information for the specified I2C.
3214 * @retval HAL state
3216 HAL_I2C_StateTypeDef HAL_I2C_GetState(I2C_HandleTypeDef *hi2c)
3218 /* Return I2C handle state */
3219 return hi2c->State;
3223 * @brief Returns the I2C Master, Slave, Memory or no mode.
3224 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
3225 * the configuration information for I2C module
3226 * @retval HAL mode
3228 HAL_I2C_ModeTypeDef HAL_I2C_GetMode(I2C_HandleTypeDef *hi2c)
3230 return hi2c->Mode;
3234 * @brief Return the I2C error code.
3235 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
3236 * the configuration information for the specified I2C.
3237 * @retval I2C Error Code
3239 uint32_t HAL_I2C_GetError(I2C_HandleTypeDef *hi2c)
3241 return hi2c->ErrorCode;
3245 * @}
3249 * @}
3252 /** @addtogroup I2C_Private_Functions
3253 * @{
3257 * @brief Interrupt Sub-Routine which handle the Interrupt Flags Master Mode with Interrupt.
3258 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
3259 * the configuration information for the specified I2C.
3260 * @param ITFlags Interrupt flags to handle.
3261 * @param ITSources Interrupt sources enabled.
3262 * @retval HAL status
3264 static HAL_StatusTypeDef I2C_Master_ISR_IT(struct __I2C_HandleTypeDef *hi2c, uint32_t ITFlags, uint32_t ITSources)
3266 uint16_t devaddress = 0U;
3268 /* Process Locked */
3269 __HAL_LOCK(hi2c);
3271 if (((ITFlags & I2C_FLAG_AF) != RESET) && ((ITSources & I2C_IT_NACKI) != RESET))
3273 /* Clear NACK Flag */
3274 __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_AF);
3276 /* Set corresponding Error Code */
3277 /* No need to generate STOP, it is automatically done */
3278 /* Error callback will be send during stop flag treatment */
3279 hi2c->ErrorCode |= HAL_I2C_ERROR_AF;
3281 /* Flush TX register */
3282 I2C_Flush_TXDR(hi2c);
3284 else if (((ITFlags & I2C_FLAG_RXNE) != RESET) && ((ITSources & I2C_IT_RXI) != RESET))
3286 /* Read data from RXDR */
3287 (*hi2c->pBuffPtr++) = hi2c->Instance->RXDR;
3288 hi2c->XferSize--;
3289 hi2c->XferCount--;
3291 else if (((ITFlags & I2C_FLAG_TXIS) != RESET) && ((ITSources & I2C_IT_TXI) != RESET))
3293 /* Write data to TXDR */
3294 hi2c->Instance->TXDR = (*hi2c->pBuffPtr++);
3295 hi2c->XferSize--;
3296 hi2c->XferCount--;
3298 else if (((ITFlags & I2C_FLAG_TCR) != RESET) && ((ITSources & I2C_IT_TCI) != RESET))
3300 if ((hi2c->XferSize == 0U) && (hi2c->XferCount != 0U))
3302 devaddress = (hi2c->Instance->CR2 & I2C_CR2_SADD);
3304 if (hi2c->XferCount > MAX_NBYTE_SIZE)
3306 hi2c->XferSize = MAX_NBYTE_SIZE;
3307 I2C_TransferConfig(hi2c, devaddress, hi2c->XferSize, I2C_RELOAD_MODE, I2C_NO_STARTSTOP);
3309 else
3311 hi2c->XferSize = hi2c->XferCount;
3312 if (hi2c->XferOptions != I2C_NO_OPTION_FRAME)
3314 I2C_TransferConfig(hi2c, devaddress, hi2c->XferSize, hi2c->XferOptions, I2C_NO_STARTSTOP);
3316 else
3318 I2C_TransferConfig(hi2c, devaddress, hi2c->XferSize, I2C_AUTOEND_MODE, I2C_NO_STARTSTOP);
3322 else
3324 /* Call TxCpltCallback() if no stop mode is set */
3325 if (I2C_GET_STOP_MODE(hi2c) != I2C_AUTOEND_MODE)
3327 /* Call I2C Master Sequential complete process */
3328 I2C_ITMasterSequentialCplt(hi2c);
3330 else
3332 /* Wrong size Status regarding TCR flag event */
3333 /* Call the corresponding callback to inform upper layer of End of Transfer */
3334 I2C_ITError(hi2c, HAL_I2C_ERROR_SIZE);
3338 else if (((ITFlags & I2C_FLAG_TC) != RESET) && ((ITSources & I2C_IT_TCI) != RESET))
3340 if (hi2c->XferCount == 0U)
3342 if (I2C_GET_STOP_MODE(hi2c) != I2C_AUTOEND_MODE)
3344 /* Generate a stop condition in case of no transfer option */
3345 if (hi2c->XferOptions == I2C_NO_OPTION_FRAME)
3347 /* Generate Stop */
3348 hi2c->Instance->CR2 |= I2C_CR2_STOP;
3350 else
3352 /* Call I2C Master Sequential complete process */
3353 I2C_ITMasterSequentialCplt(hi2c);
3357 else
3359 /* Wrong size Status regarding TC flag event */
3360 /* Call the corresponding callback to inform upper layer of End of Transfer */
3361 I2C_ITError(hi2c, HAL_I2C_ERROR_SIZE);
3365 if (((ITFlags & I2C_FLAG_STOPF) != RESET) && ((ITSources & I2C_IT_STOPI) != RESET))
3367 /* Call I2C Master complete process */
3368 I2C_ITMasterCplt(hi2c, ITFlags);
3371 /* Process Unlocked */
3372 __HAL_UNLOCK(hi2c);
3374 return HAL_OK;
3378 * @brief Interrupt Sub-Routine which handle the Interrupt Flags Slave Mode with Interrupt.
3379 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
3380 * the configuration information for the specified I2C.
3381 * @param ITFlags Interrupt flags to handle.
3382 * @param ITSources Interrupt sources enabled.
3383 * @retval HAL status
3385 static HAL_StatusTypeDef I2C_Slave_ISR_IT(struct __I2C_HandleTypeDef *hi2c, uint32_t ITFlags, uint32_t ITSources)
3387 /* Process locked */
3388 __HAL_LOCK(hi2c);
3390 if (((ITFlags & I2C_FLAG_AF) != RESET) && ((ITSources & I2C_IT_NACKI) != RESET))
3392 /* Check that I2C transfer finished */
3393 /* if yes, normal use case, a NACK is sent by the MASTER when Transfer is finished */
3394 /* Mean XferCount == 0*/
3395 /* So clear Flag NACKF only */
3396 if (hi2c->XferCount == 0U)
3398 if (((hi2c->XferOptions == I2C_FIRST_AND_LAST_FRAME) || (hi2c->XferOptions == I2C_LAST_FRAME)) && \
3399 (hi2c->State == HAL_I2C_STATE_LISTEN))
3401 /* Call I2C Listen complete process */
3402 I2C_ITListenCplt(hi2c, ITFlags);
3404 else if ((hi2c->XferOptions != I2C_NO_OPTION_FRAME) && (hi2c->State == HAL_I2C_STATE_BUSY_TX_LISTEN))
3406 /* Clear NACK Flag */
3407 __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_AF);
3409 /* Flush TX register */
3410 I2C_Flush_TXDR(hi2c);
3412 /* Last Byte is Transmitted */
3413 /* Call I2C Slave Sequential complete process */
3414 I2C_ITSlaveSequentialCplt(hi2c);
3416 else
3418 /* Clear NACK Flag */
3419 __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_AF);
3422 else
3424 /* if no, error use case, a Non-Acknowledge of last Data is generated by the MASTER*/
3425 /* Clear NACK Flag */
3426 __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_AF);
3428 /* Set ErrorCode corresponding to a Non-Acknowledge */
3429 hi2c->ErrorCode |= HAL_I2C_ERROR_AF;
3432 else if (((ITFlags & I2C_FLAG_RXNE) != RESET) && ((ITSources & I2C_IT_RXI) != RESET))
3434 if (hi2c->XferCount > 0U)
3436 /* Read data from RXDR */
3437 (*hi2c->pBuffPtr++) = hi2c->Instance->RXDR;
3438 hi2c->XferSize--;
3439 hi2c->XferCount--;
3442 if ((hi2c->XferCount == 0U) && \
3443 (hi2c->XferOptions != I2C_NO_OPTION_FRAME))
3445 /* Call I2C Slave Sequential complete process */
3446 I2C_ITSlaveSequentialCplt(hi2c);
3449 else if (((ITFlags & I2C_FLAG_ADDR) != RESET) && ((ITSources & I2C_IT_ADDRI) != RESET))
3451 I2C_ITAddrCplt(hi2c, ITFlags);
3453 else if (((ITFlags & I2C_FLAG_TXIS) != RESET) && ((ITSources & I2C_IT_TXI) != RESET))
3455 /* Write data to TXDR only if XferCount not reach "0" */
3456 /* A TXIS flag can be set, during STOP treatment */
3457 /* Check if all Datas have already been sent */
3458 /* If it is the case, this last write in TXDR is not sent, correspond to a dummy TXIS event */
3459 if (hi2c->XferCount > 0U)
3461 /* Write data to TXDR */
3462 hi2c->Instance->TXDR = (*hi2c->pBuffPtr++);
3463 hi2c->XferCount--;
3464 hi2c->XferSize--;
3466 else
3468 if ((hi2c->XferOptions == I2C_NEXT_FRAME) || (hi2c->XferOptions == I2C_FIRST_FRAME))
3470 /* Last Byte is Transmitted */
3471 /* Call I2C Slave Sequential complete process */
3472 I2C_ITSlaveSequentialCplt(hi2c);
3477 /* Check if STOPF is set */
3478 if (((ITFlags & I2C_FLAG_STOPF) != RESET) && ((ITSources & I2C_IT_STOPI) != RESET))
3480 /* Call I2C Slave complete process */
3481 I2C_ITSlaveCplt(hi2c, ITFlags);
3484 /* Process Unlocked */
3485 __HAL_UNLOCK(hi2c);
3487 return HAL_OK;
3491 * @brief Interrupt Sub-Routine which handle the Interrupt Flags Master Mode with DMA.
3492 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
3493 * the configuration information for the specified I2C.
3494 * @param ITFlags Interrupt flags to handle.
3495 * @param ITSources Interrupt sources enabled.
3496 * @retval HAL status
3498 static HAL_StatusTypeDef I2C_Master_ISR_DMA(struct __I2C_HandleTypeDef *hi2c, uint32_t ITFlags, uint32_t ITSources)
3500 uint16_t devaddress = 0U;
3501 uint32_t xfermode = 0U;
3503 /* Process Locked */
3504 __HAL_LOCK(hi2c);
3506 if (((ITFlags & I2C_FLAG_AF) != RESET) && ((ITSources & I2C_IT_NACKI) != RESET))
3508 /* Clear NACK Flag */
3509 __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_AF);
3511 /* Set corresponding Error Code */
3512 hi2c->ErrorCode |= HAL_I2C_ERROR_AF;
3514 /* No need to generate STOP, it is automatically done */
3515 /* But enable STOP interrupt, to treat it */
3516 /* Error callback will be send during stop flag treatment */
3517 I2C_Enable_IRQ(hi2c, I2C_XFER_CPLT_IT);
3519 /* Flush TX register */
3520 I2C_Flush_TXDR(hi2c);
3522 else if (((ITFlags & I2C_FLAG_TCR) != RESET) && ((ITSources & I2C_IT_TCI) != RESET))
3524 /* Disable TC interrupt */
3525 __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_TCI);
3527 if (hi2c->XferCount != 0U)
3529 /* Recover Slave address */
3530 devaddress = (hi2c->Instance->CR2 & I2C_CR2_SADD);
3532 /* Prepare the new XferSize to transfer */
3533 if (hi2c->XferCount > MAX_NBYTE_SIZE)
3535 hi2c->XferSize = MAX_NBYTE_SIZE;
3536 xfermode = I2C_RELOAD_MODE;
3538 else
3540 hi2c->XferSize = hi2c->XferCount;
3541 xfermode = I2C_AUTOEND_MODE;
3544 /* Set the new XferSize in Nbytes register */
3545 I2C_TransferConfig(hi2c, devaddress, hi2c->XferSize, xfermode, I2C_NO_STARTSTOP);
3547 /* Update XferCount value */
3548 hi2c->XferCount -= hi2c->XferSize;
3550 /* Enable DMA Request */
3551 if (hi2c->State == HAL_I2C_STATE_BUSY_RX)
3553 hi2c->Instance->CR1 |= I2C_CR1_RXDMAEN;
3555 else
3557 hi2c->Instance->CR1 |= I2C_CR1_TXDMAEN;
3560 else
3562 /* Wrong size Status regarding TCR flag event */
3563 /* Call the corresponding callback to inform upper layer of End of Transfer */
3564 I2C_ITError(hi2c, HAL_I2C_ERROR_SIZE);
3567 else if (((ITFlags & I2C_FLAG_STOPF) != RESET) && ((ITSources & I2C_IT_STOPI) != RESET))
3569 /* Call I2C Master complete process */
3570 I2C_ITMasterCplt(hi2c, ITFlags);
3573 /* Process Unlocked */
3574 __HAL_UNLOCK(hi2c);
3576 return HAL_OK;
3580 * @brief Interrupt Sub-Routine which handle the Interrupt Flags Slave Mode with DMA.
3581 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
3582 * the configuration information for the specified I2C.
3583 * @param ITFlags Interrupt flags to handle.
3584 * @param ITSources Interrupt sources enabled.
3585 * @retval HAL status
3587 static HAL_StatusTypeDef I2C_Slave_ISR_DMA(struct __I2C_HandleTypeDef *hi2c, uint32_t ITFlags, uint32_t ITSources)
3589 /* Process locked */
3590 __HAL_LOCK(hi2c);
3592 if (((ITFlags & I2C_FLAG_AF) != RESET) && ((ITSources & I2C_IT_NACKI) != RESET))
3594 /* Check that I2C transfer finished */
3595 /* if yes, normal use case, a NACK is sent by the MASTER when Transfer is finished */
3596 /* Mean XferCount == 0 */
3597 /* So clear Flag NACKF only */
3598 if (I2C_GET_DMA_REMAIN_DATA(hi2c) == 0U)
3600 /* Clear NACK Flag */
3601 __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_AF);
3603 else
3605 /* if no, error use case, a Non-Acknowledge of last Data is generated by the MASTER*/
3606 /* Clear NACK Flag */
3607 __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_AF);
3609 /* Set ErrorCode corresponding to a Non-Acknowledge */
3610 hi2c->ErrorCode |= HAL_I2C_ERROR_AF;
3613 else if (((ITFlags & I2C_FLAG_ADDR) != RESET) && ((ITSources & I2C_IT_ADDRI) != RESET))
3615 /* Clear ADDR flag */
3616 __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_ADDR);
3618 else if (((ITFlags & I2C_FLAG_STOPF) != RESET) && ((ITSources & I2C_IT_STOPI) != RESET))
3620 /* Call I2C Slave complete process */
3621 I2C_ITSlaveCplt(hi2c, ITFlags);
3624 /* Process Unlocked */
3625 __HAL_UNLOCK(hi2c);
3627 return HAL_OK;
3631 * @brief Master sends target device address followed by internal memory address for write request.
3632 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
3633 * the configuration information for the specified I2C.
3634 * @param DevAddress Target device address: The device 7 bits address value
3635 * in datasheet must be shift at right before call interface
3636 * @param MemAddress Internal memory address
3637 * @param MemAddSize Size of internal memory address
3638 * @param Timeout Timeout duration
3639 * @param Tickstart Tick start value
3640 * @retval HAL status
3642 static HAL_StatusTypeDef I2C_RequestMemoryWrite(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint32_t Timeout, uint32_t Tickstart)
3644 I2C_TransferConfig(hi2c, DevAddress, MemAddSize, I2C_RELOAD_MODE, I2C_GENERATE_START_WRITE);
3646 /* Wait until TXIS flag is set */
3647 if (I2C_WaitOnTXISFlagUntilTimeout(hi2c, Timeout, Tickstart) != HAL_OK)
3649 if (hi2c->ErrorCode == HAL_I2C_ERROR_AF)
3651 return HAL_ERROR;
3653 else
3655 return HAL_TIMEOUT;
3659 /* If Memory address size is 8Bit */
3660 if (MemAddSize == I2C_MEMADD_SIZE_8BIT)
3662 /* Send Memory Address */
3663 hi2c->Instance->TXDR = I2C_MEM_ADD_LSB(MemAddress);
3665 /* If Memory address size is 16Bit */
3666 else
3668 /* Send MSB of Memory Address */
3669 hi2c->Instance->TXDR = I2C_MEM_ADD_MSB(MemAddress);
3671 /* Wait until TXIS flag is set */
3672 if (I2C_WaitOnTXISFlagUntilTimeout(hi2c, Timeout, Tickstart) != HAL_OK)
3674 if (hi2c->ErrorCode == HAL_I2C_ERROR_AF)
3676 return HAL_ERROR;
3678 else
3680 return HAL_TIMEOUT;
3684 /* Send LSB of Memory Address */
3685 hi2c->Instance->TXDR = I2C_MEM_ADD_LSB(MemAddress);
3688 /* Wait until TCR flag is set */
3689 if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_TCR, RESET, Timeout, Tickstart) != HAL_OK)
3691 return HAL_TIMEOUT;
3694 return HAL_OK;
3698 * @brief Master sends target device address followed by internal memory address for read request.
3699 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
3700 * the configuration information for the specified I2C.
3701 * @param DevAddress Target device address: The device 7 bits address value
3702 * in datasheet must be shift at right before call interface
3703 * @param MemAddress Internal memory address
3704 * @param MemAddSize Size of internal memory address
3705 * @param Timeout Timeout duration
3706 * @param Tickstart Tick start value
3707 * @retval HAL status
3709 static HAL_StatusTypeDef I2C_RequestMemoryRead(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint32_t Timeout, uint32_t Tickstart)
3711 I2C_TransferConfig(hi2c, DevAddress, MemAddSize, I2C_SOFTEND_MODE, I2C_GENERATE_START_WRITE);
3713 /* Wait until TXIS flag is set */
3714 if (I2C_WaitOnTXISFlagUntilTimeout(hi2c, Timeout, Tickstart) != HAL_OK)
3716 if (hi2c->ErrorCode == HAL_I2C_ERROR_AF)
3718 return HAL_ERROR;
3720 else
3722 return HAL_TIMEOUT;
3726 /* If Memory address size is 8Bit */
3727 if (MemAddSize == I2C_MEMADD_SIZE_8BIT)
3729 /* Send Memory Address */
3730 hi2c->Instance->TXDR = I2C_MEM_ADD_LSB(MemAddress);
3732 /* If Memory address size is 16Bit */
3733 else
3735 /* Send MSB of Memory Address */
3736 hi2c->Instance->TXDR = I2C_MEM_ADD_MSB(MemAddress);
3738 /* Wait until TXIS flag is set */
3739 if (I2C_WaitOnTXISFlagUntilTimeout(hi2c, Timeout, Tickstart) != HAL_OK)
3741 if (hi2c->ErrorCode == HAL_I2C_ERROR_AF)
3743 return HAL_ERROR;
3745 else
3747 return HAL_TIMEOUT;
3751 /* Send LSB of Memory Address */
3752 hi2c->Instance->TXDR = I2C_MEM_ADD_LSB(MemAddress);
3755 /* Wait until TC flag is set */
3756 if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_TC, RESET, Timeout, Tickstart) != HAL_OK)
3758 return HAL_TIMEOUT;
3761 return HAL_OK;
3765 * @brief I2C Address complete process callback.
3766 * @param hi2c I2C handle.
3767 * @param ITFlags Interrupt flags to handle.
3768 * @retval None
3770 static void I2C_ITAddrCplt(I2C_HandleTypeDef *hi2c, uint32_t ITFlags)
3772 uint8_t transferdirection = 0U;
3773 uint16_t slaveaddrcode = 0U;
3774 uint16_t ownadd1code = 0U;
3775 uint16_t ownadd2code = 0U;
3777 /* Prevent unused argument(s) compilation warning */
3778 UNUSED(ITFlags);
3780 /* In case of Listen state, need to inform upper layer of address match code event */
3781 if ((hi2c->State & HAL_I2C_STATE_LISTEN) == HAL_I2C_STATE_LISTEN)
3783 transferdirection = I2C_GET_DIR(hi2c);
3784 slaveaddrcode = I2C_GET_ADDR_MATCH(hi2c);
3785 ownadd1code = I2C_GET_OWN_ADDRESS1(hi2c);
3786 ownadd2code = I2C_GET_OWN_ADDRESS2(hi2c);
3788 /* If 10bits addressing mode is selected */
3789 if (hi2c->Init.AddressingMode == I2C_ADDRESSINGMODE_10BIT)
3791 if ((slaveaddrcode & SlaveAddr_MSK) == ((ownadd1code >> SlaveAddr_SHIFT) & SlaveAddr_MSK))
3793 slaveaddrcode = ownadd1code;
3794 hi2c->AddrEventCount++;
3795 if (hi2c->AddrEventCount == 2U)
3797 /* Reset Address Event counter */
3798 hi2c->AddrEventCount = 0U;
3800 /* Clear ADDR flag */
3801 __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_ADDR);
3803 /* Process Unlocked */
3804 __HAL_UNLOCK(hi2c);
3806 /* Call Slave Addr callback */
3807 HAL_I2C_AddrCallback(hi2c, transferdirection, slaveaddrcode);
3810 else
3812 slaveaddrcode = ownadd2code;
3814 /* Disable ADDR Interrupts */
3815 I2C_Disable_IRQ(hi2c, I2C_XFER_LISTEN_IT);
3817 /* Process Unlocked */
3818 __HAL_UNLOCK(hi2c);
3820 /* Call Slave Addr callback */
3821 HAL_I2C_AddrCallback(hi2c, transferdirection, slaveaddrcode);
3824 /* else 7 bits addressing mode is selected */
3825 else
3827 /* Disable ADDR Interrupts */
3828 I2C_Disable_IRQ(hi2c, I2C_XFER_LISTEN_IT);
3830 /* Process Unlocked */
3831 __HAL_UNLOCK(hi2c);
3833 /* Call Slave Addr callback */
3834 HAL_I2C_AddrCallback(hi2c, transferdirection, slaveaddrcode);
3837 /* Else clear address flag only */
3838 else
3840 /* Clear ADDR flag */
3841 __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_ADDR);
3843 /* Process Unlocked */
3844 __HAL_UNLOCK(hi2c);
3849 * @brief I2C Master sequential complete process.
3850 * @param hi2c I2C handle.
3851 * @retval None
3853 static void I2C_ITMasterSequentialCplt(I2C_HandleTypeDef *hi2c)
3855 /* Reset I2C handle mode */
3856 hi2c->Mode = HAL_I2C_MODE_NONE;
3858 /* No Generate Stop, to permit restart mode */
3859 /* The stop will be done at the end of transfer, when I2C_AUTOEND_MODE enable */
3860 if (hi2c->State == HAL_I2C_STATE_BUSY_TX)
3862 hi2c->State = HAL_I2C_STATE_READY;
3863 hi2c->PreviousState = I2C_STATE_MASTER_BUSY_TX;
3864 hi2c->XferISR = NULL;
3866 /* Disable Interrupts */
3867 I2C_Disable_IRQ(hi2c, I2C_XFER_TX_IT);
3869 /* Process Unlocked */
3870 __HAL_UNLOCK(hi2c);
3872 /* Call the corresponding callback to inform upper layer of End of Transfer */
3873 HAL_I2C_MasterTxCpltCallback(hi2c);
3875 /* hi2c->State == HAL_I2C_STATE_BUSY_RX */
3876 else
3878 hi2c->State = HAL_I2C_STATE_READY;
3879 hi2c->PreviousState = I2C_STATE_MASTER_BUSY_RX;
3880 hi2c->XferISR = NULL;
3882 /* Disable Interrupts */
3883 I2C_Disable_IRQ(hi2c, I2C_XFER_RX_IT);
3885 /* Process Unlocked */
3886 __HAL_UNLOCK(hi2c);
3888 /* Call the corresponding callback to inform upper layer of End of Transfer */
3889 HAL_I2C_MasterRxCpltCallback(hi2c);
3894 * @brief I2C Slave sequential complete process.
3895 * @param hi2c I2C handle.
3896 * @retval None
3898 static void I2C_ITSlaveSequentialCplt(I2C_HandleTypeDef *hi2c)
3900 /* Reset I2C handle mode */
3901 hi2c->Mode = HAL_I2C_MODE_NONE;
3903 if (hi2c->State == HAL_I2C_STATE_BUSY_TX_LISTEN)
3905 /* Remove HAL_I2C_STATE_SLAVE_BUSY_TX, keep only HAL_I2C_STATE_LISTEN */
3906 hi2c->State = HAL_I2C_STATE_LISTEN;
3907 hi2c->PreviousState = I2C_STATE_SLAVE_BUSY_TX;
3909 /* Disable Interrupts */
3910 I2C_Disable_IRQ(hi2c, I2C_XFER_TX_IT);
3912 /* Process Unlocked */
3913 __HAL_UNLOCK(hi2c);
3915 /* Call the Tx complete callback to inform upper layer of the end of transmit process */
3916 HAL_I2C_SlaveTxCpltCallback(hi2c);
3919 else if (hi2c->State == HAL_I2C_STATE_BUSY_RX_LISTEN)
3921 /* Remove HAL_I2C_STATE_SLAVE_BUSY_RX, keep only HAL_I2C_STATE_LISTEN */
3922 hi2c->State = HAL_I2C_STATE_LISTEN;
3923 hi2c->PreviousState = I2C_STATE_SLAVE_BUSY_RX;
3925 /* Disable Interrupts */
3926 I2C_Disable_IRQ(hi2c, I2C_XFER_RX_IT);
3928 /* Process Unlocked */
3929 __HAL_UNLOCK(hi2c);
3931 /* Call the Rx complete callback to inform upper layer of the end of receive process */
3932 HAL_I2C_SlaveRxCpltCallback(hi2c);
3937 * @brief I2C Master complete process.
3938 * @param hi2c I2C handle.
3939 * @param ITFlags Interrupt flags to handle.
3940 * @retval None
3942 static void I2C_ITMasterCplt(I2C_HandleTypeDef *hi2c, uint32_t ITFlags)
3944 /* Clear STOP Flag */
3945 __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_STOPF);
3947 /* Clear Configuration Register 2 */
3948 I2C_RESET_CR2(hi2c);
3950 /* Reset handle parameters */
3951 hi2c->PreviousState = I2C_STATE_NONE;
3952 hi2c->XferISR = NULL;
3953 hi2c->XferOptions = I2C_NO_OPTION_FRAME;
3955 if ((ITFlags & I2C_FLAG_AF) != RESET)
3957 /* Clear NACK Flag */
3958 __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_AF);
3960 /* Set acknowledge error code */
3961 hi2c->ErrorCode |= HAL_I2C_ERROR_AF;
3964 /* Flush TX register */
3965 I2C_Flush_TXDR(hi2c);
3967 /* Disable Interrupts */
3968 I2C_Disable_IRQ(hi2c, I2C_XFER_TX_IT | I2C_XFER_RX_IT);
3970 /* Call the corresponding callback to inform upper layer of End of Transfer */
3971 if ((hi2c->ErrorCode != HAL_I2C_ERROR_NONE) || (hi2c->State == HAL_I2C_STATE_ABORT))
3973 /* Call the corresponding callback to inform upper layer of End of Transfer */
3974 I2C_ITError(hi2c, hi2c->ErrorCode);
3976 /* hi2c->State == HAL_I2C_STATE_BUSY_TX */
3977 else if (hi2c->State == HAL_I2C_STATE_BUSY_TX)
3979 hi2c->State = HAL_I2C_STATE_READY;
3981 if (hi2c->Mode == HAL_I2C_MODE_MEM)
3983 hi2c->Mode = HAL_I2C_MODE_NONE;
3985 /* Process Unlocked */
3986 __HAL_UNLOCK(hi2c);
3988 /* Call the corresponding callback to inform upper layer of End of Transfer */
3989 HAL_I2C_MemTxCpltCallback(hi2c);
3991 else
3993 hi2c->Mode = HAL_I2C_MODE_NONE;
3995 /* Process Unlocked */
3996 __HAL_UNLOCK(hi2c);
3998 /* Call the corresponding callback to inform upper layer of End of Transfer */
3999 HAL_I2C_MasterTxCpltCallback(hi2c);
4002 /* hi2c->State == HAL_I2C_STATE_BUSY_RX */
4003 else if (hi2c->State == HAL_I2C_STATE_BUSY_RX)
4005 hi2c->State = HAL_I2C_STATE_READY;
4007 if (hi2c->Mode == HAL_I2C_MODE_MEM)
4009 hi2c->Mode = HAL_I2C_MODE_NONE;
4011 /* Process Unlocked */
4012 __HAL_UNLOCK(hi2c);
4014 HAL_I2C_MemRxCpltCallback(hi2c);
4016 else
4018 hi2c->Mode = HAL_I2C_MODE_NONE;
4020 /* Process Unlocked */
4021 __HAL_UNLOCK(hi2c);
4023 HAL_I2C_MasterRxCpltCallback(hi2c);
4029 * @brief I2C Slave complete process.
4030 * @param hi2c I2C handle.
4031 * @param ITFlags Interrupt flags to handle.
4032 * @retval None
4034 static void I2C_ITSlaveCplt(I2C_HandleTypeDef *hi2c, uint32_t ITFlags)
4036 /* Clear STOP Flag */
4037 __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_STOPF);
4039 /* Clear ADDR flag */
4040 __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_ADDR);
4042 /* Disable all interrupts */
4043 I2C_Disable_IRQ(hi2c, I2C_XFER_LISTEN_IT | I2C_XFER_TX_IT | I2C_XFER_RX_IT);
4045 /* Disable Address Acknowledge */
4046 hi2c->Instance->CR2 |= I2C_CR2_NACK;
4048 /* Clear Configuration Register 2 */
4049 I2C_RESET_CR2(hi2c);
4051 /* Flush TX register */
4052 I2C_Flush_TXDR(hi2c);
4054 /* If a DMA is ongoing, Update handle size context */
4055 if (((hi2c->Instance->CR1 & I2C_CR1_TXDMAEN) == I2C_CR1_TXDMAEN) ||
4056 ((hi2c->Instance->CR1 & I2C_CR1_RXDMAEN) == I2C_CR1_RXDMAEN))
4058 hi2c->XferCount = I2C_GET_DMA_REMAIN_DATA(hi2c);
4061 /* All data are not transferred, so set error code accordingly */
4062 if (hi2c->XferCount != 0U)
4064 /* Set ErrorCode corresponding to a Non-Acknowledge */
4065 hi2c->ErrorCode |= HAL_I2C_ERROR_AF;
4068 /* Store Last receive data if any */
4069 if (((ITFlags & I2C_FLAG_RXNE) != RESET))
4071 /* Read data from RXDR */
4072 (*hi2c->pBuffPtr++) = hi2c->Instance->RXDR;
4074 if ((hi2c->XferSize > 0U))
4076 hi2c->XferSize--;
4077 hi2c->XferCount--;
4079 /* Set ErrorCode corresponding to a Non-Acknowledge */
4080 hi2c->ErrorCode |= HAL_I2C_ERROR_AF;
4084 hi2c->PreviousState = I2C_STATE_NONE;
4085 hi2c->Mode = HAL_I2C_MODE_NONE;
4086 hi2c->XferISR = NULL;
4088 if (hi2c->ErrorCode != HAL_I2C_ERROR_NONE)
4090 /* Call the corresponding callback to inform upper layer of End of Transfer */
4091 I2C_ITError(hi2c, hi2c->ErrorCode);
4093 /* Call the Listen Complete callback, to inform upper layer of the end of Listen usecase */
4094 if (hi2c->State == HAL_I2C_STATE_LISTEN)
4096 /* Call I2C Listen complete process */
4097 I2C_ITListenCplt(hi2c, ITFlags);
4100 else if (hi2c->XferOptions != I2C_NO_OPTION_FRAME)
4102 hi2c->XferOptions = I2C_NO_OPTION_FRAME;
4103 hi2c->State = HAL_I2C_STATE_READY;
4105 /* Process Unlocked */
4106 __HAL_UNLOCK(hi2c);
4108 /* Call the Listen Complete callback, to inform upper layer of the end of Listen usecase */
4109 HAL_I2C_ListenCpltCallback(hi2c);
4111 /* Call the corresponding callback to inform upper layer of End of Transfer */
4112 else if (hi2c->State == HAL_I2C_STATE_BUSY_RX)
4114 hi2c->State = HAL_I2C_STATE_READY;
4116 /* Process Unlocked */
4117 __HAL_UNLOCK(hi2c);
4119 /* Call the Slave Rx Complete callback */
4120 HAL_I2C_SlaveRxCpltCallback(hi2c);
4122 else
4124 hi2c->State = HAL_I2C_STATE_READY;
4126 /* Process Unlocked */
4127 __HAL_UNLOCK(hi2c);
4129 /* Call the Slave Tx Complete callback */
4130 HAL_I2C_SlaveTxCpltCallback(hi2c);
4135 * @brief I2C Listen complete process.
4136 * @param hi2c I2C handle.
4137 * @param ITFlags Interrupt flags to handle.
4138 * @retval None
4140 static void I2C_ITListenCplt(I2C_HandleTypeDef *hi2c, uint32_t ITFlags)
4142 /* Reset handle parameters */
4143 hi2c->XferOptions = I2C_NO_OPTION_FRAME;
4144 hi2c->PreviousState = I2C_STATE_NONE;
4145 hi2c->State = HAL_I2C_STATE_READY;
4146 hi2c->Mode = HAL_I2C_MODE_NONE;
4147 hi2c->XferISR = NULL;
4149 /* Store Last receive data if any */
4150 if (((ITFlags & I2C_FLAG_RXNE) != RESET))
4152 /* Read data from RXDR */
4153 (*hi2c->pBuffPtr++) = hi2c->Instance->RXDR;
4155 if ((hi2c->XferSize > 0U))
4157 hi2c->XferSize--;
4158 hi2c->XferCount--;
4160 /* Set ErrorCode corresponding to a Non-Acknowledge */
4161 hi2c->ErrorCode |= HAL_I2C_ERROR_AF;
4165 /* Disable all Interrupts*/
4166 I2C_Disable_IRQ(hi2c, I2C_XFER_LISTEN_IT | I2C_XFER_RX_IT | I2C_XFER_TX_IT);
4168 /* Clear NACK Flag */
4169 __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_AF);
4171 /* Process Unlocked */
4172 __HAL_UNLOCK(hi2c);
4174 /* Call the Listen Complete callback, to inform upper layer of the end of Listen usecase */
4175 HAL_I2C_ListenCpltCallback(hi2c);
4179 * @brief I2C interrupts error process.
4180 * @param hi2c I2C handle.
4181 * @param ErrorCode Error code to handle.
4182 * @retval None
4184 static void I2C_ITError(I2C_HandleTypeDef *hi2c, uint32_t ErrorCode)
4186 /* Reset handle parameters */
4187 hi2c->Mode = HAL_I2C_MODE_NONE;
4188 hi2c->XferOptions = I2C_NO_OPTION_FRAME;
4189 hi2c->XferCount = 0U;
4191 /* Set new error code */
4192 hi2c->ErrorCode |= ErrorCode;
4194 /* Disable Interrupts */
4195 if ((hi2c->State == HAL_I2C_STATE_LISTEN) ||
4196 (hi2c->State == HAL_I2C_STATE_BUSY_TX_LISTEN) ||
4197 (hi2c->State == HAL_I2C_STATE_BUSY_RX_LISTEN))
4199 /* Disable all interrupts, except interrupts related to LISTEN state */
4200 I2C_Disable_IRQ(hi2c, I2C_XFER_RX_IT | I2C_XFER_TX_IT);
4202 /* keep HAL_I2C_STATE_LISTEN if set */
4203 hi2c->State = HAL_I2C_STATE_LISTEN;
4204 hi2c->PreviousState = I2C_STATE_NONE;
4205 hi2c->XferISR = I2C_Slave_ISR_IT;
4207 else
4209 /* Disable all interrupts */
4210 I2C_Disable_IRQ(hi2c, I2C_XFER_LISTEN_IT | I2C_XFER_RX_IT | I2C_XFER_TX_IT);
4212 /* If state is an abort treatment on goind, don't change state */
4213 /* This change will be do later */
4214 if (hi2c->State != HAL_I2C_STATE_ABORT)
4216 /* Set HAL_I2C_STATE_READY */
4217 hi2c->State = HAL_I2C_STATE_READY;
4219 hi2c->PreviousState = I2C_STATE_NONE;
4220 hi2c->XferISR = NULL;
4223 /* Abort DMA TX transfer if any */
4224 if ((hi2c->Instance->CR1 & I2C_CR1_TXDMAEN) == I2C_CR1_TXDMAEN)
4226 hi2c->Instance->CR1 &= ~I2C_CR1_TXDMAEN;
4228 /* Set the I2C DMA Abort callback :
4229 will lead to call HAL_I2C_ErrorCallback() at end of DMA abort procedure */
4230 hi2c->hdmatx->XferAbortCallback = I2C_DMAAbort;
4232 /* Process Unlocked */
4233 __HAL_UNLOCK(hi2c);
4235 /* Abort DMA TX */
4236 if (HAL_DMA_Abort_IT(hi2c->hdmatx) != HAL_OK)
4238 /* Call Directly XferAbortCallback function in case of error */
4239 hi2c->hdmatx->XferAbortCallback(hi2c->hdmatx);
4242 /* Abort DMA RX transfer if any */
4243 else if ((hi2c->Instance->CR1 & I2C_CR1_RXDMAEN) == I2C_CR1_RXDMAEN)
4245 hi2c->Instance->CR1 &= ~I2C_CR1_RXDMAEN;
4247 /* Set the I2C DMA Abort callback :
4248 will lead to call HAL_I2C_ErrorCallback() at end of DMA abort procedure */
4249 hi2c->hdmarx->XferAbortCallback = I2C_DMAAbort;
4251 /* Process Unlocked */
4252 __HAL_UNLOCK(hi2c);
4254 /* Abort DMA RX */
4255 if (HAL_DMA_Abort_IT(hi2c->hdmarx) != HAL_OK)
4257 /* Call Directly hi2c->hdmarx->XferAbortCallback function in case of error */
4258 hi2c->hdmarx->XferAbortCallback(hi2c->hdmarx);
4261 else if (hi2c->State == HAL_I2C_STATE_ABORT)
4263 hi2c->State = HAL_I2C_STATE_READY;
4265 /* Process Unlocked */
4266 __HAL_UNLOCK(hi2c);
4268 /* Call the corresponding callback to inform upper layer of End of Transfer */
4269 HAL_I2C_AbortCpltCallback(hi2c);
4271 else
4273 /* Process Unlocked */
4274 __HAL_UNLOCK(hi2c);
4276 /* Call the corresponding callback to inform upper layer of End of Transfer */
4277 HAL_I2C_ErrorCallback(hi2c);
4282 * @brief I2C Tx data register flush process.
4283 * @param hi2c I2C handle.
4284 * @retval None
4286 static void I2C_Flush_TXDR(I2C_HandleTypeDef *hi2c)
4288 /* If a pending TXIS flag is set */
4289 /* Write a dummy data in TXDR to clear it */
4290 if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_TXIS) != RESET)
4292 hi2c->Instance->TXDR = 0x00U;
4295 /* Flush TX register if not empty */
4296 if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_TXE) == RESET)
4298 __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_TXE);
4303 * @brief DMA I2C master transmit process complete callback.
4304 * @param hdma DMA handle
4305 * @retval None
4307 static void I2C_DMAMasterTransmitCplt(DMA_HandleTypeDef *hdma)
4309 I2C_HandleTypeDef *hi2c = (I2C_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent;
4311 /* Disable DMA Request */
4312 hi2c->Instance->CR1 &= ~I2C_CR1_TXDMAEN;
4314 /* If last transfer, enable STOP interrupt */
4315 if (hi2c->XferCount == 0U)
4317 /* Enable STOP interrupt */
4318 I2C_Enable_IRQ(hi2c, I2C_XFER_CPLT_IT);
4320 /* else prepare a new DMA transfer and enable TCReload interrupt */
4321 else
4323 /* Update Buffer pointer */
4324 hi2c->pBuffPtr += hi2c->XferSize;
4326 /* Set the XferSize to transfer */
4327 if (hi2c->XferCount > MAX_NBYTE_SIZE)
4329 hi2c->XferSize = MAX_NBYTE_SIZE;
4331 else
4333 hi2c->XferSize = hi2c->XferCount;
4336 /* Enable the DMA channel */
4337 HAL_DMA_Start_IT(hi2c->hdmatx, (uint32_t)hi2c->pBuffPtr, (uint32_t)&hi2c->Instance->TXDR, hi2c->XferSize);
4339 /* Enable TC interrupts */
4340 I2C_Enable_IRQ(hi2c, I2C_XFER_RELOAD_IT);
4345 * @brief DMA I2C slave transmit process complete callback.
4346 * @param hdma DMA handle
4347 * @retval None
4349 static void I2C_DMASlaveTransmitCplt(DMA_HandleTypeDef *hdma)
4351 /* Prevent unused argument(s) compilation warning */
4352 UNUSED(hdma);
4354 /* No specific action, Master fully manage the generation of STOP condition */
4355 /* Mean that this generation can arrive at any time, at the end or during DMA process */
4356 /* So STOP condition should be manage through Interrupt treatment */
4360 * @brief DMA I2C master receive process complete callback.
4361 * @param hdma DMA handle
4362 * @retval None
4364 static void I2C_DMAMasterReceiveCplt(DMA_HandleTypeDef *hdma)
4366 I2C_HandleTypeDef *hi2c = (I2C_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent;
4368 /* Disable DMA Request */
4369 hi2c->Instance->CR1 &= ~I2C_CR1_RXDMAEN;
4371 /* If last transfer, enable STOP interrupt */
4372 if (hi2c->XferCount == 0U)
4374 /* Enable STOP interrupt */
4375 I2C_Enable_IRQ(hi2c, I2C_XFER_CPLT_IT);
4377 /* else prepare a new DMA transfer and enable TCReload interrupt */
4378 else
4380 /* Update Buffer pointer */
4381 hi2c->pBuffPtr += hi2c->XferSize;
4383 /* Set the XferSize to transfer */
4384 if (hi2c->XferCount > MAX_NBYTE_SIZE)
4386 hi2c->XferSize = MAX_NBYTE_SIZE;
4388 else
4390 hi2c->XferSize = hi2c->XferCount;
4393 /* Enable the DMA channel */
4394 HAL_DMA_Start_IT(hi2c->hdmarx, (uint32_t)&hi2c->Instance->RXDR, (uint32_t)hi2c->pBuffPtr, hi2c->XferSize);
4396 /* Enable TC interrupts */
4397 I2C_Enable_IRQ(hi2c, I2C_XFER_RELOAD_IT);
4402 * @brief DMA I2C slave receive process complete callback.
4403 * @param hdma DMA handle
4404 * @retval None
4406 static void I2C_DMASlaveReceiveCplt(DMA_HandleTypeDef *hdma)
4408 /* Prevent unused argument(s) compilation warning */
4409 UNUSED(hdma);
4411 /* No specific action, Master fully manage the generation of STOP condition */
4412 /* Mean that this generation can arrive at any time, at the end or during DMA process */
4413 /* So STOP condition should be manage through Interrupt treatment */
4417 * @brief DMA I2C communication error callback.
4418 * @param hdma DMA handle
4419 * @retval None
4421 static void I2C_DMAError(DMA_HandleTypeDef *hdma)
4423 I2C_HandleTypeDef *hi2c = (I2C_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent;
4425 /* Disable Acknowledge */
4426 hi2c->Instance->CR2 |= I2C_CR2_NACK;
4428 /* Call the corresponding callback to inform upper layer of End of Transfer */
4429 I2C_ITError(hi2c, HAL_I2C_ERROR_DMA);
4433 * @brief DMA I2C communication abort callback
4434 * (To be called at end of DMA Abort procedure).
4435 * @param hdma DMA handle.
4436 * @retval None
4438 static void I2C_DMAAbort(DMA_HandleTypeDef *hdma)
4440 I2C_HandleTypeDef *hi2c = (I2C_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent;
4442 /* Disable Acknowledge */
4443 hi2c->Instance->CR2 |= I2C_CR2_NACK;
4445 /* Reset AbortCpltCallback */
4446 hi2c->hdmatx->XferAbortCallback = NULL;
4447 hi2c->hdmarx->XferAbortCallback = NULL;
4449 /* Check if come from abort from user */
4450 if (hi2c->State == HAL_I2C_STATE_ABORT)
4452 hi2c->State = HAL_I2C_STATE_READY;
4454 /* Call the corresponding callback to inform upper layer of End of Transfer */
4455 HAL_I2C_AbortCpltCallback(hi2c);
4457 else
4459 /* Call the corresponding callback to inform upper layer of End of Transfer */
4460 HAL_I2C_ErrorCallback(hi2c);
4465 * @brief This function handles I2C Communication Timeout.
4466 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
4467 * the configuration information for the specified I2C.
4468 * @param Flag Specifies the I2C flag to check.
4469 * @param Status The new Flag status (SET or RESET).
4470 * @param Timeout Timeout duration
4471 * @param Tickstart Tick start value
4472 * @retval HAL status
4474 static HAL_StatusTypeDef I2C_WaitOnFlagUntilTimeout(I2C_HandleTypeDef *hi2c, uint32_t Flag, FlagStatus Status, uint32_t Timeout, uint32_t Tickstart)
4476 while (__HAL_I2C_GET_FLAG(hi2c, Flag) == Status)
4478 /* Check for the Timeout */
4479 if (Timeout != HAL_MAX_DELAY)
4481 if ((Timeout == 0U) || ((HAL_GetTick() - Tickstart) > Timeout))
4483 hi2c->State = HAL_I2C_STATE_READY;
4484 hi2c->Mode = HAL_I2C_MODE_NONE;
4486 /* Process Unlocked */
4487 __HAL_UNLOCK(hi2c);
4488 return HAL_TIMEOUT;
4492 return HAL_OK;
4496 * @brief This function handles I2C Communication Timeout for specific usage of TXIS flag.
4497 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
4498 * the configuration information for the specified I2C.
4499 * @param Timeout Timeout duration
4500 * @param Tickstart Tick start value
4501 * @retval HAL status
4503 static HAL_StatusTypeDef I2C_WaitOnTXISFlagUntilTimeout(I2C_HandleTypeDef *hi2c, uint32_t Timeout, uint32_t Tickstart)
4505 while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_TXIS) == RESET)
4507 /* Check if a NACK is detected */
4508 if (I2C_IsAcknowledgeFailed(hi2c, Timeout, Tickstart) != HAL_OK)
4510 return HAL_ERROR;
4513 /* Check for the Timeout */
4514 if (Timeout != HAL_MAX_DELAY)
4516 if ((Timeout == 0U) || ((HAL_GetTick() - Tickstart) > Timeout))
4518 hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT;
4519 hi2c->State = HAL_I2C_STATE_READY;
4520 hi2c->Mode = HAL_I2C_MODE_NONE;
4522 /* Process Unlocked */
4523 __HAL_UNLOCK(hi2c);
4525 return HAL_TIMEOUT;
4529 return HAL_OK;
4533 * @brief This function handles I2C Communication Timeout for specific usage of STOP flag.
4534 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
4535 * the configuration information for the specified I2C.
4536 * @param Timeout Timeout duration
4537 * @param Tickstart Tick start value
4538 * @retval HAL status
4540 static HAL_StatusTypeDef I2C_WaitOnSTOPFlagUntilTimeout(I2C_HandleTypeDef *hi2c, uint32_t Timeout, uint32_t Tickstart)
4542 while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_STOPF) == RESET)
4544 /* Check if a NACK is detected */
4545 if (I2C_IsAcknowledgeFailed(hi2c, Timeout, Tickstart) != HAL_OK)
4547 return HAL_ERROR;
4550 /* Check for the Timeout */
4551 if ((Timeout == 0U) || ((HAL_GetTick() - Tickstart) > Timeout))
4553 hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT;
4554 hi2c->State = HAL_I2C_STATE_READY;
4555 hi2c->Mode = HAL_I2C_MODE_NONE;
4557 /* Process Unlocked */
4558 __HAL_UNLOCK(hi2c);
4560 return HAL_TIMEOUT;
4563 return HAL_OK;
4567 * @brief This function handles I2C Communication Timeout for specific usage of RXNE flag.
4568 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
4569 * the configuration information for the specified I2C.
4570 * @param Timeout Timeout duration
4571 * @param Tickstart Tick start value
4572 * @retval HAL status
4574 static HAL_StatusTypeDef I2C_WaitOnRXNEFlagUntilTimeout(I2C_HandleTypeDef *hi2c, uint32_t Timeout, uint32_t Tickstart)
4576 while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_RXNE) == RESET)
4578 /* Check if a NACK is detected */
4579 if (I2C_IsAcknowledgeFailed(hi2c, Timeout, Tickstart) != HAL_OK)
4581 return HAL_ERROR;
4584 /* Check if a STOPF is detected */
4585 if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_STOPF) == SET)
4587 /* Clear STOP Flag */
4588 __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_STOPF);
4590 /* Clear Configuration Register 2 */
4591 I2C_RESET_CR2(hi2c);
4593 hi2c->ErrorCode = HAL_I2C_ERROR_NONE;
4594 hi2c->State = HAL_I2C_STATE_READY;
4595 hi2c->Mode = HAL_I2C_MODE_NONE;
4597 /* Process Unlocked */
4598 __HAL_UNLOCK(hi2c);
4600 return HAL_ERROR;
4603 /* Check for the Timeout */
4604 if ((Timeout == 0U) || ((HAL_GetTick() - Tickstart) > Timeout))
4606 hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT;
4607 hi2c->State = HAL_I2C_STATE_READY;
4609 /* Process Unlocked */
4610 __HAL_UNLOCK(hi2c);
4612 return HAL_TIMEOUT;
4615 return HAL_OK;
4619 * @brief This function handles Acknowledge failed detection during an I2C Communication.
4620 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
4621 * the configuration information for the specified I2C.
4622 * @param Timeout Timeout duration
4623 * @param Tickstart Tick start value
4624 * @retval HAL status
4626 static HAL_StatusTypeDef I2C_IsAcknowledgeFailed(I2C_HandleTypeDef *hi2c, uint32_t Timeout, uint32_t Tickstart)
4628 if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_AF) == SET)
4630 /* Wait until STOP Flag is reset */
4631 /* AutoEnd should be initiate after AF */
4632 while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_STOPF) == RESET)
4634 /* Check for the Timeout */
4635 if (Timeout != HAL_MAX_DELAY)
4637 if ((Timeout == 0U) || ((HAL_GetTick() - Tickstart) > Timeout))
4639 hi2c->State = HAL_I2C_STATE_READY;
4640 hi2c->Mode = HAL_I2C_MODE_NONE;
4642 /* Process Unlocked */
4643 __HAL_UNLOCK(hi2c);
4644 return HAL_TIMEOUT;
4649 /* Clear NACKF Flag */
4650 __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_AF);
4652 /* Clear STOP Flag */
4653 __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_STOPF);
4655 /* Flush TX register */
4656 I2C_Flush_TXDR(hi2c);
4658 /* Clear Configuration Register 2 */
4659 I2C_RESET_CR2(hi2c);
4661 hi2c->ErrorCode = HAL_I2C_ERROR_AF;
4662 hi2c->State = HAL_I2C_STATE_READY;
4663 hi2c->Mode = HAL_I2C_MODE_NONE;
4665 /* Process Unlocked */
4666 __HAL_UNLOCK(hi2c);
4668 return HAL_ERROR;
4670 return HAL_OK;
4674 * @brief Handles I2Cx communication when starting transfer or during transfer (TC or TCR flag are set).
4675 * @param hi2c I2C handle.
4676 * @param DevAddress Specifies the slave address to be programmed.
4677 * @param Size Specifies the number of bytes to be programmed.
4678 * This parameter must be a value between 0 and 255.
4679 * @param Mode New state of the I2C START condition generation.
4680 * This parameter can be one of the following values:
4681 * @arg @ref I2C_RELOAD_MODE Enable Reload mode .
4682 * @arg @ref I2C_AUTOEND_MODE Enable Automatic end mode.
4683 * @arg @ref I2C_SOFTEND_MODE Enable Software end mode.
4684 * @param Request New state of the I2C START condition generation.
4685 * This parameter can be one of the following values:
4686 * @arg @ref I2C_NO_STARTSTOP Don't Generate stop and start condition.
4687 * @arg @ref I2C_GENERATE_STOP Generate stop condition (Size should be set to 0).
4688 * @arg @ref I2C_GENERATE_START_READ Generate Restart for read request.
4689 * @arg @ref I2C_GENERATE_START_WRITE Generate Restart for write request.
4690 * @retval None
4692 static void I2C_TransferConfig(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t Size, uint32_t Mode, uint32_t Request)
4694 uint32_t tmpreg = 0U;
4696 /* Check the parameters */
4697 assert_param(IS_I2C_ALL_INSTANCE(hi2c->Instance));
4698 assert_param(IS_TRANSFER_MODE(Mode));
4699 assert_param(IS_TRANSFER_REQUEST(Request));
4701 /* Get the CR2 register value */
4702 tmpreg = hi2c->Instance->CR2;
4704 /* clear tmpreg specific bits */
4705 tmpreg &= (uint32_t)~((uint32_t)(I2C_CR2_SADD | I2C_CR2_NBYTES | I2C_CR2_RELOAD | I2C_CR2_AUTOEND | I2C_CR2_RD_WRN | I2C_CR2_START | I2C_CR2_STOP));
4707 /* update tmpreg */
4708 tmpreg |= (uint32_t)(((uint32_t)DevAddress & I2C_CR2_SADD) | (((uint32_t)Size << 16) & I2C_CR2_NBYTES) | \
4709 (uint32_t)Mode | (uint32_t)Request);
4711 /* update CR2 register */
4712 hi2c->Instance->CR2 = tmpreg;
4716 * @brief Manage the enabling of Interrupts.
4717 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
4718 * the configuration information for the specified I2C.
4719 * @param InterruptRequest Value of @ref I2C_Interrupt_configuration_definition.
4720 * @retval HAL status
4722 static HAL_StatusTypeDef I2C_Enable_IRQ(I2C_HandleTypeDef *hi2c, uint16_t InterruptRequest)
4724 uint32_t tmpisr = 0U;
4726 if ((hi2c->XferISR == I2C_Master_ISR_DMA) || \
4727 (hi2c->XferISR == I2C_Slave_ISR_DMA))
4729 if ((InterruptRequest & I2C_XFER_LISTEN_IT) == I2C_XFER_LISTEN_IT)
4731 /* Enable ERR, STOP, NACK and ADDR interrupts */
4732 tmpisr |= I2C_IT_ADDRI | I2C_IT_STOPI | I2C_IT_NACKI | I2C_IT_ERRI;
4735 if ((InterruptRequest & I2C_XFER_ERROR_IT) == I2C_XFER_ERROR_IT)
4737 /* Enable ERR and NACK interrupts */
4738 tmpisr |= I2C_IT_ERRI | I2C_IT_NACKI;
4741 if ((InterruptRequest & I2C_XFER_CPLT_IT) == I2C_XFER_CPLT_IT)
4743 /* Enable STOP interrupts */
4744 tmpisr |= I2C_IT_STOPI;
4747 if ((InterruptRequest & I2C_XFER_RELOAD_IT) == I2C_XFER_RELOAD_IT)
4749 /* Enable TC interrupts */
4750 tmpisr |= I2C_IT_TCI;
4753 else
4755 if ((InterruptRequest & I2C_XFER_LISTEN_IT) == I2C_XFER_LISTEN_IT)
4757 /* Enable ERR, STOP, NACK, and ADDR interrupts */
4758 tmpisr |= I2C_IT_ADDRI | I2C_IT_STOPI | I2C_IT_NACKI | I2C_IT_ERRI;
4761 if ((InterruptRequest & I2C_XFER_TX_IT) == I2C_XFER_TX_IT)
4763 /* Enable ERR, TC, STOP, NACK and RXI interrupts */
4764 tmpisr |= I2C_IT_ERRI | I2C_IT_TCI | I2C_IT_STOPI | I2C_IT_NACKI | I2C_IT_TXI;
4767 if ((InterruptRequest & I2C_XFER_RX_IT) == I2C_XFER_RX_IT)
4769 /* Enable ERR, TC, STOP, NACK and TXI interrupts */
4770 tmpisr |= I2C_IT_ERRI | I2C_IT_TCI | I2C_IT_STOPI | I2C_IT_NACKI | I2C_IT_RXI;
4773 if ((InterruptRequest & I2C_XFER_CPLT_IT) == I2C_XFER_CPLT_IT)
4775 /* Enable STOP interrupts */
4776 tmpisr |= I2C_IT_STOPI;
4780 /* Enable interrupts only at the end */
4781 /* to avoid the risk of I2C interrupt handle execution before */
4782 /* all interrupts requested done */
4783 __HAL_I2C_ENABLE_IT(hi2c, tmpisr);
4785 return HAL_OK;
4789 * @brief Manage the disabling of Interrupts.
4790 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
4791 * the configuration information for the specified I2C.
4792 * @param InterruptRequest Value of @ref I2C_Interrupt_configuration_definition.
4793 * @retval HAL status
4795 static HAL_StatusTypeDef I2C_Disable_IRQ(I2C_HandleTypeDef *hi2c, uint16_t InterruptRequest)
4797 uint32_t tmpisr = 0U;
4799 if ((InterruptRequest & I2C_XFER_TX_IT) == I2C_XFER_TX_IT)
4801 /* Disable TC and TXI interrupts */
4802 tmpisr |= I2C_IT_TCI | I2C_IT_TXI;
4804 if ((hi2c->State & HAL_I2C_STATE_LISTEN) != HAL_I2C_STATE_LISTEN)
4806 /* Disable NACK and STOP interrupts */
4807 tmpisr |= I2C_IT_STOPI | I2C_IT_NACKI | I2C_IT_ERRI;
4811 if ((InterruptRequest & I2C_XFER_RX_IT) == I2C_XFER_RX_IT)
4813 /* Disable TC and RXI interrupts */
4814 tmpisr |= I2C_IT_TCI | I2C_IT_RXI;
4816 if ((hi2c->State & HAL_I2C_STATE_LISTEN) != HAL_I2C_STATE_LISTEN)
4818 /* Disable NACK and STOP interrupts */
4819 tmpisr |= I2C_IT_STOPI | I2C_IT_NACKI | I2C_IT_ERRI;
4823 if ((InterruptRequest & I2C_XFER_LISTEN_IT) == I2C_XFER_LISTEN_IT)
4825 /* Disable ADDR, NACK and STOP interrupts */
4826 tmpisr |= I2C_IT_ADDRI | I2C_IT_STOPI | I2C_IT_NACKI | I2C_IT_ERRI;
4829 if ((InterruptRequest & I2C_XFER_ERROR_IT) == I2C_XFER_ERROR_IT)
4831 /* Enable ERR and NACK interrupts */
4832 tmpisr |= I2C_IT_ERRI | I2C_IT_NACKI;
4835 if ((InterruptRequest & I2C_XFER_CPLT_IT) == I2C_XFER_CPLT_IT)
4837 /* Enable STOP interrupts */
4838 tmpisr |= I2C_IT_STOPI;
4841 if ((InterruptRequest & I2C_XFER_RELOAD_IT) == I2C_XFER_RELOAD_IT)
4843 /* Enable TC interrupts */
4844 tmpisr |= I2C_IT_TCI;
4847 /* Disable interrupts only at the end */
4848 /* to avoid a breaking situation like at "t" time */
4849 /* all disable interrupts request are not done */
4850 __HAL_I2C_DISABLE_IT(hi2c, tmpisr);
4852 return HAL_OK;
4856 * @}
4859 #endif /* HAL_I2C_MODULE_ENABLED */
4861 * @}
4865 * @}
4868 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/