2 ******************************************************************************
3 * @file stm32f7xx_hal_i2c.c
4 * @author MCD Application Team
7 * @brief I2C HAL module driver.
8 * This file provides firmware functions to manage the following
9 * functionalities of the Inter Integrated Circuit (I2C) peripheral:
10 * + Initialization and de-initialization functions
11 * + IO operation functions
12 * + Peripheral State and Errors functions
15 ==============================================================================
16 ##### How to use this driver #####
17 ==============================================================================
19 The I2C HAL driver can be used as follows:
21 (#) Declare a I2C_HandleTypeDef handle structure, for example:
22 I2C_HandleTypeDef hi2c;
24 (#)Initialize the I2C low level resources by implementing the HAL_I2C_MspInit() API:
25 (##) Enable the I2Cx interface clock
26 (##) I2C pins configuration
27 (+++) Enable the clock for the I2C GPIOs
28 (+++) Configure I2C pins as alternate function open-drain
29 (##) NVIC configuration if you need to use interrupt process
30 (+++) Configure the I2Cx interrupt priority
31 (+++) Enable the NVIC I2C IRQ Channel
32 (##) DMA Configuration if you need to use DMA process
33 (+++) Declare a DMA_HandleTypeDef handle structure for the transmit or receive stream
34 (+++) Enable the DMAx interface clock using
35 (+++) Configure the DMA handle parameters
36 (+++) Configure the DMA Tx or Rx stream
37 (+++) Associate the initialized DMA handle to the hi2c DMA Tx or Rx handle
38 (+++) Configure the priority and enable the NVIC for the transfer complete interrupt on
39 the DMA Tx or Rx stream
41 (#) Configure the Communication Clock Timing, Own Address1, Master Addressing mode, Dual Addressing mode,
42 Own Address2, Own Address2 Mask, General call and Nostretch mode in the hi2c Init structure.
44 (#) Initialize the I2C registers by calling the HAL_I2C_Init(), configures also the low level Hardware
45 (GPIO, CLOCK, NVIC...etc) by calling the customized HAL_I2C_MspInit(&hi2c) API.
47 (#) To check if target device is ready for communication, use the function HAL_I2C_IsDeviceReady()
49 (#) For I2C IO and IO MEM operations, three operation modes are available within this driver :
51 *** Polling mode IO operation ***
52 =================================
54 (+) Transmit in master mode an amount of data in blocking mode using HAL_I2C_Master_Transmit()
55 (+) Receive in master mode an amount of data in blocking mode using HAL_I2C_Master_Receive()
56 (+) Transmit in slave mode an amount of data in blocking mode using HAL_I2C_Slave_Transmit()
57 (+) Receive in slave mode an amount of data in blocking mode using HAL_I2C_Slave_Receive()
59 *** Polling mode IO MEM operation ***
60 =====================================
62 (+) Write an amount of data in blocking mode to a specific memory address using HAL_I2C_Mem_Write()
63 (+) Read an amount of data in blocking mode from a specific memory address using HAL_I2C_Mem_Read()
66 *** Interrupt mode IO operation ***
67 ===================================
69 (+) Transmit in master mode an amount of data in non-blocking mode using HAL_I2C_Master_Transmit_IT()
70 (+) At transmission end of transfer, HAL_I2C_MasterTxCpltCallback() is executed and user can
71 add his own code by customization of function pointer HAL_I2C_MasterTxCpltCallback()
72 (+) Receive in master mode an amount of data in non-blocking mode using HAL_I2C_Master_Receive_IT()
73 (+) At reception end of transfer, HAL_I2C_MasterRxCpltCallback() is executed and user can
74 add his own code by customization of function pointer HAL_I2C_MasterRxCpltCallback()
75 (+) Transmit in slave mode an amount of data in non-blocking mode using HAL_I2C_Slave_Transmit_IT()
76 (+) At transmission end of transfer, HAL_I2C_SlaveTxCpltCallback() is executed and user can
77 add his own code by customization of function pointer HAL_I2C_SlaveTxCpltCallback()
78 (+) Receive in slave mode an amount of data in non-blocking mode using HAL_I2C_Slave_Receive_IT()
79 (+) At reception end of transfer, HAL_I2C_SlaveRxCpltCallback() is executed and user can
80 add his own code by customization of function pointer HAL_I2C_SlaveRxCpltCallback()
81 (+) In case of transfer Error, HAL_I2C_ErrorCallback() function is executed and user can
82 add his own code by customization of function pointer HAL_I2C_ErrorCallback()
83 (+) Abort a master I2C process communication with Interrupt using HAL_I2C_Master_Abort_IT()
84 (+) End of abort process, HAL_I2C_AbortCpltCallback() is executed and user can
85 add his own code by customization of function pointer HAL_I2C_AbortCpltCallback()
86 (+) Discard a slave I2C process communication using __HAL_I2C_GENERATE_NACK() macro.
87 This action will inform Master to generate a Stop condition to discard the communication.
90 *** Interrupt mode IO sequential operation ***
91 ==============================================
93 (@) These interfaces allow to manage a sequential transfer with a repeated start condition
94 when a direction change during transfer
96 (+) A specific option field manage the different steps of a sequential transfer
97 (+) Option field values are defined through @ref I2C_XFEROPTIONS and are listed below:
98 (++) I2C_FIRST_AND_LAST_FRAME: No sequential usage, functionnal is same as associated interfaces in no sequential mode
99 (++) I2C_FIRST_FRAME: Sequential usage, this option allow to manage a sequence with start condition, address
100 and data to transfer without a final stop condition
101 (++) I2C_FIRST_AND_NEXT_FRAME: Sequential usage (Master only), this option allow to manage a sequence with start condition, address
102 and data to transfer without a final stop condition, an then permit a call the same master sequential interface
103 several times (like HAL_I2C_Master_Sequential_Transmit_IT() then HAL_I2C_Master_Sequential_Transmit_IT())
104 (++) I2C_NEXT_FRAME: Sequential usage, this option allow to manage a sequence with a restart condition, address
105 and with new data to transfer if the direction change or manage only the new data to transfer
106 if no direction change and without a final stop condition in both cases
107 (++) I2C_LAST_FRAME: Sequential usage, this option allow to manage a sequance with a restart condition, address
108 and with new data to transfer if the direction change or manage only the new data to transfer
109 if no direction change and with a final stop condition in both cases
111 (+) Differents sequential I2C interfaces are listed below:
112 (++) Sequential transmit in master I2C mode an amount of data in non-blocking mode using HAL_I2C_Master_Sequential_Transmit_IT()
113 (+++) At transmission end of current frame transfer, HAL_I2C_MasterTxCpltCallback() is executed and user can
114 add his own code by customization of function pointer HAL_I2C_MasterTxCpltCallback()
115 (++) Sequential receive in master I2C mode an amount of data in non-blocking mode using HAL_I2C_Master_Sequential_Receive_IT()
116 (+++) At reception end of current frame transfer, HAL_I2C_MasterRxCpltCallback() is executed and user can
117 add his own code by customization of function pointer HAL_I2C_MasterRxCpltCallback()
118 (++) Abort a master I2C process communication with Interrupt using HAL_I2C_Master_Abort_IT()
119 (+++) End of abort process, HAL_I2C_AbortCpltCallback() is executed and user can
120 add his own code by customization of function pointer HAL_I2C_AbortCpltCallback()
121 (++) Enable/disable the Address listen mode in slave I2C mode using HAL_I2C_EnableListen_IT() HAL_I2C_DisableListen_IT()
122 (+++) When address slave I2C match, HAL_I2C_AddrCallback() is executed and user can
123 add his own code to check the Address Match Code and the transmission direction request by master (Write/Read).
124 (+++) At Listen mode end HAL_I2C_ListenCpltCallback() is executed and user can
125 add his own code by customization of function pointer HAL_I2C_ListenCpltCallback()
126 (++) Sequential transmit in slave I2C mode an amount of data in non-blocking mode using HAL_I2C_Slave_Sequential_Transmit_IT()
127 (+++) At transmission end of current frame transfer, HAL_I2C_SlaveTxCpltCallback() is executed and user can
128 add his own code by customization of function pointer HAL_I2C_SlaveTxCpltCallback()
129 (++) Sequential receive in slave I2C mode an amount of data in non-blocking mode using HAL_I2C_Slave_Sequential_Receive_IT()
130 (+++) At reception end of current frame transfer, HAL_I2C_SlaveRxCpltCallback() is executed and user can
131 add his own code by customization of function pointer HAL_I2C_SlaveRxCpltCallback()
132 (++) In case of transfer Error, HAL_I2C_ErrorCallback() function is executed and user can
133 add his own code by customization of function pointer HAL_I2C_ErrorCallback()
134 (++) Abort a master I2C process communication with Interrupt using HAL_I2C_Master_Abort_IT()
135 (++) End of abort process, HAL_I2C_AbortCpltCallback() is executed and user can
136 add his own code by customization of function pointer HAL_I2C_AbortCpltCallback()
137 (++) Discard a slave I2C process communication using __HAL_I2C_GENERATE_NACK() macro.
138 This action will inform Master to generate a Stop condition to discard the communication.
140 *** Interrupt mode IO MEM operation ***
141 =======================================
143 (+) Write an amount of data in non-blocking mode with Interrupt to a specific memory address using
144 HAL_I2C_Mem_Write_IT()
145 (+) At Memory end of write transfer, HAL_I2C_MemTxCpltCallback() is executed and user can
146 add his own code by customization of function pointer HAL_I2C_MemTxCpltCallback()
147 (+) Read an amount of data in non-blocking mode with Interrupt from a specific memory address using
148 HAL_I2C_Mem_Read_IT()
149 (+) At Memory end of read transfer, HAL_I2C_MemRxCpltCallback() is executed and user can
150 add his own code by customization of function pointer HAL_I2C_MemRxCpltCallback()
151 (+) In case of transfer Error, HAL_I2C_ErrorCallback() function is executed and user can
152 add his own code by customization of function pointer HAL_I2C_ErrorCallback()
154 *** DMA mode IO operation ***
155 ==============================
157 (+) Transmit in master mode an amount of data in non-blocking mode (DMA) using
158 HAL_I2C_Master_Transmit_DMA()
159 (+) At transmission end of transfer, HAL_I2C_MasterTxCpltCallback() is executed and user can
160 add his own code by customization of function pointer HAL_I2C_MasterTxCpltCallback()
161 (+) Receive in master mode an amount of data in non-blocking mode (DMA) using
162 HAL_I2C_Master_Receive_DMA()
163 (+) At reception end of transfer, HAL_I2C_MasterRxCpltCallback() is executed and user can
164 add his own code by customization of function pointer HAL_I2C_MasterRxCpltCallback()
165 (+) Transmit in slave mode an amount of data in non-blocking mode (DMA) using
166 HAL_I2C_Slave_Transmit_DMA()
167 (+) At transmission end of transfer, HAL_I2C_SlaveTxCpltCallback() is executed and user can
168 add his own code by customization of function pointer HAL_I2C_SlaveTxCpltCallback()
169 (+) Receive in slave mode an amount of data in non-blocking mode (DMA) using
170 HAL_I2C_Slave_Receive_DMA()
171 (+) At reception end of transfer, HAL_I2C_SlaveRxCpltCallback() is executed and user can
172 add his own code by customization of function pointer HAL_I2C_SlaveRxCpltCallback()
173 (+) In case of transfer Error, HAL_I2C_ErrorCallback() function is executed and user can
174 add his own code by customization of function pointer HAL_I2C_ErrorCallback()
175 (+) Abort a master I2C process communication with Interrupt using HAL_I2C_Master_Abort_IT()
176 (+) End of abort process, HAL_I2C_AbortCpltCallback() is executed and user can
177 add his own code by customization of function pointer HAL_I2C_AbortCpltCallback()
178 (+) Discard a slave I2C process communication using __HAL_I2C_GENERATE_NACK() macro.
179 This action will inform Master to generate a Stop condition to discard the communication.
181 *** DMA mode IO MEM operation ***
182 =================================
184 (+) Write an amount of data in non-blocking mode with DMA to a specific memory address using
185 HAL_I2C_Mem_Write_DMA()
186 (+) At Memory end of write transfer, HAL_I2C_MemTxCpltCallback() is executed and user can
187 add his own code by customization of function pointer HAL_I2C_MemTxCpltCallback()
188 (+) Read an amount of data in non-blocking mode with DMA from a specific memory address using
189 HAL_I2C_Mem_Read_DMA()
190 (+) At Memory end of read transfer, HAL_I2C_MemRxCpltCallback() is executed and user can
191 add his own code by customization of function pointer HAL_I2C_MemRxCpltCallback()
192 (+) In case of transfer Error, HAL_I2C_ErrorCallback() function is executed and user can
193 add his own code by customization of function pointer HAL_I2C_ErrorCallback()
196 *** I2C HAL driver macros list ***
197 ==================================
199 Below the list of most used macros in I2C HAL driver.
201 (+) __HAL_I2C_ENABLE: Enable the I2C peripheral
202 (+) __HAL_I2C_DISABLE: Disable the I2C peripheral
203 (+) __HAL_I2C_GENERATE_NACK: Generate a Non-Acknowledge I2C peripheral in Slave mode
204 (+) __HAL_I2C_GET_FLAG: Check whether the specified I2C flag is set or not
205 (+) __HAL_I2C_CLEAR_FLAG: Clear the specified I2C pending flag
206 (+) __HAL_I2C_ENABLE_IT: Enable the specified I2C interrupt
207 (+) __HAL_I2C_DISABLE_IT: Disable the specified I2C interrupt
210 (@) You can refer to the I2C HAL driver header file for more useful macros
213 ******************************************************************************
216 * <h2><center>© COPYRIGHT(c) 2017 STMicroelectronics</center></h2>
218 * Redistribution and use in source and binary forms, with or without modification,
219 * are permitted provided that the following conditions are met:
220 * 1. Redistributions of source code must retain the above copyright notice,
221 * this list of conditions and the following disclaimer.
222 * 2. Redistributions in binary form must reproduce the above copyright notice,
223 * this list of conditions and the following disclaimer in the documentation
224 * and/or other materials provided with the distribution.
225 * 3. Neither the name of STMicroelectronics nor the names of its contributors
226 * may be used to endorse or promote products derived from this software
227 * without specific prior written permission.
229 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
230 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
231 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
232 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
233 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
234 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
235 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
236 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
237 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
238 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
240 ******************************************************************************
243 /* Includes ------------------------------------------------------------------*/
244 #include "stm32f7xx_hal.h"
246 /** @addtogroup STM32F7xx_HAL_Driver
250 /** @defgroup I2C I2C
251 * @brief I2C HAL module driver
255 #ifdef HAL_I2C_MODULE_ENABLED
257 /* Private typedef -----------------------------------------------------------*/
258 /* Private define ------------------------------------------------------------*/
260 /** @defgroup I2C_Private_Define I2C Private Define
263 #define TIMING_CLEAR_MASK (0xF0FFFFFFU) /*!< I2C TIMING clear register Mask */
264 #define I2C_TIMEOUT_ADDR (10000U) /*!< 10 s */
265 #define I2C_TIMEOUT_BUSY (25U) /*!< 25 ms */
266 #define I2C_TIMEOUT_DIR (25U) /*!< 25 ms */
267 #define I2C_TIMEOUT_RXNE (25U) /*!< 25 ms */
268 #define I2C_TIMEOUT_STOPF (25U) /*!< 25 ms */
269 #define I2C_TIMEOUT_TC (25U) /*!< 25 ms */
270 #define I2C_TIMEOUT_TCR (25U) /*!< 25 ms */
271 #define I2C_TIMEOUT_TXIS (25U) /*!< 25 ms */
272 #define I2C_TIMEOUT_FLAG (25U) /*!< 25 ms */
274 #define MAX_NBYTE_SIZE 255U
275 #define SlaveAddr_SHIFT 7U
276 #define SlaveAddr_MSK 0x06U
278 /* Private define for @ref PreviousState usage */
279 #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 */
280 #define I2C_STATE_NONE ((uint32_t)(HAL_I2C_MODE_NONE)) /*!< Default Value */
281 #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 */
282 #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 */
283 #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 */
284 #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 */
285 #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 */
286 #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 */
289 /* Private define to centralize the enable/disable of Interrupts */
290 #define I2C_XFER_TX_IT (0x00000001U)
291 #define I2C_XFER_RX_IT (0x00000002U)
292 #define I2C_XFER_LISTEN_IT (0x00000004U)
294 #define I2C_XFER_ERROR_IT (0x00000011U)
295 #define I2C_XFER_CPLT_IT (0x00000012U)
296 #define I2C_XFER_RELOAD_IT (0x00000012U)
298 /* Private define Sequential Transfer Options default/reset value */
299 #define I2C_NO_OPTION_FRAME (0xFFFF0000U)
304 /* Private macro -------------------------------------------------------------*/
305 #define I2C_GET_DMA_REMAIN_DATA(__HANDLE__) ((((__HANDLE__)->State) == HAL_I2C_STATE_BUSY_TX) ? \
306 ((uint32_t)((__HANDLE__)->hdmatx->Instance->NDTR)) : \
307 ((uint32_t)((__HANDLE__)->hdmarx->Instance->NDTR)))
309 /* Private variables ---------------------------------------------------------*/
310 /* Private function prototypes -----------------------------------------------*/
312 /** @defgroup I2C_Private_Functions I2C Private Functions
315 /* Private functions to handle DMA transfer */
316 static void I2C_DMAMasterTransmitCplt(DMA_HandleTypeDef
*hdma
);
317 static void I2C_DMAMasterReceiveCplt(DMA_HandleTypeDef
*hdma
);
318 static void I2C_DMASlaveTransmitCplt(DMA_HandleTypeDef
*hdma
);
319 static void I2C_DMASlaveReceiveCplt(DMA_HandleTypeDef
*hdma
);
320 static void I2C_DMAError(DMA_HandleTypeDef
*hdma
);
321 static void I2C_DMAAbort(DMA_HandleTypeDef
*hdma
);
323 /* Private functions to handle IT transfer */
324 static void I2C_ITAddrCplt(I2C_HandleTypeDef
*hi2c
, uint32_t ITFlags
);
325 static void I2C_ITMasterSequentialCplt(I2C_HandleTypeDef
*hi2c
);
326 static void I2C_ITSlaveSequentialCplt(I2C_HandleTypeDef
*hi2c
);
327 static void I2C_ITMasterCplt(I2C_HandleTypeDef
*hi2c
, uint32_t ITFlags
);
328 static void I2C_ITSlaveCplt(I2C_HandleTypeDef
*hi2c
, uint32_t ITFlags
);
329 static void I2C_ITListenCplt(I2C_HandleTypeDef
*hi2c
, uint32_t ITFlags
);
330 static void I2C_ITError(I2C_HandleTypeDef
*hi2c
, uint32_t ErrorCode
);
332 /* Private functions to handle IT transfer */
333 static HAL_StatusTypeDef
I2C_RequestMemoryWrite(I2C_HandleTypeDef
*hi2c
, uint16_t DevAddress
, uint16_t MemAddress
, uint16_t MemAddSize
, uint32_t Timeout
, uint32_t Tickstart
);
334 static HAL_StatusTypeDef
I2C_RequestMemoryRead(I2C_HandleTypeDef
*hi2c
, uint16_t DevAddress
, uint16_t MemAddress
, uint16_t MemAddSize
, uint32_t Timeout
, uint32_t Tickstart
);
336 /* Private functions for I2C transfer IRQ handler */
337 static HAL_StatusTypeDef
I2C_Master_ISR_IT(struct __I2C_HandleTypeDef
*hi2c
, uint32_t ITFlags
, uint32_t ITSources
);
338 static HAL_StatusTypeDef
I2C_Slave_ISR_IT(struct __I2C_HandleTypeDef
*hi2c
, uint32_t ITFlags
, uint32_t ITSources
);
339 static HAL_StatusTypeDef
I2C_Master_ISR_DMA(struct __I2C_HandleTypeDef
*hi2c
, uint32_t ITFlags
, uint32_t ITSources
);
340 static HAL_StatusTypeDef
I2C_Slave_ISR_DMA(struct __I2C_HandleTypeDef
*hi2c
, uint32_t ITFlags
, uint32_t ITSources
);
342 /* Private functions to handle flags during polling transfer */
343 static HAL_StatusTypeDef
I2C_WaitOnFlagUntilTimeout(I2C_HandleTypeDef
*hi2c
, uint32_t Flag
, FlagStatus Status
, uint32_t Timeout
, uint32_t Tickstart
);
344 static HAL_StatusTypeDef
I2C_WaitOnTXISFlagUntilTimeout(I2C_HandleTypeDef
*hi2c
, uint32_t Timeout
, uint32_t Tickstart
);
345 static HAL_StatusTypeDef
I2C_WaitOnRXNEFlagUntilTimeout(I2C_HandleTypeDef
*hi2c
, uint32_t Timeout
, uint32_t Tickstart
);
346 static HAL_StatusTypeDef
I2C_WaitOnSTOPFlagUntilTimeout(I2C_HandleTypeDef
*hi2c
, uint32_t Timeout
, uint32_t Tickstart
);
347 static HAL_StatusTypeDef
I2C_IsAcknowledgeFailed(I2C_HandleTypeDef
*hi2c
, uint32_t Timeout
, uint32_t Tickstart
);
349 /* Private functions to centralize the enable/disable of Interrupts */
350 static HAL_StatusTypeDef
I2C_Enable_IRQ(I2C_HandleTypeDef
*hi2c
, uint16_t InterruptRequest
);
351 static HAL_StatusTypeDef
I2C_Disable_IRQ(I2C_HandleTypeDef
*hi2c
, uint16_t InterruptRequest
);
353 /* Private functions to flush TXDR register */
354 static void I2C_Flush_TXDR(I2C_HandleTypeDef
*hi2c
);
356 /* Private functions to handle start, restart or stop a transfer */
357 static void I2C_TransferConfig(I2C_HandleTypeDef
*hi2c
, uint16_t DevAddress
, uint8_t Size
, uint32_t Mode
, uint32_t Request
);
362 /* Exported functions --------------------------------------------------------*/
364 /** @defgroup I2C_Exported_Functions I2C Exported Functions
368 /** @defgroup I2C_Exported_Functions_Group1 Initialization and de-initialization functions
369 * @brief Initialization and Configuration functions
372 ===============================================================================
373 ##### Initialization and de-initialization functions #####
374 ===============================================================================
375 [..] This subsection provides a set of functions allowing to initialize and
376 deinitialize the I2Cx peripheral:
378 (+) User must Implement HAL_I2C_MspInit() function in which he configures
379 all related peripherals resources (CLOCK, GPIO, DMA, IT and NVIC ).
381 (+) Call the function HAL_I2C_Init() to configure the selected device with
382 the selected configuration:
385 (++) Addressing mode (Master, Slave)
386 (++) Dual Addressing mode
388 (++) Own Address 2 Mask
389 (++) General call mode
392 (+) Call the function HAL_I2C_DeInit() to restore the default configuration
393 of the selected I2Cx peripheral.
400 * @brief Initializes the I2C according to the specified parameters
401 * in the I2C_InitTypeDef and initialize the associated handle.
402 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
403 * the configuration information for the specified I2C.
406 HAL_StatusTypeDef
HAL_I2C_Init(I2C_HandleTypeDef
*hi2c
)
408 /* Check the I2C handle allocation */
414 /* Check the parameters */
415 assert_param(IS_I2C_ALL_INSTANCE(hi2c
->Instance
));
416 assert_param(IS_I2C_OWN_ADDRESS1(hi2c
->Init
.OwnAddress1
));
417 assert_param(IS_I2C_ADDRESSING_MODE(hi2c
->Init
.AddressingMode
));
418 assert_param(IS_I2C_DUAL_ADDRESS(hi2c
->Init
.DualAddressMode
));
419 assert_param(IS_I2C_OWN_ADDRESS2(hi2c
->Init
.OwnAddress2
));
420 assert_param(IS_I2C_OWN_ADDRESS2_MASK(hi2c
->Init
.OwnAddress2Masks
));
421 assert_param(IS_I2C_GENERAL_CALL(hi2c
->Init
.GeneralCallMode
));
422 assert_param(IS_I2C_NO_STRETCH(hi2c
->Init
.NoStretchMode
));
424 if(hi2c
->State
== HAL_I2C_STATE_RESET
)
426 /* Allocate lock resource and initialize it */
427 hi2c
->Lock
= HAL_UNLOCKED
;
429 /* Init the low level hardware : GPIO, CLOCK, CORTEX...etc */
430 HAL_I2C_MspInit(hi2c
);
433 hi2c
->State
= HAL_I2C_STATE_BUSY
;
435 /* Disable the selected I2C peripheral */
436 __HAL_I2C_DISABLE(hi2c
);
438 /*---------------------------- I2Cx TIMINGR Configuration ------------------*/
439 /* Configure I2Cx: Frequency range */
440 hi2c
->Instance
->TIMINGR
= hi2c
->Init
.Timing
& TIMING_CLEAR_MASK
;
442 /*---------------------------- I2Cx OAR1 Configuration ---------------------*/
443 /* Disable Own Address1 before set the Own Address1 configuration */
444 hi2c
->Instance
->OAR1
&= ~I2C_OAR1_OA1EN
;
446 /* Configure I2Cx: Own Address1 and ack own address1 mode */
447 if(hi2c
->Init
.AddressingMode
== I2C_ADDRESSINGMODE_7BIT
)
449 hi2c
->Instance
->OAR1
= (I2C_OAR1_OA1EN
| hi2c
->Init
.OwnAddress1
);
451 else /* I2C_ADDRESSINGMODE_10BIT */
453 hi2c
->Instance
->OAR1
= (I2C_OAR1_OA1EN
| I2C_OAR1_OA1MODE
| hi2c
->Init
.OwnAddress1
);
456 /*---------------------------- I2Cx CR2 Configuration ----------------------*/
457 /* Configure I2Cx: Addressing Master mode */
458 if(hi2c
->Init
.AddressingMode
== I2C_ADDRESSINGMODE_10BIT
)
460 hi2c
->Instance
->CR2
= (I2C_CR2_ADD10
);
462 /* Enable the AUTOEND by default, and enable NACK (should be disable only during Slave process */
463 hi2c
->Instance
->CR2
|= (I2C_CR2_AUTOEND
| I2C_CR2_NACK
);
465 /*---------------------------- I2Cx OAR2 Configuration ---------------------*/
466 /* Disable Own Address2 before set the Own Address2 configuration */
467 hi2c
->Instance
->OAR2
&= ~I2C_DUALADDRESS_ENABLE
;
469 /* Configure I2Cx: Dual mode and Own Address2 */
470 hi2c
->Instance
->OAR2
= (hi2c
->Init
.DualAddressMode
| hi2c
->Init
.OwnAddress2
| (hi2c
->Init
.OwnAddress2Masks
<< 8));
472 /*---------------------------- I2Cx CR1 Configuration ----------------------*/
473 /* Configure I2Cx: Generalcall and NoStretch mode */
474 hi2c
->Instance
->CR1
= (hi2c
->Init
.GeneralCallMode
| hi2c
->Init
.NoStretchMode
);
476 /* Enable the selected I2C peripheral */
477 __HAL_I2C_ENABLE(hi2c
);
479 hi2c
->ErrorCode
= HAL_I2C_ERROR_NONE
;
480 hi2c
->State
= HAL_I2C_STATE_READY
;
481 hi2c
->PreviousState
= I2C_STATE_NONE
;
482 hi2c
->Mode
= HAL_I2C_MODE_NONE
;
488 * @brief DeInitialize the I2C peripheral.
489 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
490 * the configuration information for the specified I2C.
493 HAL_StatusTypeDef
HAL_I2C_DeInit(I2C_HandleTypeDef
*hi2c
)
495 /* Check the I2C handle allocation */
501 /* Check the parameters */
502 assert_param(IS_I2C_ALL_INSTANCE(hi2c
->Instance
));
504 hi2c
->State
= HAL_I2C_STATE_BUSY
;
506 /* Disable the I2C Peripheral Clock */
507 __HAL_I2C_DISABLE(hi2c
);
509 /* DeInit the low level hardware: GPIO, CLOCK, NVIC */
510 HAL_I2C_MspDeInit(hi2c
);
512 hi2c
->ErrorCode
= HAL_I2C_ERROR_NONE
;
513 hi2c
->State
= HAL_I2C_STATE_RESET
;
514 hi2c
->PreviousState
= I2C_STATE_NONE
;
515 hi2c
->Mode
= HAL_I2C_MODE_NONE
;
524 * @brief Initialize the I2C MSP.
525 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
526 * the configuration information for the specified I2C.
529 __weak
void HAL_I2C_MspInit(I2C_HandleTypeDef
*hi2c
)
531 /* Prevent unused argument(s) compilation warning */
534 /* NOTE : This function should not be modified, when the callback is needed,
535 the HAL_I2C_MspInit could be implemented in the user file
540 * @brief DeInitialize the I2C MSP.
541 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
542 * the configuration information for the specified I2C.
545 __weak
void HAL_I2C_MspDeInit(I2C_HandleTypeDef
*hi2c
)
547 /* Prevent unused argument(s) compilation warning */
550 /* NOTE : This function should not be modified, when the callback is needed,
551 the HAL_I2C_MspDeInit could be implemented in the user file
559 /** @defgroup I2C_Exported_Functions_Group2 Input and Output operation functions
560 * @brief Data transfers functions
563 ===============================================================================
564 ##### IO operation functions #####
565 ===============================================================================
567 This subsection provides a set of functions allowing to manage the I2C data
570 (#) There are two modes of transfer:
571 (++) Blocking mode : The communication is performed in the polling mode.
572 The status of all data processing is returned by the same function
573 after finishing transfer.
574 (++) No-Blocking mode : The communication is performed using Interrupts
575 or DMA. These functions return the status of the transfer startup.
576 The end of the data processing will be indicated through the
577 dedicated I2C IRQ when using Interrupt mode or the DMA IRQ when
580 (#) Blocking mode functions are :
581 (++) HAL_I2C_Master_Transmit()
582 (++) HAL_I2C_Master_Receive()
583 (++) HAL_I2C_Slave_Transmit()
584 (++) HAL_I2C_Slave_Receive()
585 (++) HAL_I2C_Mem_Write()
586 (++) HAL_I2C_Mem_Read()
587 (++) HAL_I2C_IsDeviceReady()
589 (#) No-Blocking mode functions with Interrupt are :
590 (++) HAL_I2C_Master_Transmit_IT()
591 (++) HAL_I2C_Master_Receive_IT()
592 (++) HAL_I2C_Slave_Transmit_IT()
593 (++) HAL_I2C_Slave_Receive_IT()
594 (++) HAL_I2C_Mem_Write_IT()
595 (++) HAL_I2C_Mem_Read_IT()
597 (#) No-Blocking mode functions with DMA are :
598 (++) HAL_I2C_Master_Transmit_DMA()
599 (++) HAL_I2C_Master_Receive_DMA()
600 (++) HAL_I2C_Slave_Transmit_DMA()
601 (++) HAL_I2C_Slave_Receive_DMA()
602 (++) HAL_I2C_Mem_Write_DMA()
603 (++) HAL_I2C_Mem_Read_DMA()
605 (#) A set of Transfer Complete Callbacks are provided in non Blocking mode:
606 (++) HAL_I2C_MemTxCpltCallback()
607 (++) HAL_I2C_MemRxCpltCallback()
608 (++) HAL_I2C_MasterTxCpltCallback()
609 (++) HAL_I2C_MasterRxCpltCallback()
610 (++) HAL_I2C_SlaveTxCpltCallback()
611 (++) HAL_I2C_SlaveRxCpltCallback()
612 (++) HAL_I2C_ErrorCallback()
619 * @brief Transmits in master mode an amount of data in blocking mode.
620 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
621 * the configuration information for the specified I2C.
622 * @param DevAddress Target device address: The device 7 bits address value
623 * in datasheet must be shift at right before call interface
624 * @param pData Pointer to data buffer
625 * @param Size Amount of data to be sent
626 * @param Timeout Timeout duration
629 HAL_StatusTypeDef
HAL_I2C_Master_Transmit(I2C_HandleTypeDef
*hi2c
, uint16_t DevAddress
, uint8_t *pData
, uint16_t Size
, uint32_t Timeout
)
631 uint32_t tickstart
= 0U;
633 if(hi2c
->State
== HAL_I2C_STATE_READY
)
638 /* Init tickstart for timeout management*/
639 tickstart
= HAL_GetTick();
641 if(I2C_WaitOnFlagUntilTimeout(hi2c
, I2C_FLAG_BUSY
, SET
, I2C_TIMEOUT_BUSY
, tickstart
) != HAL_OK
)
646 hi2c
->State
= HAL_I2C_STATE_BUSY_TX
;
647 hi2c
->Mode
= HAL_I2C_MODE_MASTER
;
648 hi2c
->ErrorCode
= HAL_I2C_ERROR_NONE
;
650 /* Prepare transfer parameters */
651 hi2c
->pBuffPtr
= pData
;
652 hi2c
->XferCount
= Size
;
653 hi2c
->XferISR
= NULL
;
655 /* Send Slave Address */
656 /* Set NBYTES to write and reload if hi2c->XferCount > MAX_NBYTE_SIZE and generate RESTART */
657 if(hi2c
->XferCount
> MAX_NBYTE_SIZE
)
659 hi2c
->XferSize
= MAX_NBYTE_SIZE
;
660 I2C_TransferConfig(hi2c
, DevAddress
, hi2c
->XferSize
, I2C_RELOAD_MODE
, I2C_GENERATE_START_WRITE
);
664 hi2c
->XferSize
= hi2c
->XferCount
;
665 I2C_TransferConfig(hi2c
, DevAddress
, hi2c
->XferSize
, I2C_AUTOEND_MODE
, I2C_GENERATE_START_WRITE
);
668 while(hi2c
->XferCount
> 0U)
670 /* Wait until TXIS flag is set */
671 if(I2C_WaitOnTXISFlagUntilTimeout(hi2c
, Timeout
, tickstart
) != HAL_OK
)
673 if(hi2c
->ErrorCode
== HAL_I2C_ERROR_AF
)
682 /* Write data to TXDR */
683 hi2c
->Instance
->TXDR
= (*hi2c
->pBuffPtr
++);
687 if((hi2c
->XferSize
== 0U) && (hi2c
->XferCount
!=0U))
689 /* Wait until TCR flag is set */
690 if(I2C_WaitOnFlagUntilTimeout(hi2c
, I2C_FLAG_TCR
, RESET
, Timeout
, tickstart
) != HAL_OK
)
695 if(hi2c
->XferCount
> MAX_NBYTE_SIZE
)
697 hi2c
->XferSize
= MAX_NBYTE_SIZE
;
698 I2C_TransferConfig(hi2c
, DevAddress
, hi2c
->XferSize
, I2C_RELOAD_MODE
, I2C_NO_STARTSTOP
);
702 hi2c
->XferSize
= hi2c
->XferCount
;
703 I2C_TransferConfig(hi2c
, DevAddress
, hi2c
->XferSize
, I2C_AUTOEND_MODE
, I2C_NO_STARTSTOP
);
708 /* No need to Check TC flag, with AUTOEND mode the stop is automatically generated */
709 /* Wait until STOPF flag is set */
710 if(I2C_WaitOnSTOPFlagUntilTimeout(hi2c
, Timeout
, tickstart
) != HAL_OK
)
712 if(hi2c
->ErrorCode
== HAL_I2C_ERROR_AF
)
722 /* Clear STOP Flag */
723 __HAL_I2C_CLEAR_FLAG(hi2c
, I2C_FLAG_STOPF
);
725 /* Clear Configuration Register 2 */
728 hi2c
->State
= HAL_I2C_STATE_READY
;
729 hi2c
->Mode
= HAL_I2C_MODE_NONE
;
731 /* Process Unlocked */
743 * @brief Receives in master mode an amount of data in blocking mode.
744 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
745 * the configuration information for the specified I2C.
746 * @param DevAddress Target device address: The device 7 bits address value
747 * in datasheet must be shift at right before call interface
748 * @param pData Pointer to data buffer
749 * @param Size Amount of data to be sent
750 * @param Timeout Timeout duration
753 HAL_StatusTypeDef
HAL_I2C_Master_Receive(I2C_HandleTypeDef
*hi2c
, uint16_t DevAddress
, uint8_t *pData
, uint16_t Size
, uint32_t Timeout
)
755 uint32_t tickstart
= 0U;
757 if(hi2c
->State
== HAL_I2C_STATE_READY
)
762 /* Init tickstart for timeout management*/
763 tickstart
= HAL_GetTick();
765 if(I2C_WaitOnFlagUntilTimeout(hi2c
, I2C_FLAG_BUSY
, SET
, I2C_TIMEOUT_BUSY
, tickstart
) != HAL_OK
)
770 hi2c
->State
= HAL_I2C_STATE_BUSY_RX
;
771 hi2c
->Mode
= HAL_I2C_MODE_MASTER
;
772 hi2c
->ErrorCode
= HAL_I2C_ERROR_NONE
;
774 /* Prepare transfer parameters */
775 hi2c
->pBuffPtr
= pData
;
776 hi2c
->XferCount
= Size
;
777 hi2c
->XferISR
= NULL
;
779 /* Send Slave Address */
780 /* Set NBYTES to write and reload if hi2c->XferCount > MAX_NBYTE_SIZE and generate RESTART */
781 if(hi2c
->XferCount
> MAX_NBYTE_SIZE
)
783 hi2c
->XferSize
= MAX_NBYTE_SIZE
;
784 I2C_TransferConfig(hi2c
, DevAddress
, hi2c
->XferSize
, I2C_RELOAD_MODE
, I2C_GENERATE_START_READ
);
788 hi2c
->XferSize
= hi2c
->XferCount
;
789 I2C_TransferConfig(hi2c
, DevAddress
, hi2c
->XferSize
, I2C_AUTOEND_MODE
, I2C_GENERATE_START_READ
);
792 while(hi2c
->XferCount
> 0U)
794 /* Wait until RXNE flag is set */
795 if(I2C_WaitOnRXNEFlagUntilTimeout(hi2c
, Timeout
, tickstart
) != HAL_OK
)
797 if(hi2c
->ErrorCode
== HAL_I2C_ERROR_AF
)
807 /* Read data from RXDR */
808 (*hi2c
->pBuffPtr
++) = hi2c
->Instance
->RXDR
;
812 if((hi2c
->XferSize
== 0U) && (hi2c
->XferCount
!= 0U))
814 /* Wait until TCR flag is set */
815 if(I2C_WaitOnFlagUntilTimeout(hi2c
, I2C_FLAG_TCR
, RESET
, Timeout
, tickstart
) != HAL_OK
)
820 if(hi2c
->XferCount
> MAX_NBYTE_SIZE
)
822 hi2c
->XferSize
= MAX_NBYTE_SIZE
;
823 I2C_TransferConfig(hi2c
, DevAddress
, hi2c
->XferSize
, I2C_RELOAD_MODE
, I2C_NO_STARTSTOP
);
827 hi2c
->XferSize
= hi2c
->XferCount
;
828 I2C_TransferConfig(hi2c
, DevAddress
, hi2c
->XferSize
, I2C_AUTOEND_MODE
, I2C_NO_STARTSTOP
);
833 /* No need to Check TC flag, with AUTOEND mode the stop is automatically generated */
834 /* Wait until STOPF flag is set */
835 if(I2C_WaitOnSTOPFlagUntilTimeout(hi2c
, Timeout
, tickstart
) != HAL_OK
)
837 if(hi2c
->ErrorCode
== HAL_I2C_ERROR_AF
)
847 /* Clear STOP Flag */
848 __HAL_I2C_CLEAR_FLAG(hi2c
, I2C_FLAG_STOPF
);
850 /* Clear Configuration Register 2 */
853 hi2c
->State
= HAL_I2C_STATE_READY
;
854 hi2c
->Mode
= HAL_I2C_MODE_NONE
;
856 /* Process Unlocked */
868 * @brief Transmits in slave mode an amount of data in blocking mode.
869 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
870 * the configuration information for the specified I2C.
871 * @param pData Pointer to data buffer
872 * @param Size Amount of data to be sent
873 * @param Timeout Timeout duration
876 HAL_StatusTypeDef
HAL_I2C_Slave_Transmit(I2C_HandleTypeDef
*hi2c
, uint8_t *pData
, uint16_t Size
, uint32_t Timeout
)
878 uint32_t tickstart
= 0U;
880 if(hi2c
->State
== HAL_I2C_STATE_READY
)
882 if((pData
== NULL
) || (Size
== 0U))
889 /* Init tickstart for timeout management*/
890 tickstart
= HAL_GetTick();
892 hi2c
->State
= HAL_I2C_STATE_BUSY_TX
;
893 hi2c
->Mode
= HAL_I2C_MODE_SLAVE
;
894 hi2c
->ErrorCode
= HAL_I2C_ERROR_NONE
;
896 /* Prepare transfer parameters */
897 hi2c
->pBuffPtr
= pData
;
898 hi2c
->XferCount
= Size
;
899 hi2c
->XferISR
= NULL
;
901 /* Enable Address Acknowledge */
902 hi2c
->Instance
->CR2
&= ~I2C_CR2_NACK
;
904 /* Wait until ADDR flag is set */
905 if(I2C_WaitOnFlagUntilTimeout(hi2c
, I2C_FLAG_ADDR
, RESET
, Timeout
, tickstart
) != HAL_OK
)
907 /* Disable Address Acknowledge */
908 hi2c
->Instance
->CR2
|= I2C_CR2_NACK
;
912 /* Clear ADDR flag */
913 __HAL_I2C_CLEAR_FLAG(hi2c
,I2C_FLAG_ADDR
);
915 /* If 10bit addressing mode is selected */
916 if(hi2c
->Init
.AddressingMode
== I2C_ADDRESSINGMODE_10BIT
)
918 /* Wait until ADDR flag is set */
919 if(I2C_WaitOnFlagUntilTimeout(hi2c
, I2C_FLAG_ADDR
, RESET
, Timeout
, tickstart
) != HAL_OK
)
921 /* Disable Address Acknowledge */
922 hi2c
->Instance
->CR2
|= I2C_CR2_NACK
;
926 /* Clear ADDR flag */
927 __HAL_I2C_CLEAR_FLAG(hi2c
,I2C_FLAG_ADDR
);
930 /* Wait until DIR flag is set Transmitter mode */
931 if(I2C_WaitOnFlagUntilTimeout(hi2c
, I2C_FLAG_DIR
, RESET
, Timeout
, tickstart
) != HAL_OK
)
933 /* Disable Address Acknowledge */
934 hi2c
->Instance
->CR2
|= I2C_CR2_NACK
;
938 while(hi2c
->XferCount
> 0U)
940 /* Wait until TXIS flag is set */
941 if(I2C_WaitOnTXISFlagUntilTimeout(hi2c
, Timeout
, tickstart
) != HAL_OK
)
943 /* Disable Address Acknowledge */
944 hi2c
->Instance
->CR2
|= I2C_CR2_NACK
;
946 if(hi2c
->ErrorCode
== HAL_I2C_ERROR_AF
)
956 /* Write data to TXDR */
957 hi2c
->Instance
->TXDR
= (*hi2c
->pBuffPtr
++);
961 /* Wait until STOP flag is set */
962 if(I2C_WaitOnSTOPFlagUntilTimeout(hi2c
, Timeout
, tickstart
) != HAL_OK
)
964 /* Disable Address Acknowledge */
965 hi2c
->Instance
->CR2
|= I2C_CR2_NACK
;
967 if(hi2c
->ErrorCode
== HAL_I2C_ERROR_AF
)
969 /* Normal use case for Transmitter mode */
970 /* A NACK is generated to confirm the end of transfer */
971 hi2c
->ErrorCode
= HAL_I2C_ERROR_NONE
;
979 /* Clear STOP flag */
980 __HAL_I2C_CLEAR_FLAG(hi2c
,I2C_FLAG_STOPF
);
982 /* Wait until BUSY flag is reset */
983 if(I2C_WaitOnFlagUntilTimeout(hi2c
, I2C_FLAG_BUSY
, SET
, Timeout
, tickstart
) != HAL_OK
)
985 /* Disable Address Acknowledge */
986 hi2c
->Instance
->CR2
|= I2C_CR2_NACK
;
990 /* Disable Address Acknowledge */
991 hi2c
->Instance
->CR2
|= I2C_CR2_NACK
;
993 hi2c
->State
= HAL_I2C_STATE_READY
;
994 hi2c
->Mode
= HAL_I2C_MODE_NONE
;
996 /* Process Unlocked */
1008 * @brief Receive in slave mode an amount of data in blocking mode
1009 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
1010 * the configuration information for the specified I2C.
1011 * @param pData Pointer to data buffer
1012 * @param Size Amount of data to be sent
1013 * @param Timeout Timeout duration
1014 * @retval HAL status
1016 HAL_StatusTypeDef
HAL_I2C_Slave_Receive(I2C_HandleTypeDef
*hi2c
, uint8_t *pData
, uint16_t Size
, uint32_t Timeout
)
1018 uint32_t tickstart
= 0U;
1020 if(hi2c
->State
== HAL_I2C_STATE_READY
)
1022 if((pData
== NULL
) || (Size
== 0U))
1026 /* Process Locked */
1029 /* Init tickstart for timeout management*/
1030 tickstart
= HAL_GetTick();
1032 hi2c
->State
= HAL_I2C_STATE_BUSY_RX
;
1033 hi2c
->Mode
= HAL_I2C_MODE_SLAVE
;
1034 hi2c
->ErrorCode
= HAL_I2C_ERROR_NONE
;
1036 /* Prepare transfer parameters */
1037 hi2c
->pBuffPtr
= pData
;
1038 hi2c
->XferCount
= Size
;
1039 hi2c
->XferISR
= NULL
;
1041 /* Enable Address Acknowledge */
1042 hi2c
->Instance
->CR2
&= ~I2C_CR2_NACK
;
1044 /* Wait until ADDR flag is set */
1045 if(I2C_WaitOnFlagUntilTimeout(hi2c
, I2C_FLAG_ADDR
, RESET
, Timeout
, tickstart
) != HAL_OK
)
1047 /* Disable Address Acknowledge */
1048 hi2c
->Instance
->CR2
|= I2C_CR2_NACK
;
1052 /* Clear ADDR flag */
1053 __HAL_I2C_CLEAR_FLAG(hi2c
,I2C_FLAG_ADDR
);
1055 /* Wait until DIR flag is reset Receiver mode */
1056 if(I2C_WaitOnFlagUntilTimeout(hi2c
, I2C_FLAG_DIR
, SET
, Timeout
, tickstart
) != HAL_OK
)
1058 /* Disable Address Acknowledge */
1059 hi2c
->Instance
->CR2
|= I2C_CR2_NACK
;
1063 while(hi2c
->XferCount
> 0U)
1065 /* Wait until RXNE flag is set */
1066 if(I2C_WaitOnRXNEFlagUntilTimeout(hi2c
, Timeout
, tickstart
) != HAL_OK
)
1068 /* Disable Address Acknowledge */
1069 hi2c
->Instance
->CR2
|= I2C_CR2_NACK
;
1071 /* Store Last receive data if any */
1072 if(__HAL_I2C_GET_FLAG(hi2c
, I2C_FLAG_RXNE
) == SET
)
1074 /* Read data from RXDR */
1075 (*hi2c
->pBuffPtr
++) = hi2c
->Instance
->RXDR
;
1079 if(hi2c
->ErrorCode
== HAL_I2C_ERROR_TIMEOUT
)
1089 /* Read data from RXDR */
1090 (*hi2c
->pBuffPtr
++) = hi2c
->Instance
->RXDR
;
1094 /* Wait until STOP flag is set */
1095 if(I2C_WaitOnSTOPFlagUntilTimeout(hi2c
, Timeout
, tickstart
) != HAL_OK
)
1097 /* Disable Address Acknowledge */
1098 hi2c
->Instance
->CR2
|= I2C_CR2_NACK
;
1100 if(hi2c
->ErrorCode
== HAL_I2C_ERROR_AF
)
1110 /* Clear STOP flag */
1111 __HAL_I2C_CLEAR_FLAG(hi2c
,I2C_FLAG_STOPF
);
1113 /* Wait until BUSY flag is reset */
1114 if(I2C_WaitOnFlagUntilTimeout(hi2c
, I2C_FLAG_BUSY
, SET
, Timeout
, tickstart
) != HAL_OK
)
1116 /* Disable Address Acknowledge */
1117 hi2c
->Instance
->CR2
|= I2C_CR2_NACK
;
1121 /* Disable Address Acknowledge */
1122 hi2c
->Instance
->CR2
|= I2C_CR2_NACK
;
1124 hi2c
->State
= HAL_I2C_STATE_READY
;
1125 hi2c
->Mode
= HAL_I2C_MODE_NONE
;
1127 /* Process Unlocked */
1139 * @brief Transmit in master mode an amount of data in non-blocking mode with Interrupt
1140 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
1141 * the configuration information for the specified I2C.
1142 * @param DevAddress Target device address: The device 7 bits address value
1143 * in datasheet must be shift at right before call interface
1144 * @param pData Pointer to data buffer
1145 * @param Size Amount of data to be sent
1146 * @retval HAL status
1148 HAL_StatusTypeDef
HAL_I2C_Master_Transmit_IT(I2C_HandleTypeDef
*hi2c
, uint16_t DevAddress
, uint8_t *pData
, uint16_t Size
)
1150 uint32_t xfermode
= 0U;
1152 if(hi2c
->State
== HAL_I2C_STATE_READY
)
1154 if(__HAL_I2C_GET_FLAG(hi2c
, I2C_FLAG_BUSY
) == SET
)
1159 /* Process Locked */
1162 hi2c
->State
= HAL_I2C_STATE_BUSY_TX
;
1163 hi2c
->Mode
= HAL_I2C_MODE_MASTER
;
1164 hi2c
->ErrorCode
= HAL_I2C_ERROR_NONE
;
1166 /* Prepare transfer parameters */
1167 hi2c
->pBuffPtr
= pData
;
1168 hi2c
->XferCount
= Size
;
1169 hi2c
->XferOptions
= I2C_NO_OPTION_FRAME
;
1170 hi2c
->XferISR
= I2C_Master_ISR_IT
;
1172 if(hi2c
->XferCount
> MAX_NBYTE_SIZE
)
1174 hi2c
->XferSize
= MAX_NBYTE_SIZE
;
1175 xfermode
= I2C_RELOAD_MODE
;
1179 hi2c
->XferSize
= hi2c
->XferCount
;
1180 xfermode
= I2C_AUTOEND_MODE
;
1183 /* Send Slave Address */
1184 /* Set NBYTES to write and reload if hi2c->XferCount > MAX_NBYTE_SIZE */
1185 I2C_TransferConfig(hi2c
, DevAddress
, hi2c
->XferSize
, xfermode
, I2C_GENERATE_START_WRITE
);
1187 /* Process Unlocked */
1190 /* Note : The I2C interrupts must be enabled after unlocking current process
1191 to avoid the risk of I2C interrupt handle execution before current
1194 /* Enable ERR, TC, STOP, NACK, TXI interrupt */
1195 /* possible to enable all of these */
1196 /* I2C_IT_ERRI | I2C_IT_TCI| I2C_IT_STOPI| I2C_IT_NACKI | I2C_IT_ADDRI | I2C_IT_RXI | I2C_IT_TXI */
1197 I2C_Enable_IRQ(hi2c
, I2C_XFER_TX_IT
);
1208 * @brief Receive in master mode an amount of data in non-blocking mode with Interrupt
1209 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
1210 * the configuration information for the specified I2C.
1211 * @param DevAddress Target device address: The device 7 bits address value
1212 * in datasheet must be shift at right before call interface
1213 * @param pData Pointer to data buffer
1214 * @param Size Amount of data to be sent
1215 * @retval HAL status
1217 HAL_StatusTypeDef
HAL_I2C_Master_Receive_IT(I2C_HandleTypeDef
*hi2c
, uint16_t DevAddress
, uint8_t *pData
, uint16_t Size
)
1219 uint32_t xfermode
= 0U;
1221 if(hi2c
->State
== HAL_I2C_STATE_READY
)
1223 if(__HAL_I2C_GET_FLAG(hi2c
, I2C_FLAG_BUSY
) == SET
)
1228 /* Process Locked */
1231 hi2c
->State
= HAL_I2C_STATE_BUSY_RX
;
1232 hi2c
->Mode
= HAL_I2C_MODE_MASTER
;
1233 hi2c
->ErrorCode
= HAL_I2C_ERROR_NONE
;
1235 /* Prepare transfer parameters */
1236 hi2c
->pBuffPtr
= pData
;
1237 hi2c
->XferCount
= Size
;
1238 hi2c
->XferOptions
= I2C_NO_OPTION_FRAME
;
1239 hi2c
->XferISR
= I2C_Master_ISR_IT
;
1241 if(hi2c
->XferCount
> MAX_NBYTE_SIZE
)
1243 hi2c
->XferSize
= MAX_NBYTE_SIZE
;
1244 xfermode
= I2C_RELOAD_MODE
;
1248 hi2c
->XferSize
= hi2c
->XferCount
;
1249 xfermode
= I2C_AUTOEND_MODE
;
1252 /* Send Slave Address */
1253 /* Set NBYTES to write and reload if hi2c->XferCount > MAX_NBYTE_SIZE */
1254 I2C_TransferConfig(hi2c
, DevAddress
, hi2c
->XferSize
, xfermode
, I2C_GENERATE_START_READ
);
1256 /* Process Unlocked */
1259 /* Note : The I2C interrupts must be enabled after unlocking current process
1260 to avoid the risk of I2C interrupt handle execution before current
1263 /* Enable ERR, TC, STOP, NACK, RXI interrupt */
1264 /* possible to enable all of these */
1265 /* I2C_IT_ERRI | I2C_IT_TCI| I2C_IT_STOPI| I2C_IT_NACKI | I2C_IT_ADDRI | I2C_IT_RXI | I2C_IT_TXI */
1266 I2C_Enable_IRQ(hi2c
, I2C_XFER_RX_IT
);
1277 * @brief Transmit in slave mode an amount of data in non-blocking mode with Interrupt
1278 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
1279 * the configuration information for the specified I2C.
1280 * @param pData Pointer to data buffer
1281 * @param Size Amount of data to be sent
1282 * @retval HAL status
1284 HAL_StatusTypeDef
HAL_I2C_Slave_Transmit_IT(I2C_HandleTypeDef
*hi2c
, uint8_t *pData
, uint16_t Size
)
1286 if(hi2c
->State
== HAL_I2C_STATE_READY
)
1288 /* Process Locked */
1291 hi2c
->State
= HAL_I2C_STATE_BUSY_TX
;
1292 hi2c
->Mode
= HAL_I2C_MODE_SLAVE
;
1293 hi2c
->ErrorCode
= HAL_I2C_ERROR_NONE
;
1295 /* Enable Address Acknowledge */
1296 hi2c
->Instance
->CR2
&= ~I2C_CR2_NACK
;
1298 /* Prepare transfer parameters */
1299 hi2c
->pBuffPtr
= pData
;
1300 hi2c
->XferCount
= Size
;
1301 hi2c
->XferSize
= hi2c
->XferCount
;
1302 hi2c
->XferOptions
= I2C_NO_OPTION_FRAME
;
1303 hi2c
->XferISR
= I2C_Slave_ISR_IT
;
1305 /* Process Unlocked */
1308 /* Note : The I2C interrupts must be enabled after unlocking current process
1309 to avoid the risk of I2C interrupt handle execution before current
1312 /* Enable ERR, TC, STOP, NACK, TXI interrupt */
1313 /* possible to enable all of these */
1314 /* I2C_IT_ERRI | I2C_IT_TCI| I2C_IT_STOPI| I2C_IT_NACKI | I2C_IT_ADDRI | I2C_IT_RXI | I2C_IT_TXI */
1315 I2C_Enable_IRQ(hi2c
, I2C_XFER_TX_IT
| I2C_XFER_LISTEN_IT
);
1326 * @brief Receive in slave mode an amount of data in non-blocking mode with Interrupt
1327 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
1328 * the configuration information for the specified I2C.
1329 * @param pData Pointer to data buffer
1330 * @param Size Amount of data to be sent
1331 * @retval HAL status
1333 HAL_StatusTypeDef
HAL_I2C_Slave_Receive_IT(I2C_HandleTypeDef
*hi2c
, uint8_t *pData
, uint16_t Size
)
1335 if(hi2c
->State
== HAL_I2C_STATE_READY
)
1337 /* Process Locked */
1340 hi2c
->State
= HAL_I2C_STATE_BUSY_RX
;
1341 hi2c
->Mode
= HAL_I2C_MODE_SLAVE
;
1342 hi2c
->ErrorCode
= HAL_I2C_ERROR_NONE
;
1344 /* Enable Address Acknowledge */
1345 hi2c
->Instance
->CR2
&= ~I2C_CR2_NACK
;
1347 /* Prepare transfer parameters */
1348 hi2c
->pBuffPtr
= pData
;
1349 hi2c
->XferCount
= Size
;
1350 hi2c
->XferSize
= hi2c
->XferCount
;
1351 hi2c
->XferOptions
= I2C_NO_OPTION_FRAME
;
1352 hi2c
->XferISR
= I2C_Slave_ISR_IT
;
1354 /* Process Unlocked */
1357 /* Note : The I2C interrupts must be enabled after unlocking current process
1358 to avoid the risk of I2C interrupt handle execution before current
1361 /* Enable ERR, TC, STOP, NACK, RXI interrupt */
1362 /* possible to enable all of these */
1363 /* I2C_IT_ERRI | I2C_IT_TCI| I2C_IT_STOPI| I2C_IT_NACKI | I2C_IT_ADDRI | I2C_IT_RXI | I2C_IT_TXI */
1364 I2C_Enable_IRQ(hi2c
, I2C_XFER_RX_IT
| I2C_XFER_LISTEN_IT
);
1375 * @brief Transmit in master mode an amount of data in non-blocking mode with DMA
1376 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
1377 * the configuration information for the specified I2C.
1378 * @param DevAddress Target device address: The device 7 bits address value
1379 * in datasheet must be shift at right before call interface
1380 * @param pData Pointer to data buffer
1381 * @param Size Amount of data to be sent
1382 * @retval HAL status
1384 HAL_StatusTypeDef
HAL_I2C_Master_Transmit_DMA(I2C_HandleTypeDef
*hi2c
, uint16_t DevAddress
, uint8_t *pData
, uint16_t Size
)
1386 uint32_t xfermode
= 0U;
1388 if(hi2c
->State
== HAL_I2C_STATE_READY
)
1390 if(__HAL_I2C_GET_FLAG(hi2c
, I2C_FLAG_BUSY
) == SET
)
1395 /* Process Locked */
1398 hi2c
->State
= HAL_I2C_STATE_BUSY_TX
;
1399 hi2c
->Mode
= HAL_I2C_MODE_MASTER
;
1400 hi2c
->ErrorCode
= HAL_I2C_ERROR_NONE
;
1402 /* Prepare transfer parameters */
1403 hi2c
->pBuffPtr
= pData
;
1404 hi2c
->XferCount
= Size
;
1405 hi2c
->XferOptions
= I2C_NO_OPTION_FRAME
;
1406 hi2c
->XferISR
= I2C_Master_ISR_DMA
;
1408 if(hi2c
->XferCount
> MAX_NBYTE_SIZE
)
1410 hi2c
->XferSize
= MAX_NBYTE_SIZE
;
1411 xfermode
= I2C_RELOAD_MODE
;
1415 hi2c
->XferSize
= hi2c
->XferCount
;
1416 xfermode
= I2C_AUTOEND_MODE
;
1419 if(hi2c
->XferSize
> 0U)
1421 /* Set the I2C DMA transfer complete callback */
1422 hi2c
->hdmatx
->XferCpltCallback
= I2C_DMAMasterTransmitCplt
;
1424 /* Set the DMA error callback */
1425 hi2c
->hdmatx
->XferErrorCallback
= I2C_DMAError
;
1427 /* Set the unused DMA callbacks to NULL */
1428 hi2c
->hdmatx
->XferHalfCpltCallback
= NULL
;
1429 hi2c
->hdmatx
->XferAbortCallback
= NULL
;
1431 /* Enable the DMA channel */
1432 HAL_DMA_Start_IT(hi2c
->hdmatx
, (uint32_t)pData
, (uint32_t)&hi2c
->Instance
->TXDR
, hi2c
->XferSize
);
1434 /* Send Slave Address */
1435 /* Set NBYTES to write and reload if hi2c->XferCount > MAX_NBYTE_SIZE and generate RESTART */
1436 I2C_TransferConfig(hi2c
, DevAddress
, hi2c
->XferSize
, xfermode
, I2C_GENERATE_START_WRITE
);
1438 /* Update XferCount value */
1439 hi2c
->XferCount
-= hi2c
->XferSize
;
1441 /* Process Unlocked */
1444 /* Note : The I2C interrupts must be enabled after unlocking current process
1445 to avoid the risk of I2C interrupt handle execution before current
1447 /* Enable ERR and NACK interrupts */
1448 I2C_Enable_IRQ(hi2c
, I2C_XFER_ERROR_IT
);
1450 /* Enable DMA Request */
1451 hi2c
->Instance
->CR1
|= I2C_CR1_TXDMAEN
;
1455 /* Update Transfer ISR function pointer */
1456 hi2c
->XferISR
= I2C_Master_ISR_IT
;
1458 /* Send Slave Address */
1459 /* Set NBYTES to write and generate START condition */
1460 I2C_TransferConfig(hi2c
, DevAddress
, hi2c
->XferSize
, I2C_AUTOEND_MODE
, I2C_GENERATE_START_WRITE
);
1462 /* Process Unlocked */
1465 /* Note : The I2C interrupts must be enabled after unlocking current process
1466 to avoid the risk of I2C interrupt handle execution before current
1468 /* Enable ERR, TC, STOP, NACK, TXI interrupt */
1469 /* possible to enable all of these */
1470 /* I2C_IT_ERRI | I2C_IT_TCI| I2C_IT_STOPI| I2C_IT_NACKI | I2C_IT_ADDRI | I2C_IT_RXI | I2C_IT_TXI */
1471 I2C_Enable_IRQ(hi2c
, I2C_XFER_TX_IT
);
1483 * @brief Receive in master mode an amount of data in non-blocking mode with DMA
1484 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
1485 * the configuration information for the specified I2C.
1486 * @param DevAddress Target device address: The device 7 bits address value
1487 * in datasheet must be shift at right before call interface
1488 * @param pData Pointer to data buffer
1489 * @param Size Amount of data to be sent
1490 * @retval HAL status
1492 HAL_StatusTypeDef
HAL_I2C_Master_Receive_DMA(I2C_HandleTypeDef
*hi2c
, uint16_t DevAddress
, uint8_t *pData
, uint16_t Size
)
1494 uint32_t xfermode
= 0U;
1496 if(hi2c
->State
== HAL_I2C_STATE_READY
)
1498 if(__HAL_I2C_GET_FLAG(hi2c
, I2C_FLAG_BUSY
) == SET
)
1503 /* Process Locked */
1506 hi2c
->State
= HAL_I2C_STATE_BUSY_RX
;
1507 hi2c
->Mode
= HAL_I2C_MODE_MASTER
;
1508 hi2c
->ErrorCode
= HAL_I2C_ERROR_NONE
;
1510 /* Prepare transfer parameters */
1511 hi2c
->pBuffPtr
= pData
;
1512 hi2c
->XferCount
= Size
;
1513 hi2c
->XferOptions
= I2C_NO_OPTION_FRAME
;
1514 hi2c
->XferISR
= I2C_Master_ISR_DMA
;
1516 if(hi2c
->XferCount
> MAX_NBYTE_SIZE
)
1518 hi2c
->XferSize
= MAX_NBYTE_SIZE
;
1519 xfermode
= I2C_RELOAD_MODE
;
1523 hi2c
->XferSize
= hi2c
->XferCount
;
1524 xfermode
= I2C_AUTOEND_MODE
;
1527 if(hi2c
->XferSize
> 0U)
1529 /* Set the I2C DMA transfer complete callback */
1530 hi2c
->hdmarx
->XferCpltCallback
= I2C_DMAMasterReceiveCplt
;
1532 /* Set the DMA error callback */
1533 hi2c
->hdmarx
->XferErrorCallback
= I2C_DMAError
;
1535 /* Set the unused DMA callbacks to NULL */
1536 hi2c
->hdmarx
->XferHalfCpltCallback
= NULL
;
1537 hi2c
->hdmarx
->XferAbortCallback
= NULL
;
1539 /* Enable the DMA channel */
1540 HAL_DMA_Start_IT(hi2c
->hdmarx
, (uint32_t)&hi2c
->Instance
->RXDR
, (uint32_t)pData
, hi2c
->XferSize
);
1542 /* Send Slave Address */
1543 /* Set NBYTES to read and reload if hi2c->XferCount > MAX_NBYTE_SIZE and generate RESTART */
1544 I2C_TransferConfig(hi2c
,DevAddress
,hi2c
->XferSize
, xfermode
, I2C_GENERATE_START_READ
);
1546 /* Update XferCount value */
1547 hi2c
->XferCount
-= hi2c
->XferSize
;
1549 /* Process Unlocked */
1552 /* Note : The I2C interrupts must be enabled after unlocking current process
1553 to avoid the risk of I2C interrupt handle execution before current
1555 /* Enable ERR and NACK interrupts */
1556 I2C_Enable_IRQ(hi2c
, I2C_XFER_ERROR_IT
);
1558 /* Enable DMA Request */
1559 hi2c
->Instance
->CR1
|= I2C_CR1_RXDMAEN
;
1563 /* Update Transfer ISR function pointer */
1564 hi2c
->XferISR
= I2C_Master_ISR_IT
;
1566 /* Send Slave Address */
1567 /* Set NBYTES to read and generate START condition */
1568 I2C_TransferConfig(hi2c
, DevAddress
, hi2c
->XferSize
, I2C_AUTOEND_MODE
, I2C_GENERATE_START_READ
);
1570 /* Process Unlocked */
1573 /* Note : The I2C interrupts must be enabled after unlocking current process
1574 to avoid the risk of I2C interrupt handle execution before current
1576 /* Enable ERR, TC, STOP, NACK, TXI interrupt */
1577 /* possible to enable all of these */
1578 /* I2C_IT_ERRI | I2C_IT_TCI| I2C_IT_STOPI| I2C_IT_NACKI | I2C_IT_ADDRI | I2C_IT_RXI | I2C_IT_TXI */
1579 I2C_Enable_IRQ(hi2c
, I2C_XFER_TX_IT
);
1590 * @brief Transmit in slave mode an amount of data in non-blocking mode with DMA
1591 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
1592 * the configuration information for the specified I2C.
1593 * @param pData Pointer to data buffer
1594 * @param Size Amount of data to be sent
1595 * @retval HAL status
1597 HAL_StatusTypeDef
HAL_I2C_Slave_Transmit_DMA(I2C_HandleTypeDef
*hi2c
, uint8_t *pData
, uint16_t Size
)
1599 if(hi2c
->State
== HAL_I2C_STATE_READY
)
1601 if((pData
== NULL
) || (Size
== 0U))
1605 /* Process Locked */
1608 hi2c
->State
= HAL_I2C_STATE_BUSY_TX
;
1609 hi2c
->Mode
= HAL_I2C_MODE_SLAVE
;
1610 hi2c
->ErrorCode
= HAL_I2C_ERROR_NONE
;
1612 /* Prepare transfer parameters */
1613 hi2c
->pBuffPtr
= pData
;
1614 hi2c
->XferCount
= Size
;
1615 hi2c
->XferSize
= hi2c
->XferCount
;
1616 hi2c
->XferOptions
= I2C_NO_OPTION_FRAME
;
1617 hi2c
->XferISR
= I2C_Slave_ISR_DMA
;
1619 /* Set the I2C DMA transfer complete callback */
1620 hi2c
->hdmatx
->XferCpltCallback
= I2C_DMASlaveTransmitCplt
;
1622 /* Set the DMA error callback */
1623 hi2c
->hdmatx
->XferErrorCallback
= I2C_DMAError
;
1625 /* Set the unused DMA callbacks to NULL */
1626 hi2c
->hdmatx
->XferHalfCpltCallback
= NULL
;
1627 hi2c
->hdmatx
->XferAbortCallback
= NULL
;
1629 /* Enable the DMA channel */
1630 HAL_DMA_Start_IT(hi2c
->hdmatx
, (uint32_t)pData
, (uint32_t)&hi2c
->Instance
->TXDR
, hi2c
->XferSize
);
1632 /* Enable Address Acknowledge */
1633 hi2c
->Instance
->CR2
&= ~I2C_CR2_NACK
;
1635 /* Process Unlocked */
1638 /* Note : The I2C interrupts must be enabled after unlocking current process
1639 to avoid the risk of I2C interrupt handle execution before current
1641 /* Enable ERR, STOP, NACK, ADDR interrupts */
1642 I2C_Enable_IRQ(hi2c
, I2C_XFER_LISTEN_IT
);
1644 /* Enable DMA Request */
1645 hi2c
->Instance
->CR1
|= I2C_CR1_TXDMAEN
;
1656 * @brief Receive in slave mode an amount of data in non-blocking mode with DMA
1657 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
1658 * the configuration information for the specified I2C.
1659 * @param pData Pointer to data buffer
1660 * @param Size Amount of data to be sent
1661 * @retval HAL status
1663 HAL_StatusTypeDef
HAL_I2C_Slave_Receive_DMA(I2C_HandleTypeDef
*hi2c
, uint8_t *pData
, uint16_t Size
)
1665 if(hi2c
->State
== HAL_I2C_STATE_READY
)
1667 if((pData
== NULL
) || (Size
== 0U))
1671 /* Process Locked */
1674 hi2c
->State
= HAL_I2C_STATE_BUSY_RX
;
1675 hi2c
->Mode
= HAL_I2C_MODE_SLAVE
;
1676 hi2c
->ErrorCode
= HAL_I2C_ERROR_NONE
;
1678 /* Prepare transfer parameters */
1679 hi2c
->pBuffPtr
= pData
;
1680 hi2c
->XferCount
= Size
;
1681 hi2c
->XferSize
= hi2c
->XferCount
;
1682 hi2c
->XferOptions
= I2C_NO_OPTION_FRAME
;
1683 hi2c
->XferISR
= I2C_Slave_ISR_DMA
;
1685 /* Set the I2C DMA transfer complete callback */
1686 hi2c
->hdmarx
->XferCpltCallback
= I2C_DMASlaveReceiveCplt
;
1688 /* Set the DMA error callback */
1689 hi2c
->hdmarx
->XferErrorCallback
= I2C_DMAError
;
1691 /* Set the unused DMA callbacks to NULL */
1692 hi2c
->hdmarx
->XferHalfCpltCallback
= NULL
;
1693 hi2c
->hdmarx
->XferAbortCallback
= NULL
;
1695 /* Enable the DMA channel */
1696 HAL_DMA_Start_IT(hi2c
->hdmarx
, (uint32_t)&hi2c
->Instance
->RXDR
, (uint32_t)pData
, hi2c
->XferSize
);
1698 /* Enable Address Acknowledge */
1699 hi2c
->Instance
->CR2
&= ~I2C_CR2_NACK
;
1701 /* Process Unlocked */
1704 /* Note : The I2C interrupts must be enabled after unlocking current process
1705 to avoid the risk of I2C interrupt handle execution before current
1707 /* Enable ERR, STOP, NACK, ADDR interrupts */
1708 I2C_Enable_IRQ(hi2c
, I2C_XFER_LISTEN_IT
);
1710 /* Enable DMA Request */
1711 hi2c
->Instance
->CR1
|= I2C_CR1_RXDMAEN
;
1721 * @brief Write an amount of data in blocking mode to a specific memory address
1722 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
1723 * the configuration information for the specified I2C.
1724 * @param DevAddress Target device address: The device 7 bits address value
1725 * in datasheet must be shift at right before call interface
1726 * @param MemAddress Internal memory address
1727 * @param MemAddSize Size of internal memory address
1728 * @param pData Pointer to data buffer
1729 * @param Size Amount of data to be sent
1730 * @param Timeout Timeout duration
1731 * @retval HAL status
1733 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
)
1735 uint32_t tickstart
= 0U;
1737 /* Check the parameters */
1738 assert_param(IS_I2C_MEMADD_SIZE(MemAddSize
));
1740 if(hi2c
->State
== HAL_I2C_STATE_READY
)
1742 if((pData
== NULL
) || (Size
== 0U))
1747 /* Process Locked */
1750 /* Init tickstart for timeout management*/
1751 tickstart
= HAL_GetTick();
1753 if(I2C_WaitOnFlagUntilTimeout(hi2c
, I2C_FLAG_BUSY
, SET
, I2C_TIMEOUT_BUSY
, tickstart
) != HAL_OK
)
1758 hi2c
->State
= HAL_I2C_STATE_BUSY_TX
;
1759 hi2c
->Mode
= HAL_I2C_MODE_MEM
;
1760 hi2c
->ErrorCode
= HAL_I2C_ERROR_NONE
;
1762 /* Prepare transfer parameters */
1763 hi2c
->pBuffPtr
= pData
;
1764 hi2c
->XferCount
= Size
;
1765 hi2c
->XferISR
= NULL
;
1767 /* Send Slave Address and Memory Address */
1768 if(I2C_RequestMemoryWrite(hi2c
, DevAddress
, MemAddress
, MemAddSize
, Timeout
, tickstart
) != HAL_OK
)
1770 if(hi2c
->ErrorCode
== HAL_I2C_ERROR_AF
)
1772 /* Process Unlocked */
1778 /* Process Unlocked */
1784 /* Set NBYTES to write and reload if hi2c->XferCount > MAX_NBYTE_SIZE */
1785 if(hi2c
->XferCount
> MAX_NBYTE_SIZE
)
1787 hi2c
->XferSize
= MAX_NBYTE_SIZE
;
1788 I2C_TransferConfig(hi2c
, DevAddress
, hi2c
->XferSize
, I2C_RELOAD_MODE
, I2C_NO_STARTSTOP
);
1792 hi2c
->XferSize
= hi2c
->XferCount
;
1793 I2C_TransferConfig(hi2c
, DevAddress
, hi2c
->XferSize
, I2C_AUTOEND_MODE
, I2C_NO_STARTSTOP
);
1798 /* Wait until TXIS flag is set */
1799 if(I2C_WaitOnTXISFlagUntilTimeout(hi2c
, Timeout
, tickstart
) != HAL_OK
)
1801 if(hi2c
->ErrorCode
== HAL_I2C_ERROR_AF
)
1811 /* Write data to TXDR */
1812 hi2c
->Instance
->TXDR
= (*hi2c
->pBuffPtr
++);
1816 if((hi2c
->XferSize
== 0U) && (hi2c
->XferCount
!=0U))
1818 /* Wait until TCR flag is set */
1819 if(I2C_WaitOnFlagUntilTimeout(hi2c
, I2C_FLAG_TCR
, RESET
, Timeout
, tickstart
) != HAL_OK
)
1824 if(hi2c
->XferCount
> MAX_NBYTE_SIZE
)
1826 hi2c
->XferSize
= MAX_NBYTE_SIZE
;
1827 I2C_TransferConfig(hi2c
, DevAddress
, hi2c
->XferSize
, I2C_RELOAD_MODE
, I2C_NO_STARTSTOP
);
1831 hi2c
->XferSize
= hi2c
->XferCount
;
1832 I2C_TransferConfig(hi2c
, DevAddress
, hi2c
->XferSize
, I2C_AUTOEND_MODE
, I2C_NO_STARTSTOP
);
1836 }while(hi2c
->XferCount
> 0U);
1838 /* No need to Check TC flag, with AUTOEND mode the stop is automatically generated */
1839 /* Wait until STOPF flag is reset */
1840 if(I2C_WaitOnSTOPFlagUntilTimeout(hi2c
, Timeout
, tickstart
) != HAL_OK
)
1842 if(hi2c
->ErrorCode
== HAL_I2C_ERROR_AF
)
1852 /* Clear STOP Flag */
1853 __HAL_I2C_CLEAR_FLAG(hi2c
, I2C_FLAG_STOPF
);
1855 /* Clear Configuration Register 2 */
1856 I2C_RESET_CR2(hi2c
);
1858 hi2c
->State
= HAL_I2C_STATE_READY
;
1859 hi2c
->Mode
= HAL_I2C_MODE_NONE
;
1861 /* Process Unlocked */
1873 * @brief Read an amount of data in blocking mode from a specific memory address
1874 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
1875 * the configuration information for the specified I2C.
1876 * @param DevAddress Target device address: The device 7 bits address value
1877 * in datasheet must be shift at right before call interface
1878 * @param MemAddress Internal memory address
1879 * @param MemAddSize Size of internal memory address
1880 * @param pData Pointer to data buffer
1881 * @param Size Amount of data to be sent
1882 * @param Timeout Timeout duration
1883 * @retval HAL status
1885 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
)
1887 uint32_t tickstart
= 0U;
1889 /* Check the parameters */
1890 assert_param(IS_I2C_MEMADD_SIZE(MemAddSize
));
1892 if(hi2c
->State
== HAL_I2C_STATE_READY
)
1894 if((pData
== NULL
) || (Size
== 0U))
1899 /* Process Locked */
1902 /* Init tickstart for timeout management*/
1903 tickstart
= HAL_GetTick();
1905 if(I2C_WaitOnFlagUntilTimeout(hi2c
, I2C_FLAG_BUSY
, SET
, I2C_TIMEOUT_BUSY
, tickstart
) != HAL_OK
)
1910 hi2c
->State
= HAL_I2C_STATE_BUSY_RX
;
1911 hi2c
->Mode
= HAL_I2C_MODE_MEM
;
1912 hi2c
->ErrorCode
= HAL_I2C_ERROR_NONE
;
1914 /* Prepare transfer parameters */
1915 hi2c
->pBuffPtr
= pData
;
1916 hi2c
->XferCount
= Size
;
1917 hi2c
->XferISR
= NULL
;
1919 /* Send Slave Address and Memory Address */
1920 if(I2C_RequestMemoryRead(hi2c
, DevAddress
, MemAddress
, MemAddSize
, Timeout
, tickstart
) != HAL_OK
)
1922 if(hi2c
->ErrorCode
== HAL_I2C_ERROR_AF
)
1924 /* Process Unlocked */
1930 /* Process Unlocked */
1936 /* Send Slave Address */
1937 /* Set NBYTES to write and reload if hi2c->XferCount > MAX_NBYTE_SIZE and generate RESTART */
1938 if(hi2c
->XferCount
> MAX_NBYTE_SIZE
)
1940 hi2c
->XferSize
= MAX_NBYTE_SIZE
;
1941 I2C_TransferConfig(hi2c
, DevAddress
, hi2c
->XferSize
, I2C_RELOAD_MODE
, I2C_GENERATE_START_READ
);
1945 hi2c
->XferSize
= hi2c
->XferCount
;
1946 I2C_TransferConfig(hi2c
, DevAddress
, hi2c
->XferSize
, I2C_AUTOEND_MODE
, I2C_GENERATE_START_READ
);
1951 /* Wait until RXNE flag is set */
1952 if(I2C_WaitOnFlagUntilTimeout(hi2c
, I2C_FLAG_RXNE
, RESET
, Timeout
, tickstart
) != HAL_OK
)
1957 /* Read data from RXDR */
1958 (*hi2c
->pBuffPtr
++) = hi2c
->Instance
->RXDR
;
1962 if((hi2c
->XferSize
== 0U) && (hi2c
->XferCount
!= 0U))
1964 /* Wait until TCR flag is set */
1965 if(I2C_WaitOnFlagUntilTimeout(hi2c
, I2C_FLAG_TCR
, RESET
, Timeout
, tickstart
) != HAL_OK
)
1970 if(hi2c
->XferCount
> MAX_NBYTE_SIZE
)
1972 hi2c
->XferSize
= MAX_NBYTE_SIZE
;
1973 I2C_TransferConfig(hi2c
, DevAddress
, hi2c
->XferSize
, I2C_RELOAD_MODE
, I2C_NO_STARTSTOP
);
1977 hi2c
->XferSize
= hi2c
->XferCount
;
1978 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
)
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 */
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))
2043 if(__HAL_I2C_GET_FLAG(hi2c
, I2C_FLAG_BUSY
) == SET
)
2048 /* Process Locked */
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
;
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 */
2086 /* Process Unlocked */
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 */
2098 /* Note : The I2C interrupts must be enabled after unlocking current process
2099 to avoid the risk of I2C interrupt handle execution before current
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
);
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))
2142 if(__HAL_I2C_GET_FLAG(hi2c
, I2C_FLAG_BUSY
) == SET
)
2147 /* Process Locked */
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
;
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 */
2185 /* Process Unlocked */
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 */
2197 /* Note : The I2C interrupts must be enabled after unlocking current process
2198 to avoid the risk of I2C interrupt handle execution before current
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
);
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))
2240 if(__HAL_I2C_GET_FLAG(hi2c
, I2C_FLAG_BUSY
) == SET
)
2245 /* Process Locked */
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
;
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 */
2283 /* Process Unlocked */
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 */
2312 /* Note : The I2C interrupts must be enabled after unlocking current process
2313 to avoid the risk of I2C interrupt handle execution before current
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
;
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))
2356 if(__HAL_I2C_GET_FLAG(hi2c
, I2C_FLAG_BUSY
) == SET
)
2361 /* Process Locked */
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
;
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 */
2399 /* Process Unlocked */
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 */
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
2433 /* Enable ERR and NACK interrupts */
2434 I2C_Enable_IRQ(hi2c
, I2C_XFER_ERROR_IT
);
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
)
2468 /* Process Locked */
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 */
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
)
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 */
2519 /* Wait until STOPF flag is reset */
2520 if(I2C_WaitOnFlagUntilTimeout(hi2c
, I2C_FLAG_STOPF
, RESET
, Timeout
, tickstart
) != HAL_OK
)
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
)
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
)
2544 /* Clear STOP Flag */
2545 __HAL_I2C_CLEAR_FLAG(hi2c
, I2C_FLAG_STOPF
);
2547 }while(I2C_Trials
< Trials
);
2549 hi2c
->State
= HAL_I2C_STATE_READY
;
2551 /* Process Unlocked */
2563 * @brief Sequential transmit in master I2C mode an amount of data in non-blocking mode with Interrupt.
2564 * @note This interface allow to manage repeated start condition when a direction change during transfer
2565 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
2566 * the configuration information for the specified I2C.
2567 * @param DevAddress Target device address: The device 7 bits address value
2568 * in datasheet must be shift at right before call interface
2569 * @param pData Pointer to data buffer
2570 * @param Size Amount of data to be sent
2571 * @param XferOptions Options of Transfer, value of @ref I2C_XFEROPTIONS
2572 * @retval HAL status
2574 HAL_StatusTypeDef
HAL_I2C_Master_Sequential_Transmit_IT(I2C_HandleTypeDef
*hi2c
, uint16_t DevAddress
, uint8_t *pData
, uint16_t Size
, uint32_t XferOptions
)
2576 uint32_t xfermode
= 0U;
2577 uint32_t xferrequest
= I2C_GENERATE_START_WRITE
;
2579 /* Check the parameters */
2580 assert_param(IS_I2C_TRANSFER_OPTIONS_REQUEST(XferOptions
));
2582 if(hi2c
->State
== HAL_I2C_STATE_READY
)
2584 /* Process Locked */
2587 hi2c
->State
= HAL_I2C_STATE_BUSY_TX
;
2588 hi2c
->Mode
= HAL_I2C_MODE_MASTER
;
2589 hi2c
->ErrorCode
= HAL_I2C_ERROR_NONE
;
2591 /* Prepare transfer parameters */
2592 hi2c
->pBuffPtr
= pData
;
2593 hi2c
->XferCount
= Size
;
2594 hi2c
->XferOptions
= XferOptions
;
2595 hi2c
->XferISR
= I2C_Master_ISR_IT
;
2597 /* If size > MAX_NBYTE_SIZE, use reload mode */
2598 if(hi2c
->XferCount
> MAX_NBYTE_SIZE
)
2600 hi2c
->XferSize
= MAX_NBYTE_SIZE
;
2601 xfermode
= I2C_RELOAD_MODE
;
2605 hi2c
->XferSize
= hi2c
->XferCount
;
2606 xfermode
= hi2c
->XferOptions
;
2609 /* If transfer direction not change, do not generate Restart Condition */
2610 /* Mean Previous state is same as current state */
2611 if(hi2c
->PreviousState
== I2C_STATE_MASTER_BUSY_TX
)
2613 xferrequest
= I2C_NO_STARTSTOP
;
2616 /* Send Slave Address and set NBYTES to write */
2617 I2C_TransferConfig(hi2c
, DevAddress
, hi2c
->XferSize
, xfermode
, xferrequest
);
2619 /* Process Unlocked */
2622 /* Note : The I2C interrupts must be enabled after unlocking current process
2623 to avoid the risk of I2C interrupt handle execution before current
2625 I2C_Enable_IRQ(hi2c
, I2C_XFER_TX_IT
);
2636 * @brief Sequential receive in master I2C mode an amount of data in non-blocking mode with Interrupt
2637 * @note This interface allow to manage repeated start condition when a direction change during transfer
2638 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
2639 * the configuration information for the specified I2C.
2640 * @param DevAddress Target device address: The device 7 bits address value
2641 * in datasheet must be shift at right before call interface
2642 * @param pData Pointer to data buffer
2643 * @param Size Amount of data to be sent
2644 * @param XferOptions Options of Transfer, value of @ref I2C_XFEROPTIONS
2645 * @retval HAL status
2647 HAL_StatusTypeDef
HAL_I2C_Master_Sequential_Receive_IT(I2C_HandleTypeDef
*hi2c
, uint16_t DevAddress
, uint8_t *pData
, uint16_t Size
, uint32_t XferOptions
)
2649 uint32_t xfermode
= 0U;
2650 uint32_t xferrequest
= I2C_GENERATE_START_READ
;
2652 /* Check the parameters */
2653 assert_param(IS_I2C_TRANSFER_OPTIONS_REQUEST(XferOptions
));
2655 if(hi2c
->State
== HAL_I2C_STATE_READY
)
2657 /* Process Locked */
2660 hi2c
->State
= HAL_I2C_STATE_BUSY_RX
;
2661 hi2c
->Mode
= HAL_I2C_MODE_MASTER
;
2662 hi2c
->ErrorCode
= HAL_I2C_ERROR_NONE
;
2664 /* Prepare transfer parameters */
2665 hi2c
->pBuffPtr
= pData
;
2666 hi2c
->XferCount
= Size
;
2667 hi2c
->XferOptions
= XferOptions
;
2668 hi2c
->XferISR
= I2C_Master_ISR_IT
;
2670 /* If hi2c->XferCount > MAX_NBYTE_SIZE, use reload mode */
2671 if(hi2c
->XferCount
> MAX_NBYTE_SIZE
)
2673 hi2c
->XferSize
= MAX_NBYTE_SIZE
;
2674 xfermode
= I2C_RELOAD_MODE
;
2678 hi2c
->XferSize
= hi2c
->XferCount
;
2679 xfermode
= hi2c
->XferOptions
;
2682 /* If transfer direction not change, do not generate Restart Condition */
2683 /* Mean Previous state is same as current state */
2684 if(hi2c
->PreviousState
== I2C_STATE_MASTER_BUSY_RX
)
2686 xferrequest
= I2C_NO_STARTSTOP
;
2689 /* Send Slave Address and set NBYTES to read */
2690 I2C_TransferConfig(hi2c
,DevAddress
, hi2c
->XferSize
, xfermode
, xferrequest
);
2692 /* Process Unlocked */
2695 /* Note : The I2C interrupts must be enabled after unlocking current process
2696 to avoid the risk of I2C interrupt handle execution before current
2698 I2C_Enable_IRQ(hi2c
, I2C_XFER_RX_IT
);
2709 * @brief Sequential transmit in slave/device I2C mode an amount of data in non-blocking mode with Interrupt
2710 * @note This interface allow to manage repeated start condition when a direction change during transfer
2711 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
2712 * the configuration information for the specified I2C.
2713 * @param pData Pointer to data buffer
2714 * @param Size Amount of data to be sent
2715 * @param XferOptions Options of Transfer, value of @ref I2C_XFEROPTIONS
2716 * @retval HAL status
2718 HAL_StatusTypeDef
HAL_I2C_Slave_Sequential_Transmit_IT(I2C_HandleTypeDef
*hi2c
, uint8_t *pData
, uint16_t Size
, uint32_t XferOptions
)
2720 /* Check the parameters */
2721 assert_param(IS_I2C_TRANSFER_OPTIONS_REQUEST(XferOptions
));
2723 if((hi2c
->State
& HAL_I2C_STATE_LISTEN
) == HAL_I2C_STATE_LISTEN
)
2725 if((pData
== NULL
) || (Size
== 0U))
2730 /* Disable Interrupts, to prevent preemption during treatment in case of multicall */
2731 I2C_Disable_IRQ(hi2c
, I2C_XFER_LISTEN_IT
| I2C_XFER_TX_IT
);
2733 /* Process Locked */
2736 /* I2C cannot manage full duplex exchange so disable previous IT enabled if any */
2737 /* and then toggle the HAL slave RX state to TX state */
2738 if(hi2c
->State
== HAL_I2C_STATE_BUSY_RX_LISTEN
)
2740 /* Disable associated Interrupts */
2741 I2C_Disable_IRQ(hi2c
, I2C_XFER_RX_IT
);
2744 hi2c
->State
= HAL_I2C_STATE_BUSY_TX_LISTEN
;
2745 hi2c
->Mode
= HAL_I2C_MODE_SLAVE
;
2746 hi2c
->ErrorCode
= HAL_I2C_ERROR_NONE
;
2748 /* Enable Address Acknowledge */
2749 hi2c
->Instance
->CR2
&= ~I2C_CR2_NACK
;
2751 /* Prepare transfer parameters */
2752 hi2c
->pBuffPtr
= pData
;
2753 hi2c
->XferCount
= Size
;
2754 hi2c
->XferSize
= hi2c
->XferCount
;
2755 hi2c
->XferOptions
= XferOptions
;
2756 hi2c
->XferISR
= I2C_Slave_ISR_IT
;
2758 if(I2C_GET_DIR(hi2c
) == I2C_DIRECTION_RECEIVE
)
2760 /* Clear ADDR flag after prepare the transfer parameters */
2761 /* This action will generate an acknowledge to the Master */
2762 __HAL_I2C_CLEAR_FLAG(hi2c
,I2C_FLAG_ADDR
);
2765 /* Process Unlocked */
2768 /* Note : The I2C interrupts must be enabled after unlocking current process
2769 to avoid the risk of I2C interrupt handle execution before current
2771 /* REnable ADDR interrupt */
2772 I2C_Enable_IRQ(hi2c
, I2C_XFER_TX_IT
| I2C_XFER_LISTEN_IT
);
2783 * @brief Sequential receive in slave/device I2C mode an amount of data in non-blocking mode with Interrupt
2784 * @note This interface allow to manage repeated start condition when a direction change during transfer
2785 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
2786 * the configuration information for the specified I2C.
2787 * @param pData Pointer to data buffer
2788 * @param Size Amount of data to be sent
2789 * @param XferOptions Options of Transfer, value of @ref I2C_XFEROPTIONS
2790 * @retval HAL status
2792 HAL_StatusTypeDef
HAL_I2C_Slave_Sequential_Receive_IT(I2C_HandleTypeDef
*hi2c
, uint8_t *pData
, uint16_t Size
, uint32_t XferOptions
)
2794 /* Check the parameters */
2795 assert_param(IS_I2C_TRANSFER_OPTIONS_REQUEST(XferOptions
));
2797 if((hi2c
->State
& HAL_I2C_STATE_LISTEN
) == HAL_I2C_STATE_LISTEN
)
2799 if((pData
== NULL
) || (Size
== 0U))
2804 /* Disable Interrupts, to prevent preemption during treatment in case of multicall */
2805 I2C_Disable_IRQ(hi2c
, I2C_XFER_LISTEN_IT
| I2C_XFER_RX_IT
);
2807 /* Process Locked */
2810 /* I2C cannot manage full duplex exchange so disable previous IT enabled if any */
2811 /* and then toggle the HAL slave TX state to RX state */
2812 if(hi2c
->State
== HAL_I2C_STATE_BUSY_TX_LISTEN
)
2814 /* Disable associated Interrupts */
2815 I2C_Disable_IRQ(hi2c
, I2C_XFER_TX_IT
);
2818 hi2c
->State
= HAL_I2C_STATE_BUSY_RX_LISTEN
;
2819 hi2c
->Mode
= HAL_I2C_MODE_SLAVE
;
2820 hi2c
->ErrorCode
= HAL_I2C_ERROR_NONE
;
2822 /* Enable Address Acknowledge */
2823 hi2c
->Instance
->CR2
&= ~I2C_CR2_NACK
;
2825 /* Prepare transfer parameters */
2826 hi2c
->pBuffPtr
= pData
;
2827 hi2c
->XferCount
= Size
;
2828 hi2c
->XferSize
= hi2c
->XferCount
;
2829 hi2c
->XferOptions
= XferOptions
;
2830 hi2c
->XferISR
= I2C_Slave_ISR_IT
;
2832 if(I2C_GET_DIR(hi2c
) == I2C_DIRECTION_TRANSMIT
)
2834 /* Clear ADDR flag after prepare the transfer parameters */
2835 /* This action will generate an acknowledge to the Master */
2836 __HAL_I2C_CLEAR_FLAG(hi2c
,I2C_FLAG_ADDR
);
2839 /* Process Unlocked */
2842 /* Note : The I2C interrupts must be enabled after unlocking current process
2843 to avoid the risk of I2C interrupt handle execution before current
2845 /* REnable ADDR interrupt */
2846 I2C_Enable_IRQ(hi2c
, I2C_XFER_RX_IT
| I2C_XFER_LISTEN_IT
);
2857 * @brief Enable the Address listen mode with Interrupt.
2858 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
2859 * the configuration information for the specified I2C.
2860 * @retval HAL status
2862 HAL_StatusTypeDef
HAL_I2C_EnableListen_IT(I2C_HandleTypeDef
*hi2c
)
2864 if(hi2c
->State
== HAL_I2C_STATE_READY
)
2866 hi2c
->State
= HAL_I2C_STATE_LISTEN
;
2867 hi2c
->XferISR
= I2C_Slave_ISR_IT
;
2869 /* Enable the Address Match interrupt */
2870 I2C_Enable_IRQ(hi2c
, I2C_XFER_LISTEN_IT
);
2881 * @brief Disable the Address listen mode with Interrupt.
2882 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
2883 * the configuration information for the specified I2C
2884 * @retval HAL status
2886 HAL_StatusTypeDef
HAL_I2C_DisableListen_IT(I2C_HandleTypeDef
*hi2c
)
2888 /* Declaration of tmp to prevent undefined behavior of volatile usage */
2891 /* Disable Address listen mode only if a transfer is not ongoing */
2892 if(hi2c
->State
== HAL_I2C_STATE_LISTEN
)
2894 tmp
= (uint32_t)(hi2c
->State
) & I2C_STATE_MSK
;
2895 hi2c
->PreviousState
= tmp
| (uint32_t)(hi2c
->Mode
);
2896 hi2c
->State
= HAL_I2C_STATE_READY
;
2897 hi2c
->Mode
= HAL_I2C_MODE_NONE
;
2898 hi2c
->XferISR
= NULL
;
2900 /* Disable the Address Match interrupt */
2901 I2C_Disable_IRQ(hi2c
, I2C_XFER_LISTEN_IT
);
2912 * @brief Abort a master I2C IT or DMA process communication with Interrupt.
2913 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
2914 * the configuration information for the specified I2C.
2915 * @param DevAddress Target device address: The device 7 bits address value
2916 * in datasheet must be shift at right before call interface
2917 * @retval HAL status
2919 HAL_StatusTypeDef
HAL_I2C_Master_Abort_IT(I2C_HandleTypeDef
*hi2c
, uint16_t DevAddress
)
2921 if(hi2c
->Mode
== HAL_I2C_MODE_MASTER
)
2923 /* Process Locked */
2926 /* Disable Interrupts */
2927 I2C_Disable_IRQ(hi2c
, I2C_XFER_RX_IT
);
2928 I2C_Disable_IRQ(hi2c
, I2C_XFER_TX_IT
);
2930 /* Set State at HAL_I2C_STATE_ABORT */
2931 hi2c
->State
= HAL_I2C_STATE_ABORT
;
2933 /* Set NBYTES to 1 to generate a dummy read on I2C peripheral */
2934 /* Set AUTOEND mode, this will generate a NACK then STOP condition to abort the current transfer */
2935 I2C_TransferConfig(hi2c
, DevAddress
, 1, I2C_AUTOEND_MODE
, I2C_GENERATE_STOP
);
2937 /* Process Unlocked */
2940 /* Note : The I2C interrupts must be enabled after unlocking current process
2941 to avoid the risk of I2C interrupt handle execution before current
2943 I2C_Enable_IRQ(hi2c
, I2C_XFER_CPLT_IT
);
2949 /* Wrong usage of abort function */
2950 /* This function should be used only in case of abort monitored by master device */
2959 /** @defgroup I2C_IRQ_Handler_and_Callbacks IRQ Handler and Callbacks
2964 * @brief This function handles I2C event interrupt request.
2965 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
2966 * the configuration information for the specified I2C.
2969 void HAL_I2C_EV_IRQHandler(I2C_HandleTypeDef
*hi2c
)
2971 /* Get current IT Flags and IT sources value */
2972 uint32_t itflags
= READ_REG(hi2c
->Instance
->ISR
);
2973 uint32_t itsources
= READ_REG(hi2c
->Instance
->CR1
);
2975 /* I2C events treatment -------------------------------------*/
2976 if(hi2c
->XferISR
!= NULL
)
2978 hi2c
->XferISR(hi2c
, itflags
, itsources
);
2983 * @brief This function handles I2C error interrupt request.
2984 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
2985 * the configuration information for the specified I2C.
2988 void HAL_I2C_ER_IRQHandler(I2C_HandleTypeDef
*hi2c
)
2990 uint32_t itflags
= READ_REG(hi2c
->Instance
->ISR
);
2991 uint32_t itsources
= READ_REG(hi2c
->Instance
->CR1
);
2993 /* I2C Bus error interrupt occurred ------------------------------------*/
2994 if(((itflags
& I2C_FLAG_BERR
) != RESET
) && ((itsources
& I2C_IT_ERRI
) != RESET
))
2996 hi2c
->ErrorCode
|= HAL_I2C_ERROR_BERR
;
2998 /* Clear BERR flag */
2999 __HAL_I2C_CLEAR_FLAG(hi2c
, I2C_FLAG_BERR
);
3002 /* I2C Over-Run/Under-Run interrupt occurred ----------------------------------------*/
3003 if(((itflags
& I2C_FLAG_OVR
) != RESET
) && ((itsources
& I2C_IT_ERRI
) != RESET
))
3005 hi2c
->ErrorCode
|= HAL_I2C_ERROR_OVR
;
3007 /* Clear OVR flag */
3008 __HAL_I2C_CLEAR_FLAG(hi2c
, I2C_FLAG_OVR
);
3011 /* I2C Arbitration Loss error interrupt occurred -------------------------------------*/
3012 if(((itflags
& I2C_FLAG_ARLO
) != RESET
) && ((itsources
& I2C_IT_ERRI
) != RESET
))
3014 hi2c
->ErrorCode
|= HAL_I2C_ERROR_ARLO
;
3016 /* Clear ARLO flag */
3017 __HAL_I2C_CLEAR_FLAG(hi2c
, I2C_FLAG_ARLO
);
3020 /* Call the Error Callback in case of Error detected */
3021 if((hi2c
->ErrorCode
& (HAL_I2C_ERROR_BERR
| HAL_I2C_ERROR_OVR
| HAL_I2C_ERROR_ARLO
)) != HAL_I2C_ERROR_NONE
)
3023 I2C_ITError(hi2c
, hi2c
->ErrorCode
);
3028 * @brief Master Tx Transfer completed callback.
3029 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
3030 * the configuration information for the specified I2C.
3033 __weak
void HAL_I2C_MasterTxCpltCallback(I2C_HandleTypeDef
*hi2c
)
3035 /* Prevent unused argument(s) compilation warning */
3038 /* NOTE : This function should not be modified, when the callback is needed,
3039 the HAL_I2C_MasterTxCpltCallback could be implemented in the user file
3044 * @brief Master Rx Transfer completed callback.
3045 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
3046 * the configuration information for the specified I2C.
3049 __weak
void HAL_I2C_MasterRxCpltCallback(I2C_HandleTypeDef
*hi2c
)
3051 /* Prevent unused argument(s) compilation warning */
3054 /* NOTE : This function should not be modified, when the callback is needed,
3055 the HAL_I2C_MasterRxCpltCallback could be implemented in the user file
3059 /** @brief Slave Tx Transfer completed callback.
3060 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
3061 * the configuration information for the specified I2C.
3064 __weak
void HAL_I2C_SlaveTxCpltCallback(I2C_HandleTypeDef
*hi2c
)
3066 /* Prevent unused argument(s) compilation warning */
3069 /* NOTE : This function should not be modified, when the callback is needed,
3070 the HAL_I2C_SlaveTxCpltCallback could be implemented in the user file
3075 * @brief Slave Rx Transfer completed callback.
3076 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
3077 * the configuration information for the specified I2C.
3080 __weak
void HAL_I2C_SlaveRxCpltCallback(I2C_HandleTypeDef
*hi2c
)
3082 /* Prevent unused argument(s) compilation warning */
3085 /* NOTE : This function should not be modified, when the callback is needed,
3086 the HAL_I2C_SlaveRxCpltCallback could be implemented in the user file
3091 * @brief Slave Address Match callback.
3092 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
3093 * the configuration information for the specified I2C.
3094 * @param TransferDirection: Master request Transfer Direction (Write/Read), value of @ref I2C_XFERDIRECTION
3095 * @param AddrMatchCode: Address Match Code
3098 __weak
void HAL_I2C_AddrCallback(I2C_HandleTypeDef
*hi2c
, uint8_t TransferDirection
, uint16_t AddrMatchCode
)
3100 /* Prevent unused argument(s) compilation warning */
3102 UNUSED(TransferDirection
);
3103 UNUSED(AddrMatchCode
);
3105 /* NOTE : This function should not be modified, when the callback is needed,
3106 the HAL_I2C_AddrCallback() could be implemented in the user file
3111 * @brief Listen Complete callback.
3112 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
3113 * the configuration information for the specified I2C.
3116 __weak
void HAL_I2C_ListenCpltCallback(I2C_HandleTypeDef
*hi2c
)
3118 /* Prevent unused argument(s) compilation warning */
3121 /* NOTE : This function should not be modified, when the callback is needed,
3122 the HAL_I2C_ListenCpltCallback() could be implemented in the user file
3127 * @brief Memory Tx Transfer completed callback.
3128 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
3129 * the configuration information for the specified I2C.
3132 __weak
void HAL_I2C_MemTxCpltCallback(I2C_HandleTypeDef
*hi2c
)
3134 /* Prevent unused argument(s) compilation warning */
3137 /* NOTE : This function should not be modified, when the callback is needed,
3138 the HAL_I2C_MemTxCpltCallback could be implemented in the user file
3143 * @brief Memory Rx Transfer completed callback.
3144 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
3145 * the configuration information for the specified I2C.
3148 __weak
void HAL_I2C_MemRxCpltCallback(I2C_HandleTypeDef
*hi2c
)
3150 /* Prevent unused argument(s) compilation warning */
3153 /* NOTE : This function should not be modified, when the callback is needed,
3154 the HAL_I2C_MemRxCpltCallback could be implemented in the user file
3159 * @brief I2C error callback.
3160 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
3161 * the configuration information for the specified I2C.
3164 __weak
void HAL_I2C_ErrorCallback(I2C_HandleTypeDef
*hi2c
)
3166 /* Prevent unused argument(s) compilation warning */
3169 /* NOTE : This function should not be modified, when the callback is needed,
3170 the HAL_I2C_ErrorCallback could be implemented in the user file
3175 * @brief I2C abort callback.
3176 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
3177 * the configuration information for the specified I2C.
3180 __weak
void HAL_I2C_AbortCpltCallback(I2C_HandleTypeDef
*hi2c
)
3182 /* Prevent unused argument(s) compilation warning */
3185 /* NOTE : This function should not be modified, when the callback is needed,
3186 the HAL_I2C_AbortCpltCallback could be implemented in the user file
3194 /** @defgroup I2C_Exported_Functions_Group3 Peripheral State, Mode and Error functions
3195 * @brief Peripheral State, Mode and Error functions
3198 ===============================================================================
3199 ##### Peripheral State, Mode and Error functions #####
3200 ===============================================================================
3202 This subsection permit to get in run-time the status of the peripheral
3210 * @brief Return the I2C handle state.
3211 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
3212 * the configuration information for the specified I2C.
3215 HAL_I2C_StateTypeDef
HAL_I2C_GetState(I2C_HandleTypeDef
*hi2c
)
3217 /* Return I2C handle state */
3222 * @brief Returns the I2C Master, Slave, Memory or no mode.
3223 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
3224 * the configuration information for I2C module
3227 HAL_I2C_ModeTypeDef
HAL_I2C_GetMode(I2C_HandleTypeDef
*hi2c
)
3233 * @brief Return the I2C error code.
3234 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
3235 * the configuration information for the specified I2C.
3236 * @retval I2C Error Code
3238 uint32_t HAL_I2C_GetError(I2C_HandleTypeDef
*hi2c
)
3240 return hi2c
->ErrorCode
;
3251 /** @addtogroup I2C_Private_Functions
3256 * @brief Interrupt Sub-Routine which handle the Interrupt Flags Master Mode with Interrupt.
3257 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
3258 * the configuration information for the specified I2C.
3259 * @param ITFlags Interrupt flags to handle.
3260 * @param ITSources Interrupt sources enabled.
3261 * @retval HAL status
3263 static HAL_StatusTypeDef
I2C_Master_ISR_IT(struct __I2C_HandleTypeDef
*hi2c
, uint32_t ITFlags
, uint32_t ITSources
)
3265 uint16_t devaddress
= 0U;
3267 /* Process Locked */
3270 if(((ITFlags
& I2C_FLAG_AF
) != RESET
) && ((ITSources
& I2C_IT_NACKI
) != RESET
))
3272 /* Clear NACK Flag */
3273 __HAL_I2C_CLEAR_FLAG(hi2c
, I2C_FLAG_AF
);
3275 /* Set corresponding Error Code */
3276 /* No need to generate STOP, it is automatically done */
3277 /* Error callback will be send during stop flag treatment */
3278 hi2c
->ErrorCode
|= HAL_I2C_ERROR_AF
;
3280 /* Flush TX register */
3281 I2C_Flush_TXDR(hi2c
);
3283 else if(((ITFlags
& I2C_FLAG_RXNE
) != RESET
) && ((ITSources
& I2C_IT_RXI
) != RESET
))
3285 /* Read data from RXDR */
3286 (*hi2c
->pBuffPtr
++) = hi2c
->Instance
->RXDR
;
3290 else if(((ITFlags
& I2C_FLAG_TXIS
) != RESET
) && ((ITSources
& I2C_IT_TXI
) != RESET
))
3292 /* Write data to TXDR */
3293 hi2c
->Instance
->TXDR
= (*hi2c
->pBuffPtr
++);
3297 else if(((ITFlags
& I2C_FLAG_TCR
) != RESET
) && ((ITSources
& I2C_IT_TCI
) != RESET
))
3299 if((hi2c
->XferSize
== 0U) && (hi2c
->XferCount
!= 0U))
3301 devaddress
= (hi2c
->Instance
->CR2
& I2C_CR2_SADD
);
3303 if(hi2c
->XferCount
> MAX_NBYTE_SIZE
)
3305 hi2c
->XferSize
= MAX_NBYTE_SIZE
;
3306 I2C_TransferConfig(hi2c
, devaddress
, hi2c
->XferSize
, I2C_RELOAD_MODE
, I2C_NO_STARTSTOP
);
3310 hi2c
->XferSize
= hi2c
->XferCount
;
3311 if(hi2c
->XferOptions
!= I2C_NO_OPTION_FRAME
)
3313 I2C_TransferConfig(hi2c
, devaddress
, hi2c
->XferSize
, hi2c
->XferOptions
, I2C_NO_STARTSTOP
);
3317 I2C_TransferConfig(hi2c
, devaddress
, hi2c
->XferSize
, I2C_AUTOEND_MODE
, I2C_NO_STARTSTOP
);
3323 /* Call TxCpltCallback() if no stop mode is set */
3324 if(I2C_GET_STOP_MODE(hi2c
) != I2C_AUTOEND_MODE
)
3326 /* Call I2C Master Sequential complete process */
3327 I2C_ITMasterSequentialCplt(hi2c
);
3331 /* Wrong size Status regarding TCR flag event */
3332 /* Call the corresponding callback to inform upper layer of End of Transfer */
3333 I2C_ITError(hi2c
, HAL_I2C_ERROR_SIZE
);
3337 else if(((ITFlags
& I2C_FLAG_TC
) != RESET
) && ((ITSources
& I2C_IT_TCI
) != RESET
))
3339 if(hi2c
->XferCount
== 0U)
3341 if(I2C_GET_STOP_MODE(hi2c
) != I2C_AUTOEND_MODE
)
3343 /* Generate a stop condition in case of no transfer option */
3344 if(hi2c
->XferOptions
== I2C_NO_OPTION_FRAME
)
3347 hi2c
->Instance
->CR2
|= I2C_CR2_STOP
;
3351 /* Call I2C Master Sequential complete process */
3352 I2C_ITMasterSequentialCplt(hi2c
);
3358 /* Wrong size Status regarding TC flag event */
3359 /* Call the corresponding callback to inform upper layer of End of Transfer */
3360 I2C_ITError(hi2c
, HAL_I2C_ERROR_SIZE
);
3364 if(((ITFlags
& I2C_FLAG_STOPF
) != RESET
) && ((ITSources
& I2C_IT_STOPI
) != RESET
))
3366 /* Call I2C Master complete process */
3367 I2C_ITMasterCplt(hi2c
, ITFlags
);
3370 /* Process Unlocked */
3377 * @brief Interrupt Sub-Routine which handle the Interrupt Flags Slave Mode with Interrupt.
3378 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
3379 * the configuration information for the specified I2C.
3380 * @param ITFlags Interrupt flags to handle.
3381 * @param ITSources Interrupt sources enabled.
3382 * @retval HAL status
3384 static HAL_StatusTypeDef
I2C_Slave_ISR_IT(struct __I2C_HandleTypeDef
*hi2c
, uint32_t ITFlags
, uint32_t ITSources
)
3386 /* Process locked */
3389 if(((ITFlags
& I2C_FLAG_AF
) != RESET
) && ((ITSources
& I2C_IT_NACKI
) != RESET
))
3391 /* Check that I2C transfer finished */
3392 /* if yes, normal use case, a NACK is sent by the MASTER when Transfer is finished */
3393 /* Mean XferCount == 0*/
3394 /* So clear Flag NACKF only */
3395 if(hi2c
->XferCount
== 0U)
3397 if(((hi2c
->XferOptions
== I2C_FIRST_AND_LAST_FRAME
) || (hi2c
->XferOptions
== I2C_LAST_FRAME
)) && \
3398 (hi2c
->State
== HAL_I2C_STATE_LISTEN
))
3400 /* Call I2C Listen complete process */
3401 I2C_ITListenCplt(hi2c
, ITFlags
);
3403 else if((hi2c
->XferOptions
!= I2C_NO_OPTION_FRAME
) && (hi2c
->State
== HAL_I2C_STATE_BUSY_TX_LISTEN
))
3405 /* Clear NACK Flag */
3406 __HAL_I2C_CLEAR_FLAG(hi2c
, I2C_FLAG_AF
);
3408 /* Flush TX register */
3409 I2C_Flush_TXDR(hi2c
);
3411 /* Last Byte is Transmitted */
3412 /* Call I2C Slave Sequential complete process */
3413 I2C_ITSlaveSequentialCplt(hi2c
);
3417 /* Clear NACK Flag */
3418 __HAL_I2C_CLEAR_FLAG(hi2c
, I2C_FLAG_AF
);
3423 /* if no, error use case, a Non-Acknowledge of last Data is generated by the MASTER*/
3424 /* Clear NACK Flag */
3425 __HAL_I2C_CLEAR_FLAG(hi2c
, I2C_FLAG_AF
);
3427 /* Set ErrorCode corresponding to a Non-Acknowledge */
3428 hi2c
->ErrorCode
|= HAL_I2C_ERROR_AF
;
3431 else if(((ITFlags
& I2C_FLAG_RXNE
) != RESET
) && ((ITSources
& I2C_IT_RXI
) != RESET
))
3433 if(hi2c
->XferCount
> 0U)
3435 /* Read data from RXDR */
3436 (*hi2c
->pBuffPtr
++) = hi2c
->Instance
->RXDR
;
3441 if((hi2c
->XferCount
== 0U) && \
3442 (hi2c
->XferOptions
!= I2C_NO_OPTION_FRAME
))
3444 /* Call I2C Slave Sequential complete process */
3445 I2C_ITSlaveSequentialCplt(hi2c
);
3448 else if(((ITFlags
& I2C_FLAG_ADDR
) != RESET
) && ((ITSources
& I2C_IT_ADDRI
) != RESET
))
3450 I2C_ITAddrCplt(hi2c
, ITFlags
);
3452 else if(((ITFlags
& I2C_FLAG_TXIS
) != RESET
) && ((ITSources
& I2C_IT_TXI
) != RESET
))
3454 /* Write data to TXDR only if XferCount not reach "0" */
3455 /* A TXIS flag can be set, during STOP treatment */
3456 /* Check if all Datas have already been sent */
3457 /* If it is the case, this last write in TXDR is not sent, correspond to a dummy TXIS event */
3458 if(hi2c
->XferCount
> 0U)
3460 /* Write data to TXDR */
3461 hi2c
->Instance
->TXDR
= (*hi2c
->pBuffPtr
++);
3467 if((hi2c
->XferOptions
== I2C_NEXT_FRAME
) || (hi2c
->XferOptions
== I2C_FIRST_FRAME
))
3469 /* Last Byte is Transmitted */
3470 /* Call I2C Slave Sequential complete process */
3471 I2C_ITSlaveSequentialCplt(hi2c
);
3476 /* Check if STOPF is set */
3477 if(((ITFlags
& I2C_FLAG_STOPF
) != RESET
) && ((ITSources
& I2C_IT_STOPI
) != RESET
))
3479 /* Call I2C Slave complete process */
3480 I2C_ITSlaveCplt(hi2c
, ITFlags
);
3483 /* Process Unlocked */
3490 * @brief Interrupt Sub-Routine which handle the Interrupt Flags Master Mode with DMA.
3491 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
3492 * the configuration information for the specified I2C.
3493 * @param ITFlags Interrupt flags to handle.
3494 * @param ITSources Interrupt sources enabled.
3495 * @retval HAL status
3497 static HAL_StatusTypeDef
I2C_Master_ISR_DMA(struct __I2C_HandleTypeDef
*hi2c
, uint32_t ITFlags
, uint32_t ITSources
)
3499 uint16_t devaddress
= 0U;
3500 uint32_t xfermode
= 0U;
3502 /* Process Locked */
3505 if(((ITFlags
& I2C_FLAG_AF
) != RESET
) && ((ITSources
& I2C_IT_NACKI
) != RESET
))
3507 /* Clear NACK Flag */
3508 __HAL_I2C_CLEAR_FLAG(hi2c
, I2C_FLAG_AF
);
3510 /* Set corresponding Error Code */
3511 hi2c
->ErrorCode
|= HAL_I2C_ERROR_AF
;
3513 /* No need to generate STOP, it is automatically done */
3514 /* But enable STOP interrupt, to treat it */
3515 /* Error callback will be send during stop flag treatment */
3516 I2C_Enable_IRQ(hi2c
, I2C_XFER_CPLT_IT
);
3518 /* Flush TX register */
3519 I2C_Flush_TXDR(hi2c
);
3521 else if(((ITFlags
& I2C_FLAG_TCR
) != RESET
) && ((ITSources
& I2C_IT_TCI
) != RESET
))
3523 /* Disable TC interrupt */
3524 __HAL_I2C_DISABLE_IT(hi2c
, I2C_IT_TCI
);
3526 if(hi2c
->XferCount
!= 0U)
3528 /* Recover Slave address */
3529 devaddress
= (hi2c
->Instance
->CR2
& I2C_CR2_SADD
);
3531 /* Prepare the new XferSize to transfer */
3532 if(hi2c
->XferCount
> MAX_NBYTE_SIZE
)
3534 hi2c
->XferSize
= MAX_NBYTE_SIZE
;
3535 xfermode
= I2C_RELOAD_MODE
;
3539 hi2c
->XferSize
= hi2c
->XferCount
;
3540 xfermode
= I2C_AUTOEND_MODE
;
3543 /* Set the new XferSize in Nbytes register */
3544 I2C_TransferConfig(hi2c
, devaddress
, hi2c
->XferSize
, xfermode
, I2C_NO_STARTSTOP
);
3546 /* Update XferCount value */
3547 hi2c
->XferCount
-= hi2c
->XferSize
;
3549 /* Enable DMA Request */
3550 if(hi2c
->State
== HAL_I2C_STATE_BUSY_RX
)
3552 hi2c
->Instance
->CR1
|= I2C_CR1_RXDMAEN
;
3556 hi2c
->Instance
->CR1
|= I2C_CR1_TXDMAEN
;
3561 /* Wrong size Status regarding TCR flag event */
3562 /* Call the corresponding callback to inform upper layer of End of Transfer */
3563 I2C_ITError(hi2c
, HAL_I2C_ERROR_SIZE
);
3566 else if(((ITFlags
& I2C_FLAG_STOPF
) != RESET
) && ((ITSources
& I2C_IT_STOPI
) != RESET
))
3568 /* Call I2C Master complete process */
3569 I2C_ITMasterCplt(hi2c
, ITFlags
);
3572 /* Process Unlocked */
3579 * @brief Interrupt Sub-Routine which handle the Interrupt Flags Slave Mode with DMA.
3580 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
3581 * the configuration information for the specified I2C.
3582 * @param ITFlags Interrupt flags to handle.
3583 * @param ITSources Interrupt sources enabled.
3584 * @retval HAL status
3586 static HAL_StatusTypeDef
I2C_Slave_ISR_DMA(struct __I2C_HandleTypeDef
*hi2c
, uint32_t ITFlags
, uint32_t ITSources
)
3588 /* Process locked */
3591 if(((ITFlags
& I2C_FLAG_AF
) != RESET
) && ((ITSources
& I2C_IT_NACKI
) != RESET
))
3593 /* Check that I2C transfer finished */
3594 /* if yes, normal use case, a NACK is sent by the MASTER when Transfer is finished */
3595 /* Mean XferCount == 0 */
3596 /* So clear Flag NACKF only */
3597 if(I2C_GET_DMA_REMAIN_DATA(hi2c
) == 0U)
3599 /* Clear NACK Flag */
3600 __HAL_I2C_CLEAR_FLAG(hi2c
, I2C_FLAG_AF
);
3604 /* if no, error use case, a Non-Acknowledge of last Data is generated by the MASTER*/
3605 /* Clear NACK Flag */
3606 __HAL_I2C_CLEAR_FLAG(hi2c
, I2C_FLAG_AF
);
3608 /* Set ErrorCode corresponding to a Non-Acknowledge */
3609 hi2c
->ErrorCode
|= HAL_I2C_ERROR_AF
;
3612 else if(((ITFlags
& I2C_FLAG_ADDR
) != RESET
) && ((ITSources
& I2C_IT_ADDRI
) != RESET
))
3614 /* Clear ADDR flag */
3615 __HAL_I2C_CLEAR_FLAG(hi2c
, I2C_FLAG_ADDR
);
3617 else if(((ITFlags
& I2C_FLAG_STOPF
) != RESET
) && ((ITSources
& I2C_IT_STOPI
) != RESET
))
3619 /* Call I2C Slave complete process */
3620 I2C_ITSlaveCplt(hi2c
, ITFlags
);
3623 /* Process Unlocked */
3630 * @brief Master sends target device address followed by internal memory address for write request.
3631 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
3632 * the configuration information for the specified I2C.
3633 * @param DevAddress Target device address: The device 7 bits address value
3634 * in datasheet must be shift at right before call interface
3635 * @param MemAddress Internal memory address
3636 * @param MemAddSize Size of internal memory address
3637 * @param Timeout Timeout duration
3638 * @param Tickstart Tick start value
3639 * @retval HAL status
3641 static HAL_StatusTypeDef
I2C_RequestMemoryWrite(I2C_HandleTypeDef
*hi2c
, uint16_t DevAddress
, uint16_t MemAddress
, uint16_t MemAddSize
, uint32_t Timeout
, uint32_t Tickstart
)
3643 I2C_TransferConfig(hi2c
,DevAddress
,MemAddSize
, I2C_RELOAD_MODE
, I2C_GENERATE_START_WRITE
);
3645 /* Wait until TXIS flag is set */
3646 if(I2C_WaitOnTXISFlagUntilTimeout(hi2c
, Timeout
, Tickstart
) != HAL_OK
)
3648 if(hi2c
->ErrorCode
== HAL_I2C_ERROR_AF
)
3658 /* If Memory address size is 8Bit */
3659 if(MemAddSize
== I2C_MEMADD_SIZE_8BIT
)
3661 /* Send Memory Address */
3662 hi2c
->Instance
->TXDR
= I2C_MEM_ADD_LSB(MemAddress
);
3664 /* If Memory address size is 16Bit */
3667 /* Send MSB of Memory Address */
3668 hi2c
->Instance
->TXDR
= I2C_MEM_ADD_MSB(MemAddress
);
3670 /* Wait until TXIS flag is set */
3671 if(I2C_WaitOnTXISFlagUntilTimeout(hi2c
, Timeout
, Tickstart
) != HAL_OK
)
3673 if(hi2c
->ErrorCode
== HAL_I2C_ERROR_AF
)
3683 /* Send LSB of Memory Address */
3684 hi2c
->Instance
->TXDR
= I2C_MEM_ADD_LSB(MemAddress
);
3687 /* Wait until TCR flag is set */
3688 if(I2C_WaitOnFlagUntilTimeout(hi2c
, I2C_FLAG_TCR
, RESET
, Timeout
, Tickstart
) != HAL_OK
)
3697 * @brief Master sends target device address followed by internal memory address for read request.
3698 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
3699 * the configuration information for the specified I2C.
3700 * @param DevAddress Target device address: The device 7 bits address value
3701 * in datasheet must be shift at right before call interface
3702 * @param MemAddress Internal memory address
3703 * @param MemAddSize Size of internal memory address
3704 * @param Timeout Timeout duration
3705 * @param Tickstart Tick start value
3706 * @retval HAL status
3708 static HAL_StatusTypeDef
I2C_RequestMemoryRead(I2C_HandleTypeDef
*hi2c
, uint16_t DevAddress
, uint16_t MemAddress
, uint16_t MemAddSize
, uint32_t Timeout
, uint32_t Tickstart
)
3710 I2C_TransferConfig(hi2c
,DevAddress
,MemAddSize
, I2C_SOFTEND_MODE
, I2C_GENERATE_START_WRITE
);
3712 /* Wait until TXIS flag is set */
3713 if(I2C_WaitOnTXISFlagUntilTimeout(hi2c
, Timeout
, Tickstart
) != HAL_OK
)
3715 if(hi2c
->ErrorCode
== HAL_I2C_ERROR_AF
)
3725 /* If Memory address size is 8Bit */
3726 if(MemAddSize
== I2C_MEMADD_SIZE_8BIT
)
3728 /* Send Memory Address */
3729 hi2c
->Instance
->TXDR
= I2C_MEM_ADD_LSB(MemAddress
);
3731 /* If Memory address size is 16Bit */
3734 /* Send MSB of Memory Address */
3735 hi2c
->Instance
->TXDR
= I2C_MEM_ADD_MSB(MemAddress
);
3737 /* Wait until TXIS flag is set */
3738 if(I2C_WaitOnTXISFlagUntilTimeout(hi2c
, Timeout
, Tickstart
) != HAL_OK
)
3740 if(hi2c
->ErrorCode
== HAL_I2C_ERROR_AF
)
3750 /* Send LSB of Memory Address */
3751 hi2c
->Instance
->TXDR
= I2C_MEM_ADD_LSB(MemAddress
);
3754 /* Wait until TC flag is set */
3755 if(I2C_WaitOnFlagUntilTimeout(hi2c
, I2C_FLAG_TC
, RESET
, Timeout
, Tickstart
) != HAL_OK
)
3764 * @brief I2C Address complete process callback.
3765 * @param hi2c I2C handle.
3766 * @param ITFlags Interrupt flags to handle.
3769 static void I2C_ITAddrCplt(I2C_HandleTypeDef
*hi2c
, uint32_t ITFlags
)
3771 uint8_t transferdirection
= 0U;
3772 uint16_t slaveaddrcode
= 0U;
3773 uint16_t ownadd1code
= 0U;
3774 uint16_t ownadd2code
= 0U;
3776 /* Prevent unused argument(s) compilation warning */
3779 /* In case of Listen state, need to inform upper layer of address match code event */
3780 if((hi2c
->State
& HAL_I2C_STATE_LISTEN
) == HAL_I2C_STATE_LISTEN
)
3782 transferdirection
= I2C_GET_DIR(hi2c
);
3783 slaveaddrcode
= I2C_GET_ADDR_MATCH(hi2c
);
3784 ownadd1code
= I2C_GET_OWN_ADDRESS1(hi2c
);
3785 ownadd2code
= I2C_GET_OWN_ADDRESS2(hi2c
);
3787 /* If 10bits addressing mode is selected */
3788 if(hi2c
->Init
.AddressingMode
== I2C_ADDRESSINGMODE_10BIT
)
3790 if((slaveaddrcode
& SlaveAddr_MSK
) == ((ownadd1code
>> SlaveAddr_SHIFT
) & SlaveAddr_MSK
))
3792 slaveaddrcode
= ownadd1code
;
3793 hi2c
->AddrEventCount
++;
3794 if(hi2c
->AddrEventCount
== 2U)
3796 /* Reset Address Event counter */
3797 hi2c
->AddrEventCount
= 0U;
3799 /* Clear ADDR flag */
3800 __HAL_I2C_CLEAR_FLAG(hi2c
,I2C_FLAG_ADDR
);
3802 /* Process Unlocked */
3805 /* Call Slave Addr callback */
3806 HAL_I2C_AddrCallback(hi2c
, transferdirection
, slaveaddrcode
);
3811 slaveaddrcode
= ownadd2code
;
3813 /* Disable ADDR Interrupts */
3814 I2C_Disable_IRQ(hi2c
, I2C_XFER_LISTEN_IT
);
3816 /* Process Unlocked */
3819 /* Call Slave Addr callback */
3820 HAL_I2C_AddrCallback(hi2c
, transferdirection
, slaveaddrcode
);
3823 /* else 7 bits addressing mode is selected */
3826 /* Disable ADDR Interrupts */
3827 I2C_Disable_IRQ(hi2c
, I2C_XFER_LISTEN_IT
);
3829 /* Process Unlocked */
3832 /* Call Slave Addr callback */
3833 HAL_I2C_AddrCallback(hi2c
, transferdirection
, slaveaddrcode
);
3836 /* Else clear address flag only */
3839 /* Clear ADDR flag */
3840 __HAL_I2C_CLEAR_FLAG(hi2c
, I2C_FLAG_ADDR
);
3842 /* Process Unlocked */
3848 * @brief I2C Master sequential complete process.
3849 * @param hi2c I2C handle.
3852 static void I2C_ITMasterSequentialCplt(I2C_HandleTypeDef
*hi2c
)
3854 /* Reset I2C handle mode */
3855 hi2c
->Mode
= HAL_I2C_MODE_NONE
;
3857 /* No Generate Stop, to permit restart mode */
3858 /* The stop will be done at the end of transfer, when I2C_AUTOEND_MODE enable */
3859 if (hi2c
->State
== HAL_I2C_STATE_BUSY_TX
)
3861 hi2c
->State
= HAL_I2C_STATE_READY
;
3862 hi2c
->PreviousState
= I2C_STATE_MASTER_BUSY_TX
;
3863 hi2c
->XferISR
= NULL
;
3865 /* Disable Interrupts */
3866 I2C_Disable_IRQ(hi2c
, I2C_XFER_TX_IT
);
3868 /* Process Unlocked */
3871 /* Call the corresponding callback to inform upper layer of End of Transfer */
3872 HAL_I2C_MasterTxCpltCallback(hi2c
);
3874 /* hi2c->State == HAL_I2C_STATE_BUSY_RX */
3877 hi2c
->State
= HAL_I2C_STATE_READY
;
3878 hi2c
->PreviousState
= I2C_STATE_MASTER_BUSY_RX
;
3879 hi2c
->XferISR
= NULL
;
3881 /* Disable Interrupts */
3882 I2C_Disable_IRQ(hi2c
, I2C_XFER_RX_IT
);
3884 /* Process Unlocked */
3887 /* Call the corresponding callback to inform upper layer of End of Transfer */
3888 HAL_I2C_MasterRxCpltCallback(hi2c
);
3893 * @brief I2C Slave sequential complete process.
3894 * @param hi2c I2C handle.
3897 static void I2C_ITSlaveSequentialCplt(I2C_HandleTypeDef
*hi2c
)
3899 /* Reset I2C handle mode */
3900 hi2c
->Mode
= HAL_I2C_MODE_NONE
;
3902 if(hi2c
->State
== HAL_I2C_STATE_BUSY_TX_LISTEN
)
3904 /* Remove HAL_I2C_STATE_SLAVE_BUSY_TX, keep only HAL_I2C_STATE_LISTEN */
3905 hi2c
->State
= HAL_I2C_STATE_LISTEN
;
3906 hi2c
->PreviousState
= I2C_STATE_SLAVE_BUSY_TX
;
3908 /* Disable Interrupts */
3909 I2C_Disable_IRQ(hi2c
, I2C_XFER_TX_IT
);
3911 /* Process Unlocked */
3914 /* Call the Tx complete callback to inform upper layer of the end of transmit process */
3915 HAL_I2C_SlaveTxCpltCallback(hi2c
);
3918 else if(hi2c
->State
== HAL_I2C_STATE_BUSY_RX_LISTEN
)
3920 /* Remove HAL_I2C_STATE_SLAVE_BUSY_RX, keep only HAL_I2C_STATE_LISTEN */
3921 hi2c
->State
= HAL_I2C_STATE_LISTEN
;
3922 hi2c
->PreviousState
= I2C_STATE_SLAVE_BUSY_RX
;
3924 /* Disable Interrupts */
3925 I2C_Disable_IRQ(hi2c
, I2C_XFER_RX_IT
);
3927 /* Process Unlocked */
3930 /* Call the Rx complete callback to inform upper layer of the end of receive process */
3931 HAL_I2C_SlaveRxCpltCallback(hi2c
);
3936 * @brief I2C Master complete process.
3937 * @param hi2c I2C handle.
3938 * @param ITFlags Interrupt flags to handle.
3941 static void I2C_ITMasterCplt(I2C_HandleTypeDef
*hi2c
, uint32_t ITFlags
)
3943 /* Clear STOP Flag */
3944 __HAL_I2C_CLEAR_FLAG(hi2c
, I2C_FLAG_STOPF
);
3946 /* Clear Configuration Register 2 */
3947 I2C_RESET_CR2(hi2c
);
3949 /* Reset handle parameters */
3950 hi2c
->PreviousState
= I2C_STATE_NONE
;
3951 hi2c
->XferISR
= NULL
;
3952 hi2c
->XferOptions
= I2C_NO_OPTION_FRAME
;
3954 if((ITFlags
& I2C_FLAG_AF
) != RESET
)
3956 /* Clear NACK Flag */
3957 __HAL_I2C_CLEAR_FLAG(hi2c
, I2C_FLAG_AF
);
3959 /* Set acknowledge error code */
3960 hi2c
->ErrorCode
|= HAL_I2C_ERROR_AF
;
3963 /* Flush TX register */
3964 I2C_Flush_TXDR(hi2c
);
3966 /* Disable Interrupts */
3967 I2C_Disable_IRQ(hi2c
, I2C_XFER_TX_IT
| I2C_XFER_RX_IT
);
3969 /* Call the corresponding callback to inform upper layer of End of Transfer */
3970 if((hi2c
->ErrorCode
!= HAL_I2C_ERROR_NONE
) || (hi2c
->State
== HAL_I2C_STATE_ABORT
))
3972 /* Call the corresponding callback to inform upper layer of End of Transfer */
3973 I2C_ITError(hi2c
, hi2c
->ErrorCode
);
3975 /* hi2c->State == HAL_I2C_STATE_BUSY_TX */
3976 else if(hi2c
->State
== HAL_I2C_STATE_BUSY_TX
)
3978 hi2c
->State
= HAL_I2C_STATE_READY
;
3980 if (hi2c
->Mode
== HAL_I2C_MODE_MEM
)
3982 hi2c
->Mode
= HAL_I2C_MODE_NONE
;
3984 /* Process Unlocked */
3987 /* Call the corresponding callback to inform upper layer of End of Transfer */
3988 HAL_I2C_MemTxCpltCallback(hi2c
);
3992 hi2c
->Mode
= HAL_I2C_MODE_NONE
;
3994 /* Process Unlocked */
3997 /* Call the corresponding callback to inform upper layer of End of Transfer */
3998 HAL_I2C_MasterTxCpltCallback(hi2c
);
4001 /* hi2c->State == HAL_I2C_STATE_BUSY_RX */
4002 else if(hi2c
->State
== HAL_I2C_STATE_BUSY_RX
)
4004 hi2c
->State
= HAL_I2C_STATE_READY
;
4006 if (hi2c
->Mode
== HAL_I2C_MODE_MEM
)
4008 hi2c
->Mode
= HAL_I2C_MODE_NONE
;
4010 /* Process Unlocked */
4013 HAL_I2C_MemRxCpltCallback(hi2c
);
4017 hi2c
->Mode
= HAL_I2C_MODE_NONE
;
4019 /* Process Unlocked */
4022 HAL_I2C_MasterRxCpltCallback(hi2c
);
4028 * @brief I2C Slave complete process.
4029 * @param hi2c I2C handle.
4030 * @param ITFlags Interrupt flags to handle.
4033 static void I2C_ITSlaveCplt(I2C_HandleTypeDef
*hi2c
, uint32_t ITFlags
)
4035 /* Clear STOP Flag */
4036 __HAL_I2C_CLEAR_FLAG(hi2c
, I2C_FLAG_STOPF
);
4038 /* Clear ADDR flag */
4039 __HAL_I2C_CLEAR_FLAG(hi2c
,I2C_FLAG_ADDR
);
4041 /* Disable all interrupts */
4042 I2C_Disable_IRQ(hi2c
, I2C_XFER_LISTEN_IT
| I2C_XFER_TX_IT
| I2C_XFER_RX_IT
);
4044 /* Disable Address Acknowledge */
4045 hi2c
->Instance
->CR2
|= I2C_CR2_NACK
;
4047 /* Clear Configuration Register 2 */
4048 I2C_RESET_CR2(hi2c
);
4050 /* Flush TX register */
4051 I2C_Flush_TXDR(hi2c
);
4053 /* If a DMA is ongoing, Update handle size context */
4054 if(((hi2c
->Instance
->CR1
& I2C_CR1_TXDMAEN
) == I2C_CR1_TXDMAEN
) ||
4055 ((hi2c
->Instance
->CR1
& I2C_CR1_RXDMAEN
) == I2C_CR1_RXDMAEN
))
4057 hi2c
->XferCount
= I2C_GET_DMA_REMAIN_DATA(hi2c
);
4060 /* All data are not transferred, so set error code accordingly */
4061 if(hi2c
->XferCount
!= 0U)
4063 /* Set ErrorCode corresponding to a Non-Acknowledge */
4064 hi2c
->ErrorCode
|= HAL_I2C_ERROR_AF
;
4067 /* Store Last receive data if any */
4068 if(((ITFlags
& I2C_FLAG_RXNE
) != RESET
))
4070 /* Read data from RXDR */
4071 (*hi2c
->pBuffPtr
++) = hi2c
->Instance
->RXDR
;
4073 if((hi2c
->XferSize
> 0U))
4078 /* Set ErrorCode corresponding to a Non-Acknowledge */
4079 hi2c
->ErrorCode
|= HAL_I2C_ERROR_AF
;
4083 hi2c
->PreviousState
= I2C_STATE_NONE
;
4084 hi2c
->Mode
= HAL_I2C_MODE_NONE
;
4085 hi2c
->XferISR
= NULL
;
4087 if(hi2c
->ErrorCode
!= HAL_I2C_ERROR_NONE
)
4089 /* Call the corresponding callback to inform upper layer of End of Transfer */
4090 I2C_ITError(hi2c
, hi2c
->ErrorCode
);
4092 /* Call the Listen Complete callback, to inform upper layer of the end of Listen usecase */
4093 if(hi2c
->State
== HAL_I2C_STATE_LISTEN
)
4095 /* Call I2C Listen complete process */
4096 I2C_ITListenCplt(hi2c
, ITFlags
);
4099 else if(hi2c
->XferOptions
!= I2C_NO_OPTION_FRAME
)
4101 hi2c
->XferOptions
= I2C_NO_OPTION_FRAME
;
4102 hi2c
->State
= HAL_I2C_STATE_READY
;
4104 /* Process Unlocked */
4107 /* Call the Listen Complete callback, to inform upper layer of the end of Listen usecase */
4108 HAL_I2C_ListenCpltCallback(hi2c
);
4110 /* Call the corresponding callback to inform upper layer of End of Transfer */
4111 else if(hi2c
->State
== HAL_I2C_STATE_BUSY_RX
)
4113 hi2c
->State
= HAL_I2C_STATE_READY
;
4115 /* Process Unlocked */
4118 /* Call the Slave Rx Complete callback */
4119 HAL_I2C_SlaveRxCpltCallback(hi2c
);
4123 hi2c
->State
= HAL_I2C_STATE_READY
;
4125 /* Process Unlocked */
4128 /* Call the Slave Tx Complete callback */
4129 HAL_I2C_SlaveTxCpltCallback(hi2c
);
4134 * @brief I2C Listen complete process.
4135 * @param hi2c I2C handle.
4136 * @param ITFlags Interrupt flags to handle.
4139 static void I2C_ITListenCplt(I2C_HandleTypeDef
*hi2c
, uint32_t ITFlags
)
4141 /* Reset handle parameters */
4142 hi2c
->XferOptions
= I2C_NO_OPTION_FRAME
;
4143 hi2c
->PreviousState
= I2C_STATE_NONE
;
4144 hi2c
->State
= HAL_I2C_STATE_READY
;
4145 hi2c
->Mode
= HAL_I2C_MODE_NONE
;
4146 hi2c
->XferISR
= NULL
;
4148 /* Store Last receive data if any */
4149 if(((ITFlags
& I2C_FLAG_RXNE
) != RESET
))
4151 /* Read data from RXDR */
4152 (*hi2c
->pBuffPtr
++) = hi2c
->Instance
->RXDR
;
4154 if((hi2c
->XferSize
> 0U))
4159 /* Set ErrorCode corresponding to a Non-Acknowledge */
4160 hi2c
->ErrorCode
|= HAL_I2C_ERROR_AF
;
4164 /* Disable all Interrupts*/
4165 I2C_Disable_IRQ(hi2c
, I2C_XFER_LISTEN_IT
| I2C_XFER_RX_IT
| I2C_XFER_TX_IT
);
4167 /* Clear NACK Flag */
4168 __HAL_I2C_CLEAR_FLAG(hi2c
, I2C_FLAG_AF
);
4170 /* Process Unlocked */
4173 /* Call the Listen Complete callback, to inform upper layer of the end of Listen usecase */
4174 HAL_I2C_ListenCpltCallback(hi2c
);
4178 * @brief I2C interrupts error process.
4179 * @param hi2c I2C handle.
4180 * @param ErrorCode Error code to handle.
4183 static void I2C_ITError(I2C_HandleTypeDef
*hi2c
, uint32_t ErrorCode
)
4185 /* Reset handle parameters */
4186 hi2c
->Mode
= HAL_I2C_MODE_NONE
;
4187 hi2c
->XferOptions
= I2C_NO_OPTION_FRAME
;
4188 hi2c
->XferCount
= 0U;
4190 /* Set new error code */
4191 hi2c
->ErrorCode
|= ErrorCode
;
4193 /* Disable Interrupts */
4194 if((hi2c
->State
== HAL_I2C_STATE_LISTEN
) ||
4195 (hi2c
->State
== HAL_I2C_STATE_BUSY_TX_LISTEN
) ||
4196 (hi2c
->State
== HAL_I2C_STATE_BUSY_RX_LISTEN
))
4198 /* Disable all interrupts, except interrupts related to LISTEN state */
4199 I2C_Disable_IRQ(hi2c
, I2C_XFER_RX_IT
| I2C_XFER_TX_IT
);
4201 /* keep HAL_I2C_STATE_LISTEN if set */
4202 hi2c
->State
= HAL_I2C_STATE_LISTEN
;
4203 hi2c
->PreviousState
= I2C_STATE_NONE
;
4204 hi2c
->XferISR
= I2C_Slave_ISR_IT
;
4208 /* Disable all interrupts */
4209 I2C_Disable_IRQ(hi2c
, I2C_XFER_LISTEN_IT
| I2C_XFER_RX_IT
| I2C_XFER_TX_IT
);
4211 /* If state is an abort treatment on goind, don't change state */
4212 /* This change will be do later */
4213 if(hi2c
->State
!= HAL_I2C_STATE_ABORT
)
4215 /* Set HAL_I2C_STATE_READY */
4216 hi2c
->State
= HAL_I2C_STATE_READY
;
4218 hi2c
->PreviousState
= I2C_STATE_NONE
;
4219 hi2c
->XferISR
= NULL
;
4222 /* Abort DMA TX transfer if any */
4223 if((hi2c
->Instance
->CR1
& I2C_CR1_TXDMAEN
) == I2C_CR1_TXDMAEN
)
4225 hi2c
->Instance
->CR1
&= ~I2C_CR1_TXDMAEN
;
4227 /* Set the I2C DMA Abort callback :
4228 will lead to call HAL_I2C_ErrorCallback() at end of DMA abort procedure */
4229 hi2c
->hdmatx
->XferAbortCallback
= I2C_DMAAbort
;
4231 /* Process Unlocked */
4235 if(HAL_DMA_Abort_IT(hi2c
->hdmatx
) != HAL_OK
)
4237 /* Call Directly XferAbortCallback function in case of error */
4238 hi2c
->hdmatx
->XferAbortCallback(hi2c
->hdmatx
);
4241 /* Abort DMA RX transfer if any */
4242 else if((hi2c
->Instance
->CR1
& I2C_CR1_RXDMAEN
) == I2C_CR1_RXDMAEN
)
4244 hi2c
->Instance
->CR1
&= ~I2C_CR1_RXDMAEN
;
4246 /* Set the I2C DMA Abort callback :
4247 will lead to call HAL_I2C_ErrorCallback() at end of DMA abort procedure */
4248 hi2c
->hdmarx
->XferAbortCallback
= I2C_DMAAbort
;
4250 /* Process Unlocked */
4254 if(HAL_DMA_Abort_IT(hi2c
->hdmarx
) != HAL_OK
)
4256 /* Call Directly hi2c->hdmarx->XferAbortCallback function in case of error */
4257 hi2c
->hdmarx
->XferAbortCallback(hi2c
->hdmarx
);
4260 else if(hi2c
->State
== HAL_I2C_STATE_ABORT
)
4262 hi2c
->State
= HAL_I2C_STATE_READY
;
4264 /* Process Unlocked */
4267 /* Call the corresponding callback to inform upper layer of End of Transfer */
4268 HAL_I2C_AbortCpltCallback(hi2c
);
4272 /* Process Unlocked */
4275 /* Call the corresponding callback to inform upper layer of End of Transfer */
4276 HAL_I2C_ErrorCallback(hi2c
);
4281 * @brief I2C Tx data register flush process.
4282 * @param hi2c I2C handle.
4285 static void I2C_Flush_TXDR(I2C_HandleTypeDef
*hi2c
)
4287 /* If a pending TXIS flag is set */
4288 /* Write a dummy data in TXDR to clear it */
4289 if(__HAL_I2C_GET_FLAG(hi2c
, I2C_FLAG_TXIS
) != RESET
)
4291 hi2c
->Instance
->TXDR
= 0x00U
;
4294 /* Flush TX register if not empty */
4295 if(__HAL_I2C_GET_FLAG(hi2c
, I2C_FLAG_TXE
) == RESET
)
4297 __HAL_I2C_CLEAR_FLAG(hi2c
, I2C_FLAG_TXE
);
4302 * @brief DMA I2C master transmit process complete callback.
4303 * @param hdma DMA handle
4306 static void I2C_DMAMasterTransmitCplt(DMA_HandleTypeDef
*hdma
)
4308 I2C_HandleTypeDef
* hi2c
= (I2C_HandleTypeDef
*)((DMA_HandleTypeDef
*)hdma
)->Parent
;
4310 /* Disable DMA Request */
4311 hi2c
->Instance
->CR1
&= ~I2C_CR1_TXDMAEN
;
4313 /* If last transfer, enable STOP interrupt */
4314 if(hi2c
->XferCount
== 0U)
4316 /* Enable STOP interrupt */
4317 I2C_Enable_IRQ(hi2c
, I2C_XFER_CPLT_IT
);
4319 /* else prepare a new DMA transfer and enable TCReload interrupt */
4322 /* Update Buffer pointer */
4323 hi2c
->pBuffPtr
+= hi2c
->XferSize
;
4325 /* Set the XferSize to transfer */
4326 if(hi2c
->XferCount
> MAX_NBYTE_SIZE
)
4328 hi2c
->XferSize
= MAX_NBYTE_SIZE
;
4332 hi2c
->XferSize
= hi2c
->XferCount
;
4335 /* Enable the DMA channel */
4336 HAL_DMA_Start_IT(hi2c
->hdmatx
, (uint32_t)hi2c
->pBuffPtr
, (uint32_t)&hi2c
->Instance
->TXDR
, hi2c
->XferSize
);
4338 /* Enable TC interrupts */
4339 I2C_Enable_IRQ(hi2c
, I2C_XFER_RELOAD_IT
);
4344 * @brief DMA I2C slave transmit process complete callback.
4345 * @param hdma DMA handle
4348 static void I2C_DMASlaveTransmitCplt(DMA_HandleTypeDef
*hdma
)
4350 /* Prevent unused argument(s) compilation warning */
4353 /* No specific action, Master fully manage the generation of STOP condition */
4354 /* Mean that this generation can arrive at any time, at the end or during DMA process */
4355 /* So STOP condition should be manage through Interrupt treatment */
4359 * @brief DMA I2C master receive process complete callback.
4360 * @param hdma DMA handle
4363 static void I2C_DMAMasterReceiveCplt(DMA_HandleTypeDef
*hdma
)
4365 I2C_HandleTypeDef
* hi2c
= (I2C_HandleTypeDef
*)((DMA_HandleTypeDef
*)hdma
)->Parent
;
4367 /* Disable DMA Request */
4368 hi2c
->Instance
->CR1
&= ~I2C_CR1_RXDMAEN
;
4370 /* If last transfer, enable STOP interrupt */
4371 if(hi2c
->XferCount
== 0U)
4373 /* Enable STOP interrupt */
4374 I2C_Enable_IRQ(hi2c
, I2C_XFER_CPLT_IT
);
4376 /* else prepare a new DMA transfer and enable TCReload interrupt */
4379 /* Update Buffer pointer */
4380 hi2c
->pBuffPtr
+= hi2c
->XferSize
;
4382 /* Set the XferSize to transfer */
4383 if(hi2c
->XferCount
> MAX_NBYTE_SIZE
)
4385 hi2c
->XferSize
= MAX_NBYTE_SIZE
;
4389 hi2c
->XferSize
= hi2c
->XferCount
;
4392 /* Enable the DMA channel */
4393 HAL_DMA_Start_IT(hi2c
->hdmarx
, (uint32_t)&hi2c
->Instance
->RXDR
, (uint32_t)hi2c
->pBuffPtr
, hi2c
->XferSize
);
4395 /* Enable TC interrupts */
4396 I2C_Enable_IRQ(hi2c
, I2C_XFER_RELOAD_IT
);
4401 * @brief DMA I2C slave receive process complete callback.
4402 * @param hdma DMA handle
4405 static void I2C_DMASlaveReceiveCplt(DMA_HandleTypeDef
*hdma
)
4407 /* Prevent unused argument(s) compilation warning */
4410 /* No specific action, Master fully manage the generation of STOP condition */
4411 /* Mean that this generation can arrive at any time, at the end or during DMA process */
4412 /* So STOP condition should be manage through Interrupt treatment */
4416 * @brief DMA I2C communication error callback.
4417 * @param hdma DMA handle
4420 static void I2C_DMAError(DMA_HandleTypeDef
*hdma
)
4422 I2C_HandleTypeDef
* hi2c
= ( I2C_HandleTypeDef
* )((DMA_HandleTypeDef
* )hdma
)->Parent
;
4424 /* Disable Acknowledge */
4425 hi2c
->Instance
->CR2
|= I2C_CR2_NACK
;
4427 /* Call the corresponding callback to inform upper layer of End of Transfer */
4428 I2C_ITError(hi2c
, HAL_I2C_ERROR_DMA
);
4432 * @brief DMA I2C communication abort callback
4433 * (To be called at end of DMA Abort procedure).
4434 * @param hdma: DMA handle.
4437 static void I2C_DMAAbort(DMA_HandleTypeDef
*hdma
)
4439 I2C_HandleTypeDef
* hi2c
= ( I2C_HandleTypeDef
* )((DMA_HandleTypeDef
* )hdma
)->Parent
;
4441 /* Disable Acknowledge */
4442 hi2c
->Instance
->CR2
|= I2C_CR2_NACK
;
4444 /* Reset AbortCpltCallback */
4445 hi2c
->hdmatx
->XferAbortCallback
= NULL
;
4446 hi2c
->hdmarx
->XferAbortCallback
= NULL
;
4448 /* Check if come from abort from user */
4449 if(hi2c
->State
== HAL_I2C_STATE_ABORT
)
4451 hi2c
->State
= HAL_I2C_STATE_READY
;
4453 /* Call the corresponding callback to inform upper layer of End of Transfer */
4454 HAL_I2C_AbortCpltCallback(hi2c
);
4458 /* Call the corresponding callback to inform upper layer of End of Transfer */
4459 HAL_I2C_ErrorCallback(hi2c
);
4464 * @brief This function handles I2C Communication Timeout.
4465 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
4466 * the configuration information for the specified I2C.
4467 * @param Flag Specifies the I2C flag to check.
4468 * @param Status The new Flag status (SET or RESET).
4469 * @param Timeout Timeout duration
4470 * @param Tickstart Tick start value
4471 * @retval HAL status
4473 static HAL_StatusTypeDef
I2C_WaitOnFlagUntilTimeout(I2C_HandleTypeDef
*hi2c
, uint32_t Flag
, FlagStatus Status
, uint32_t Timeout
, uint32_t Tickstart
)
4475 while(__HAL_I2C_GET_FLAG(hi2c
, Flag
) == Status
)
4477 /* Check for the Timeout */
4478 if(Timeout
!= HAL_MAX_DELAY
)
4480 if((Timeout
== 0U)||((HAL_GetTick() - Tickstart
) > Timeout
))
4482 hi2c
->State
= HAL_I2C_STATE_READY
;
4483 hi2c
->Mode
= HAL_I2C_MODE_NONE
;
4485 /* Process Unlocked */
4495 * @brief This function handles I2C Communication Timeout for specific usage of TXIS flag.
4496 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
4497 * the configuration information for the specified I2C.
4498 * @param Timeout Timeout duration
4499 * @param Tickstart Tick start value
4500 * @retval HAL status
4502 static HAL_StatusTypeDef
I2C_WaitOnTXISFlagUntilTimeout(I2C_HandleTypeDef
*hi2c
, uint32_t Timeout
, uint32_t Tickstart
)
4504 while(__HAL_I2C_GET_FLAG(hi2c
, I2C_FLAG_TXIS
) == RESET
)
4506 /* Check if a NACK is detected */
4507 if(I2C_IsAcknowledgeFailed(hi2c
, Timeout
, Tickstart
) != HAL_OK
)
4512 /* Check for the Timeout */
4513 if(Timeout
!= HAL_MAX_DELAY
)
4515 if((Timeout
== 0U)||((HAL_GetTick() - Tickstart
) > Timeout
))
4517 hi2c
->ErrorCode
|= HAL_I2C_ERROR_TIMEOUT
;
4518 hi2c
->State
= HAL_I2C_STATE_READY
;
4519 hi2c
->Mode
= HAL_I2C_MODE_NONE
;
4521 /* Process Unlocked */
4532 * @brief This function handles I2C Communication Timeout for specific usage of STOP flag.
4533 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
4534 * the configuration information for the specified I2C.
4535 * @param Timeout Timeout duration
4536 * @param Tickstart Tick start value
4537 * @retval HAL status
4539 static HAL_StatusTypeDef
I2C_WaitOnSTOPFlagUntilTimeout(I2C_HandleTypeDef
*hi2c
, uint32_t Timeout
, uint32_t Tickstart
)
4541 while(__HAL_I2C_GET_FLAG(hi2c
, I2C_FLAG_STOPF
) == RESET
)
4543 /* Check if a NACK is detected */
4544 if(I2C_IsAcknowledgeFailed(hi2c
, Timeout
, Tickstart
) != HAL_OK
)
4549 /* Check for the Timeout */
4550 if((Timeout
== 0U)||((HAL_GetTick() - Tickstart
) > Timeout
))
4552 hi2c
->ErrorCode
|= HAL_I2C_ERROR_TIMEOUT
;
4553 hi2c
->State
= HAL_I2C_STATE_READY
;
4554 hi2c
->Mode
= HAL_I2C_MODE_NONE
;
4556 /* Process Unlocked */
4566 * @brief This function handles I2C Communication Timeout for specific usage of RXNE flag.
4567 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
4568 * the configuration information for the specified I2C.
4569 * @param Timeout Timeout duration
4570 * @param Tickstart Tick start value
4571 * @retval HAL status
4573 static HAL_StatusTypeDef
I2C_WaitOnRXNEFlagUntilTimeout(I2C_HandleTypeDef
*hi2c
, uint32_t Timeout
, uint32_t Tickstart
)
4575 while(__HAL_I2C_GET_FLAG(hi2c
, I2C_FLAG_RXNE
) == RESET
)
4577 /* Check if a NACK is detected */
4578 if(I2C_IsAcknowledgeFailed(hi2c
, Timeout
, Tickstart
) != HAL_OK
)
4583 /* Check if a STOPF is detected */
4584 if(__HAL_I2C_GET_FLAG(hi2c
, I2C_FLAG_STOPF
) == SET
)
4586 /* Clear STOP Flag */
4587 __HAL_I2C_CLEAR_FLAG(hi2c
, I2C_FLAG_STOPF
);
4589 /* Clear Configuration Register 2 */
4590 I2C_RESET_CR2(hi2c
);
4592 hi2c
->ErrorCode
= HAL_I2C_ERROR_NONE
;
4593 hi2c
->State
= HAL_I2C_STATE_READY
;
4594 hi2c
->Mode
= HAL_I2C_MODE_NONE
;
4596 /* Process Unlocked */
4602 /* Check for the Timeout */
4603 if((Timeout
== 0U)||((HAL_GetTick() - Tickstart
) > Timeout
))
4605 hi2c
->ErrorCode
|= HAL_I2C_ERROR_TIMEOUT
;
4606 hi2c
->State
= HAL_I2C_STATE_READY
;
4608 /* Process Unlocked */
4618 * @brief This function handles Acknowledge failed detection during an I2C Communication.
4619 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
4620 * the configuration information for the specified I2C.
4621 * @param Timeout Timeout duration
4622 * @param Tickstart Tick start value
4623 * @retval HAL status
4625 static HAL_StatusTypeDef
I2C_IsAcknowledgeFailed(I2C_HandleTypeDef
*hi2c
, uint32_t Timeout
, uint32_t Tickstart
)
4627 if(__HAL_I2C_GET_FLAG(hi2c
, I2C_FLAG_AF
) == SET
)
4629 /* Wait until STOP Flag is reset */
4630 /* AutoEnd should be initiate after AF */
4631 while(__HAL_I2C_GET_FLAG(hi2c
, I2C_FLAG_STOPF
) == RESET
)
4633 /* Check for the Timeout */
4634 if(Timeout
!= HAL_MAX_DELAY
)
4636 if((Timeout
== 0U)||((HAL_GetTick() - Tickstart
) > Timeout
))
4638 hi2c
->State
= HAL_I2C_STATE_READY
;
4639 hi2c
->Mode
= HAL_I2C_MODE_NONE
;
4641 /* Process Unlocked */
4648 /* Clear NACKF Flag */
4649 __HAL_I2C_CLEAR_FLAG(hi2c
, I2C_FLAG_AF
);
4651 /* Clear STOP Flag */
4652 __HAL_I2C_CLEAR_FLAG(hi2c
, I2C_FLAG_STOPF
);
4654 /* Flush TX register */
4655 I2C_Flush_TXDR(hi2c
);
4657 /* Clear Configuration Register 2 */
4658 I2C_RESET_CR2(hi2c
);
4660 hi2c
->ErrorCode
= HAL_I2C_ERROR_AF
;
4661 hi2c
->State
= HAL_I2C_STATE_READY
;
4662 hi2c
->Mode
= HAL_I2C_MODE_NONE
;
4664 /* Process Unlocked */
4673 * @brief Handles I2Cx communication when starting transfer or during transfer (TC or TCR flag are set).
4674 * @param hi2c I2C handle.
4675 * @param DevAddress Specifies the slave address to be programmed.
4676 * @param Size Specifies the number of bytes to be programmed.
4677 * This parameter must be a value between 0 and 255.
4678 * @param Mode New state of the I2C START condition generation.
4679 * This parameter can be one of the following values:
4680 * @arg @ref I2C_RELOAD_MODE Enable Reload mode .
4681 * @arg @ref I2C_AUTOEND_MODE Enable Automatic end mode.
4682 * @arg @ref I2C_SOFTEND_MODE Enable Software end mode.
4683 * @param Request New state of the I2C START condition generation.
4684 * This parameter can be one of the following values:
4685 * @arg @ref I2C_NO_STARTSTOP Don't Generate stop and start condition.
4686 * @arg @ref I2C_GENERATE_STOP Generate stop condition (Size should be set to 0).
4687 * @arg @ref I2C_GENERATE_START_READ Generate Restart for read request.
4688 * @arg @ref I2C_GENERATE_START_WRITE Generate Restart for write request.
4691 static void I2C_TransferConfig(I2C_HandleTypeDef
*hi2c
, uint16_t DevAddress
, uint8_t Size
, uint32_t Mode
, uint32_t Request
)
4693 uint32_t tmpreg
= 0U;
4695 /* Check the parameters */
4696 assert_param(IS_I2C_ALL_INSTANCE(hi2c
->Instance
));
4697 assert_param(IS_TRANSFER_MODE(Mode
));
4698 assert_param(IS_TRANSFER_REQUEST(Request
));
4700 /* Get the CR2 register value */
4701 tmpreg
= hi2c
->Instance
->CR2
;
4703 /* clear tmpreg specific bits */
4704 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 tmpreg
|= (uint32_t)(((uint32_t)DevAddress
& I2C_CR2_SADD
) | (((uint32_t)Size
<< 16 ) & I2C_CR2_NBYTES
) | \
4708 (uint32_t)Mode
| (uint32_t)Request
);
4710 /* update CR2 register */
4711 hi2c
->Instance
->CR2
= tmpreg
;
4715 * @brief Manage the enabling of Interrupts.
4716 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
4717 * the configuration information for the specified I2C.
4718 * @param InterruptRequest Value of @ref I2C_Interrupt_configuration_definition.
4719 * @retval HAL status
4721 static HAL_StatusTypeDef
I2C_Enable_IRQ(I2C_HandleTypeDef
*hi2c
, uint16_t InterruptRequest
)
4723 uint32_t tmpisr
= 0U;
4725 if((hi2c
->XferISR
== I2C_Master_ISR_DMA
) || \
4726 (hi2c
->XferISR
== I2C_Slave_ISR_DMA
))
4728 if((InterruptRequest
& I2C_XFER_LISTEN_IT
) == I2C_XFER_LISTEN_IT
)
4730 /* Enable ERR, STOP, NACK and ADDR interrupts */
4731 tmpisr
|= I2C_IT_ADDRI
| I2C_IT_STOPI
| I2C_IT_NACKI
| I2C_IT_ERRI
;
4734 if((InterruptRequest
& I2C_XFER_ERROR_IT
) == I2C_XFER_ERROR_IT
)
4736 /* Enable ERR and NACK interrupts */
4737 tmpisr
|= I2C_IT_ERRI
| I2C_IT_NACKI
;
4740 if((InterruptRequest
& I2C_XFER_CPLT_IT
) == I2C_XFER_CPLT_IT
)
4742 /* Enable STOP interrupts */
4743 tmpisr
|= I2C_IT_STOPI
;
4746 if((InterruptRequest
& I2C_XFER_RELOAD_IT
) == I2C_XFER_RELOAD_IT
)
4748 /* Enable TC interrupts */
4749 tmpisr
|= I2C_IT_TCI
;
4754 if((InterruptRequest
& I2C_XFER_LISTEN_IT
) == I2C_XFER_LISTEN_IT
)
4756 /* Enable ERR, STOP, NACK, and ADDR interrupts */
4757 tmpisr
|= I2C_IT_ADDRI
| I2C_IT_STOPI
| I2C_IT_NACKI
| I2C_IT_ERRI
;
4760 if((InterruptRequest
& I2C_XFER_TX_IT
) == I2C_XFER_TX_IT
)
4762 /* Enable ERR, TC, STOP, NACK and RXI interrupts */
4763 tmpisr
|= I2C_IT_ERRI
| I2C_IT_TCI
| I2C_IT_STOPI
| I2C_IT_NACKI
| I2C_IT_TXI
;
4766 if((InterruptRequest
& I2C_XFER_RX_IT
) == I2C_XFER_RX_IT
)
4768 /* Enable ERR, TC, STOP, NACK and TXI interrupts */
4769 tmpisr
|= I2C_IT_ERRI
| I2C_IT_TCI
| I2C_IT_STOPI
| I2C_IT_NACKI
| I2C_IT_RXI
;
4772 if((InterruptRequest
& I2C_XFER_CPLT_IT
) == I2C_XFER_CPLT_IT
)
4774 /* Enable STOP interrupts */
4775 tmpisr
|= I2C_IT_STOPI
;
4779 /* Enable interrupts only at the end */
4780 /* to avoid the risk of I2C interrupt handle execution before */
4781 /* all interrupts requested done */
4782 __HAL_I2C_ENABLE_IT(hi2c
, tmpisr
);
4788 * @brief Manage the disabling of Interrupts.
4789 * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
4790 * the configuration information for the specified I2C.
4791 * @param InterruptRequest Value of @ref I2C_Interrupt_configuration_definition.
4792 * @retval HAL status
4794 static HAL_StatusTypeDef
I2C_Disable_IRQ(I2C_HandleTypeDef
*hi2c
, uint16_t InterruptRequest
)
4796 uint32_t tmpisr
= 0U;
4798 if((InterruptRequest
& I2C_XFER_TX_IT
) == I2C_XFER_TX_IT
)
4800 /* Disable TC and TXI interrupts */
4801 tmpisr
|= I2C_IT_TCI
| I2C_IT_TXI
;
4803 if((hi2c
->State
& HAL_I2C_STATE_LISTEN
) != HAL_I2C_STATE_LISTEN
)
4805 /* Disable NACK and STOP interrupts */
4806 tmpisr
|= I2C_IT_STOPI
| I2C_IT_NACKI
| I2C_IT_ERRI
;
4810 if((InterruptRequest
& I2C_XFER_RX_IT
) == I2C_XFER_RX_IT
)
4812 /* Disable TC and RXI interrupts */
4813 tmpisr
|= I2C_IT_TCI
| I2C_IT_RXI
;
4815 if((hi2c
->State
& HAL_I2C_STATE_LISTEN
) != HAL_I2C_STATE_LISTEN
)
4817 /* Disable NACK and STOP interrupts */
4818 tmpisr
|= I2C_IT_STOPI
| I2C_IT_NACKI
| I2C_IT_ERRI
;
4822 if((InterruptRequest
& I2C_XFER_LISTEN_IT
) == I2C_XFER_LISTEN_IT
)
4824 /* Disable ADDR, NACK and STOP interrupts */
4825 tmpisr
|= I2C_IT_ADDRI
| I2C_IT_STOPI
| I2C_IT_NACKI
| I2C_IT_ERRI
;
4828 if((InterruptRequest
& I2C_XFER_ERROR_IT
) == I2C_XFER_ERROR_IT
)
4830 /* Enable ERR and NACK interrupts */
4831 tmpisr
|= I2C_IT_ERRI
| I2C_IT_NACKI
;
4834 if((InterruptRequest
& I2C_XFER_CPLT_IT
) == I2C_XFER_CPLT_IT
)
4836 /* Enable STOP interrupts */
4837 tmpisr
|= I2C_IT_STOPI
;
4840 if((InterruptRequest
& I2C_XFER_RELOAD_IT
) == I2C_XFER_RELOAD_IT
)
4842 /* Enable TC interrupts */
4843 tmpisr
|= I2C_IT_TCI
;
4846 /* Disable interrupts only at the end */
4847 /* to avoid a breaking situation like at "t" time */
4848 /* all disable interrupts request are not done */
4849 __HAL_I2C_DISABLE_IT(hi2c
, tmpisr
);
4858 #endif /* HAL_I2C_MODULE_ENABLED */
4867 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/