2 ******************************************************************************
3 * @file stm32f4xx_hal_fmpi2c.c
4 * @author MCD Application Team
7 * @brief FMPI2C HAL module driver.
8 * This file provides firmware functions to manage the following
9 * functionalities of the Inter Integrated Circuit (FMPI2C) 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 FMPI2C HAL driver can be used as follows:
21 (#) Declare a FMPI2C_HandleTypeDef handle structure, for example:
22 FMPI2C_HandleTypeDef hfmpi2c;
24 (#)Initialize the FMPI2C low level resources by implementing the HAL_FMPI2C_MspInit() API:
25 (##) Enable the FMPI2Cx interface clock
26 (##) FMPI2C pins configuration
27 (+++) Enable the clock for the FMPI2C GPIOs
28 (+++) Configure FMPI2C pins as alternate function open-drain
29 (##) NVIC configuration if you need to use interrupt process
30 (+++) Configure the FMPI2Cx interrupt priority
31 (+++) Enable the NVIC FMPI2C IRQ Channel
32 (##) DMA Configuration if you need to use DMA process
33 (+++) Declare a DMA_HandleTypeDef handle structure for the transmit or receive channel
34 (+++) Enable the DMAx interface clock using
35 (+++) Configure the DMA handle parameters
36 (+++) Configure the DMA Tx or Rx channel
37 (+++) Associate the initialized DMA handle to the hfmpi2c 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 channel
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 hfmpi2c Init structure.
44 (#) Initialize the FMPI2C registers by calling the HAL_FMPI2C_Init(), configures also the low level Hardware
45 (GPIO, CLOCK, NVIC...etc) by calling the customized HAL_FMPI2C_MspInit(&hfmpi2c) API.
47 (#) To check if target device is ready for communication, use the function HAL_FMPI2C_IsDeviceReady()
49 (#) For FMPI2C 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_FMPI2C_Master_Transmit()
55 (+) Receive in master mode an amount of data in blocking mode using HAL_FMPI2C_Master_Receive()
56 (+) Transmit in slave mode an amount of data in blocking mode using HAL_FMPI2C_Slave_Transmit()
57 (+) Receive in slave mode an amount of data in blocking mode using HAL_FMPI2C_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_FMPI2C_Mem_Write()
63 (+) Read an amount of data in blocking mode from a specific memory address using HAL_FMPI2C_Mem_Read()
66 *** Interrupt mode IO operation ***
67 ===================================
69 (+) Transmit in master mode an amount of data in non-blocking mode using HAL_FMPI2C_Master_Transmit_IT()
70 (+) At transmission end of transfer, HAL_FMPI2C_MasterTxCpltCallback() is executed and user can
71 add his own code by customization of function pointer HAL_FMPI2C_MasterTxCpltCallback()
72 (+) Receive in master mode an amount of data in non-blocking mode using HAL_FMPI2C_Master_Receive_IT()
73 (+) At reception end of transfer, HAL_FMPI2C_MasterRxCpltCallback() is executed and user can
74 add his own code by customization of function pointer HAL_FMPI2C_MasterRxCpltCallback()
75 (+) Transmit in slave mode an amount of data in non-blocking mode using HAL_FMPI2C_Slave_Transmit_IT()
76 (+) At transmission end of transfer, HAL_FMPI2C_SlaveTxCpltCallback() is executed and user can
77 add his own code by customization of function pointer HAL_FMPI2C_SlaveTxCpltCallback()
78 (+) Receive in slave mode an amount of data in non-blocking mode using HAL_FMPI2C_Slave_Receive_IT()
79 (+) At reception end of transfer, HAL_FMPI2C_SlaveRxCpltCallback() is executed and user can
80 add his own code by customization of function pointer HAL_FMPI2C_SlaveRxCpltCallback()
81 (+) In case of transfer Error, HAL_FMPI2C_ErrorCallback() function is executed and user can
82 add his own code by customization of function pointer HAL_FMPI2C_ErrorCallback()
83 (+) Abort a master FMPI2C process communication with Interrupt using HAL_FMPI2C_Master_Abort_IT()
84 (+) End of abort process, HAL_FMPI2C_MasterRxCpltCallback() or HAL_FMPI2C_MasterTxCpltCallback() is executed and user can
85 add his own code by customization of function pointer HAL_FMPI2C_MasterRxCpltCallback() or HAL_FMPI2C_MasterTxCpltCallback()
86 (+) Discard a slave FMPI2C process communication using __HAL_FMPI2C_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 FMPI2C_XFEROPTIONS and are listed below:
98 (++) FMPI2C_FIRST_AND_LAST_FRAME: No sequential usage, functionnal is same as associated interfaces in no sequential mode
99 (++) FMPI2C_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 (++) FMPI2C_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_FMPI2C_Master_Sequential_Transmit_IT() then HAL_FMPI2C_Master_Sequential_Transmit_IT())
104 (++) FMPI2C_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 (++) FMPI2C_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 FMPI2C interfaces are listed below:
112 (++) Sequential transmit in master FMPI2C mode an amount of data in non-blocking mode using HAL_FMPI2C_Master_Sequential_Transmit_IT()
113 (+++) At transmission end of current frame transfer, HAL_FMPI2C_MasterTxCpltCallback() is executed and user can
114 add his own code by customization of function pointer HAL_FMPI2C_MasterTxCpltCallback()
115 (++) Sequential receive in master FMPI2C mode an amount of data in non-blocking mode using HAL_FMPI2C_Master_Sequential_Receive_IT()
116 (+++) At reception end of current frame transfer, HAL_FMPI2C_MasterRxCpltCallback() is executed and user can
117 add his own code by customization of function pointer HAL_FMPI2C_MasterRxCpltCallback()
118 (++) Abort a master FMPI2C process communication with Interrupt using HAL_FMPI2C_Master_Abort_IT()
119 (+++) End of abort process, HAL_FMPI2C_AbortCpltCallback() is executed and user can
120 add his own code by customization of function pointer HAL_FMPI2C_AbortCpltCallback()
121 (+++) mean HAL_FMPI2C_MasterTxCpltCallback() in case of previous state was master transmit
122 (+++) mean HAL_FMPI2C_MasterRxCpltCallback() in case of previous state was master receive
123 (++) Enable/disable the Address listen mode in slave FMPI2C mode using HAL_FMPI2C_EnableListen_IT() HAL_FMPI2C_DisableListen_IT()
124 (+++) When address slave FMPI2C match, HAL_FMPI2C_AddrCallback() is executed and user can
125 add his own code to check the Address Match Code and the transmission direction request by master (Write/Read).
126 (+++) At Listen mode end HAL_FMPI2C_ListenCpltCallback() is executed and user can
127 add his own code by customization of function pointer HAL_FMPI2C_ListenCpltCallback()
128 (++) Sequential transmit in slave FMPI2C mode an amount of data in non-blocking mode using HAL_FMPI2C_Slave_Sequential_Transmit_IT()
129 (+++) At transmission end of current frame transfer, HAL_FMPI2C_SlaveTxCpltCallback() is executed and user can
130 add his own code by customization of function pointer HAL_FMPI2C_SlaveTxCpltCallback()
131 (++) Sequential receive in slave FMPI2C mode an amount of data in non-blocking mode using HAL_FMPI2C_Slave_Sequential_Receive_IT()
132 (+++) At reception end of current frame transfer, HAL_FMPI2C_SlaveRxCpltCallback() is executed and user can
133 add his own code by customization of function pointer HAL_FMPI2C_SlaveRxCpltCallback()
134 (++) In case of transfer Error, HAL_FMPI2C_ErrorCallback() function is executed and user can
135 add his own code by customization of function pointer HAL_FMPI2C_ErrorCallback()
136 (++) Abort a master FMPI2C process communication with Interrupt using HAL_FMPI2C_Master_Abort_IT()
137 (++) End of abort process, HAL_FMPI2C_AbortCpltCallback() is executed and user can
138 add his own code by customization of function pointer HAL_FMPI2C_AbortCpltCallback()
139 (++) Discard a slave FMPI2C process communication using __HAL_FMPI2C_GENERATE_NACK() macro.
140 This action will inform Master to generate a Stop condition to discard the communication.
142 *** Interrupt mode IO MEM operation ***
143 =======================================
145 (+) Write an amount of data in non-blocking mode with Interrupt to a specific memory address using
146 HAL_FMPI2C_Mem_Write_IT()
147 (+) At Memory end of write transfer, HAL_FMPI2C_MemTxCpltCallback() is executed and user can
148 add his own code by customization of function pointer HAL_FMPI2C_MemTxCpltCallback()
149 (+) Read an amount of data in non-blocking mode with Interrupt from a specific memory address using
150 HAL_FMPI2C_Mem_Read_IT()
151 (+) At Memory end of read transfer, HAL_FMPI2C_MemRxCpltCallback() is executed and user can
152 add his own code by customization of function pointer HAL_FMPI2C_MemRxCpltCallback()
153 (+) In case of transfer Error, HAL_FMPI2C_ErrorCallback() function is executed and user can
154 add his own code by customization of function pointer HAL_FMPI2C_ErrorCallback()
156 *** DMA mode IO operation ***
157 ==============================
159 (+) Transmit in master mode an amount of data in non-blocking mode (DMA) using
160 HAL_FMPI2C_Master_Transmit_DMA()
161 (+) At transmission end of transfer, HAL_FMPI2C_MasterTxCpltCallback() is executed and user can
162 add his own code by customization of function pointer HAL_FMPI2C_MasterTxCpltCallback()
163 (+) Receive in master mode an amount of data in non-blocking mode (DMA) using
164 HAL_FMPI2C_Master_Receive_DMA()
165 (+) At reception end of transfer, HAL_FMPI2C_MasterRxCpltCallback() is executed and user can
166 add his own code by customization of function pointer HAL_FMPI2C_MasterRxCpltCallback()
167 (+) Transmit in slave mode an amount of data in non-blocking mode (DMA) using
168 HAL_FMPI2C_Slave_Transmit_DMA()
169 (+) At transmission end of transfer, HAL_FMPI2C_SlaveTxCpltCallback() is executed and user can
170 add his own code by customization of function pointer HAL_FMPI2C_SlaveTxCpltCallback()
171 (+) Receive in slave mode an amount of data in non-blocking mode (DMA) using
172 HAL_FMPI2C_Slave_Receive_DMA()
173 (+) At reception end of transfer, HAL_FMPI2C_SlaveRxCpltCallback() is executed and user can
174 add his own code by customization of function pointer HAL_FMPI2C_SlaveRxCpltCallback()
175 (+) In case of transfer Error, HAL_FMPI2C_ErrorCallback() function is executed and user can
176 add his own code by customization of function pointer HAL_FMPI2C_ErrorCallback()
177 (+) Abort a master FMPI2C process communication with Interrupt using HAL_FMPI2C_Master_Abort_IT()
178 (+) End of abort process, HAL_FMPI2C_MasterRxCpltCallback() or HAL_FMPI2C_MasterTxCpltCallback() is executed and user can
179 add his own code by customization of function pointer HAL_FMPI2C_MasterRxCpltCallback() or HAL_FMPI2C_MasterTxCpltCallback()
180 (+) Discard a slave FMPI2C process communication using __HAL_FMPI2C_GENERATE_NACK() macro.
181 This action will inform Master to generate a Stop condition to discard the communication.
183 *** DMA mode IO MEM operation ***
184 =================================
186 (+) Write an amount of data in non-blocking mode with DMA to a specific memory address using
187 HAL_FMPI2C_Mem_Write_DMA()
188 (+) At Memory end of write transfer, HAL_FMPI2C_MemTxCpltCallback() is executed and user can
189 add his own code by customization of function pointer HAL_FMPI2C_MemTxCpltCallback()
190 (+) Read an amount of data in non-blocking mode with DMA from a specific memory address using
191 HAL_FMPI2C_Mem_Read_DMA()
192 (+) At Memory end of read transfer, HAL_FMPI2C_MemRxCpltCallback() is executed and user can
193 add his own code by customization of function pointer HAL_FMPI2C_MemRxCpltCallback()
194 (+) In case of transfer Error, HAL_FMPI2C_ErrorCallback() function is executed and user can
195 add his own code by customization of function pointer HAL_FMPI2C_ErrorCallback()
198 *** FMPI2C HAL driver macros list ***
199 ==================================
201 Below the list of most used macros in FMPI2C HAL driver.
203 (+) __HAL_FMPI2C_ENABLE: Enable the FMPI2C peripheral
204 (+) __HAL_FMPI2C_DISABLE: Disable the FMPI2C peripheral
205 (+) __HAL_FMPI2C_GENERATE_NACK: Generate a Non-Acknowledge FMPI2C peripheral in Slave mode
206 (+) __HAL_FMPI2C_GET_FLAG: Check whether the specified FMPI2C flag is set or not
207 (+) __HAL_FMPI2C_CLEAR_FLAG: Clear the specified FMPI2C pending flag
208 (+) __HAL_FMPI2C_ENABLE_IT: Enable the specified FMPI2C interrupt
209 (+) __HAL_FMPI2C_DISABLE_IT: Disable the specified FMPI2C interrupt
212 (@) You can refer to the FMPI2C HAL driver header file for more useful macros
215 ******************************************************************************
218 * <h2><center>© COPYRIGHT(c) 2017 STMicroelectronics</center></h2>
220 * Redistribution and use in source and binary forms, with or without modification,
221 * are permitted provided that the following conditions are met:
222 * 1. Redistributions of source code must retain the above copyright notice,
223 * this list of conditions and the following disclaimer.
224 * 2. Redistributions in binary form must reproduce the above copyright notice,
225 * this list of conditions and the following disclaimer in the documentation
226 * and/or other materials provided with the distribution.
227 * 3. Neither the name of STMicroelectronics nor the names of its contributors
228 * may be used to endorse or promote products derived from this software
229 * without specific prior written permission.
231 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
232 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
233 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
234 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
235 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
236 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
237 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
238 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
239 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
240 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
242 ******************************************************************************
245 /* Includes ------------------------------------------------------------------*/
246 #include "stm32f4xx_hal.h"
248 /** @addtogroup STM32F4xx_HAL_Driver
252 /** @defgroup FMPI2C FMPI2C
253 * @brief FMPI2C HAL module driver
257 #ifdef HAL_FMPI2C_MODULE_ENABLED
259 #if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F446xx) || defined(STM32F412Zx) ||\
260 defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx)
262 /* Private typedef -----------------------------------------------------------*/
263 /* Private define ------------------------------------------------------------*/
265 /** @defgroup FMPI2C_Private_Define FMPI2C Private Define
268 #define TIMING_CLEAR_MASK 0xF0FFFFFFU /*!< FMPI2C TIMING clear register Mask */
269 #define FMPI2C_TIMEOUT_ADDR 10000U /*!< 10 s */
270 #define FMPI2C_TIMEOUT_BUSY 25U /*!< 25 ms */
271 #define FMPI2C_TIMEOUT_DIR 25U /*!< 25 ms */
272 #define FMPI2C_TIMEOUT_RXNE 25U /*!< 25 ms */
273 #define FMPI2C_TIMEOUT_STOPF 25U /*!< 25 ms */
274 #define FMPI2C_TIMEOUT_TC 25U /*!< 25 ms */
275 #define FMPI2C_TIMEOUT_TCR 25U /*!< 25 ms */
276 #define FMPI2C_TIMEOUT_TXIS 25U /*!< 25 ms */
277 #define FMPI2C_TIMEOUT_FLAG 25U /*!< 25 ms */
279 #define MAX_NBYTE_SIZE 255U
280 #define SlaveAddr_SHIFT 7U
281 #define SlaveAddr_MSK 0x06U
283 /* Private define for @ref PreviousState usage */
284 #define FMPI2C_STATE_MSK ((uint32_t)((HAL_FMPI2C_STATE_BUSY_TX | HAL_FMPI2C_STATE_BUSY_RX) & (~((uint32_t)HAL_FMPI2C_STATE_READY)))) /*!< Mask State define, keep only RX and TX bits */
285 #define FMPI2C_STATE_NONE ((uint32_t)(HAL_FMPI2C_MODE_NONE)) /*!< Default Value */
286 #define FMPI2C_STATE_MASTER_BUSY_TX ((uint32_t)((HAL_FMPI2C_STATE_BUSY_TX & FMPI2C_STATE_MSK) | HAL_FMPI2C_MODE_MASTER)) /*!< Master Busy TX, combinaison of State LSB and Mode enum */
287 #define FMPI2C_STATE_MASTER_BUSY_RX ((uint32_t)((HAL_FMPI2C_STATE_BUSY_RX & FMPI2C_STATE_MSK) | HAL_FMPI2C_MODE_MASTER)) /*!< Master Busy RX, combinaison of State LSB and Mode enum */
288 #define FMPI2C_STATE_SLAVE_BUSY_TX ((uint32_t)((HAL_FMPI2C_STATE_BUSY_TX & FMPI2C_STATE_MSK) | HAL_FMPI2C_MODE_SLAVE)) /*!< Slave Busy TX, combinaison of State LSB and Mode enum */
289 #define FMPI2C_STATE_SLAVE_BUSY_RX ((uint32_t)((HAL_FMPI2C_STATE_BUSY_RX & FMPI2C_STATE_MSK) | HAL_FMPI2C_MODE_SLAVE)) /*!< Slave Busy RX, combinaison of State LSB and Mode enum */
290 #define FMPI2C_STATE_MEM_BUSY_TX ((uint32_t)((HAL_FMPI2C_STATE_BUSY_TX & FMPI2C_STATE_MSK) | HAL_FMPI2C_MODE_MEM)) /*!< Memory Busy TX, combinaison of State LSB and Mode enum */
291 #define FMPI2C_STATE_MEM_BUSY_RX ((uint32_t)((HAL_FMPI2C_STATE_BUSY_RX & FMPI2C_STATE_MSK) | HAL_FMPI2C_MODE_MEM)) /*!< Memory Busy RX, combinaison of State LSB and Mode enum */
294 /* Private define to centralize the enable/disable of Interrupts */
295 #define FMPI2C_XFER_TX_IT 0x00000001U
296 #define FMPI2C_XFER_RX_IT 0x00000002U
297 #define FMPI2C_XFER_LISTEN_IT 0x00000004U
299 #define FMPI2C_XFER_ERROR_IT 0x00000011U
300 #define FMPI2C_XFER_CPLT_IT 0x00000012U
301 #define FMPI2C_XFER_RELOAD_IT 0x00000012U
303 /* Private define Sequential Transfer Options default/reset value */
304 #define FMPI2C_NO_OPTION_FRAME 0xFFFF0000U
309 /* Private macro -------------------------------------------------------------*/
310 #define FMPI2C_GET_DMA_REMAIN_DATA(__HANDLE__) ((((__HANDLE__)->State) == HAL_FMPI2C_STATE_BUSY_TX) ? \
311 ((uint32_t)((__HANDLE__)->hdmatx->Instance->NDTR)) : \
312 ((uint32_t)((__HANDLE__)->hdmarx->Instance->NDTR)))
314 /* Private variables ---------------------------------------------------------*/
315 /* Private function prototypes -----------------------------------------------*/
317 /** @defgroup FMPI2C_Private_Functions FMPI2C Private Functions
320 /* Private functions to handle DMA transfer */
321 static void FMPI2C_DMAMasterTransmitCplt(DMA_HandleTypeDef
*hdma
);
322 static void FMPI2C_DMAMasterReceiveCplt(DMA_HandleTypeDef
*hdma
);
323 static void FMPI2C_DMASlaveTransmitCplt(DMA_HandleTypeDef
*hdma
);
324 static void FMPI2C_DMASlaveReceiveCplt(DMA_HandleTypeDef
*hdma
);
325 static void FMPI2C_DMAError(DMA_HandleTypeDef
*hdma
);
326 static void FMPI2C_DMAAbort(DMA_HandleTypeDef
*hdma
);
328 /* Private functions to handle IT transfer */
329 static void FMPI2C_ITAddrCplt (FMPI2C_HandleTypeDef
*hfmpi2c
, uint32_t ITFlags
);
330 static void FMPI2C_ITMasterSequentialCplt (FMPI2C_HandleTypeDef
*hfmpi2c
);
331 static void FMPI2C_ITSlaveSequentialCplt (FMPI2C_HandleTypeDef
*hfmpi2c
);
332 static void FMPI2C_ITMasterCplt (FMPI2C_HandleTypeDef
*hfmpi2c
, uint32_t ITFlags
);
333 static void FMPI2C_ITSlaveCplt (FMPI2C_HandleTypeDef
*hfmpi2c
, uint32_t ITFlags
);
334 static void FMPI2C_ITListenCplt (FMPI2C_HandleTypeDef
*hfmpi2c
, uint32_t ITFlags
);
335 static void FMPI2C_ITError (FMPI2C_HandleTypeDef
*hfmpi2c
, uint32_t ITFlags
);
337 /* Private functions to handle IT transfer */
338 static HAL_StatusTypeDef
FMPI2C_RequestMemoryWrite (FMPI2C_HandleTypeDef
*hfmpi2c
, uint16_t DevAddress
, uint16_t MemAddress
, uint16_t MemAddSize
, uint32_t Timeout
, uint32_t Tickstart
);
339 static HAL_StatusTypeDef
FMPI2C_RequestMemoryRead (FMPI2C_HandleTypeDef
*hfmpi2c
, uint16_t DevAddress
, uint16_t MemAddress
, uint16_t MemAddSize
, uint32_t Timeout
, uint32_t Tickstart
);
341 /* Private functions for FMPI2C transfer IRQ handler */
342 static HAL_StatusTypeDef
FMPI2C_Master_ISR_IT(struct __FMPI2C_HandleTypeDef
*hfmpi2c
, uint32_t ITFlags
, uint32_t ITSources
);
343 static HAL_StatusTypeDef
FMPI2C_Slave_ISR_IT(struct __FMPI2C_HandleTypeDef
*hfmpi2c
, uint32_t ITFlags
, uint32_t ITSources
);
344 static HAL_StatusTypeDef
FMPI2C_Master_ISR_DMA(struct __FMPI2C_HandleTypeDef
*hfmpi2c
, uint32_t ITFlags
, uint32_t ITSources
);
345 static HAL_StatusTypeDef
FMPI2C_Slave_ISR_DMA(struct __FMPI2C_HandleTypeDef
*hfmpi2c
, uint32_t ITFlags
, uint32_t ITSources
);
347 /* Private functions to handle flags during polling transfer */
348 static HAL_StatusTypeDef
FMPI2C_WaitOnFlagUntilTimeout (FMPI2C_HandleTypeDef
*hfmpi2c
, uint32_t Flag
, FlagStatus Status
, uint32_t Timeout
, uint32_t Tickstart
);
349 static HAL_StatusTypeDef
FMPI2C_WaitOnTXISFlagUntilTimeout (FMPI2C_HandleTypeDef
*hfmpi2c
, uint32_t Timeout
, uint32_t Tickstart
);
350 static HAL_StatusTypeDef
FMPI2C_WaitOnRXNEFlagUntilTimeout (FMPI2C_HandleTypeDef
*hfmpi2c
, uint32_t Timeout
, uint32_t Tickstart
);
351 static HAL_StatusTypeDef
FMPI2C_WaitOnSTOPFlagUntilTimeout (FMPI2C_HandleTypeDef
*hfmpi2c
, uint32_t Timeout
, uint32_t Tickstart
);
352 static HAL_StatusTypeDef
FMPI2C_IsAcknowledgeFailed (FMPI2C_HandleTypeDef
*hfmpi2c
, uint32_t Timeout
, uint32_t Tickstart
);
354 /* Private functions to centralize the enable/disable of Interrupts */
355 static HAL_StatusTypeDef
FMPI2C_Enable_IRQ (FMPI2C_HandleTypeDef
*hfmpi2c
, uint16_t InterruptRequest
);
356 static HAL_StatusTypeDef
FMPI2C_Disable_IRQ (FMPI2C_HandleTypeDef
*hfmpi2c
, uint16_t InterruptRequest
);
358 /* Private functions to flush TXDR register */
359 static void FMPI2C_Flush_TXDR (FMPI2C_HandleTypeDef
*hfmpi2c
);
361 /* Private functions to handle start, restart or stop a transfer */
362 static void FMPI2C_TransferConfig (FMPI2C_HandleTypeDef
*hfmpi2c
, uint16_t DevAddress
, uint8_t Size
, uint32_t Mode
, uint32_t Request
);
367 /* Exported functions --------------------------------------------------------*/
369 /** @defgroup FMPI2C_Exported_Functions FMPI2C Exported Functions
373 /** @defgroup FMPI2C_Exported_Functions_Group1 Initialization and de-initialization functions
374 * @brief Initialization and Configuration functions
377 ===============================================================================
378 ##### Initialization and de-initialization functions #####
379 ===============================================================================
380 [..] This subsection provides a set of functions allowing to initialize and
381 deinitialize the FMPI2Cx peripheral:
383 (+) User must Implement HAL_FMPI2C_MspInit() function in which he configures
384 all related peripherals resources (CLOCK, GPIO, DMA, IT and NVIC ).
386 (+) Call the function HAL_FMPI2C_Init() to configure the selected device with
387 the selected configuration:
390 (++) Addressing mode (Master, Slave)
391 (++) Dual Addressing mode
393 (++) Own Address 2 Mask
394 (++) General call mode
397 (+) Call the function HAL_FMPI2C_DeInit() to restore the default configuration
398 of the selected FMPI2Cx peripheral.
405 * @brief Initializes the FMPI2C according to the specified parameters
406 * in the FMPI2C_InitTypeDef and initialize the associated handle.
407 * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains
408 * the configuration information for the specified FMPI2C.
411 HAL_StatusTypeDef
HAL_FMPI2C_Init(FMPI2C_HandleTypeDef
*hfmpi2c
)
413 /* Check the FMPI2C handle allocation */
419 /* Check the parameters */
420 assert_param(IS_FMPI2C_ALL_INSTANCE(hfmpi2c
->Instance
));
421 assert_param(IS_FMPI2C_OWN_ADDRESS1(hfmpi2c
->Init
.OwnAddress1
));
422 assert_param(IS_FMPI2C_ADDRESSING_MODE(hfmpi2c
->Init
.AddressingMode
));
423 assert_param(IS_FMPI2C_DUAL_ADDRESS(hfmpi2c
->Init
.DualAddressMode
));
424 assert_param(IS_FMPI2C_OWN_ADDRESS2(hfmpi2c
->Init
.OwnAddress2
));
425 assert_param(IS_FMPI2C_OWN_ADDRESS2_MASK(hfmpi2c
->Init
.OwnAddress2Masks
));
426 assert_param(IS_FMPI2C_GENERAL_CALL(hfmpi2c
->Init
.GeneralCallMode
));
427 assert_param(IS_FMPI2C_NO_STRETCH(hfmpi2c
->Init
.NoStretchMode
));
429 if(hfmpi2c
->State
== HAL_FMPI2C_STATE_RESET
)
431 /* Allocate lock resource and initialize it */
432 hfmpi2c
->Lock
= HAL_UNLOCKED
;
434 /* Init the low level hardware : GPIO, CLOCK, CORTEX...etc */
435 HAL_FMPI2C_MspInit(hfmpi2c
);
438 hfmpi2c
->State
= HAL_FMPI2C_STATE_BUSY
;
440 /* Disable the selected FMPI2C peripheral */
441 __HAL_FMPI2C_DISABLE(hfmpi2c
);
443 /*---------------------------- FMPI2Cx TIMINGR Configuration ------------------*/
444 /* Configure FMPI2Cx: Frequency range */
445 hfmpi2c
->Instance
->TIMINGR
= hfmpi2c
->Init
.Timing
& TIMING_CLEAR_MASK
;
447 /*---------------------------- FMPI2Cx OAR1 Configuration ---------------------*/
448 /* Disable Own Address1 before set the Own Address1 configuration */
449 hfmpi2c
->Instance
->OAR1
&= ~FMPI2C_OAR1_OA1EN
;
451 /* Configure FMPI2Cx: Own Address1 and ack own address1 mode */
452 if(hfmpi2c
->Init
.OwnAddress1
!= 0U)
454 if(hfmpi2c
->Init
.AddressingMode
== FMPI2C_ADDRESSINGMODE_7BIT
)
456 hfmpi2c
->Instance
->OAR1
= (FMPI2C_OAR1_OA1EN
| hfmpi2c
->Init
.OwnAddress1
);
458 else /* FMPI2C_ADDRESSINGMODE_10BIT */
460 hfmpi2c
->Instance
->OAR1
= (FMPI2C_OAR1_OA1EN
| FMPI2C_OAR1_OA1MODE
| hfmpi2c
->Init
.OwnAddress1
);
464 /*---------------------------- FMPI2Cx CR2 Configuration ----------------------*/
465 /* Configure FMPI2Cx: Addressing Master mode */
466 if(hfmpi2c
->Init
.AddressingMode
== FMPI2C_ADDRESSINGMODE_10BIT
)
468 hfmpi2c
->Instance
->CR2
= (FMPI2C_CR2_ADD10
);
470 /* Enable the AUTOEND by default, and enable NACK (should be disable only during Slave process */
471 hfmpi2c
->Instance
->CR2
|= (FMPI2C_CR2_AUTOEND
| FMPI2C_CR2_NACK
);
473 /*---------------------------- FMPI2Cx OAR2 Configuration ---------------------*/
474 /* Disable Own Address2 before set the Own Address2 configuration */
475 hfmpi2c
->Instance
->OAR2
&= ~FMPI2C_DUALADDRESS_ENABLE
;
477 /* Configure FMPI2Cx: Dual mode and Own Address2 */
478 hfmpi2c
->Instance
->OAR2
= (hfmpi2c
->Init
.DualAddressMode
| hfmpi2c
->Init
.OwnAddress2
| (hfmpi2c
->Init
.OwnAddress2Masks
<< 8));
480 /*---------------------------- FMPI2Cx CR1 Configuration ----------------------*/
481 /* Configure FMPI2Cx: Generalcall and NoStretch mode */
482 hfmpi2c
->Instance
->CR1
= (hfmpi2c
->Init
.GeneralCallMode
| hfmpi2c
->Init
.NoStretchMode
);
484 /* Enable the selected FMPI2C peripheral */
485 __HAL_FMPI2C_ENABLE(hfmpi2c
);
487 hfmpi2c
->ErrorCode
= HAL_FMPI2C_ERROR_NONE
;
488 hfmpi2c
->State
= HAL_FMPI2C_STATE_READY
;
489 hfmpi2c
->PreviousState
= FMPI2C_STATE_NONE
;
490 hfmpi2c
->Mode
= HAL_FMPI2C_MODE_NONE
;
496 * @brief DeInitialize the FMPI2C peripheral.
497 * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains
498 * the configuration information for the specified FMPI2C.
501 HAL_StatusTypeDef
HAL_FMPI2C_DeInit(FMPI2C_HandleTypeDef
*hfmpi2c
)
503 /* Check the FMPI2C handle allocation */
509 /* Check the parameters */
510 assert_param(IS_FMPI2C_ALL_INSTANCE(hfmpi2c
->Instance
));
512 hfmpi2c
->State
= HAL_FMPI2C_STATE_BUSY
;
514 /* Disable the FMPI2C Peripheral Clock */
515 __HAL_FMPI2C_DISABLE(hfmpi2c
);
517 /* DeInit the low level hardware: GPIO, CLOCK, NVIC */
518 HAL_FMPI2C_MspDeInit(hfmpi2c
);
520 hfmpi2c
->ErrorCode
= HAL_FMPI2C_ERROR_NONE
;
521 hfmpi2c
->State
= HAL_FMPI2C_STATE_RESET
;
522 hfmpi2c
->PreviousState
= FMPI2C_STATE_NONE
;
523 hfmpi2c
->Mode
= HAL_FMPI2C_MODE_NONE
;
526 __HAL_UNLOCK(hfmpi2c
);
532 * @brief Initialize the FMPI2C MSP.
533 * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains
534 * the configuration information for the specified FMPI2C.
537 __weak
void HAL_FMPI2C_MspInit(FMPI2C_HandleTypeDef
*hfmpi2c
)
539 /* Prevent unused argument(s) compilation warning */
542 /* NOTE : This function should not be modified, when the callback is needed,
543 the HAL_FMPI2C_MspInit could be implemented in the user file
548 * @brief DeInitialize the FMPI2C MSP.
549 * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains
550 * the configuration information for the specified FMPI2C.
553 __weak
void HAL_FMPI2C_MspDeInit(FMPI2C_HandleTypeDef
*hfmpi2c
)
555 /* Prevent unused argument(s) compilation warning */
558 /* NOTE : This function should not be modified, when the callback is needed,
559 the HAL_FMPI2C_MspDeInit could be implemented in the user file
567 /** @defgroup FMPI2C_Exported_Functions_Group2 Input and Output operation functions
568 * @brief Data transfers functions
571 ===============================================================================
572 ##### IO operation functions #####
573 ===============================================================================
575 This subsection provides a set of functions allowing to manage the FMPI2C data
578 (#) There are two modes of transfer:
579 (++) Blocking mode : The communication is performed in the polling mode.
580 The status of all data processing is returned by the same function
581 after finishing transfer.
582 (++) No-Blocking mode : The communication is performed using Interrupts
583 or DMA. These functions return the status of the transfer startup.
584 The end of the data processing will be indicated through the
585 dedicated FMPI2C IRQ when using Interrupt mode or the DMA IRQ when
588 (#) Blocking mode functions are :
589 (++) HAL_FMPI2C_Master_Transmit()
590 (++) HAL_FMPI2C_Master_Receive()
591 (++) HAL_FMPI2C_Slave_Transmit()
592 (++) HAL_FMPI2C_Slave_Receive()
593 (++) HAL_FMPI2C_Mem_Write()
594 (++) HAL_FMPI2C_Mem_Read()
595 (++) HAL_FMPI2C_IsDeviceReady()
597 (#) No-Blocking mode functions with Interrupt are :
598 (++) HAL_FMPI2C_Master_Transmit_IT()
599 (++) HAL_FMPI2C_Master_Receive_IT()
600 (++) HAL_FMPI2C_Slave_Transmit_IT()
601 (++) HAL_FMPI2C_Slave_Receive_IT()
602 (++) HAL_FMPI2C_Master_Sequential_Transmit_IT()
603 (++) HAL_FMPI2C_Master_Sequential_Receive_IT()
604 (++) HAL_FMPI2C_Slave_Sequential_Transmit_IT()
605 (++) HAL_FMPI2C_Slave_Sequential_Receive_IT()
606 (++) HAL_FMPI2C_Mem_Write_IT()
607 (++) HAL_FMPI2C_Mem_Read_IT()
609 (#) No-Blocking mode functions with DMA are :
610 (++) HAL_FMPI2C_Master_Transmit_DMA()
611 (++) HAL_FMPI2C_Master_Receive_DMA()
612 (++) HAL_FMPI2C_Slave_Transmit_DMA()
613 (++) HAL_FMPI2C_Slave_Receive_DMA()
614 (++) HAL_FMPI2C_Mem_Write_DMA()
615 (++) HAL_FMPI2C_Mem_Read_DMA()
617 (#) A set of Transfer Complete Callbacks are provided in non Blocking mode:
618 (++) HAL_FMPI2C_MemTxCpltCallback()
619 (++) HAL_FMPI2C_MemRxCpltCallback()
620 (++) HAL_FMPI2C_MasterTxCpltCallback()
621 (++) HAL_FMPI2C_MasterRxCpltCallback()
622 (++) HAL_FMPI2C_SlaveTxCpltCallback()
623 (++) HAL_FMPI2C_SlaveRxCpltCallback()
624 (++) HAL_FMPI2C_ErrorCallback()
625 (++) HAL_FMPI2C_AbortCpltCallback()
632 * @brief Transmits in master mode an amount of data in blocking mode.
633 * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains
634 * the configuration information for the specified FMPI2C.
635 * @param DevAddress Target device address: The device 7 bits address value
636 * in datasheet must be shift at right before call interface
637 * @param pData Pointer to data buffer
638 * @param Size Amount of data to be sent
639 * @param Timeout Timeout duration
642 HAL_StatusTypeDef
HAL_FMPI2C_Master_Transmit(FMPI2C_HandleTypeDef
*hfmpi2c
, uint16_t DevAddress
, uint8_t *pData
, uint16_t Size
, uint32_t Timeout
)
644 uint32_t tickstart
= 0U;
646 if(hfmpi2c
->State
== HAL_FMPI2C_STATE_READY
)
651 /* Init tickstart for timeout management*/
652 tickstart
= HAL_GetTick();
654 if(FMPI2C_WaitOnFlagUntilTimeout(hfmpi2c
, FMPI2C_FLAG_BUSY
, SET
, FMPI2C_TIMEOUT_BUSY
, tickstart
) != HAL_OK
)
659 hfmpi2c
->State
= HAL_FMPI2C_STATE_BUSY_TX
;
660 hfmpi2c
->Mode
= HAL_FMPI2C_MODE_MASTER
;
661 hfmpi2c
->ErrorCode
= HAL_FMPI2C_ERROR_NONE
;
663 /* Prepare transfer parameters */
664 hfmpi2c
->pBuffPtr
= pData
;
665 hfmpi2c
->XferCount
= Size
;
666 hfmpi2c
->XferISR
= NULL
;
668 /* Send Slave Address */
669 /* Set NBYTES to write and reload if hfmpi2c->XferCount > MAX_NBYTE_SIZE and generate RESTART */
670 if(hfmpi2c
->XferCount
> MAX_NBYTE_SIZE
)
672 hfmpi2c
->XferSize
= MAX_NBYTE_SIZE
;
673 FMPI2C_TransferConfig(hfmpi2c
, DevAddress
, hfmpi2c
->XferSize
, FMPI2C_RELOAD_MODE
, FMPI2C_GENERATE_START_WRITE
);
677 hfmpi2c
->XferSize
= hfmpi2c
->XferCount
;
678 FMPI2C_TransferConfig(hfmpi2c
, DevAddress
, hfmpi2c
->XferSize
, FMPI2C_AUTOEND_MODE
, FMPI2C_GENERATE_START_WRITE
);
681 while(hfmpi2c
->XferSize
> 0U)
683 /* Wait until TXIS flag is set */
684 if(FMPI2C_WaitOnTXISFlagUntilTimeout(hfmpi2c
, Timeout
, tickstart
) != HAL_OK
)
686 if(hfmpi2c
->ErrorCode
== HAL_FMPI2C_ERROR_AF
)
695 /* Write data to TXDR */
696 hfmpi2c
->Instance
->TXDR
= (*hfmpi2c
->pBuffPtr
++);
697 hfmpi2c
->XferCount
--;
700 if((hfmpi2c
->XferSize
== 0U) && (hfmpi2c
->XferCount
!=0U))
702 /* Wait until TCR flag is set */
703 if(FMPI2C_WaitOnFlagUntilTimeout(hfmpi2c
, FMPI2C_FLAG_TCR
, RESET
, Timeout
, tickstart
) != HAL_OK
)
708 if(hfmpi2c
->XferCount
> MAX_NBYTE_SIZE
)
710 hfmpi2c
->XferSize
= MAX_NBYTE_SIZE
;
711 FMPI2C_TransferConfig(hfmpi2c
, DevAddress
, hfmpi2c
->XferSize
, FMPI2C_RELOAD_MODE
, FMPI2C_NO_STARTSTOP
);
715 hfmpi2c
->XferSize
= hfmpi2c
->XferCount
;
716 FMPI2C_TransferConfig(hfmpi2c
, DevAddress
, hfmpi2c
->XferSize
, FMPI2C_AUTOEND_MODE
, FMPI2C_NO_STARTSTOP
);
721 /* No need to Check TC flag, with AUTOEND mode the stop is automatically generated */
722 /* Wait until STOPF flag is set */
723 if(FMPI2C_WaitOnSTOPFlagUntilTimeout(hfmpi2c
, Timeout
, tickstart
) != HAL_OK
)
725 if(hfmpi2c
->ErrorCode
== HAL_FMPI2C_ERROR_AF
)
735 /* Clear STOP Flag */
736 __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c
, FMPI2C_FLAG_STOPF
);
738 /* Clear Configuration Register 2 */
739 FMPI2C_RESET_CR2(hfmpi2c
);
741 hfmpi2c
->State
= HAL_FMPI2C_STATE_READY
;
742 hfmpi2c
->Mode
= HAL_FMPI2C_MODE_NONE
;
744 /* Process Unlocked */
745 __HAL_UNLOCK(hfmpi2c
);
756 * @brief Receives in master mode an amount of data in blocking mode.
757 * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains
758 * the configuration information for the specified FMPI2C.
759 * @param DevAddress Target device address: The device 7 bits address value
760 * in datasheet must be shift at right before call interface
761 * @param pData Pointer to data buffer
762 * @param Size Amount of data to be sent
763 * @param Timeout Timeout duration
766 HAL_StatusTypeDef
HAL_FMPI2C_Master_Receive(FMPI2C_HandleTypeDef
*hfmpi2c
, uint16_t DevAddress
, uint8_t *pData
, uint16_t Size
, uint32_t Timeout
)
768 uint32_t tickstart
= 0U;
770 if(hfmpi2c
->State
== HAL_FMPI2C_STATE_READY
)
775 /* Init tickstart for timeout management*/
776 tickstart
= HAL_GetTick();
778 if(FMPI2C_WaitOnFlagUntilTimeout(hfmpi2c
, FMPI2C_FLAG_BUSY
, SET
, FMPI2C_TIMEOUT_BUSY
, tickstart
) != HAL_OK
)
783 hfmpi2c
->State
= HAL_FMPI2C_STATE_BUSY_RX
;
784 hfmpi2c
->Mode
= HAL_FMPI2C_MODE_MASTER
;
785 hfmpi2c
->ErrorCode
= HAL_FMPI2C_ERROR_NONE
;
787 /* Prepare transfer parameters */
788 hfmpi2c
->pBuffPtr
= pData
;
789 hfmpi2c
->XferCount
= Size
;
790 hfmpi2c
->XferISR
= NULL
;
792 /* Send Slave Address */
793 /* Set NBYTES to write and reload if hfmpi2c->XferCount > MAX_NBYTE_SIZE and generate RESTART */
794 if(hfmpi2c
->XferCount
> MAX_NBYTE_SIZE
)
796 hfmpi2c
->XferSize
= MAX_NBYTE_SIZE
;
797 FMPI2C_TransferConfig(hfmpi2c
, DevAddress
, hfmpi2c
->XferSize
, FMPI2C_RELOAD_MODE
, FMPI2C_GENERATE_START_READ
);
801 hfmpi2c
->XferSize
= hfmpi2c
->XferCount
;
802 FMPI2C_TransferConfig(hfmpi2c
, DevAddress
, hfmpi2c
->XferSize
, FMPI2C_AUTOEND_MODE
, FMPI2C_GENERATE_START_READ
);
805 while(hfmpi2c
->XferSize
> 0U)
807 /* Wait until RXNE flag is set */
808 if(FMPI2C_WaitOnRXNEFlagUntilTimeout(hfmpi2c
, Timeout
, tickstart
) != HAL_OK
)
810 if(hfmpi2c
->ErrorCode
== HAL_FMPI2C_ERROR_AF
)
820 /* Read data from RXDR */
821 (*hfmpi2c
->pBuffPtr
++) = hfmpi2c
->Instance
->RXDR
;
823 hfmpi2c
->XferCount
--;
825 if((hfmpi2c
->XferSize
== 0U) && (hfmpi2c
->XferCount
!= 0U))
827 /* Wait until TCR flag is set */
828 if(FMPI2C_WaitOnFlagUntilTimeout(hfmpi2c
, FMPI2C_FLAG_TCR
, RESET
, Timeout
, tickstart
) != HAL_OK
)
833 if(hfmpi2c
->XferCount
> MAX_NBYTE_SIZE
)
835 hfmpi2c
->XferSize
= MAX_NBYTE_SIZE
;
836 FMPI2C_TransferConfig(hfmpi2c
, DevAddress
, hfmpi2c
->XferSize
, FMPI2C_RELOAD_MODE
, FMPI2C_NO_STARTSTOP
);
840 hfmpi2c
->XferSize
= hfmpi2c
->XferCount
;
841 FMPI2C_TransferConfig(hfmpi2c
, DevAddress
, hfmpi2c
->XferSize
, FMPI2C_AUTOEND_MODE
, FMPI2C_NO_STARTSTOP
);
846 /* No need to Check TC flag, with AUTOEND mode the stop is automatically generated */
847 /* Wait until STOPF flag is set */
848 if(FMPI2C_WaitOnSTOPFlagUntilTimeout(hfmpi2c
, Timeout
, tickstart
) != HAL_OK
)
850 if(hfmpi2c
->ErrorCode
== HAL_FMPI2C_ERROR_AF
)
860 /* Clear STOP Flag */
861 __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c
, FMPI2C_FLAG_STOPF
);
863 /* Clear Configuration Register 2 */
864 FMPI2C_RESET_CR2(hfmpi2c
);
866 hfmpi2c
->State
= HAL_FMPI2C_STATE_READY
;
867 hfmpi2c
->Mode
= HAL_FMPI2C_MODE_NONE
;
869 /* Process Unlocked */
870 __HAL_UNLOCK(hfmpi2c
);
881 * @brief Transmits in slave mode an amount of data in blocking mode.
882 * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains
883 * the configuration information for the specified FMPI2C.
884 * @param pData Pointer to data buffer
885 * @param Size Amount of data to be sent
886 * @param Timeout Timeout duration
889 HAL_StatusTypeDef
HAL_FMPI2C_Slave_Transmit(FMPI2C_HandleTypeDef
*hfmpi2c
, uint8_t *pData
, uint16_t Size
, uint32_t Timeout
)
891 uint32_t tickstart
= 0U;
893 if(hfmpi2c
->State
== HAL_FMPI2C_STATE_READY
)
895 if((pData
== NULL
) || (Size
== 0U))
902 /* Init tickstart for timeout management*/
903 tickstart
= HAL_GetTick();
905 hfmpi2c
->State
= HAL_FMPI2C_STATE_BUSY_TX
;
906 hfmpi2c
->Mode
= HAL_FMPI2C_MODE_SLAVE
;
907 hfmpi2c
->ErrorCode
= HAL_FMPI2C_ERROR_NONE
;
909 /* Prepare transfer parameters */
910 hfmpi2c
->pBuffPtr
= pData
;
911 hfmpi2c
->XferCount
= Size
;
912 hfmpi2c
->XferISR
= NULL
;
914 /* Enable Address Acknowledge */
915 hfmpi2c
->Instance
->CR2
&= ~FMPI2C_CR2_NACK
;
917 /* Wait until ADDR flag is set */
918 if(FMPI2C_WaitOnFlagUntilTimeout(hfmpi2c
, FMPI2C_FLAG_ADDR
, RESET
, Timeout
, tickstart
) != HAL_OK
)
920 /* Disable Address Acknowledge */
921 hfmpi2c
->Instance
->CR2
|= FMPI2C_CR2_NACK
;
925 /* Clear ADDR flag */
926 __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c
,FMPI2C_FLAG_ADDR
);
928 /* If 10bit addressing mode is selected */
929 if(hfmpi2c
->Init
.AddressingMode
== FMPI2C_ADDRESSINGMODE_10BIT
)
931 /* Wait until ADDR flag is set */
932 if(FMPI2C_WaitOnFlagUntilTimeout(hfmpi2c
, FMPI2C_FLAG_ADDR
, RESET
, Timeout
, tickstart
) != HAL_OK
)
934 /* Disable Address Acknowledge */
935 hfmpi2c
->Instance
->CR2
|= FMPI2C_CR2_NACK
;
939 /* Clear ADDR flag */
940 __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c
,FMPI2C_FLAG_ADDR
);
943 /* Wait until DIR flag is set Transmitter mode */
944 if(FMPI2C_WaitOnFlagUntilTimeout(hfmpi2c
, FMPI2C_FLAG_DIR
, RESET
, Timeout
, tickstart
) != HAL_OK
)
946 /* Disable Address Acknowledge */
947 hfmpi2c
->Instance
->CR2
|= FMPI2C_CR2_NACK
;
951 while(hfmpi2c
->XferCount
> 0U)
953 /* Wait until TXIS flag is set */
954 if(FMPI2C_WaitOnTXISFlagUntilTimeout(hfmpi2c
, Timeout
, tickstart
) != HAL_OK
)
956 /* Disable Address Acknowledge */
957 hfmpi2c
->Instance
->CR2
|= FMPI2C_CR2_NACK
;
959 if(hfmpi2c
->ErrorCode
== HAL_FMPI2C_ERROR_AF
)
969 /* Write data to TXDR */
970 hfmpi2c
->Instance
->TXDR
= (*hfmpi2c
->pBuffPtr
++);
971 hfmpi2c
->XferCount
--;
974 /* Wait until STOP flag is set */
975 if(FMPI2C_WaitOnSTOPFlagUntilTimeout(hfmpi2c
, Timeout
, tickstart
) != HAL_OK
)
977 /* Disable Address Acknowledge */
978 hfmpi2c
->Instance
->CR2
|= FMPI2C_CR2_NACK
;
980 if(hfmpi2c
->ErrorCode
== HAL_FMPI2C_ERROR_AF
)
982 /* Normal use case for Transmitter mode */
983 /* A NACK is generated to confirm the end of transfer */
984 hfmpi2c
->ErrorCode
= HAL_FMPI2C_ERROR_NONE
;
992 /* Clear STOP flag */
993 __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c
,FMPI2C_FLAG_STOPF
);
995 /* Wait until BUSY flag is reset */
996 if(FMPI2C_WaitOnFlagUntilTimeout(hfmpi2c
, FMPI2C_FLAG_BUSY
, SET
, Timeout
, tickstart
) != HAL_OK
)
998 /* Disable Address Acknowledge */
999 hfmpi2c
->Instance
->CR2
|= FMPI2C_CR2_NACK
;
1003 /* Disable Address Acknowledge */
1004 hfmpi2c
->Instance
->CR2
|= FMPI2C_CR2_NACK
;
1006 hfmpi2c
->State
= HAL_FMPI2C_STATE_READY
;
1007 hfmpi2c
->Mode
= HAL_FMPI2C_MODE_NONE
;
1009 /* Process Unlocked */
1010 __HAL_UNLOCK(hfmpi2c
);
1021 * @brief Receive in slave mode an amount of data in blocking mode
1022 * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains
1023 * the configuration information for the specified FMPI2C.
1024 * @param pData Pointer to data buffer
1025 * @param Size Amount of data to be sent
1026 * @param Timeout Timeout duration
1027 * @retval HAL status
1029 HAL_StatusTypeDef
HAL_FMPI2C_Slave_Receive(FMPI2C_HandleTypeDef
*hfmpi2c
, uint8_t *pData
, uint16_t Size
, uint32_t Timeout
)
1031 uint32_t tickstart
= 0U;
1033 if(hfmpi2c
->State
== HAL_FMPI2C_STATE_READY
)
1035 if((pData
== NULL
) || (Size
== 0U))
1039 /* Process Locked */
1040 __HAL_LOCK(hfmpi2c
);
1042 /* Init tickstart for timeout management*/
1043 tickstart
= HAL_GetTick();
1045 hfmpi2c
->State
= HAL_FMPI2C_STATE_BUSY_RX
;
1046 hfmpi2c
->Mode
= HAL_FMPI2C_MODE_SLAVE
;
1047 hfmpi2c
->ErrorCode
= HAL_FMPI2C_ERROR_NONE
;
1049 /* Prepare transfer parameters */
1050 hfmpi2c
->pBuffPtr
= pData
;
1051 hfmpi2c
->XferCount
= Size
;
1052 hfmpi2c
->XferISR
= NULL
;
1054 /* Enable Address Acknowledge */
1055 hfmpi2c
->Instance
->CR2
&= ~FMPI2C_CR2_NACK
;
1057 /* Wait until ADDR flag is set */
1058 if(FMPI2C_WaitOnFlagUntilTimeout(hfmpi2c
, FMPI2C_FLAG_ADDR
, RESET
, Timeout
, tickstart
) != HAL_OK
)
1060 /* Disable Address Acknowledge */
1061 hfmpi2c
->Instance
->CR2
|= FMPI2C_CR2_NACK
;
1065 /* Clear ADDR flag */
1066 __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c
,FMPI2C_FLAG_ADDR
);
1068 /* Wait until DIR flag is reset Receiver mode */
1069 if(FMPI2C_WaitOnFlagUntilTimeout(hfmpi2c
, FMPI2C_FLAG_DIR
, SET
, Timeout
, tickstart
) != HAL_OK
)
1071 /* Disable Address Acknowledge */
1072 hfmpi2c
->Instance
->CR2
|= FMPI2C_CR2_NACK
;
1076 while(hfmpi2c
->XferCount
> 0U)
1078 /* Wait until RXNE flag is set */
1079 if(FMPI2C_WaitOnRXNEFlagUntilTimeout(hfmpi2c
, Timeout
, tickstart
) != HAL_OK
)
1081 /* Disable Address Acknowledge */
1082 hfmpi2c
->Instance
->CR2
|= FMPI2C_CR2_NACK
;
1084 /* Store Last receive data if any */
1085 if(__HAL_FMPI2C_GET_FLAG(hfmpi2c
, FMPI2C_FLAG_RXNE
) == SET
)
1087 /* Read data from RXDR */
1088 (*hfmpi2c
->pBuffPtr
++) = hfmpi2c
->Instance
->RXDR
;
1089 hfmpi2c
->XferCount
--;
1092 if(hfmpi2c
->ErrorCode
== HAL_FMPI2C_ERROR_TIMEOUT
)
1102 /* Read data from RXDR */
1103 (*hfmpi2c
->pBuffPtr
++) = hfmpi2c
->Instance
->RXDR
;
1104 hfmpi2c
->XferCount
--;
1107 /* Wait until STOP flag is set */
1108 if(FMPI2C_WaitOnSTOPFlagUntilTimeout(hfmpi2c
, Timeout
, tickstart
) != HAL_OK
)
1110 /* Disable Address Acknowledge */
1111 hfmpi2c
->Instance
->CR2
|= FMPI2C_CR2_NACK
;
1113 if(hfmpi2c
->ErrorCode
== HAL_FMPI2C_ERROR_AF
)
1123 /* Clear STOP flag */
1124 __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c
,FMPI2C_FLAG_STOPF
);
1126 /* Wait until BUSY flag is reset */
1127 if(FMPI2C_WaitOnFlagUntilTimeout(hfmpi2c
, FMPI2C_FLAG_BUSY
, SET
, Timeout
, tickstart
) != HAL_OK
)
1129 /* Disable Address Acknowledge */
1130 hfmpi2c
->Instance
->CR2
|= FMPI2C_CR2_NACK
;
1134 /* Disable Address Acknowledge */
1135 hfmpi2c
->Instance
->CR2
|= FMPI2C_CR2_NACK
;
1137 hfmpi2c
->State
= HAL_FMPI2C_STATE_READY
;
1138 hfmpi2c
->Mode
= HAL_FMPI2C_MODE_NONE
;
1140 /* Process Unlocked */
1141 __HAL_UNLOCK(hfmpi2c
);
1152 * @brief Transmit in master mode an amount of data in non-blocking mode with Interrupt
1153 * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains
1154 * the configuration information for the specified FMPI2C.
1155 * @param DevAddress Target device address: The device 7 bits address value
1156 * in datasheet must be shift at right before call interface
1157 * @param pData Pointer to data buffer
1158 * @param Size Amount of data to be sent
1159 * @retval HAL status
1161 HAL_StatusTypeDef
HAL_FMPI2C_Master_Transmit_IT(FMPI2C_HandleTypeDef
*hfmpi2c
, uint16_t DevAddress
, uint8_t *pData
, uint16_t Size
)
1163 uint32_t xfermode
= 0U;
1165 if(hfmpi2c
->State
== HAL_FMPI2C_STATE_READY
)
1167 if(__HAL_FMPI2C_GET_FLAG(hfmpi2c
, FMPI2C_FLAG_BUSY
) == SET
)
1172 /* Process Locked */
1173 __HAL_LOCK(hfmpi2c
);
1175 hfmpi2c
->State
= HAL_FMPI2C_STATE_BUSY_TX
;
1176 hfmpi2c
->Mode
= HAL_FMPI2C_MODE_MASTER
;
1177 hfmpi2c
->ErrorCode
= HAL_FMPI2C_ERROR_NONE
;
1179 /* Prepare transfer parameters */
1180 hfmpi2c
->pBuffPtr
= pData
;
1181 hfmpi2c
->XferCount
= Size
;
1182 hfmpi2c
->XferOptions
= FMPI2C_NO_OPTION_FRAME
;
1183 hfmpi2c
->XferISR
= FMPI2C_Master_ISR_IT
;
1185 if(hfmpi2c
->XferCount
> MAX_NBYTE_SIZE
)
1187 hfmpi2c
->XferSize
= MAX_NBYTE_SIZE
;
1188 xfermode
= FMPI2C_RELOAD_MODE
;
1192 hfmpi2c
->XferSize
= hfmpi2c
->XferCount
;
1193 xfermode
= FMPI2C_AUTOEND_MODE
;
1196 /* Send Slave Address */
1197 /* Set NBYTES to write and reload if hfmpi2c->XferCount > MAX_NBYTE_SIZE */
1198 FMPI2C_TransferConfig(hfmpi2c
, DevAddress
, hfmpi2c
->XferSize
, xfermode
, FMPI2C_GENERATE_START_WRITE
);
1200 /* Process Unlocked */
1201 __HAL_UNLOCK(hfmpi2c
);
1203 /* Note : The FMPI2C interrupts must be enabled after unlocking current process
1204 to avoid the risk of FMPI2C interrupt handle execution before current
1207 /* Enable ERR, TC, STOP, NACK, TXI interrupt */
1208 /* possible to enable all of these */
1209 /* FMPI2C_IT_ERRI | FMPI2C_IT_TCI| FMPI2C_IT_STOPI| FMPI2C_IT_NACKI | FMPI2C_IT_ADDRI | FMPI2C_IT_RXI | FMPI2C_IT_TXI */
1210 FMPI2C_Enable_IRQ(hfmpi2c
, FMPI2C_XFER_TX_IT
);
1221 * @brief Receive in master mode an amount of data in non-blocking mode with Interrupt
1222 * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains
1223 * the configuration information for the specified FMPI2C.
1224 * @param DevAddress Target device address: The device 7 bits address value
1225 * in datasheet must be shift at right before call interface
1226 * @param pData Pointer to data buffer
1227 * @param Size Amount of data to be sent
1228 * @retval HAL status
1230 HAL_StatusTypeDef
HAL_FMPI2C_Master_Receive_IT(FMPI2C_HandleTypeDef
*hfmpi2c
, uint16_t DevAddress
, uint8_t *pData
, uint16_t Size
)
1232 uint32_t xfermode
= 0U;
1234 if(hfmpi2c
->State
== HAL_FMPI2C_STATE_READY
)
1236 if(__HAL_FMPI2C_GET_FLAG(hfmpi2c
, FMPI2C_FLAG_BUSY
) == SET
)
1241 /* Process Locked */
1242 __HAL_LOCK(hfmpi2c
);
1244 hfmpi2c
->State
= HAL_FMPI2C_STATE_BUSY_RX
;
1245 hfmpi2c
->Mode
= HAL_FMPI2C_MODE_MASTER
;
1246 hfmpi2c
->ErrorCode
= HAL_FMPI2C_ERROR_NONE
;
1248 /* Prepare transfer parameters */
1249 hfmpi2c
->pBuffPtr
= pData
;
1250 hfmpi2c
->XferCount
= Size
;
1251 hfmpi2c
->XferOptions
= FMPI2C_NO_OPTION_FRAME
;
1252 hfmpi2c
->XferISR
= FMPI2C_Master_ISR_IT
;
1254 if(hfmpi2c
->XferCount
> MAX_NBYTE_SIZE
)
1256 hfmpi2c
->XferSize
= MAX_NBYTE_SIZE
;
1257 xfermode
= FMPI2C_RELOAD_MODE
;
1261 hfmpi2c
->XferSize
= hfmpi2c
->XferCount
;
1262 xfermode
= FMPI2C_AUTOEND_MODE
;
1265 /* Send Slave Address */
1266 /* Set NBYTES to write and reload if hfmpi2c->XferCount > MAX_NBYTE_SIZE */
1267 FMPI2C_TransferConfig(hfmpi2c
, DevAddress
, hfmpi2c
->XferSize
, xfermode
, FMPI2C_GENERATE_START_READ
);
1269 /* Process Unlocked */
1270 __HAL_UNLOCK(hfmpi2c
);
1272 /* Note : The FMPI2C interrupts must be enabled after unlocking current process
1273 to avoid the risk of FMPI2C interrupt handle execution before current
1276 /* Enable ERR, TC, STOP, NACK, RXI interrupt */
1277 /* possible to enable all of these */
1278 /* FMPI2C_IT_ERRI | FMPI2C_IT_TCI| FMPI2C_IT_STOPI| FMPI2C_IT_NACKI | FMPI2C_IT_ADDRI | FMPI2C_IT_RXI | FMPI2C_IT_TXI */
1279 FMPI2C_Enable_IRQ(hfmpi2c
, FMPI2C_XFER_RX_IT
);
1290 * @brief Transmit in slave mode an amount of data in non-blocking mode with Interrupt
1291 * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains
1292 * the configuration information for the specified FMPI2C.
1293 * @param pData Pointer to data buffer
1294 * @param Size Amount of data to be sent
1295 * @retval HAL status
1297 HAL_StatusTypeDef
HAL_FMPI2C_Slave_Transmit_IT(FMPI2C_HandleTypeDef
*hfmpi2c
, uint8_t *pData
, uint16_t Size
)
1299 if(hfmpi2c
->State
== HAL_FMPI2C_STATE_READY
)
1301 /* Process Locked */
1302 __HAL_LOCK(hfmpi2c
);
1304 hfmpi2c
->State
= HAL_FMPI2C_STATE_BUSY_TX
;
1305 hfmpi2c
->Mode
= HAL_FMPI2C_MODE_SLAVE
;
1306 hfmpi2c
->ErrorCode
= HAL_FMPI2C_ERROR_NONE
;
1308 /* Enable Address Acknowledge */
1309 hfmpi2c
->Instance
->CR2
&= ~FMPI2C_CR2_NACK
;
1311 /* Prepare transfer parameters */
1312 hfmpi2c
->pBuffPtr
= pData
;
1313 hfmpi2c
->XferCount
= Size
;
1314 hfmpi2c
->XferSize
= hfmpi2c
->XferCount
;
1315 hfmpi2c
->XferOptions
= FMPI2C_NO_OPTION_FRAME
;
1316 hfmpi2c
->XferISR
= FMPI2C_Slave_ISR_IT
;
1318 /* Process Unlocked */
1319 __HAL_UNLOCK(hfmpi2c
);
1321 /* Note : The FMPI2C interrupts must be enabled after unlocking current process
1322 to avoid the risk of FMPI2C interrupt handle execution before current
1325 /* Enable ERR, TC, STOP, NACK, TXI interrupt */
1326 /* possible to enable all of these */
1327 /* FMPI2C_IT_ERRI | FMPI2C_IT_TCI| FMPI2C_IT_STOPI| FMPI2C_IT_NACKI | FMPI2C_IT_ADDRI | FMPI2C_IT_RXI | FMPI2C_IT_TXI */
1328 FMPI2C_Enable_IRQ(hfmpi2c
, FMPI2C_XFER_TX_IT
| FMPI2C_XFER_LISTEN_IT
);
1339 * @brief Receive in slave mode an amount of data in non-blocking mode with Interrupt
1340 * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains
1341 * the configuration information for the specified FMPI2C.
1342 * @param pData Pointer to data buffer
1343 * @param Size Amount of data to be sent
1344 * @retval HAL status
1346 HAL_StatusTypeDef
HAL_FMPI2C_Slave_Receive_IT(FMPI2C_HandleTypeDef
*hfmpi2c
, uint8_t *pData
, uint16_t Size
)
1348 if(hfmpi2c
->State
== HAL_FMPI2C_STATE_READY
)
1350 /* Process Locked */
1351 __HAL_LOCK(hfmpi2c
);
1353 hfmpi2c
->State
= HAL_FMPI2C_STATE_BUSY_RX
;
1354 hfmpi2c
->Mode
= HAL_FMPI2C_MODE_SLAVE
;
1355 hfmpi2c
->ErrorCode
= HAL_FMPI2C_ERROR_NONE
;
1357 /* Enable Address Acknowledge */
1358 hfmpi2c
->Instance
->CR2
&= ~FMPI2C_CR2_NACK
;
1360 /* Prepare transfer parameters */
1361 hfmpi2c
->pBuffPtr
= pData
;
1362 hfmpi2c
->XferCount
= Size
;
1363 hfmpi2c
->XferSize
= hfmpi2c
->XferCount
;
1364 hfmpi2c
->XferOptions
= FMPI2C_NO_OPTION_FRAME
;
1365 hfmpi2c
->XferISR
= FMPI2C_Slave_ISR_IT
;
1367 /* Process Unlocked */
1368 __HAL_UNLOCK(hfmpi2c
);
1370 /* Note : The FMPI2C interrupts must be enabled after unlocking current process
1371 to avoid the risk of FMPI2C interrupt handle execution before current
1374 /* Enable ERR, TC, STOP, NACK, RXI interrupt */
1375 /* possible to enable all of these */
1376 /* FMPI2C_IT_ERRI | FMPI2C_IT_TCI| FMPI2C_IT_STOPI| FMPI2C_IT_NACKI | FMPI2C_IT_ADDRI | FMPI2C_IT_RXI | FMPI2C_IT_TXI */
1377 FMPI2C_Enable_IRQ(hfmpi2c
, FMPI2C_XFER_RX_IT
| FMPI2C_XFER_LISTEN_IT
);
1388 * @brief Transmit in master mode an amount of data in non-blocking mode with DMA
1389 * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains
1390 * the configuration information for the specified FMPI2C.
1391 * @param DevAddress Target device address: The device 7 bits address value
1392 * in datasheet must be shift at right before call interface
1393 * @param pData Pointer to data buffer
1394 * @param Size Amount of data to be sent
1395 * @retval HAL status
1397 HAL_StatusTypeDef
HAL_FMPI2C_Master_Transmit_DMA(FMPI2C_HandleTypeDef
*hfmpi2c
, uint16_t DevAddress
, uint8_t *pData
, uint16_t Size
)
1399 uint32_t xfermode
= 0U;
1401 if(hfmpi2c
->State
== HAL_FMPI2C_STATE_READY
)
1403 if(__HAL_FMPI2C_GET_FLAG(hfmpi2c
, FMPI2C_FLAG_BUSY
) == SET
)
1408 /* Process Locked */
1409 __HAL_LOCK(hfmpi2c
);
1411 hfmpi2c
->State
= HAL_FMPI2C_STATE_BUSY_TX
;
1412 hfmpi2c
->Mode
= HAL_FMPI2C_MODE_MASTER
;
1413 hfmpi2c
->ErrorCode
= HAL_FMPI2C_ERROR_NONE
;
1415 /* Prepare transfer parameters */
1416 hfmpi2c
->pBuffPtr
= pData
;
1417 hfmpi2c
->XferCount
= Size
;
1418 hfmpi2c
->XferOptions
= FMPI2C_NO_OPTION_FRAME
;
1419 hfmpi2c
->XferISR
= FMPI2C_Master_ISR_DMA
;
1421 if(hfmpi2c
->XferCount
> MAX_NBYTE_SIZE
)
1423 hfmpi2c
->XferSize
= MAX_NBYTE_SIZE
;
1424 xfermode
= FMPI2C_RELOAD_MODE
;
1428 hfmpi2c
->XferSize
= hfmpi2c
->XferCount
;
1429 xfermode
= FMPI2C_AUTOEND_MODE
;
1432 /* Set the FMPI2C DMA transfer complete callback */
1433 hfmpi2c
->hdmatx
->XferCpltCallback
= FMPI2C_DMAMasterTransmitCplt
;
1435 /* Set the DMA error callback */
1436 hfmpi2c
->hdmatx
->XferErrorCallback
= FMPI2C_DMAError
;
1438 /* Set the unused DMA callbacks to NULL */
1439 hfmpi2c
->hdmatx
->XferHalfCpltCallback
= NULL
;
1440 hfmpi2c
->hdmatx
->XferAbortCallback
= NULL
;
1442 /* Enable the DMA channel */
1443 HAL_DMA_Start_IT(hfmpi2c
->hdmatx
, (uint32_t)pData
, (uint32_t)&hfmpi2c
->Instance
->TXDR
, hfmpi2c
->XferSize
);
1445 /* Send Slave Address */
1446 /* Set NBYTES to write and reload if hfmpi2c->XferCount > MAX_NBYTE_SIZE and generate RESTART */
1447 FMPI2C_TransferConfig(hfmpi2c
, DevAddress
, hfmpi2c
->XferSize
, xfermode
, FMPI2C_GENERATE_START_WRITE
);
1449 /* Update XferCount value */
1450 hfmpi2c
->XferCount
-= hfmpi2c
->XferSize
;
1452 /* Process Unlocked */
1453 __HAL_UNLOCK(hfmpi2c
);
1455 /* Note : The FMPI2C interrupts must be enabled after unlocking current process
1456 to avoid the risk of FMPI2C interrupt handle execution before current
1458 /* Enable ERR and NACK interrupts */
1459 FMPI2C_Enable_IRQ(hfmpi2c
, FMPI2C_XFER_ERROR_IT
);
1461 /* Enable DMA Request */
1462 hfmpi2c
->Instance
->CR1
|= FMPI2C_CR1_TXDMAEN
;
1473 * @brief Receive in master mode an amount of data in non-blocking mode with DMA
1474 * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains
1475 * the configuration information for the specified FMPI2C.
1476 * @param DevAddress Target device address: The device 7 bits address value
1477 * in datasheet must be shift at right before call interface
1478 * @param pData Pointer to data buffer
1479 * @param Size Amount of data to be sent
1480 * @retval HAL status
1482 HAL_StatusTypeDef
HAL_FMPI2C_Master_Receive_DMA(FMPI2C_HandleTypeDef
*hfmpi2c
, uint16_t DevAddress
, uint8_t *pData
, uint16_t Size
)
1484 uint32_t xfermode
= 0U;
1486 if(hfmpi2c
->State
== HAL_FMPI2C_STATE_READY
)
1488 if(__HAL_FMPI2C_GET_FLAG(hfmpi2c
, FMPI2C_FLAG_BUSY
) == SET
)
1493 /* Process Locked */
1494 __HAL_LOCK(hfmpi2c
);
1496 hfmpi2c
->State
= HAL_FMPI2C_STATE_BUSY_RX
;
1497 hfmpi2c
->Mode
= HAL_FMPI2C_MODE_MASTER
;
1498 hfmpi2c
->ErrorCode
= HAL_FMPI2C_ERROR_NONE
;
1500 /* Prepare transfer parameters */
1501 hfmpi2c
->pBuffPtr
= pData
;
1502 hfmpi2c
->XferCount
= Size
;
1503 hfmpi2c
->XferOptions
= FMPI2C_NO_OPTION_FRAME
;
1504 hfmpi2c
->XferISR
= FMPI2C_Master_ISR_DMA
;
1506 if(hfmpi2c
->XferCount
> MAX_NBYTE_SIZE
)
1508 hfmpi2c
->XferSize
= MAX_NBYTE_SIZE
;
1509 xfermode
= FMPI2C_RELOAD_MODE
;
1513 hfmpi2c
->XferSize
= hfmpi2c
->XferCount
;
1514 xfermode
= FMPI2C_AUTOEND_MODE
;
1517 if(hfmpi2c
->XferSize
> 0U)
1519 /* Set the FMPI2C DMA transfer complete callback */
1520 hfmpi2c
->hdmarx
->XferCpltCallback
= FMPI2C_DMAMasterReceiveCplt
;
1522 /* Set the DMA error callback */
1523 hfmpi2c
->hdmarx
->XferErrorCallback
= FMPI2C_DMAError
;
1525 /* Set the unused DMA callbacks to NULL */
1526 hfmpi2c
->hdmarx
->XferHalfCpltCallback
= NULL
;
1527 hfmpi2c
->hdmarx
->XferAbortCallback
= NULL
;
1529 /* Enable the DMA channel */
1530 HAL_DMA_Start_IT(hfmpi2c
->hdmarx
, (uint32_t)&hfmpi2c
->Instance
->RXDR
, (uint32_t)pData
, hfmpi2c
->XferSize
);
1532 /* Send Slave Address */
1533 /* Set NBYTES to write and reload if hfmpi2c->XferCount > MAX_NBYTE_SIZE and generate RESTART */
1534 FMPI2C_TransferConfig(hfmpi2c
,DevAddress
,hfmpi2c
->XferSize
, xfermode
, FMPI2C_GENERATE_START_READ
);
1536 /* Update XferCount value */
1537 hfmpi2c
->XferCount
-= hfmpi2c
->XferSize
;
1539 /* Process Unlocked */
1540 __HAL_UNLOCK(hfmpi2c
);
1542 /* Note : The FMPI2C interrupts must be enabled after unlocking current process
1543 to avoid the risk of FMPI2C interrupt handle execution before current
1545 /* Enable ERR and NACK interrupts */
1546 FMPI2C_Enable_IRQ(hfmpi2c
, FMPI2C_XFER_ERROR_IT
);
1548 /* Enable DMA Request */
1549 hfmpi2c
->Instance
->CR1
|= FMPI2C_CR1_RXDMAEN
;
1553 hfmpi2c
->State
= HAL_FMPI2C_STATE_READY
;
1554 hfmpi2c
->Mode
= HAL_FMPI2C_MODE_NONE
;
1556 /* Process Unlocked */
1557 __HAL_UNLOCK(hfmpi2c
);
1568 * @brief Transmit in slave mode an amount of data in non-blocking mode with DMA
1569 * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains
1570 * the configuration information for the specified FMPI2C.
1571 * @param pData Pointer to data buffer
1572 * @param Size Amount of data to be sent
1573 * @retval HAL status
1575 HAL_StatusTypeDef
HAL_FMPI2C_Slave_Transmit_DMA(FMPI2C_HandleTypeDef
*hfmpi2c
, uint8_t *pData
, uint16_t Size
)
1577 if(hfmpi2c
->State
== HAL_FMPI2C_STATE_READY
)
1579 if((pData
== NULL
) || (Size
== 0))
1583 /* Process Locked */
1584 __HAL_LOCK(hfmpi2c
);
1586 hfmpi2c
->State
= HAL_FMPI2C_STATE_BUSY_TX
;
1587 hfmpi2c
->Mode
= HAL_FMPI2C_MODE_SLAVE
;
1588 hfmpi2c
->ErrorCode
= HAL_FMPI2C_ERROR_NONE
;
1590 /* Prepare transfer parameters */
1591 hfmpi2c
->pBuffPtr
= pData
;
1592 hfmpi2c
->XferCount
= Size
;
1593 hfmpi2c
->XferSize
= hfmpi2c
->XferCount
;
1594 hfmpi2c
->XferOptions
= FMPI2C_NO_OPTION_FRAME
;
1595 hfmpi2c
->XferISR
= FMPI2C_Slave_ISR_DMA
;
1597 /* Set the FMPI2C DMA transfer complete callback */
1598 hfmpi2c
->hdmatx
->XferCpltCallback
= FMPI2C_DMASlaveTransmitCplt
;
1600 /* Set the DMA error callback */
1601 hfmpi2c
->hdmatx
->XferErrorCallback
= FMPI2C_DMAError
;
1603 /* Set the unused DMA callbacks to NULL */
1604 hfmpi2c
->hdmatx
->XferHalfCpltCallback
= NULL
;
1605 hfmpi2c
->hdmatx
->XferAbortCallback
= NULL
;
1607 /* Enable the DMA channel */
1608 HAL_DMA_Start_IT(hfmpi2c
->hdmatx
, (uint32_t)pData
, (uint32_t)&hfmpi2c
->Instance
->TXDR
, hfmpi2c
->XferSize
);
1610 /* Enable Address Acknowledge */
1611 hfmpi2c
->Instance
->CR2
&= ~FMPI2C_CR2_NACK
;
1613 /* Process Unlocked */
1614 __HAL_UNLOCK(hfmpi2c
);
1616 /* Note : The FMPI2C interrupts must be enabled after unlocking current process
1617 to avoid the risk of FMPI2C interrupt handle execution before current
1619 /* Enable ERR, STOP, NACK, ADDR interrupts */
1620 FMPI2C_Enable_IRQ(hfmpi2c
, FMPI2C_XFER_LISTEN_IT
);
1622 /* Enable DMA Request */
1623 hfmpi2c
->Instance
->CR1
|= FMPI2C_CR1_TXDMAEN
;
1634 * @brief Receive in slave mode an amount of data in non-blocking mode with DMA
1635 * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains
1636 * the configuration information for the specified FMPI2C.
1637 * @param pData Pointer to data buffer
1638 * @param Size Amount of data to be sent
1639 * @retval HAL status
1641 HAL_StatusTypeDef
HAL_FMPI2C_Slave_Receive_DMA(FMPI2C_HandleTypeDef
*hfmpi2c
, uint8_t *pData
, uint16_t Size
)
1643 if(hfmpi2c
->State
== HAL_FMPI2C_STATE_READY
)
1645 if((pData
== NULL
) || (Size
== 0))
1649 /* Process Locked */
1650 __HAL_LOCK(hfmpi2c
);
1652 hfmpi2c
->State
= HAL_FMPI2C_STATE_BUSY_RX
;
1653 hfmpi2c
->Mode
= HAL_FMPI2C_MODE_SLAVE
;
1654 hfmpi2c
->ErrorCode
= HAL_FMPI2C_ERROR_NONE
;
1656 /* Prepare transfer parameters */
1657 hfmpi2c
->pBuffPtr
= pData
;
1658 hfmpi2c
->XferCount
= Size
;
1659 hfmpi2c
->XferSize
= hfmpi2c
->XferCount
;
1660 hfmpi2c
->XferOptions
= FMPI2C_NO_OPTION_FRAME
;
1661 hfmpi2c
->XferISR
= FMPI2C_Slave_ISR_DMA
;
1663 /* Set the FMPI2C DMA transfer complete callback */
1664 hfmpi2c
->hdmarx
->XferCpltCallback
= FMPI2C_DMASlaveReceiveCplt
;
1666 /* Set the DMA error callback */
1667 hfmpi2c
->hdmarx
->XferErrorCallback
= FMPI2C_DMAError
;
1669 /* Set the unused DMA callbacks to NULL */
1670 hfmpi2c
->hdmarx
->XferHalfCpltCallback
= NULL
;
1671 hfmpi2c
->hdmarx
->XferAbortCallback
= NULL
;
1673 /* Enable the DMA channel */
1674 HAL_DMA_Start_IT(hfmpi2c
->hdmarx
, (uint32_t)&hfmpi2c
->Instance
->RXDR
, (uint32_t)pData
, hfmpi2c
->XferSize
);
1676 /* Enable Address Acknowledge */
1677 hfmpi2c
->Instance
->CR2
&= ~FMPI2C_CR2_NACK
;
1679 /* Process Unlocked */
1680 __HAL_UNLOCK(hfmpi2c
);
1682 /* Note : The FMPI2C interrupts must be enabled after unlocking current process
1683 to avoid the risk of FMPI2C interrupt handle execution before current
1685 /* Enable ERR, STOP, NACK, ADDR interrupts */
1686 FMPI2C_Enable_IRQ(hfmpi2c
, FMPI2C_XFER_LISTEN_IT
);
1688 /* Enable DMA Request */
1689 hfmpi2c
->Instance
->CR1
|= FMPI2C_CR1_RXDMAEN
;
1699 * @brief Write an amount of data in blocking mode to a specific memory address
1700 * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains
1701 * the configuration information for the specified FMPI2C.
1702 * @param DevAddress Target device address
1703 * @param MemAddress Internal memory address
1704 * @param MemAddSize Size of internal memory address
1705 * @param pData Pointer to data buffer
1706 * @param Size Amount of data to be sent
1707 * @param Timeout Timeout duration
1708 * @retval HAL status
1710 HAL_StatusTypeDef
HAL_FMPI2C_Mem_Write(FMPI2C_HandleTypeDef
*hfmpi2c
, uint16_t DevAddress
, uint16_t MemAddress
, uint16_t MemAddSize
, uint8_t *pData
, uint16_t Size
, uint32_t Timeout
)
1712 uint32_t tickstart
= 0U;
1714 /* Check the parameters */
1715 assert_param(IS_FMPI2C_MEMADD_SIZE(MemAddSize
));
1717 if(hfmpi2c
->State
== HAL_FMPI2C_STATE_READY
)
1719 if((pData
== NULL
) || (Size
== 0))
1724 /* Process Locked */
1725 __HAL_LOCK(hfmpi2c
);
1727 /* Init tickstart for timeout management*/
1728 tickstart
= HAL_GetTick();
1730 if(FMPI2C_WaitOnFlagUntilTimeout(hfmpi2c
, FMPI2C_FLAG_BUSY
, SET
, FMPI2C_TIMEOUT_BUSY
, tickstart
) != HAL_OK
)
1735 hfmpi2c
->State
= HAL_FMPI2C_STATE_BUSY_TX
;
1736 hfmpi2c
->Mode
= HAL_FMPI2C_MODE_MEM
;
1737 hfmpi2c
->ErrorCode
= HAL_FMPI2C_ERROR_NONE
;
1739 /* Prepare transfer parameters */
1740 hfmpi2c
->pBuffPtr
= pData
;
1741 hfmpi2c
->XferCount
= Size
;
1742 hfmpi2c
->XferISR
= NULL
;
1744 /* Send Slave Address and Memory Address */
1745 if(FMPI2C_RequestMemoryWrite(hfmpi2c
, DevAddress
, MemAddress
, MemAddSize
, Timeout
, tickstart
) != HAL_OK
)
1747 if(hfmpi2c
->ErrorCode
== HAL_FMPI2C_ERROR_AF
)
1749 /* Process Unlocked */
1750 __HAL_UNLOCK(hfmpi2c
);
1755 /* Process Unlocked */
1756 __HAL_UNLOCK(hfmpi2c
);
1761 /* Set NBYTES to write and reload if hfmpi2c->XferCount > MAX_NBYTE_SIZE */
1762 if(hfmpi2c
->XferCount
> MAX_NBYTE_SIZE
)
1764 hfmpi2c
->XferSize
= MAX_NBYTE_SIZE
;
1765 FMPI2C_TransferConfig(hfmpi2c
, DevAddress
, hfmpi2c
->XferSize
, FMPI2C_RELOAD_MODE
, FMPI2C_NO_STARTSTOP
);
1769 hfmpi2c
->XferSize
= hfmpi2c
->XferCount
;
1770 FMPI2C_TransferConfig(hfmpi2c
, DevAddress
, hfmpi2c
->XferSize
, FMPI2C_AUTOEND_MODE
, FMPI2C_NO_STARTSTOP
);
1775 /* Wait until TXIS flag is set */
1776 if(FMPI2C_WaitOnTXISFlagUntilTimeout(hfmpi2c
, Timeout
, tickstart
) != HAL_OK
)
1778 if(hfmpi2c
->ErrorCode
== HAL_FMPI2C_ERROR_AF
)
1788 /* Write data to TXDR */
1789 hfmpi2c
->Instance
->TXDR
= (*hfmpi2c
->pBuffPtr
++);
1790 hfmpi2c
->XferCount
--;
1791 hfmpi2c
->XferSize
--;
1793 if((hfmpi2c
->XferSize
== 0U) && (hfmpi2c
->XferCount
!=0U))
1795 /* Wait until TCR flag is set */
1796 if(FMPI2C_WaitOnFlagUntilTimeout(hfmpi2c
, FMPI2C_FLAG_TCR
, RESET
, Timeout
, tickstart
) != HAL_OK
)
1801 if(hfmpi2c
->XferCount
> MAX_NBYTE_SIZE
)
1803 hfmpi2c
->XferSize
= MAX_NBYTE_SIZE
;
1804 FMPI2C_TransferConfig(hfmpi2c
, DevAddress
, hfmpi2c
->XferSize
, FMPI2C_RELOAD_MODE
, FMPI2C_NO_STARTSTOP
);
1808 hfmpi2c
->XferSize
= hfmpi2c
->XferCount
;
1809 FMPI2C_TransferConfig(hfmpi2c
, DevAddress
, hfmpi2c
->XferSize
, FMPI2C_AUTOEND_MODE
, FMPI2C_NO_STARTSTOP
);
1813 }while(hfmpi2c
->XferCount
> 0U);
1815 /* No need to Check TC flag, with AUTOEND mode the stop is automatically generated */
1816 /* Wait until STOPF flag is reset */
1817 if(FMPI2C_WaitOnSTOPFlagUntilTimeout(hfmpi2c
, Timeout
, tickstart
) != HAL_OK
)
1819 if(hfmpi2c
->ErrorCode
== HAL_FMPI2C_ERROR_AF
)
1829 /* Clear STOP Flag */
1830 __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c
, FMPI2C_FLAG_STOPF
);
1832 /* Clear Configuration Register 2 */
1833 FMPI2C_RESET_CR2(hfmpi2c
);
1835 hfmpi2c
->State
= HAL_FMPI2C_STATE_READY
;
1836 hfmpi2c
->Mode
= HAL_FMPI2C_MODE_NONE
;
1838 /* Process Unlocked */
1839 __HAL_UNLOCK(hfmpi2c
);
1850 * @brief Read an amount of data in blocking mode from a specific memory address
1851 * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains
1852 * the configuration information for the specified FMPI2C.
1853 * @param DevAddress Target device address
1854 * @param MemAddress Internal memory address
1855 * @param MemAddSize Size of internal memory address
1856 * @param pData Pointer to data buffer
1857 * @param Size Amount of data to be sent
1858 * @param Timeout Timeout duration
1859 * @retval HAL status
1861 HAL_StatusTypeDef
HAL_FMPI2C_Mem_Read(FMPI2C_HandleTypeDef
*hfmpi2c
, uint16_t DevAddress
, uint16_t MemAddress
, uint16_t MemAddSize
, uint8_t *pData
, uint16_t Size
, uint32_t Timeout
)
1863 uint32_t tickstart
= 0U;
1865 /* Check the parameters */
1866 assert_param(IS_FMPI2C_MEMADD_SIZE(MemAddSize
));
1868 if(hfmpi2c
->State
== HAL_FMPI2C_STATE_READY
)
1870 if((pData
== NULL
) || (Size
== 0))
1875 /* Process Locked */
1876 __HAL_LOCK(hfmpi2c
);
1878 /* Init tickstart for timeout management*/
1879 tickstart
= HAL_GetTick();
1881 if(FMPI2C_WaitOnFlagUntilTimeout(hfmpi2c
, FMPI2C_FLAG_BUSY
, SET
, FMPI2C_TIMEOUT_BUSY
, tickstart
) != HAL_OK
)
1886 hfmpi2c
->State
= HAL_FMPI2C_STATE_BUSY_RX
;
1887 hfmpi2c
->Mode
= HAL_FMPI2C_MODE_MEM
;
1888 hfmpi2c
->ErrorCode
= HAL_FMPI2C_ERROR_NONE
;
1890 /* Prepare transfer parameters */
1891 hfmpi2c
->pBuffPtr
= pData
;
1892 hfmpi2c
->XferCount
= Size
;
1893 hfmpi2c
->XferISR
= NULL
;
1895 /* Send Slave Address and Memory Address */
1896 if(FMPI2C_RequestMemoryRead(hfmpi2c
, DevAddress
, MemAddress
, MemAddSize
, Timeout
, tickstart
) != HAL_OK
)
1898 if(hfmpi2c
->ErrorCode
== HAL_FMPI2C_ERROR_AF
)
1900 /* Process Unlocked */
1901 __HAL_UNLOCK(hfmpi2c
);
1906 /* Process Unlocked */
1907 __HAL_UNLOCK(hfmpi2c
);
1912 /* Send Slave Address */
1913 /* Set NBYTES to write and reload if hfmpi2c->XferCount > MAX_NBYTE_SIZE and generate RESTART */
1914 if(hfmpi2c
->XferCount
> MAX_NBYTE_SIZE
)
1916 hfmpi2c
->XferSize
= MAX_NBYTE_SIZE
;
1917 FMPI2C_TransferConfig(hfmpi2c
, DevAddress
, hfmpi2c
->XferSize
, FMPI2C_RELOAD_MODE
, FMPI2C_GENERATE_START_READ
);
1921 hfmpi2c
->XferSize
= hfmpi2c
->XferCount
;
1922 FMPI2C_TransferConfig(hfmpi2c
, DevAddress
, hfmpi2c
->XferSize
, FMPI2C_AUTOEND_MODE
, FMPI2C_GENERATE_START_READ
);
1927 /* Wait until RXNE flag is set */
1928 if(FMPI2C_WaitOnFlagUntilTimeout(hfmpi2c
, FMPI2C_FLAG_RXNE
, RESET
, Timeout
, tickstart
) != HAL_OK
)
1933 /* Read data from RXDR */
1934 (*hfmpi2c
->pBuffPtr
++) = hfmpi2c
->Instance
->RXDR
;
1935 hfmpi2c
->XferSize
--;
1936 hfmpi2c
->XferCount
--;
1938 if((hfmpi2c
->XferSize
== 0U) && (hfmpi2c
->XferCount
!= 0U))
1940 /* Wait until TCR flag is set */
1941 if(FMPI2C_WaitOnFlagUntilTimeout(hfmpi2c
, FMPI2C_FLAG_TCR
, RESET
, Timeout
, tickstart
) != HAL_OK
)
1946 if(hfmpi2c
->XferCount
> MAX_NBYTE_SIZE
)
1948 hfmpi2c
->XferSize
= MAX_NBYTE_SIZE
;
1949 FMPI2C_TransferConfig(hfmpi2c
, DevAddress
, hfmpi2c
->XferSize
, FMPI2C_RELOAD_MODE
, FMPI2C_NO_STARTSTOP
);
1953 hfmpi2c
->XferSize
= hfmpi2c
->XferCount
;
1954 FMPI2C_TransferConfig(hfmpi2c
, DevAddress
, hfmpi2c
->XferSize
, FMPI2C_AUTOEND_MODE
, FMPI2C_NO_STARTSTOP
);
1957 }while(hfmpi2c
->XferCount
> 0U);
1959 /* No need to Check TC flag, with AUTOEND mode the stop is automatically generated */
1960 /* Wait until STOPF flag is reset */
1961 if(FMPI2C_WaitOnSTOPFlagUntilTimeout(hfmpi2c
, Timeout
, tickstart
) != HAL_OK
)
1963 if(hfmpi2c
->ErrorCode
== HAL_FMPI2C_ERROR_AF
)
1973 /* Clear STOP Flag */
1974 __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c
, FMPI2C_FLAG_STOPF
);
1976 /* Clear Configuration Register 2 */
1977 FMPI2C_RESET_CR2(hfmpi2c
);
1979 hfmpi2c
->State
= HAL_FMPI2C_STATE_READY
;
1980 hfmpi2c
->Mode
= HAL_FMPI2C_MODE_NONE
;
1982 /* Process Unlocked */
1983 __HAL_UNLOCK(hfmpi2c
);
1993 * @brief Write an amount of data in non-blocking mode with Interrupt to a specific memory address
1994 * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains
1995 * the configuration information for the specified FMPI2C.
1996 * @param DevAddress Target device address
1997 * @param MemAddress Internal memory address
1998 * @param MemAddSize Size of internal memory address
1999 * @param pData Pointer to data buffer
2000 * @param Size Amount of data to be sent
2001 * @retval HAL status
2003 HAL_StatusTypeDef
HAL_FMPI2C_Mem_Write_IT(FMPI2C_HandleTypeDef
*hfmpi2c
, uint16_t DevAddress
, uint16_t MemAddress
, uint16_t MemAddSize
, uint8_t *pData
, uint16_t Size
)
2005 uint32_t tickstart
= 0U;
2006 uint32_t xfermode
= 0U;
2008 /* Check the parameters */
2009 assert_param(IS_FMPI2C_MEMADD_SIZE(MemAddSize
));
2011 if(hfmpi2c
->State
== HAL_FMPI2C_STATE_READY
)
2013 if((pData
== NULL
) || (Size
== 0))
2018 if(__HAL_FMPI2C_GET_FLAG(hfmpi2c
, FMPI2C_FLAG_BUSY
) == SET
)
2023 /* Process Locked */
2024 __HAL_LOCK(hfmpi2c
);
2026 /* Init tickstart for timeout management*/
2027 tickstart
= HAL_GetTick();
2029 hfmpi2c
->State
= HAL_FMPI2C_STATE_BUSY_TX
;
2030 hfmpi2c
->Mode
= HAL_FMPI2C_MODE_MEM
;
2031 hfmpi2c
->ErrorCode
= HAL_FMPI2C_ERROR_NONE
;
2033 /* Prepare transfer parameters */
2034 hfmpi2c
->pBuffPtr
= pData
;
2035 hfmpi2c
->XferCount
= Size
;
2036 hfmpi2c
->XferOptions
= FMPI2C_NO_OPTION_FRAME
;
2037 hfmpi2c
->XferISR
= FMPI2C_Master_ISR_IT
;
2039 if(hfmpi2c
->XferCount
> MAX_NBYTE_SIZE
)
2041 hfmpi2c
->XferSize
= MAX_NBYTE_SIZE
;
2042 xfermode
= FMPI2C_RELOAD_MODE
;
2046 hfmpi2c
->XferSize
= hfmpi2c
->XferCount
;
2047 xfermode
= FMPI2C_AUTOEND_MODE
;
2050 /* Send Slave Address and Memory Address */
2051 if(FMPI2C_RequestMemoryWrite(hfmpi2c
, DevAddress
, MemAddress
, MemAddSize
, FMPI2C_TIMEOUT_FLAG
, tickstart
) != HAL_OK
)
2053 if(hfmpi2c
->ErrorCode
== HAL_FMPI2C_ERROR_AF
)
2055 /* Process Unlocked */
2056 __HAL_UNLOCK(hfmpi2c
);
2061 /* Process Unlocked */
2062 __HAL_UNLOCK(hfmpi2c
);
2067 /* Set NBYTES to write and reload if hfmpi2c->XferCount > MAX_NBYTE_SIZE and generate RESTART */
2068 FMPI2C_TransferConfig(hfmpi2c
,DevAddress
, hfmpi2c
->XferSize
, xfermode
, FMPI2C_NO_STARTSTOP
);
2070 /* Process Unlocked */
2071 __HAL_UNLOCK(hfmpi2c
);
2073 /* Note : The FMPI2C interrupts must be enabled after unlocking current process
2074 to avoid the risk of FMPI2C interrupt handle execution before current
2077 /* Enable ERR, TC, STOP, NACK, TXI interrupt */
2078 /* possible to enable all of these */
2079 /* FMPI2C_IT_ERRI | FMPI2C_IT_TCI| FMPI2C_IT_STOPI| FMPI2C_IT_NACKI | FMPI2C_IT_ADDRI | FMPI2C_IT_RXI | FMPI2C_IT_TXI */
2080 FMPI2C_Enable_IRQ(hfmpi2c
, FMPI2C_XFER_TX_IT
);
2091 * @brief Read an amount of data in non-blocking mode with Interrupt from a specific memory address
2092 * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains
2093 * the configuration information for the specified FMPI2C.
2094 * @param DevAddress Target device address
2095 * @param MemAddress Internal memory address
2096 * @param MemAddSize Size of internal memory address
2097 * @param pData Pointer to data buffer
2098 * @param Size Amount of data to be sent
2099 * @retval HAL status
2101 HAL_StatusTypeDef
HAL_FMPI2C_Mem_Read_IT(FMPI2C_HandleTypeDef
*hfmpi2c
, uint16_t DevAddress
, uint16_t MemAddress
, uint16_t MemAddSize
, uint8_t *pData
, uint16_t Size
)
2103 uint32_t tickstart
= 0U;
2104 uint32_t xfermode
= 0U;
2106 /* Check the parameters */
2107 assert_param(IS_FMPI2C_MEMADD_SIZE(MemAddSize
));
2109 if(hfmpi2c
->State
== HAL_FMPI2C_STATE_READY
)
2111 if((pData
== NULL
) || (Size
== 0))
2116 if(__HAL_FMPI2C_GET_FLAG(hfmpi2c
, FMPI2C_FLAG_BUSY
) == SET
)
2121 /* Process Locked */
2122 __HAL_LOCK(hfmpi2c
);
2124 /* Init tickstart for timeout management*/
2125 tickstart
= HAL_GetTick();
2127 hfmpi2c
->State
= HAL_FMPI2C_STATE_BUSY_RX
;
2128 hfmpi2c
->Mode
= HAL_FMPI2C_MODE_MEM
;
2129 hfmpi2c
->ErrorCode
= HAL_FMPI2C_ERROR_NONE
;
2131 /* Prepare transfer parameters */
2132 hfmpi2c
->pBuffPtr
= pData
;
2133 hfmpi2c
->XferCount
= Size
;
2134 hfmpi2c
->XferOptions
= FMPI2C_NO_OPTION_FRAME
;
2135 hfmpi2c
->XferISR
= FMPI2C_Master_ISR_IT
;
2137 if(hfmpi2c
->XferCount
> MAX_NBYTE_SIZE
)
2139 hfmpi2c
->XferSize
= MAX_NBYTE_SIZE
;
2140 xfermode
= FMPI2C_RELOAD_MODE
;
2144 hfmpi2c
->XferSize
= hfmpi2c
->XferCount
;
2145 xfermode
= FMPI2C_AUTOEND_MODE
;
2148 /* Send Slave Address and Memory Address */
2149 if(FMPI2C_RequestMemoryRead(hfmpi2c
, DevAddress
, MemAddress
, MemAddSize
, FMPI2C_TIMEOUT_FLAG
, tickstart
) != HAL_OK
)
2151 if(hfmpi2c
->ErrorCode
== HAL_FMPI2C_ERROR_AF
)
2153 /* Process Unlocked */
2154 __HAL_UNLOCK(hfmpi2c
);
2159 /* Process Unlocked */
2160 __HAL_UNLOCK(hfmpi2c
);
2165 /* Set NBYTES to write and reload if hfmpi2c->XferCount > MAX_NBYTE_SIZE and generate RESTART */
2166 FMPI2C_TransferConfig(hfmpi2c
,DevAddress
,hfmpi2c
->XferSize
, xfermode
, FMPI2C_GENERATE_START_READ
);
2168 /* Process Unlocked */
2169 __HAL_UNLOCK(hfmpi2c
);
2171 /* Note : The FMPI2C interrupts must be enabled after unlocking current process
2172 to avoid the risk of FMPI2C interrupt handle execution before current
2175 /* Enable ERR, TC, STOP, NACK, RXI interrupt */
2176 /* possible to enable all of these */
2177 /* FMPI2C_IT_ERRI | FMPI2C_IT_TCI| FMPI2C_IT_STOPI| FMPI2C_IT_NACKI | FMPI2C_IT_ADDRI | FMPI2C_IT_RXI | FMPI2C_IT_TXI */
2178 FMPI2C_Enable_IRQ(hfmpi2c
, FMPI2C_XFER_RX_IT
);
2188 * @brief Write an amount of data in non-blocking mode with DMA to a specific memory address
2189 * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains
2190 * the configuration information for the specified FMPI2C.
2191 * @param DevAddress Target device address
2192 * @param MemAddress Internal memory address
2193 * @param MemAddSize Size of internal memory address
2194 * @param pData Pointer to data buffer
2195 * @param Size Amount of data to be sent
2196 * @retval HAL status
2198 HAL_StatusTypeDef
HAL_FMPI2C_Mem_Write_DMA(FMPI2C_HandleTypeDef
*hfmpi2c
, uint16_t DevAddress
, uint16_t MemAddress
, uint16_t MemAddSize
, uint8_t *pData
, uint16_t Size
)
2200 uint32_t tickstart
= 0U;
2201 uint32_t xfermode
= 0U;
2203 /* Check the parameters */
2204 assert_param(IS_FMPI2C_MEMADD_SIZE(MemAddSize
));
2206 if(hfmpi2c
->State
== HAL_FMPI2C_STATE_READY
)
2208 if((pData
== NULL
) || (Size
== 0))
2213 if(__HAL_FMPI2C_GET_FLAG(hfmpi2c
, FMPI2C_FLAG_BUSY
) == SET
)
2218 /* Process Locked */
2219 __HAL_LOCK(hfmpi2c
);
2221 /* Init tickstart for timeout management*/
2222 tickstart
= HAL_GetTick();
2224 hfmpi2c
->State
= HAL_FMPI2C_STATE_BUSY_TX
;
2225 hfmpi2c
->Mode
= HAL_FMPI2C_MODE_MEM
;
2226 hfmpi2c
->ErrorCode
= HAL_FMPI2C_ERROR_NONE
;
2228 /* Prepare transfer parameters */
2229 hfmpi2c
->pBuffPtr
= pData
;
2230 hfmpi2c
->XferCount
= Size
;
2231 hfmpi2c
->XferOptions
= FMPI2C_NO_OPTION_FRAME
;
2232 hfmpi2c
->XferISR
= FMPI2C_Master_ISR_DMA
;
2234 if(hfmpi2c
->XferCount
> MAX_NBYTE_SIZE
)
2236 hfmpi2c
->XferSize
= MAX_NBYTE_SIZE
;
2237 xfermode
= FMPI2C_RELOAD_MODE
;
2241 hfmpi2c
->XferSize
= hfmpi2c
->XferCount
;
2242 xfermode
= FMPI2C_AUTOEND_MODE
;
2245 /* Send Slave Address and Memory Address */
2246 if(FMPI2C_RequestMemoryWrite(hfmpi2c
, DevAddress
, MemAddress
, MemAddSize
, FMPI2C_TIMEOUT_FLAG
, tickstart
) != HAL_OK
)
2248 if(hfmpi2c
->ErrorCode
== HAL_FMPI2C_ERROR_AF
)
2250 /* Process Unlocked */
2251 __HAL_UNLOCK(hfmpi2c
);
2256 /* Process Unlocked */
2257 __HAL_UNLOCK(hfmpi2c
);
2262 /* Set the FMPI2C DMA transfer complete callback */
2263 hfmpi2c
->hdmatx
->XferCpltCallback
= FMPI2C_DMAMasterTransmitCplt
;
2265 /* Set the DMA error callback */
2266 hfmpi2c
->hdmatx
->XferErrorCallback
= FMPI2C_DMAError
;
2268 /* Set the unused DMA callbacks to NULL */
2269 hfmpi2c
->hdmatx
->XferHalfCpltCallback
= NULL
;
2270 hfmpi2c
->hdmatx
->XferAbortCallback
= NULL
;
2272 /* Enable the DMA channel */
2273 HAL_DMA_Start_IT(hfmpi2c
->hdmatx
, (uint32_t)pData
, (uint32_t)&hfmpi2c
->Instance
->TXDR
, hfmpi2c
->XferSize
);
2275 /* Send Slave Address */
2276 /* Set NBYTES to write and reload if hfmpi2c->XferCount > MAX_NBYTE_SIZE and generate RESTART */
2277 FMPI2C_TransferConfig(hfmpi2c
, DevAddress
, hfmpi2c
->XferSize
, xfermode
, FMPI2C_NO_STARTSTOP
);
2279 /* Update XferCount value */
2280 hfmpi2c
->XferCount
-= hfmpi2c
->XferSize
;
2282 /* Process Unlocked */
2283 __HAL_UNLOCK(hfmpi2c
);
2285 /* Note : The FMPI2C interrupts must be enabled after unlocking current process
2286 to avoid the risk of FMPI2C interrupt handle execution before current
2288 /* Enable ERR and NACK interrupts */
2289 FMPI2C_Enable_IRQ(hfmpi2c
, FMPI2C_XFER_ERROR_IT
);
2291 /* Enable DMA Request */
2292 hfmpi2c
->Instance
->CR1
|= FMPI2C_CR1_TXDMAEN
;
2303 * @brief Reads an amount of data in non-blocking mode with DMA from a specific memory address.
2304 * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains
2305 * the configuration information for the specified FMPI2C.
2306 * @param DevAddress Target device address
2307 * @param MemAddress Internal memory address
2308 * @param MemAddSize Size of internal memory address
2309 * @param pData Pointer to data buffer
2310 * @param Size Amount of data to be read
2311 * @retval HAL status
2313 HAL_StatusTypeDef
HAL_FMPI2C_Mem_Read_DMA(FMPI2C_HandleTypeDef
*hfmpi2c
, uint16_t DevAddress
, uint16_t MemAddress
, uint16_t MemAddSize
, uint8_t *pData
, uint16_t Size
)
2315 uint32_t tickstart
= 0U;
2316 uint32_t xfermode
= 0U;
2318 /* Check the parameters */
2319 assert_param(IS_FMPI2C_MEMADD_SIZE(MemAddSize
));
2321 if(hfmpi2c
->State
== HAL_FMPI2C_STATE_READY
)
2323 if((pData
== NULL
) || (Size
== 0))
2328 if(__HAL_FMPI2C_GET_FLAG(hfmpi2c
, FMPI2C_FLAG_BUSY
) == SET
)
2333 /* Process Locked */
2334 __HAL_LOCK(hfmpi2c
);
2336 /* Init tickstart for timeout management*/
2337 tickstart
= HAL_GetTick();
2339 hfmpi2c
->State
= HAL_FMPI2C_STATE_BUSY_RX
;
2340 hfmpi2c
->Mode
= HAL_FMPI2C_MODE_MEM
;
2341 hfmpi2c
->ErrorCode
= HAL_FMPI2C_ERROR_NONE
;
2343 /* Prepare transfer parameters */
2344 hfmpi2c
->pBuffPtr
= pData
;
2345 hfmpi2c
->XferCount
= Size
;
2346 hfmpi2c
->XferOptions
= FMPI2C_NO_OPTION_FRAME
;
2347 hfmpi2c
->XferISR
= FMPI2C_Master_ISR_DMA
;
2349 if(hfmpi2c
->XferCount
> MAX_NBYTE_SIZE
)
2351 hfmpi2c
->XferSize
= MAX_NBYTE_SIZE
;
2352 xfermode
= FMPI2C_RELOAD_MODE
;
2356 hfmpi2c
->XferSize
= hfmpi2c
->XferCount
;
2357 xfermode
= FMPI2C_AUTOEND_MODE
;
2360 /* Send Slave Address and Memory Address */
2361 if(FMPI2C_RequestMemoryRead(hfmpi2c
, DevAddress
, MemAddress
, MemAddSize
, FMPI2C_TIMEOUT_FLAG
, tickstart
) != HAL_OK
)
2363 if(hfmpi2c
->ErrorCode
== HAL_FMPI2C_ERROR_AF
)
2365 /* Process Unlocked */
2366 __HAL_UNLOCK(hfmpi2c
);
2371 /* Process Unlocked */
2372 __HAL_UNLOCK(hfmpi2c
);
2377 /* Set the FMPI2C DMA transfer complete callback */
2378 hfmpi2c
->hdmarx
->XferCpltCallback
= FMPI2C_DMAMasterReceiveCplt
;
2380 /* Set the DMA error callback */
2381 hfmpi2c
->hdmarx
->XferErrorCallback
= FMPI2C_DMAError
;
2383 /* Set the unused DMA callbacks to NULL */
2384 hfmpi2c
->hdmarx
->XferHalfCpltCallback
= NULL
;
2385 hfmpi2c
->hdmarx
->XferAbortCallback
= NULL
;
2387 /* Enable the DMA channel */
2388 HAL_DMA_Start_IT(hfmpi2c
->hdmarx
, (uint32_t)&hfmpi2c
->Instance
->RXDR
, (uint32_t)pData
, hfmpi2c
->XferSize
);
2390 /* Set NBYTES to write and reload if hfmpi2c->XferCount > MAX_NBYTE_SIZE and generate RESTART */
2391 FMPI2C_TransferConfig(hfmpi2c
,DevAddress
, hfmpi2c
->XferSize
, xfermode
, FMPI2C_GENERATE_START_READ
);
2393 /* Update XferCount value */
2394 hfmpi2c
->XferCount
-= hfmpi2c
->XferSize
;
2396 /* Process Unlocked */
2397 __HAL_UNLOCK(hfmpi2c
);
2399 /* Enable DMA Request */
2400 hfmpi2c
->Instance
->CR1
|= FMPI2C_CR1_RXDMAEN
;
2402 /* Note : The FMPI2C interrupts must be enabled after unlocking current process
2403 to avoid the risk of FMPI2C interrupt handle execution before current
2405 /* Enable ERR and NACK interrupts */
2406 FMPI2C_Enable_IRQ(hfmpi2c
, FMPI2C_XFER_ERROR_IT
);
2417 * @brief Checks if target device is ready for communication.
2418 * @note This function is used with Memory devices
2419 * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains
2420 * the configuration information for the specified FMPI2C.
2421 * @param DevAddress Target device address
2422 * @param Trials Number of trials
2423 * @param Timeout Timeout duration
2424 * @retval HAL status
2426 HAL_StatusTypeDef
HAL_FMPI2C_IsDeviceReady(FMPI2C_HandleTypeDef
*hfmpi2c
, uint16_t DevAddress
, uint32_t Trials
, uint32_t Timeout
)
2428 uint32_t tickstart
= 0U;
2430 __IO
uint32_t FMPI2C_Trials
= 0U;
2432 if(hfmpi2c
->State
== HAL_FMPI2C_STATE_READY
)
2434 if(__HAL_FMPI2C_GET_FLAG(hfmpi2c
, FMPI2C_FLAG_BUSY
) == SET
)
2439 /* Process Locked */
2440 __HAL_LOCK(hfmpi2c
);
2442 hfmpi2c
->State
= HAL_FMPI2C_STATE_BUSY
;
2443 hfmpi2c
->ErrorCode
= HAL_FMPI2C_ERROR_NONE
;
2447 /* Generate Start */
2448 hfmpi2c
->Instance
->CR2
= FMPI2C_GENERATE_START(hfmpi2c
->Init
.AddressingMode
,DevAddress
);
2450 /* No need to Check TC flag, with AUTOEND mode the stop is automatically generated */
2451 /* Wait until STOPF flag is set or a NACK flag is set*/
2452 tickstart
= HAL_GetTick();
2453 while((__HAL_FMPI2C_GET_FLAG(hfmpi2c
, FMPI2C_FLAG_STOPF
) == RESET
) && (__HAL_FMPI2C_GET_FLAG(hfmpi2c
, FMPI2C_FLAG_AF
) == RESET
) && (hfmpi2c
->State
!= HAL_FMPI2C_STATE_TIMEOUT
))
2455 if(Timeout
!= HAL_MAX_DELAY
)
2457 if((Timeout
== 0U)||((HAL_GetTick() - tickstart
) > Timeout
))
2459 /* Device is ready */
2460 hfmpi2c
->State
= HAL_FMPI2C_STATE_READY
;
2461 /* Process Unlocked */
2462 __HAL_UNLOCK(hfmpi2c
);
2468 /* Check if the NACKF flag has not been set */
2469 if (__HAL_FMPI2C_GET_FLAG(hfmpi2c
, FMPI2C_FLAG_AF
) == RESET
)
2471 /* Wait until STOPF flag is reset */
2472 if(FMPI2C_WaitOnFlagUntilTimeout(hfmpi2c
, FMPI2C_FLAG_STOPF
, RESET
, Timeout
, tickstart
) != HAL_OK
)
2477 /* Clear STOP Flag */
2478 __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c
, FMPI2C_FLAG_STOPF
);
2480 /* Device is ready */
2481 hfmpi2c
->State
= HAL_FMPI2C_STATE_READY
;
2483 /* Process Unlocked */
2484 __HAL_UNLOCK(hfmpi2c
);
2490 /* Wait until STOPF flag is reset */
2491 if(FMPI2C_WaitOnFlagUntilTimeout(hfmpi2c
, FMPI2C_FLAG_STOPF
, RESET
, Timeout
, tickstart
) != HAL_OK
)
2496 /* Clear NACK Flag */
2497 __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c
, FMPI2C_FLAG_AF
);
2499 /* Clear STOP Flag, auto generated with autoend*/
2500 __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c
, FMPI2C_FLAG_STOPF
);
2503 /* Check if the maximum allowed number of trials has been reached */
2504 if (FMPI2C_Trials
++ == Trials
)
2507 hfmpi2c
->Instance
->CR2
|= FMPI2C_CR2_STOP
;
2509 /* Wait until STOPF flag is reset */
2510 if(FMPI2C_WaitOnFlagUntilTimeout(hfmpi2c
, FMPI2C_FLAG_STOPF
, RESET
, Timeout
, tickstart
) != HAL_OK
)
2515 /* Clear STOP Flag */
2516 __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c
, FMPI2C_FLAG_STOPF
);
2518 }while(FMPI2C_Trials
< Trials
);
2520 hfmpi2c
->State
= HAL_FMPI2C_STATE_READY
;
2522 /* Process Unlocked */
2523 __HAL_UNLOCK(hfmpi2c
);
2534 * @brief Sequential transmit in master FMPI2C mode an amount of data in non-blocking mode with Interrupt.
2535 * @note This interface allow to manage repeated start condition when a direction change during transfer
2536 * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains
2537 * the configuration information for the specified FMPI2C.
2538 * @param DevAddress Target device address: The device 7 bits address value
2539 * in datasheet must be shift at right before call interface
2540 * @param pData Pointer to data buffer
2541 * @param Size Amount of data to be sent
2542 * @param XferOptions Options of Transfer, value of @ref FMPI2C_XFEROPTIONS
2543 * @retval HAL status
2545 HAL_StatusTypeDef
HAL_FMPI2C_Master_Sequential_Transmit_IT(FMPI2C_HandleTypeDef
*hfmpi2c
, uint16_t DevAddress
, uint8_t *pData
, uint16_t Size
, uint32_t XferOptions
)
2547 uint32_t xfermode
= 0U;
2548 uint32_t xferrequest
= FMPI2C_GENERATE_START_WRITE
;
2550 /* Check the parameters */
2551 assert_param(IS_FMPI2C_TRANSFER_OPTIONS_REQUEST(XferOptions
));
2553 if(hfmpi2c
->State
== HAL_FMPI2C_STATE_READY
)
2555 /* Process Locked */
2556 __HAL_LOCK(hfmpi2c
);
2558 hfmpi2c
->State
= HAL_FMPI2C_STATE_BUSY_TX
;
2559 hfmpi2c
->Mode
= HAL_FMPI2C_MODE_MASTER
;
2560 hfmpi2c
->ErrorCode
= HAL_FMPI2C_ERROR_NONE
;
2562 /* Prepare transfer parameters */
2563 hfmpi2c
->pBuffPtr
= pData
;
2564 hfmpi2c
->XferCount
= Size
;
2565 hfmpi2c
->XferOptions
= XferOptions
;
2566 hfmpi2c
->XferISR
= FMPI2C_Master_ISR_IT
;
2568 /* If size > MAX_NBYTE_SIZE, use reload mode */
2569 if(hfmpi2c
->XferCount
> MAX_NBYTE_SIZE
)
2571 hfmpi2c
->XferSize
= MAX_NBYTE_SIZE
;
2572 xfermode
= FMPI2C_RELOAD_MODE
;
2576 hfmpi2c
->XferSize
= hfmpi2c
->XferCount
;
2577 xfermode
= hfmpi2c
->XferOptions
;
2580 /* If transfer direction not change, do not generate Restart Condition */
2581 /* Mean Previous state is same as current state */
2582 if(hfmpi2c
->PreviousState
== FMPI2C_STATE_SLAVE_BUSY_TX
)
2584 xferrequest
= FMPI2C_NO_STARTSTOP
;
2587 /* Send Slave Address and set NBYTES to write */
2588 FMPI2C_TransferConfig(hfmpi2c
, DevAddress
, hfmpi2c
->XferSize
, xfermode
, xferrequest
);
2590 /* Process Unlocked */
2591 __HAL_UNLOCK(hfmpi2c
);
2593 /* Note : The FMPI2C interrupts must be enabled after unlocking current process
2594 to avoid the risk of FMPI2C interrupt handle execution before current
2596 FMPI2C_Enable_IRQ(hfmpi2c
, FMPI2C_XFER_TX_IT
);
2607 * @brief Sequential receive in master FMPI2C mode an amount of data in non-blocking mode with Interrupt
2608 * @note This interface allow to manage repeated start condition when a direction change during transfer
2609 * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains
2610 * the configuration information for the specified FMPI2C.
2611 * @param DevAddress Target device address: The device 7 bits address value
2612 * in datasheet must be shift at right before call interface
2613 * @param pData Pointer to data buffer
2614 * @param Size Amount of data to be sent
2615 * @param XferOptions Options of Transfer, value of @ref FMPI2C_XFEROPTIONS
2616 * @retval HAL status
2618 HAL_StatusTypeDef
HAL_FMPI2C_Master_Sequential_Receive_IT(FMPI2C_HandleTypeDef
*hfmpi2c
, uint16_t DevAddress
, uint8_t *pData
, uint16_t Size
, uint32_t XferOptions
)
2620 uint32_t xfermode
= 0U;
2621 uint32_t xferrequest
= FMPI2C_GENERATE_START_READ
;
2623 /* Check the parameters */
2624 assert_param(IS_FMPI2C_TRANSFER_OPTIONS_REQUEST(XferOptions
));
2626 if(hfmpi2c
->State
== HAL_FMPI2C_STATE_READY
)
2628 /* Process Locked */
2629 __HAL_LOCK(hfmpi2c
);
2631 hfmpi2c
->State
= HAL_FMPI2C_STATE_BUSY_RX
;
2632 hfmpi2c
->Mode
= HAL_FMPI2C_MODE_MASTER
;
2633 hfmpi2c
->ErrorCode
= HAL_FMPI2C_ERROR_NONE
;
2635 /* Prepare transfer parameters */
2636 hfmpi2c
->pBuffPtr
= pData
;
2637 hfmpi2c
->XferCount
= Size
;
2638 hfmpi2c
->XferOptions
= XferOptions
;
2639 hfmpi2c
->XferISR
= FMPI2C_Master_ISR_IT
;
2641 /* If hfmpi2c->XferCount > MAX_NBYTE_SIZE, use reload mode */
2642 if(hfmpi2c
->XferCount
> MAX_NBYTE_SIZE
)
2644 hfmpi2c
->XferSize
= MAX_NBYTE_SIZE
;
2645 xfermode
= FMPI2C_RELOAD_MODE
;
2649 hfmpi2c
->XferSize
= hfmpi2c
->XferCount
;
2650 xfermode
= hfmpi2c
->XferOptions
;
2653 /* If transfer direction not change, do not generate Restart Condition */
2654 /* Mean Previous state is same as current state */
2655 if(hfmpi2c
->PreviousState
== FMPI2C_STATE_MASTER_BUSY_RX
)
2657 xferrequest
= FMPI2C_NO_STARTSTOP
;
2660 /* Send Slave Address and set NBYTES to read */
2661 FMPI2C_TransferConfig(hfmpi2c
,DevAddress
, hfmpi2c
->XferSize
, xfermode
, xferrequest
);
2663 /* Process Unlocked */
2664 __HAL_UNLOCK(hfmpi2c
);
2666 /* Note : The FMPI2C interrupts must be enabled after unlocking current process
2667 to avoid the risk of FMPI2C interrupt handle execution before current
2669 FMPI2C_Enable_IRQ(hfmpi2c
, FMPI2C_XFER_RX_IT
);
2680 * @brief Sequential transmit in slave/device FMPI2C mode an amount of data in non-blocking mode with Interrupt
2681 * @note This interface allow to manage repeated start condition when a direction change during transfer
2682 * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains
2683 * the configuration information for the specified FMPI2C.
2684 * @param pData Pointer to data buffer
2685 * @param Size Amount of data to be sent
2686 * @param XferOptions Options of Transfer, value of @ref FMPI2C_XFEROPTIONS
2687 * @retval HAL status
2689 HAL_StatusTypeDef
HAL_FMPI2C_Slave_Sequential_Transmit_IT(FMPI2C_HandleTypeDef
*hfmpi2c
, uint8_t *pData
, uint16_t Size
, uint32_t XferOptions
)
2691 /* Check the parameters */
2692 assert_param(IS_FMPI2C_TRANSFER_OPTIONS_REQUEST(XferOptions
));
2694 if((hfmpi2c
->State
& HAL_FMPI2C_STATE_LISTEN
) == HAL_FMPI2C_STATE_LISTEN
)
2696 if((pData
== NULL
) || (Size
== 0))
2701 /* Disable Interrupts, to prevent preemption during treatment in case of multicall */
2702 FMPI2C_Disable_IRQ(hfmpi2c
, FMPI2C_XFER_LISTEN_IT
| FMPI2C_XFER_TX_IT
);
2704 /* Process Locked */
2705 __HAL_LOCK(hfmpi2c
);
2707 /* FMPI2C cannot manage full duplex exchange so disable previous IT enabled if any */
2708 /* and then toggle the HAL slave RX state to TX state */
2709 if(hfmpi2c
->State
== HAL_FMPI2C_STATE_BUSY_RX_LISTEN
)
2711 /* Disable associated Interrupts */
2712 FMPI2C_Disable_IRQ(hfmpi2c
, FMPI2C_XFER_RX_IT
);
2715 hfmpi2c
->State
= HAL_FMPI2C_STATE_BUSY_TX_LISTEN
;
2716 hfmpi2c
->Mode
= HAL_FMPI2C_MODE_SLAVE
;
2717 hfmpi2c
->ErrorCode
= HAL_FMPI2C_ERROR_NONE
;
2719 /* Enable Address Acknowledge */
2720 hfmpi2c
->Instance
->CR2
&= ~FMPI2C_CR2_NACK
;
2722 /* Prepare transfer parameters */
2723 hfmpi2c
->pBuffPtr
= pData
;
2724 hfmpi2c
->XferCount
= Size
;
2725 hfmpi2c
->XferSize
= hfmpi2c
->XferCount
;
2726 hfmpi2c
->XferOptions
= XferOptions
;
2727 hfmpi2c
->XferISR
= FMPI2C_Slave_ISR_IT
;
2729 if(FMPI2C_GET_DIR(hfmpi2c
) == FMPI2C_DIRECTION_RECEIVE
)
2731 /* Clear ADDR flag after prepare the transfer parameters */
2732 /* This action will generate an acknowledge to the Master */
2733 __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c
,FMPI2C_FLAG_ADDR
);
2736 /* Process Unlocked */
2737 __HAL_UNLOCK(hfmpi2c
);
2739 /* Note : The FMPI2C interrupts must be enabled after unlocking current process
2740 to avoid the risk of FMPI2C interrupt handle execution before current
2742 /* REnable ADDR interrupt */
2743 FMPI2C_Enable_IRQ(hfmpi2c
, FMPI2C_XFER_TX_IT
| FMPI2C_XFER_LISTEN_IT
);
2754 * @brief Sequential receive in slave/device FMPI2C mode an amount of data in non-blocking mode with Interrupt
2755 * @note This interface allow to manage repeated start condition when a direction change during transfer
2756 * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains
2757 * the configuration information for the specified FMPI2C.
2758 * @param pData Pointer to data buffer
2759 * @param Size Amount of data to be sent
2760 * @param XferOptions Options of Transfer, value of @ref FMPI2C_XFEROPTIONS
2761 * @retval HAL status
2763 HAL_StatusTypeDef
HAL_FMPI2C_Slave_Sequential_Receive_IT(FMPI2C_HandleTypeDef
*hfmpi2c
, uint8_t *pData
, uint16_t Size
, uint32_t XferOptions
)
2765 /* Check the parameters */
2766 assert_param(IS_FMPI2C_TRANSFER_OPTIONS_REQUEST(XferOptions
));
2768 if((hfmpi2c
->State
& HAL_FMPI2C_STATE_LISTEN
) == HAL_FMPI2C_STATE_LISTEN
)
2770 if((pData
== NULL
) || (Size
== 0))
2775 /* Disable Interrupts, to prevent preemption during treatment in case of multicall */
2776 FMPI2C_Disable_IRQ(hfmpi2c
, FMPI2C_XFER_LISTEN_IT
| FMPI2C_XFER_RX_IT
);
2778 /* Process Locked */
2779 __HAL_LOCK(hfmpi2c
);
2781 /* FMPI2C cannot manage full duplex exchange so disable previous IT enabled if any */
2782 /* and then toggle the HAL slave TX state to RX state */
2783 if(hfmpi2c
->State
== HAL_FMPI2C_STATE_BUSY_TX_LISTEN
)
2785 /* Disable associated Interrupts */
2786 FMPI2C_Disable_IRQ(hfmpi2c
, FMPI2C_XFER_TX_IT
);
2789 hfmpi2c
->State
= HAL_FMPI2C_STATE_BUSY_RX_LISTEN
;
2790 hfmpi2c
->Mode
= HAL_FMPI2C_MODE_SLAVE
;
2791 hfmpi2c
->ErrorCode
= HAL_FMPI2C_ERROR_NONE
;
2793 /* Enable Address Acknowledge */
2794 hfmpi2c
->Instance
->CR2
&= ~FMPI2C_CR2_NACK
;
2796 /* Prepare transfer parameters */
2797 hfmpi2c
->pBuffPtr
= pData
;
2798 hfmpi2c
->XferCount
= Size
;
2799 hfmpi2c
->XferSize
= hfmpi2c
->XferCount
;
2800 hfmpi2c
->XferOptions
= XferOptions
;
2801 hfmpi2c
->XferISR
= FMPI2C_Slave_ISR_IT
;
2803 if(FMPI2C_GET_DIR(hfmpi2c
) == FMPI2C_DIRECTION_TRANSMIT
)
2805 /* Clear ADDR flag after prepare the transfer parameters */
2806 /* This action will generate an acknowledge to the Master */
2807 __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c
,FMPI2C_FLAG_ADDR
);
2810 /* Process Unlocked */
2811 __HAL_UNLOCK(hfmpi2c
);
2813 /* Note : The FMPI2C interrupts must be enabled after unlocking current process
2814 to avoid the risk of FMPI2C interrupt handle execution before current
2816 /* REnable ADDR interrupt */
2817 FMPI2C_Enable_IRQ(hfmpi2c
, FMPI2C_XFER_RX_IT
| FMPI2C_XFER_LISTEN_IT
);
2828 * @brief Enable the Address listen mode with Interrupt.
2829 * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains
2830 * the configuration information for the specified FMPI2C.
2831 * @retval HAL status
2833 HAL_StatusTypeDef
HAL_FMPI2C_EnableListen_IT(FMPI2C_HandleTypeDef
*hfmpi2c
)
2835 if(hfmpi2c
->State
== HAL_FMPI2C_STATE_READY
)
2837 hfmpi2c
->State
= HAL_FMPI2C_STATE_LISTEN
;
2838 hfmpi2c
->XferISR
= FMPI2C_Slave_ISR_IT
;
2840 /* Enable the Address Match interrupt */
2841 FMPI2C_Enable_IRQ(hfmpi2c
, FMPI2C_XFER_LISTEN_IT
);
2852 * @brief Disable the Address listen mode with Interrupt.
2853 * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains
2854 * the configuration information for the specified FMPI2C
2855 * @retval HAL status
2857 HAL_StatusTypeDef
HAL_FMPI2C_DisableListen_IT(FMPI2C_HandleTypeDef
*hfmpi2c
)
2859 /* Declaration of tmp to prevent undefined behavior of volatile usage */
2862 /* Disable Address listen mode only if a transfer is not ongoing */
2863 if(hfmpi2c
->State
== HAL_FMPI2C_STATE_LISTEN
)
2865 tmp
= (uint32_t)(hfmpi2c
->State
) & FMPI2C_STATE_MSK
;
2866 hfmpi2c
->PreviousState
= tmp
| (uint32_t)(hfmpi2c
->Mode
);
2867 hfmpi2c
->State
= HAL_FMPI2C_STATE_READY
;
2868 hfmpi2c
->Mode
= HAL_FMPI2C_MODE_NONE
;
2869 hfmpi2c
->XferISR
= NULL
;
2871 /* Disable the Address Match interrupt */
2872 FMPI2C_Disable_IRQ(hfmpi2c
, FMPI2C_XFER_LISTEN_IT
);
2883 * @brief Abort a master FMPI2C IT or DMA process communication with Interrupt.
2884 * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains
2885 * the configuration information for the specified FMPI2C.
2886 * @param DevAddress Target device address: The device 7 bits address value
2887 * in datasheet must be shift at right before call interface
2888 * @retval HAL status
2890 HAL_StatusTypeDef
HAL_FMPI2C_Master_Abort_IT(FMPI2C_HandleTypeDef
*hfmpi2c
, uint16_t DevAddress
)
2892 if(hfmpi2c
->Mode
== HAL_FMPI2C_MODE_MASTER
)
2894 /* Process Locked */
2895 __HAL_LOCK(hfmpi2c
);
2897 /* Disable Interrupts */
2898 FMPI2C_Disable_IRQ(hfmpi2c
, FMPI2C_XFER_RX_IT
);
2899 FMPI2C_Disable_IRQ(hfmpi2c
, FMPI2C_XFER_TX_IT
);
2901 /* Set State at HAL_FMPI2C_STATE_ABORT */
2902 hfmpi2c
->State
= HAL_FMPI2C_STATE_ABORT
;
2904 /* Set NBYTES to 1 to generate a dummy read on FMPI2C peripheral */
2905 /* Set AUTOEND mode, this will generate a NACK then STOP condition to abort the current transfer */
2906 FMPI2C_TransferConfig(hfmpi2c
, DevAddress
, 1, FMPI2C_AUTOEND_MODE
, FMPI2C_GENERATE_STOP
);
2908 /* Process Unlocked */
2909 __HAL_UNLOCK(hfmpi2c
);
2911 /* Note : The FMPI2C interrupts must be enabled after unlocking current process
2912 to avoid the risk of FMPI2C interrupt handle execution before current
2914 FMPI2C_Enable_IRQ(hfmpi2c
, FMPI2C_XFER_CPLT_IT
);
2920 /* Wrong usage of abort function */
2921 /* This function should be used only in case of abort monitored by master device */
2930 /** @defgroup FMPI2C_IRQ_Handler_and_Callbacks IRQ Handler and Callbacks
2935 * @brief This function handles FMPI2C event interrupt request.
2936 * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains
2937 * the configuration information for the specified FMPI2C.
2940 void HAL_FMPI2C_EV_IRQHandler(FMPI2C_HandleTypeDef
*hfmpi2c
)
2942 /* Get current IT Flags and IT sources value */
2943 uint32_t itflags
= READ_REG(hfmpi2c
->Instance
->ISR
);
2944 uint32_t itsources
= READ_REG(hfmpi2c
->Instance
->CR1
);
2946 /* FMPI2C events treatment -------------------------------------*/
2947 if(hfmpi2c
->XferISR
!= NULL
)
2949 hfmpi2c
->XferISR(hfmpi2c
, itflags
, itsources
);
2954 * @brief This function handles FMPI2C error interrupt request.
2955 * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains
2956 * the configuration information for the specified FMPI2C.
2959 void HAL_FMPI2C_ER_IRQHandler(FMPI2C_HandleTypeDef
*hfmpi2c
)
2961 uint32_t itflags
= READ_REG(hfmpi2c
->Instance
->ISR
);
2962 uint32_t itsources
= READ_REG(hfmpi2c
->Instance
->CR1
);
2964 /* FMPI2C Bus error interrupt occurred ------------------------------------*/
2965 if(((itflags
& FMPI2C_FLAG_BERR
) != RESET
) && ((itsources
& FMPI2C_IT_ERRI
) != RESET
))
2967 hfmpi2c
->ErrorCode
|= HAL_FMPI2C_ERROR_BERR
;
2969 /* Clear BERR flag */
2970 __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c
, FMPI2C_FLAG_BERR
);
2973 /* FMPI2C Over-Run/Under-Run interrupt occurred ----------------------------------------*/
2974 if(((itflags
& FMPI2C_FLAG_OVR
) != RESET
) && ((itsources
& FMPI2C_IT_ERRI
) != RESET
))
2976 hfmpi2c
->ErrorCode
|= HAL_FMPI2C_ERROR_OVR
;
2978 /* Clear OVR flag */
2979 __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c
, FMPI2C_FLAG_OVR
);
2982 /* FMPI2C Arbitration Loss error interrupt occurred -------------------------------------*/
2983 if(((itflags
& FMPI2C_FLAG_ARLO
) != RESET
) && ((itsources
& FMPI2C_IT_ERRI
) != RESET
))
2985 hfmpi2c
->ErrorCode
|= HAL_FMPI2C_ERROR_ARLO
;
2987 /* Clear ARLO flag */
2988 __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c
, FMPI2C_FLAG_ARLO
);
2991 /* Call the Error Callback in case of Error detected */
2992 if((hfmpi2c
->ErrorCode
& (HAL_FMPI2C_ERROR_BERR
| HAL_FMPI2C_ERROR_OVR
| HAL_FMPI2C_ERROR_ARLO
)) != HAL_FMPI2C_ERROR_NONE
)
2994 FMPI2C_ITError(hfmpi2c
, hfmpi2c
->ErrorCode
);
2999 * @brief Master Tx Transfer completed callback.
3000 * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains
3001 * the configuration information for the specified FMPI2C.
3004 __weak
void HAL_FMPI2C_MasterTxCpltCallback(FMPI2C_HandleTypeDef
*hfmpi2c
)
3006 /* Prevent unused argument(s) compilation warning */
3009 /* NOTE : This function should not be modified, when the callback is needed,
3010 the HAL_FMPI2C_MasterTxCpltCallback could be implemented in the user file
3015 * @brief Master Rx Transfer completed callback.
3016 * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains
3017 * the configuration information for the specified FMPI2C.
3020 __weak
void HAL_FMPI2C_MasterRxCpltCallback(FMPI2C_HandleTypeDef
*hfmpi2c
)
3022 /* Prevent unused argument(s) compilation warning */
3025 /* NOTE : This function should not be modified, when the callback is needed,
3026 the HAL_FMPI2C_MasterRxCpltCallback could be implemented in the user file
3030 /** @brief Slave Tx Transfer completed callback.
3031 * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains
3032 * the configuration information for the specified FMPI2C.
3035 __weak
void HAL_FMPI2C_SlaveTxCpltCallback(FMPI2C_HandleTypeDef
*hfmpi2c
)
3037 /* Prevent unused argument(s) compilation warning */
3040 /* NOTE : This function should not be modified, when the callback is needed,
3041 the HAL_FMPI2C_SlaveTxCpltCallback could be implemented in the user file
3046 * @brief Slave Rx Transfer completed callback.
3047 * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains
3048 * the configuration information for the specified FMPI2C.
3051 __weak
void HAL_FMPI2C_SlaveRxCpltCallback(FMPI2C_HandleTypeDef
*hfmpi2c
)
3053 /* Prevent unused argument(s) compilation warning */
3056 /* NOTE : This function should not be modified, when the callback is needed,
3057 the HAL_FMPI2C_SlaveRxCpltCallback could be implemented in the user file
3062 * @brief Slave Address Match callback.
3063 * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains
3064 * the configuration information for the specified FMPI2C.
3065 * @param TransferDirection: Master request Transfer Direction (Write/Read), value of @ref FMPI2C_XFEROPTIONS
3066 * @param AddrMatchCode: Address Match Code
3069 __weak
void HAL_FMPI2C_AddrCallback(FMPI2C_HandleTypeDef
*hfmpi2c
, uint8_t TransferDirection
, uint16_t AddrMatchCode
)
3071 /* Prevent unused argument(s) compilation warning */
3073 UNUSED(TransferDirection
);
3074 UNUSED(AddrMatchCode
);
3076 /* NOTE : This function should not be modified, when the callback is needed,
3077 the HAL_FMPI2C_AddrCallback() could be implemented in the user file
3082 * @brief Listen Complete callback.
3083 * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains
3084 * the configuration information for the specified FMPI2C.
3087 __weak
void HAL_FMPI2C_ListenCpltCallback(FMPI2C_HandleTypeDef
*hfmpi2c
)
3089 /* Prevent unused argument(s) compilation warning */
3092 /* NOTE : This function should not be modified, when the callback is needed,
3093 the HAL_FMPI2C_ListenCpltCallback() could be implemented in the user file
3098 * @brief Memory Tx Transfer completed callback.
3099 * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains
3100 * the configuration information for the specified FMPI2C.
3103 __weak
void HAL_FMPI2C_MemTxCpltCallback(FMPI2C_HandleTypeDef
*hfmpi2c
)
3105 /* Prevent unused argument(s) compilation warning */
3108 /* NOTE : This function should not be modified, when the callback is needed,
3109 the HAL_FMPI2C_MemTxCpltCallback could be implemented in the user file
3114 * @brief Memory Rx Transfer completed callback.
3115 * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains
3116 * the configuration information for the specified FMPI2C.
3119 __weak
void HAL_FMPI2C_MemRxCpltCallback(FMPI2C_HandleTypeDef
*hfmpi2c
)
3121 /* Prevent unused argument(s) compilation warning */
3124 /* NOTE : This function should not be modified, when the callback is needed,
3125 the HAL_FMPI2C_MemRxCpltCallback could be implemented in the user file
3130 * @brief FMPI2C error callback.
3131 * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains
3132 * the configuration information for the specified FMPI2C.
3135 __weak
void HAL_FMPI2C_ErrorCallback(FMPI2C_HandleTypeDef
*hfmpi2c
)
3137 /* Prevent unused argument(s) compilation warning */
3140 /* NOTE : This function should not be modified, when the callback is needed,
3141 the HAL_FMPI2C_ErrorCallback could be implemented in the user file
3146 * @brief FMPI2C abort callback.
3147 * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains
3148 * the configuration information for the specified FMPI2C.
3151 __weak
void HAL_FMPI2C_AbortCpltCallback(FMPI2C_HandleTypeDef
*hfmpi2c
)
3153 /* Prevent unused argument(s) compilation warning */
3156 /* NOTE : This function should not be modified, when the callback is needed,
3157 the HAL_FMPI2C_AbortCpltCallback could be implemented in the user file
3165 /** @defgroup FMPI2C_Exported_Functions_Group3 Peripheral State, Mode and Error functions
3166 * @brief Peripheral State, Mode and Error functions
3169 ===============================================================================
3170 ##### Peripheral State, Mode and Error functions #####
3171 ===============================================================================
3173 This subsection permit to get in run-time the status of the peripheral
3181 * @brief Return the FMPI2C handle state.
3182 * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains
3183 * the configuration information for the specified FMPI2C.
3186 HAL_FMPI2C_StateTypeDef
HAL_FMPI2C_GetState(FMPI2C_HandleTypeDef
*hfmpi2c
)
3188 /* Return FMPI2C handle state */
3189 return hfmpi2c
->State
;
3193 * @brief Returns the FMPI2C Master, Slave, Memory or no mode.
3194 * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains
3195 * the configuration information for FMPI2C module
3198 HAL_FMPI2C_ModeTypeDef
HAL_FMPI2C_GetMode(FMPI2C_HandleTypeDef
*hfmpi2c
)
3200 return hfmpi2c
->Mode
;
3204 * @brief Return the FMPI2C error code.
3205 * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains
3206 * the configuration information for the specified FMPI2C.
3207 * @retval FMPI2C Error Code
3209 uint32_t HAL_FMPI2C_GetError(FMPI2C_HandleTypeDef
*hfmpi2c
)
3211 return hfmpi2c
->ErrorCode
;
3222 /** @addtogroup FMPI2C_Private_Functions
3227 * @brief Interrupt Sub-Routine which handle the Interrupt Flags Master Mode with Interrupt.
3228 * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains
3229 * the configuration information for the specified FMPI2C.
3230 * @param ITFlags Interrupt flags to handle.
3231 * @param ITSources Interrupt sources enabled.
3232 * @retval HAL status
3234 static HAL_StatusTypeDef
FMPI2C_Master_ISR_IT(struct __FMPI2C_HandleTypeDef
*hfmpi2c
, uint32_t ITFlags
, uint32_t ITSources
)
3236 uint16_t devaddress
= 0;
3238 /* Process Locked */
3239 __HAL_LOCK(hfmpi2c
);
3241 if(((ITFlags
& FMPI2C_FLAG_AF
) != RESET
) && ((ITSources
& FMPI2C_IT_NACKI
) != RESET
))
3243 /* Clear NACK Flag */
3244 __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c
, FMPI2C_FLAG_AF
);
3246 /* Set corresponding Error Code */
3247 /* No need to generate STOP, it is automatically done */
3248 /* Error callback will be send during stop flag treatment */
3249 hfmpi2c
->ErrorCode
|= HAL_FMPI2C_ERROR_AF
;
3251 /* Flush TX register */
3252 FMPI2C_Flush_TXDR(hfmpi2c
);
3254 else if(((ITFlags
& FMPI2C_FLAG_RXNE
) != RESET
) && ((ITSources
& FMPI2C_IT_RXI
) != RESET
))
3256 /* Read data from RXDR */
3257 (*hfmpi2c
->pBuffPtr
++) = hfmpi2c
->Instance
->RXDR
;
3258 hfmpi2c
->XferSize
--;
3259 hfmpi2c
->XferCount
--;
3261 else if(((ITFlags
& FMPI2C_FLAG_TXIS
) != RESET
) && ((ITSources
& FMPI2C_IT_TXI
) != RESET
))
3263 /* Write data to TXDR */
3264 hfmpi2c
->Instance
->TXDR
= (*hfmpi2c
->pBuffPtr
++);
3265 hfmpi2c
->XferSize
--;
3266 hfmpi2c
->XferCount
--;
3268 else if(((ITFlags
& FMPI2C_FLAG_TCR
) != RESET
) && ((ITSources
& FMPI2C_IT_TCI
) != RESET
))
3270 if((hfmpi2c
->XferSize
== 0U) && (hfmpi2c
->XferCount
!= 0U))
3272 devaddress
= (hfmpi2c
->Instance
->CR2
& FMPI2C_CR2_SADD
);
3274 if(hfmpi2c
->XferCount
> MAX_NBYTE_SIZE
)
3276 hfmpi2c
->XferSize
= MAX_NBYTE_SIZE
;
3277 FMPI2C_TransferConfig(hfmpi2c
, devaddress
, hfmpi2c
->XferSize
, FMPI2C_RELOAD_MODE
, FMPI2C_NO_STARTSTOP
);
3281 hfmpi2c
->XferSize
= hfmpi2c
->XferCount
;
3282 if(hfmpi2c
->XferOptions
!= FMPI2C_NO_OPTION_FRAME
)
3284 FMPI2C_TransferConfig(hfmpi2c
, devaddress
, hfmpi2c
->XferSize
, hfmpi2c
->XferOptions
, FMPI2C_NO_STARTSTOP
);
3288 FMPI2C_TransferConfig(hfmpi2c
, devaddress
, hfmpi2c
->XferSize
, FMPI2C_AUTOEND_MODE
, FMPI2C_NO_STARTSTOP
);
3294 /* Call TxCpltCallback() if no stop mode is set */
3295 if((FMPI2C_GET_STOP_MODE(hfmpi2c
) != FMPI2C_AUTOEND_MODE
)&&(hfmpi2c
->Mode
== HAL_FMPI2C_MODE_MASTER
))
3297 /* Call FMPI2C Master Sequential complete process */
3298 FMPI2C_ITMasterSequentialCplt(hfmpi2c
);
3302 /* Wrong size Status regarding TCR flag event */
3303 /* Call the corresponding callback to inform upper layer of End of Transfer */
3304 FMPI2C_ITError(hfmpi2c
, HAL_FMPI2C_ERROR_SIZE
);
3308 else if(((ITFlags
& FMPI2C_FLAG_TC
) != RESET
) && ((ITSources
& FMPI2C_IT_TCI
) != RESET
))
3310 if(hfmpi2c
->XferCount
== 0U)
3312 if((FMPI2C_GET_STOP_MODE(hfmpi2c
) != FMPI2C_AUTOEND_MODE
)&&(hfmpi2c
->Mode
== HAL_FMPI2C_MODE_MASTER
))
3314 /* Call FMPI2C Master Sequential complete process */
3315 FMPI2C_ITMasterSequentialCplt(hfmpi2c
);
3320 /* Wrong size Status regarding TC flag event */
3321 /* Call the corresponding callback to inform upper layer of End of Transfer */
3322 FMPI2C_ITError(hfmpi2c
, HAL_FMPI2C_ERROR_SIZE
);
3326 if(((ITFlags
& FMPI2C_FLAG_STOPF
) != RESET
) && ((ITSources
& FMPI2C_IT_STOPI
) != RESET
))
3328 /* Call FMPI2C Master complete process */
3329 FMPI2C_ITMasterCplt(hfmpi2c
, ITFlags
);
3332 /* Process Unlocked */
3333 __HAL_UNLOCK(hfmpi2c
);
3339 * @brief Interrupt Sub-Routine which handle the Interrupt Flags Slave Mode with Interrupt.
3340 * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains
3341 * the configuration information for the specified FMPI2C.
3342 * @param ITFlags Interrupt flags to handle.
3343 * @param ITSources Interrupt sources enabled.
3344 * @retval HAL status
3346 static HAL_StatusTypeDef
FMPI2C_Slave_ISR_IT(struct __FMPI2C_HandleTypeDef
*hfmpi2c
, uint32_t ITFlags
, uint32_t ITSources
)
3348 /* Process locked */
3349 __HAL_LOCK(hfmpi2c
);
3351 if(((ITFlags
& FMPI2C_FLAG_AF
) != RESET
) && ((ITSources
& FMPI2C_IT_NACKI
) != RESET
))
3353 /* Check that FMPI2C transfer finished */
3354 /* if yes, normal use case, a NACK is sent by the MASTER when Transfer is finished */
3355 /* Mean XferCount == 0*/
3356 /* So clear Flag NACKF only */
3357 if(hfmpi2c
->XferCount
== 0U)
3359 if(((hfmpi2c
->XferOptions
== FMPI2C_FIRST_AND_LAST_FRAME
) || (hfmpi2c
->XferOptions
== FMPI2C_LAST_FRAME
)) && \
3360 (hfmpi2c
->State
== HAL_FMPI2C_STATE_LISTEN
))
3362 /* Call FMPI2C Listen complete process */
3363 FMPI2C_ITListenCplt(hfmpi2c
, ITFlags
);
3365 else if((hfmpi2c
->XferOptions
!= FMPI2C_NO_OPTION_FRAME
) && (hfmpi2c
->State
== HAL_FMPI2C_STATE_BUSY_TX_LISTEN
))
3367 /* Clear NACK Flag */
3368 __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c
, FMPI2C_FLAG_AF
);
3370 /* Flush TX register */
3371 FMPI2C_Flush_TXDR(hfmpi2c
);
3373 /* Last Byte is Transmitted */
3374 /* Call FMPI2C Slave Sequential complete process */
3375 FMPI2C_ITSlaveSequentialCplt(hfmpi2c
);
3379 /* Clear NACK Flag */
3380 __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c
, FMPI2C_FLAG_AF
);
3385 /* if no, error use case, a Non-Acknowledge of last Data is generated by the MASTER*/
3386 /* Clear NACK Flag */
3387 __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c
, FMPI2C_FLAG_AF
);
3389 /* Set ErrorCode corresponding to a Non-Acknowledge */
3390 hfmpi2c
->ErrorCode
|= HAL_FMPI2C_ERROR_AF
;
3393 else if(((ITFlags
& FMPI2C_FLAG_RXNE
) != RESET
) && ((ITSources
& FMPI2C_IT_RXI
) != RESET
))
3395 if(hfmpi2c
->XferCount
> 0U)
3397 /* Read data from RXDR */
3398 (*hfmpi2c
->pBuffPtr
++) = hfmpi2c
->Instance
->RXDR
;
3399 hfmpi2c
->XferSize
--;
3400 hfmpi2c
->XferCount
--;
3403 if((hfmpi2c
->XferCount
== 0U) && \
3404 (hfmpi2c
->XferOptions
!= FMPI2C_NO_OPTION_FRAME
))
3406 /* Call FMPI2C Slave Sequential complete process */
3407 FMPI2C_ITSlaveSequentialCplt(hfmpi2c
);
3410 else if(((ITFlags
& FMPI2C_FLAG_ADDR
) != RESET
) && ((ITSources
& FMPI2C_IT_ADDRI
) != RESET
))
3412 FMPI2C_ITAddrCplt(hfmpi2c
, ITFlags
);
3414 else if(((ITFlags
& FMPI2C_FLAG_TXIS
) != RESET
) && ((ITSources
& FMPI2C_IT_TXI
) != RESET
))
3416 /* Write data to TXDR only if XferCount not reach "0" */
3417 /* A TXIS flag can be set, during STOP treatment */
3418 /* Check if all Datas have already been sent */
3419 /* If it is the case, this last write in TXDR is not sent, correspond to a dummy TXIS event */
3420 if(hfmpi2c
->XferCount
> 0U)
3422 /* Write data to TXDR */
3423 hfmpi2c
->Instance
->TXDR
= (*hfmpi2c
->pBuffPtr
++);
3424 hfmpi2c
->XferCount
--;
3425 hfmpi2c
->XferSize
--;
3429 if((hfmpi2c
->XferOptions
== FMPI2C_NEXT_FRAME
) || (hfmpi2c
->XferOptions
== FMPI2C_FIRST_FRAME
))
3431 /* Last Byte is Transmitted */
3432 /* Call FMPI2C Slave Sequential complete process */
3433 FMPI2C_ITSlaveSequentialCplt(hfmpi2c
);
3438 /* Check if STOPF is set */
3439 if(((ITFlags
& FMPI2C_FLAG_STOPF
) != RESET
) && ((ITSources
& FMPI2C_IT_STOPI
) != RESET
))
3441 /* Call FMPI2C Slave complete process */
3442 FMPI2C_ITSlaveCplt(hfmpi2c
, ITFlags
);
3445 /* Process Unlocked */
3446 __HAL_UNLOCK(hfmpi2c
);
3452 * @brief Interrupt Sub-Routine which handle the Interrupt Flags Master Mode with DMA.
3453 * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains
3454 * the configuration information for the specified FMPI2C.
3455 * @param ITFlags Interrupt flags to handle.
3456 * @param ITSources Interrupt sources enabled.
3457 * @retval HAL status
3459 static HAL_StatusTypeDef
FMPI2C_Master_ISR_DMA(struct __FMPI2C_HandleTypeDef
*hfmpi2c
, uint32_t ITFlags
, uint32_t ITSources
)
3461 uint16_t devaddress
= 0;
3462 uint32_t xfermode
= 0U;
3464 /* Process Locked */
3465 __HAL_LOCK(hfmpi2c
);
3467 if(((ITFlags
& FMPI2C_FLAG_AF
) != RESET
) && ((ITSources
& FMPI2C_IT_NACKI
) != RESET
))
3469 /* Clear NACK Flag */
3470 __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c
, FMPI2C_FLAG_AF
);
3472 /* Set corresponding Error Code */
3473 hfmpi2c
->ErrorCode
|= HAL_FMPI2C_ERROR_AF
;
3475 /* No need to generate STOP, it is automatically done */
3476 /* But enable STOP interrupt, to treat it */
3477 /* Error callback will be send during stop flag treatment */
3478 FMPI2C_Enable_IRQ(hfmpi2c
, FMPI2C_XFER_CPLT_IT
);
3480 /* Flush TX register */
3481 FMPI2C_Flush_TXDR(hfmpi2c
);
3483 else if(((ITFlags
& FMPI2C_FLAG_TCR
) != RESET
) && ((ITSources
& FMPI2C_IT_TCI
) != RESET
))
3485 /* Disable TC interrupt */
3486 __HAL_FMPI2C_DISABLE_IT(hfmpi2c
, FMPI2C_IT_TCI
);
3488 if(hfmpi2c
->XferCount
!= 0U)
3490 /* Recover Slave address */
3491 devaddress
= (hfmpi2c
->Instance
->CR2
& FMPI2C_CR2_SADD
);
3493 /* Prepare the new XferSize to transfer */
3494 if(hfmpi2c
->XferCount
> MAX_NBYTE_SIZE
)
3496 hfmpi2c
->XferSize
= MAX_NBYTE_SIZE
;
3497 xfermode
= FMPI2C_RELOAD_MODE
;
3501 hfmpi2c
->XferSize
= hfmpi2c
->XferCount
;
3502 xfermode
= FMPI2C_AUTOEND_MODE
;
3505 /* Set the new XferSize in Nbytes register */
3506 FMPI2C_TransferConfig(hfmpi2c
, devaddress
, hfmpi2c
->XferSize
, xfermode
, FMPI2C_NO_STARTSTOP
);
3508 /* Update XferCount value */
3509 hfmpi2c
->XferCount
-= hfmpi2c
->XferSize
;
3511 /* Enable DMA Request */
3512 if(hfmpi2c
->State
== HAL_FMPI2C_STATE_BUSY_RX
)
3514 hfmpi2c
->Instance
->CR1
|= FMPI2C_CR1_RXDMAEN
;
3518 hfmpi2c
->Instance
->CR1
|= FMPI2C_CR1_TXDMAEN
;
3523 /* Wrong size Status regarding TCR flag event */
3524 /* Call the corresponding callback to inform upper layer of End of Transfer */
3525 FMPI2C_ITError(hfmpi2c
, HAL_FMPI2C_ERROR_SIZE
);
3528 else if(((ITFlags
& FMPI2C_FLAG_STOPF
) != RESET
) && ((ITSources
& FMPI2C_IT_STOPI
) != RESET
))
3530 /* Call FMPI2C Master complete process */
3531 FMPI2C_ITMasterCplt(hfmpi2c
, ITFlags
);
3534 /* Process Unlocked */
3535 __HAL_UNLOCK(hfmpi2c
);
3541 * @brief Interrupt Sub-Routine which handle the Interrupt Flags Slave Mode with DMA.
3542 * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains
3543 * the configuration information for the specified FMPI2C.
3544 * @param ITFlags Interrupt flags to handle.
3545 * @param ITSources Interrupt sources enabled.
3546 * @retval HAL status
3548 static HAL_StatusTypeDef
FMPI2C_Slave_ISR_DMA(struct __FMPI2C_HandleTypeDef
*hfmpi2c
, uint32_t ITFlags
, uint32_t ITSources
)
3550 /* Process locked */
3551 __HAL_LOCK(hfmpi2c
);
3553 if(((ITFlags
& FMPI2C_FLAG_AF
) != RESET
) && ((ITSources
& FMPI2C_IT_NACKI
) != RESET
))
3555 /* Check that FMPI2C transfer finished */
3556 /* if yes, normal use case, a NACK is sent by the MASTER when Transfer is finished */
3557 /* Mean XferCount == 0 */
3558 /* So clear Flag NACKF only */
3559 if(FMPI2C_GET_DMA_REMAIN_DATA(hfmpi2c
) == 0U)
3561 /* Clear NACK Flag */
3562 __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c
, FMPI2C_FLAG_AF
);
3566 /* if no, error use case, a Non-Acknowledge of last Data is generated by the MASTER*/
3567 /* Clear NACK Flag */
3568 __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c
, FMPI2C_FLAG_AF
);
3570 /* Set ErrorCode corresponding to a Non-Acknowledge */
3571 hfmpi2c
->ErrorCode
|= HAL_FMPI2C_ERROR_AF
;
3574 else if(((ITFlags
& FMPI2C_FLAG_ADDR
) != RESET
) && ((ITSources
& FMPI2C_IT_ADDRI
) != RESET
))
3576 /* Clear ADDR flag */
3577 __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c
, FMPI2C_FLAG_ADDR
);
3579 else if(((ITFlags
& FMPI2C_FLAG_STOPF
) != RESET
) && ((ITSources
& FMPI2C_IT_STOPI
) != RESET
))
3581 /* Call FMPI2C Slave complete process */
3582 FMPI2C_ITSlaveCplt(hfmpi2c
, ITFlags
);
3585 /* Process Unlocked */
3586 __HAL_UNLOCK(hfmpi2c
);
3592 * @brief Master sends target device address followed by internal memory address for write request.
3593 * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains
3594 * the configuration information for the specified FMPI2C.
3595 * @param DevAddress Target device address
3596 * @param MemAddress Internal memory address
3597 * @param MemAddSize Size of internal memory address
3598 * @param Timeout Timeout duration
3599 * @param Tickstart Tick start value
3600 * @retval HAL status
3602 static HAL_StatusTypeDef
FMPI2C_RequestMemoryWrite(FMPI2C_HandleTypeDef
*hfmpi2c
, uint16_t DevAddress
, uint16_t MemAddress
, uint16_t MemAddSize
, uint32_t Timeout
, uint32_t Tickstart
)
3604 FMPI2C_TransferConfig(hfmpi2c
,DevAddress
,MemAddSize
, FMPI2C_RELOAD_MODE
, FMPI2C_GENERATE_START_WRITE
);
3606 /* Wait until TXIS flag is set */
3607 if(FMPI2C_WaitOnTXISFlagUntilTimeout(hfmpi2c
, Timeout
, Tickstart
) != HAL_OK
)
3609 if(hfmpi2c
->ErrorCode
== HAL_FMPI2C_ERROR_AF
)
3619 /* If Memory address size is 8Bit */
3620 if(MemAddSize
== FMPI2C_MEMADD_SIZE_8BIT
)
3622 /* Send Memory Address */
3623 hfmpi2c
->Instance
->TXDR
= FMPI2C_MEM_ADD_LSB(MemAddress
);
3625 /* If Memory address size is 16Bit */
3628 /* Send MSB of Memory Address */
3629 hfmpi2c
->Instance
->TXDR
= FMPI2C_MEM_ADD_MSB(MemAddress
);
3631 /* Wait until TXIS flag is set */
3632 if(FMPI2C_WaitOnTXISFlagUntilTimeout(hfmpi2c
, Timeout
, Tickstart
) != HAL_OK
)
3634 if(hfmpi2c
->ErrorCode
== HAL_FMPI2C_ERROR_AF
)
3644 /* Send LSB of Memory Address */
3645 hfmpi2c
->Instance
->TXDR
= FMPI2C_MEM_ADD_LSB(MemAddress
);
3648 /* Wait until TCR flag is set */
3649 if(FMPI2C_WaitOnFlagUntilTimeout(hfmpi2c
, FMPI2C_FLAG_TCR
, RESET
, Timeout
, Tickstart
) != HAL_OK
)
3658 * @brief Master sends target device address followed by internal memory address for read request.
3659 * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains
3660 * the configuration information for the specified FMPI2C.
3661 * @param DevAddress Target device address
3662 * @param MemAddress Internal memory address
3663 * @param MemAddSize Size of internal memory address
3664 * @param Timeout Timeout duration
3665 * @param Tickstart Tick start value
3666 * @retval HAL status
3668 static HAL_StatusTypeDef
FMPI2C_RequestMemoryRead(FMPI2C_HandleTypeDef
*hfmpi2c
, uint16_t DevAddress
, uint16_t MemAddress
, uint16_t MemAddSize
, uint32_t Timeout
, uint32_t Tickstart
)
3670 FMPI2C_TransferConfig(hfmpi2c
,DevAddress
,MemAddSize
, FMPI2C_SOFTEND_MODE
, FMPI2C_GENERATE_START_WRITE
);
3672 /* Wait until TXIS flag is set */
3673 if(FMPI2C_WaitOnTXISFlagUntilTimeout(hfmpi2c
, Timeout
, Tickstart
) != HAL_OK
)
3675 if(hfmpi2c
->ErrorCode
== HAL_FMPI2C_ERROR_AF
)
3685 /* If Memory address size is 8Bit */
3686 if(MemAddSize
== FMPI2C_MEMADD_SIZE_8BIT
)
3688 /* Send Memory Address */
3689 hfmpi2c
->Instance
->TXDR
= FMPI2C_MEM_ADD_LSB(MemAddress
);
3691 /* If Memory address size is 16Bit */
3694 /* Send MSB of Memory Address */
3695 hfmpi2c
->Instance
->TXDR
= FMPI2C_MEM_ADD_MSB(MemAddress
);
3697 /* Wait until TXIS flag is set */
3698 if(FMPI2C_WaitOnTXISFlagUntilTimeout(hfmpi2c
, Timeout
, Tickstart
) != HAL_OK
)
3700 if(hfmpi2c
->ErrorCode
== HAL_FMPI2C_ERROR_AF
)
3710 /* Send LSB of Memory Address */
3711 hfmpi2c
->Instance
->TXDR
= FMPI2C_MEM_ADD_LSB(MemAddress
);
3714 /* Wait until TC flag is set */
3715 if(FMPI2C_WaitOnFlagUntilTimeout(hfmpi2c
, FMPI2C_FLAG_TC
, RESET
, Timeout
, Tickstart
) != HAL_OK
)
3724 * @brief FMPI2C Address complete process callback.
3725 * @param hfmpi2c FMPI2C handle.
3726 * @param ITFlags Interrupt flags to handle.
3729 static void FMPI2C_ITAddrCplt(FMPI2C_HandleTypeDef
*hfmpi2c
, uint32_t ITFlags
)
3731 uint8_t transferdirection
= 0;
3732 uint16_t slaveaddrcode
= 0;
3733 uint16_t ownadd1code
= 0;
3734 uint16_t ownadd2code
= 0;
3736 /* In case of Listen state, need to inform upper layer of address match code event */
3737 if((hfmpi2c
->State
& HAL_FMPI2C_STATE_LISTEN
) == HAL_FMPI2C_STATE_LISTEN
)
3739 transferdirection
= FMPI2C_GET_DIR(hfmpi2c
);
3740 slaveaddrcode
= FMPI2C_GET_ADDR_MATCH(hfmpi2c
);
3741 ownadd1code
= FMPI2C_GET_OWN_ADDRESS1(hfmpi2c
);
3742 ownadd2code
= FMPI2C_GET_OWN_ADDRESS2(hfmpi2c
);
3744 /* If 10bits addressing mode is selected */
3745 if(hfmpi2c
->Init
.AddressingMode
== FMPI2C_ADDRESSINGMODE_10BIT
)
3747 if((slaveaddrcode
& SlaveAddr_MSK
) == ((ownadd1code
>> SlaveAddr_SHIFT
) & SlaveAddr_MSK
))
3749 slaveaddrcode
= ownadd1code
;
3750 hfmpi2c
->AddrEventCount
++;
3751 if(hfmpi2c
->AddrEventCount
== 2U)
3753 /* Reset Address Event counter */
3754 hfmpi2c
->AddrEventCount
= 0U;
3756 /* Clear ADDR flag */
3757 __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c
,FMPI2C_FLAG_ADDR
);
3759 /* Process Unlocked */
3760 __HAL_UNLOCK(hfmpi2c
);
3762 /* Call Slave Addr callback */
3763 HAL_FMPI2C_AddrCallback(hfmpi2c
, transferdirection
, slaveaddrcode
);
3768 slaveaddrcode
= ownadd2code
;
3770 /* Disable ADDR Interrupts */
3771 FMPI2C_Disable_IRQ(hfmpi2c
, FMPI2C_XFER_LISTEN_IT
);
3773 /* Process Unlocked */
3774 __HAL_UNLOCK(hfmpi2c
);
3776 /* Call Slave Addr callback */
3777 HAL_FMPI2C_AddrCallback(hfmpi2c
, transferdirection
, slaveaddrcode
);
3780 /* else 7 bits addressing mode is selected */
3783 /* Disable ADDR Interrupts */
3784 FMPI2C_Disable_IRQ(hfmpi2c
, FMPI2C_XFER_LISTEN_IT
);
3786 /* Process Unlocked */
3787 __HAL_UNLOCK(hfmpi2c
);
3789 /* Call Slave Addr callback */
3790 HAL_FMPI2C_AddrCallback(hfmpi2c
, transferdirection
, slaveaddrcode
);
3793 /* Else clear address flag only */
3796 /* Clear ADDR flag */
3797 __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c
, FMPI2C_FLAG_ADDR
);
3799 /* Process Unlocked */
3800 __HAL_UNLOCK(hfmpi2c
);
3805 * @brief FMPI2C Master sequential complete process.
3806 * @param hfmpi2c FMPI2C handle.
3809 static void FMPI2C_ITMasterSequentialCplt(FMPI2C_HandleTypeDef
*hfmpi2c
)
3811 /* Reset FMPI2C handle mode */
3812 hfmpi2c
->Mode
= HAL_FMPI2C_MODE_NONE
;
3814 /* No Generate Stop, to permit restart mode */
3815 /* The stop will be done at the end of transfer, when FMPI2C_AUTOEND_MODE enable */
3816 if (hfmpi2c
->State
== HAL_FMPI2C_STATE_BUSY_TX
)
3818 hfmpi2c
->State
= HAL_FMPI2C_STATE_READY
;
3819 hfmpi2c
->PreviousState
= FMPI2C_STATE_MASTER_BUSY_TX
;
3820 hfmpi2c
->XferISR
= NULL
;
3822 /* Disable Interrupts */
3823 FMPI2C_Disable_IRQ(hfmpi2c
, FMPI2C_XFER_TX_IT
);
3825 /* Process Unlocked */
3826 __HAL_UNLOCK(hfmpi2c
);
3828 /* Call the corresponding callback to inform upper layer of End of Transfer */
3829 HAL_FMPI2C_MasterTxCpltCallback(hfmpi2c
);
3831 /* hfmpi2c->State == HAL_FMPI2C_STATE_BUSY_RX */
3834 hfmpi2c
->State
= HAL_FMPI2C_STATE_READY
;
3835 hfmpi2c
->PreviousState
= FMPI2C_STATE_MASTER_BUSY_RX
;
3836 hfmpi2c
->XferISR
= NULL
;
3838 /* Disable Interrupts */
3839 FMPI2C_Disable_IRQ(hfmpi2c
, FMPI2C_XFER_RX_IT
);
3841 /* Process Unlocked */
3842 __HAL_UNLOCK(hfmpi2c
);
3844 /* Call the corresponding callback to inform upper layer of End of Transfer */
3845 HAL_FMPI2C_MasterRxCpltCallback(hfmpi2c
);
3850 * @brief FMPI2C Slave sequential complete process.
3851 * @param hfmpi2c FMPI2C handle.
3854 static void FMPI2C_ITSlaveSequentialCplt(FMPI2C_HandleTypeDef
*hfmpi2c
)
3856 /* Reset FMPI2C handle mode */
3857 hfmpi2c
->Mode
= HAL_FMPI2C_MODE_NONE
;
3859 if(hfmpi2c
->State
== HAL_FMPI2C_STATE_BUSY_TX_LISTEN
)
3861 /* Remove HAL_FMPI2C_STATE_SLAVE_BUSY_TX, keep only HAL_FMPI2C_STATE_LISTEN */
3862 hfmpi2c
->State
= HAL_FMPI2C_STATE_LISTEN
;
3863 hfmpi2c
->PreviousState
= FMPI2C_STATE_SLAVE_BUSY_TX
;
3865 /* Disable Interrupts */
3866 FMPI2C_Disable_IRQ(hfmpi2c
, FMPI2C_XFER_TX_IT
);
3868 /* Process Unlocked */
3869 __HAL_UNLOCK(hfmpi2c
);
3871 /* Call the Tx complete callback to inform upper layer of the end of transmit process */
3872 HAL_FMPI2C_SlaveTxCpltCallback(hfmpi2c
);
3875 else if(hfmpi2c
->State
== HAL_FMPI2C_STATE_BUSY_RX_LISTEN
)
3877 /* Remove HAL_FMPI2C_STATE_SLAVE_BUSY_RX, keep only HAL_FMPI2C_STATE_LISTEN */
3878 hfmpi2c
->State
= HAL_FMPI2C_STATE_LISTEN
;
3879 hfmpi2c
->PreviousState
= FMPI2C_STATE_SLAVE_BUSY_RX
;
3881 /* Disable Interrupts */
3882 FMPI2C_Disable_IRQ(hfmpi2c
, FMPI2C_XFER_RX_IT
);
3884 /* Process Unlocked */
3885 __HAL_UNLOCK(hfmpi2c
);
3887 /* Call the Rx complete callback to inform upper layer of the end of receive process */
3888 HAL_FMPI2C_SlaveRxCpltCallback(hfmpi2c
);
3893 * @brief FMPI2C Master complete process.
3894 * @param hfmpi2c FMPI2C handle.
3895 * @param ITFlags Interrupt flags to handle.
3898 static void FMPI2C_ITMasterCplt(FMPI2C_HandleTypeDef
*hfmpi2c
, uint32_t ITFlags
)
3900 /* Clear STOP Flag */
3901 __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c
, FMPI2C_FLAG_STOPF
);
3903 /* Clear Configuration Register 2 */
3904 FMPI2C_RESET_CR2(hfmpi2c
);
3906 /* Reset handle parameters */
3907 hfmpi2c
->PreviousState
= FMPI2C_STATE_NONE
;
3908 hfmpi2c
->XferISR
= NULL
;
3909 hfmpi2c
->XferOptions
= FMPI2C_NO_OPTION_FRAME
;
3911 if((ITFlags
& FMPI2C_FLAG_AF
) != RESET
)
3913 /* Clear NACK Flag */
3914 __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c
, FMPI2C_FLAG_AF
);
3916 /* Set acknowledge error code */
3917 hfmpi2c
->ErrorCode
|= HAL_FMPI2C_ERROR_AF
;
3920 /* Flush TX register */
3921 FMPI2C_Flush_TXDR(hfmpi2c
);
3923 /* Disable Interrupts */
3924 FMPI2C_Disable_IRQ(hfmpi2c
, FMPI2C_XFER_TX_IT
| FMPI2C_XFER_RX_IT
);
3926 /* Call the corresponding callback to inform upper layer of End of Transfer */
3927 if((hfmpi2c
->ErrorCode
!= HAL_FMPI2C_ERROR_NONE
) || (hfmpi2c
->State
== HAL_FMPI2C_STATE_ABORT
))
3929 /* Call the corresponding callback to inform upper layer of End of Transfer */
3930 FMPI2C_ITError(hfmpi2c
, hfmpi2c
->ErrorCode
);
3932 /* hfmpi2c->State == HAL_FMPI2C_STATE_BUSY_TX */
3933 else if(hfmpi2c
->State
== HAL_FMPI2C_STATE_BUSY_TX
)
3935 hfmpi2c
->State
= HAL_FMPI2C_STATE_READY
;
3937 if (hfmpi2c
->Mode
== HAL_FMPI2C_MODE_MEM
)
3939 hfmpi2c
->Mode
= HAL_FMPI2C_MODE_NONE
;
3941 /* Process Unlocked */
3942 __HAL_UNLOCK(hfmpi2c
);
3944 /* Call the corresponding callback to inform upper layer of End of Transfer */
3945 HAL_FMPI2C_MemTxCpltCallback(hfmpi2c
);
3949 hfmpi2c
->Mode
= HAL_FMPI2C_MODE_NONE
;
3951 /* Process Unlocked */
3952 __HAL_UNLOCK(hfmpi2c
);
3954 /* Call the corresponding callback to inform upper layer of End of Transfer */
3955 HAL_FMPI2C_MasterTxCpltCallback(hfmpi2c
);
3958 /* hfmpi2c->State == HAL_FMPI2C_STATE_BUSY_RX */
3959 else if(hfmpi2c
->State
== HAL_FMPI2C_STATE_BUSY_RX
)
3961 hfmpi2c
->State
= HAL_FMPI2C_STATE_READY
;
3963 if (hfmpi2c
->Mode
== HAL_FMPI2C_MODE_MEM
)
3965 hfmpi2c
->Mode
= HAL_FMPI2C_MODE_NONE
;
3967 /* Process Unlocked */
3968 __HAL_UNLOCK(hfmpi2c
);
3970 HAL_FMPI2C_MemRxCpltCallback(hfmpi2c
);
3974 hfmpi2c
->Mode
= HAL_FMPI2C_MODE_NONE
;
3976 /* Process Unlocked */
3977 __HAL_UNLOCK(hfmpi2c
);
3979 HAL_FMPI2C_MasterRxCpltCallback(hfmpi2c
);
3985 * @brief FMPI2C Slave complete process.
3986 * @param hfmpi2c FMPI2C handle.
3987 * @param ITFlags Interrupt flags to handle.
3990 static void FMPI2C_ITSlaveCplt(FMPI2C_HandleTypeDef
*hfmpi2c
, uint32_t ITFlags
)
3992 /* Clear STOP Flag */
3993 __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c
, FMPI2C_FLAG_STOPF
);
3995 /* Clear ADDR flag */
3996 __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c
,FMPI2C_FLAG_ADDR
);
3998 /* Disable all interrupts */
3999 FMPI2C_Disable_IRQ(hfmpi2c
, FMPI2C_XFER_LISTEN_IT
| FMPI2C_XFER_TX_IT
| FMPI2C_XFER_RX_IT
);
4001 /* Disable Address Acknowledge */
4002 hfmpi2c
->Instance
->CR2
|= FMPI2C_CR2_NACK
;
4004 /* Clear Configuration Register 2 */
4005 FMPI2C_RESET_CR2(hfmpi2c
);
4007 /* Flush TX register */
4008 FMPI2C_Flush_TXDR(hfmpi2c
);
4010 /* If a DMA is ongoing, Update handle size context */
4011 if(((hfmpi2c
->Instance
->CR1
& FMPI2C_CR1_TXDMAEN
) == FMPI2C_CR1_TXDMAEN
) ||
4012 ((hfmpi2c
->Instance
->CR1
& FMPI2C_CR1_RXDMAEN
) == FMPI2C_CR1_RXDMAEN
))
4014 hfmpi2c
->XferCount
= FMPI2C_GET_DMA_REMAIN_DATA(hfmpi2c
);
4017 /* All data are not transferred, so set error code accordingly */
4018 if(hfmpi2c
->XferCount
!= 0U)
4020 /* Set ErrorCode corresponding to a Non-Acknowledge */
4021 hfmpi2c
->ErrorCode
|= HAL_FMPI2C_ERROR_AF
;
4024 /* Store Last receive data if any */
4025 if(((ITFlags
& FMPI2C_FLAG_RXNE
) != RESET
))
4027 /* Read data from RXDR */
4028 (*hfmpi2c
->pBuffPtr
++) = hfmpi2c
->Instance
->RXDR
;
4030 if((hfmpi2c
->XferSize
> 0U))
4032 hfmpi2c
->XferSize
--;
4033 hfmpi2c
->XferCount
--;
4035 /* Set ErrorCode corresponding to a Non-Acknowledge */
4036 hfmpi2c
->ErrorCode
|= HAL_FMPI2C_ERROR_AF
;
4040 hfmpi2c
->PreviousState
= FMPI2C_STATE_NONE
;
4041 hfmpi2c
->Mode
= HAL_FMPI2C_MODE_NONE
;
4042 hfmpi2c
->XferISR
= NULL
;
4044 if(hfmpi2c
->ErrorCode
!= HAL_FMPI2C_ERROR_NONE
)
4046 /* Call the corresponding callback to inform upper layer of End of Transfer */
4047 FMPI2C_ITError(hfmpi2c
, hfmpi2c
->ErrorCode
);
4049 /* Call the Listen Complete callback, to inform upper layer of the end of Listen usecase */
4050 if(hfmpi2c
->State
== HAL_FMPI2C_STATE_LISTEN
)
4052 /* Call FMPI2C Listen complete process */
4053 FMPI2C_ITListenCplt(hfmpi2c
, ITFlags
);
4056 else if(hfmpi2c
->XferOptions
!= FMPI2C_NO_OPTION_FRAME
)
4058 hfmpi2c
->XferOptions
= FMPI2C_NO_OPTION_FRAME
;
4059 hfmpi2c
->State
= HAL_FMPI2C_STATE_READY
;
4061 /* Process Unlocked */
4062 __HAL_UNLOCK(hfmpi2c
);
4064 /* Call the Listen Complete callback, to inform upper layer of the end of Listen usecase */
4065 HAL_FMPI2C_ListenCpltCallback(hfmpi2c
);
4067 /* Call the corresponding callback to inform upper layer of End of Transfer */
4068 else if(hfmpi2c
->State
== HAL_FMPI2C_STATE_BUSY_RX
)
4070 hfmpi2c
->State
= HAL_FMPI2C_STATE_READY
;
4072 /* Process Unlocked */
4073 __HAL_UNLOCK(hfmpi2c
);
4075 /* Call the Slave Rx Complete callback */
4076 HAL_FMPI2C_SlaveRxCpltCallback(hfmpi2c
);
4080 hfmpi2c
->State
= HAL_FMPI2C_STATE_READY
;
4082 /* Process Unlocked */
4083 __HAL_UNLOCK(hfmpi2c
);
4085 /* Call the Slave Tx Complete callback */
4086 HAL_FMPI2C_SlaveTxCpltCallback(hfmpi2c
);
4091 * @brief FMPI2C Listen complete process.
4092 * @param hfmpi2c FMPI2C handle.
4093 * @param ITFlags Interrupt flags to handle.
4096 static void FMPI2C_ITListenCplt(FMPI2C_HandleTypeDef
*hfmpi2c
, uint32_t ITFlags
)
4098 /* Reset handle parameters */
4099 hfmpi2c
->XferOptions
= FMPI2C_NO_OPTION_FRAME
;
4100 hfmpi2c
->PreviousState
= FMPI2C_STATE_NONE
;
4101 hfmpi2c
->State
= HAL_FMPI2C_STATE_READY
;
4102 hfmpi2c
->Mode
= HAL_FMPI2C_MODE_NONE
;
4103 hfmpi2c
->XferISR
= NULL
;
4105 /* Store Last receive data if any */
4106 if(((ITFlags
& FMPI2C_FLAG_RXNE
) != RESET
))
4108 /* Read data from RXDR */
4109 (*hfmpi2c
->pBuffPtr
++) = hfmpi2c
->Instance
->RXDR
;
4111 if((hfmpi2c
->XferSize
> 0U))
4113 hfmpi2c
->XferSize
--;
4114 hfmpi2c
->XferCount
--;
4116 /* Set ErrorCode corresponding to a Non-Acknowledge */
4117 hfmpi2c
->ErrorCode
|= HAL_FMPI2C_ERROR_AF
;
4121 /* Disable all Interrupts*/
4122 FMPI2C_Disable_IRQ(hfmpi2c
, FMPI2C_XFER_LISTEN_IT
| FMPI2C_XFER_RX_IT
| FMPI2C_XFER_TX_IT
);
4124 /* Clear NACK Flag */
4125 __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c
, FMPI2C_FLAG_AF
);
4127 /* Process Unlocked */
4128 __HAL_UNLOCK(hfmpi2c
);
4130 /* Call the Listen Complete callback, to inform upper layer of the end of Listen usecase */
4131 HAL_FMPI2C_ListenCpltCallback(hfmpi2c
);
4135 * @brief FMPI2C interrupts error process.
4136 * @param hfmpi2c FMPI2C handle.
4137 * @param ErrorCode Error code to handle.
4140 static void FMPI2C_ITError(FMPI2C_HandleTypeDef
*hfmpi2c
, uint32_t ErrorCode
)
4142 /* Reset handle parameters */
4143 hfmpi2c
->Mode
= HAL_FMPI2C_MODE_NONE
;
4144 hfmpi2c
->XferOptions
= FMPI2C_NO_OPTION_FRAME
;
4145 hfmpi2c
->XferCount
= 0U;
4147 /* Set new error code */
4148 hfmpi2c
->ErrorCode
|= ErrorCode
;
4150 /* Disable Interrupts */
4151 if((hfmpi2c
->State
== HAL_FMPI2C_STATE_LISTEN
) ||
4152 (hfmpi2c
->State
== HAL_FMPI2C_STATE_BUSY_TX_LISTEN
) ||
4153 (hfmpi2c
->State
== HAL_FMPI2C_STATE_BUSY_RX_LISTEN
))
4155 /* Disable all interrupts, except interrupts related to LISTEN state */
4156 FMPI2C_Disable_IRQ(hfmpi2c
, FMPI2C_XFER_RX_IT
| FMPI2C_XFER_TX_IT
);
4158 /* keep HAL_FMPI2C_STATE_LISTEN if set */
4159 hfmpi2c
->State
= HAL_FMPI2C_STATE_LISTEN
;
4160 hfmpi2c
->PreviousState
= FMPI2C_STATE_NONE
;
4161 hfmpi2c
->XferISR
= FMPI2C_Slave_ISR_IT
;
4165 /* Disable all interrupts */
4166 FMPI2C_Disable_IRQ(hfmpi2c
, FMPI2C_XFER_LISTEN_IT
| FMPI2C_XFER_RX_IT
| FMPI2C_XFER_TX_IT
);
4168 /* If state is an abort treatment on goind, don't change state */
4169 /* This change will be do later */
4170 if(hfmpi2c
->State
!= HAL_FMPI2C_STATE_ABORT
)
4172 /* Set HAL_FMPI2C_STATE_READY */
4173 hfmpi2c
->State
= HAL_FMPI2C_STATE_READY
;
4175 hfmpi2c
->PreviousState
= FMPI2C_STATE_NONE
;
4176 hfmpi2c
->XferISR
= NULL
;
4179 /* Abort DMA TX transfer if any */
4180 if((hfmpi2c
->Instance
->CR1
& FMPI2C_CR1_TXDMAEN
) == FMPI2C_CR1_TXDMAEN
)
4182 hfmpi2c
->Instance
->CR1
&= ~FMPI2C_CR1_TXDMAEN
;
4184 /* Set the FMPI2C DMA Abort callback :
4185 will lead to call HAL_FMPI2C_ErrorCallback() at end of DMA abort procedure */
4186 hfmpi2c
->hdmatx
->XferAbortCallback
= FMPI2C_DMAAbort
;
4188 /* Process Unlocked */
4189 __HAL_UNLOCK(hfmpi2c
);
4191 if(HAL_DMA_Abort_IT(hfmpi2c
->hdmatx
) != HAL_OK
)
4193 /* Call Directly XferAbortCallback function in case of error */
4194 hfmpi2c
->hdmatx
->XferAbortCallback(hfmpi2c
->hdmatx
);
4197 /* Abort DMA RX transfer if any */
4198 else if((hfmpi2c
->Instance
->CR1
& FMPI2C_CR1_RXDMAEN
) == FMPI2C_CR1_RXDMAEN
)
4200 hfmpi2c
->Instance
->CR1
&= ~FMPI2C_CR1_RXDMAEN
;
4202 /* Set the FMPI2C DMA Abort callback :
4203 will lead to call HAL_FMPI2C_ErrorCallback() at end of DMA abort procedure */
4204 hfmpi2c
->hdmarx
->XferAbortCallback
= FMPI2C_DMAAbort
;
4206 /* Process Unlocked */
4207 __HAL_UNLOCK(hfmpi2c
);
4209 if(HAL_DMA_Abort_IT(hfmpi2c
->hdmarx
) != HAL_OK
)
4211 /* Call Directly XferAbortCallback function in case of error */
4212 hfmpi2c
->hdmarx
->XferAbortCallback(hfmpi2c
->hdmarx
);
4215 else if(hfmpi2c
->State
== HAL_FMPI2C_STATE_ABORT
)
4217 hfmpi2c
->State
= HAL_FMPI2C_STATE_READY
;
4219 /* Process Unlocked */
4220 __HAL_UNLOCK(hfmpi2c
);
4222 /* Call the corresponding callback to inform upper layer of End of Transfer */
4223 HAL_FMPI2C_AbortCpltCallback(hfmpi2c
);
4227 /* Process Unlocked */
4228 __HAL_UNLOCK(hfmpi2c
);
4230 /* Call the corresponding callback to inform upper layer of End of Transfer */
4231 HAL_FMPI2C_ErrorCallback(hfmpi2c
);
4236 * @brief FMPI2C Tx data register flush process.
4237 * @param hfmpi2c FMPI2C handle.
4240 static void FMPI2C_Flush_TXDR(FMPI2C_HandleTypeDef
*hfmpi2c
)
4242 /* If a pending TXIS flag is set */
4243 /* Write a dummy data in TXDR to clear it */
4244 if(__HAL_FMPI2C_GET_FLAG(hfmpi2c
, FMPI2C_FLAG_TXIS
) != RESET
)
4246 hfmpi2c
->Instance
->TXDR
= 0x00U
;
4249 /* Flush TX register if not empty */
4250 if(__HAL_FMPI2C_GET_FLAG(hfmpi2c
, FMPI2C_FLAG_TXE
) == RESET
)
4252 __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c
, FMPI2C_FLAG_TXE
);
4257 * @brief DMA FMPI2C master transmit process complete callback.
4258 * @param hdma DMA handle
4261 static void FMPI2C_DMAMasterTransmitCplt(DMA_HandleTypeDef
*hdma
)
4263 FMPI2C_HandleTypeDef
* hfmpi2c
= (FMPI2C_HandleTypeDef
*)((DMA_HandleTypeDef
*)hdma
)->Parent
;
4265 /* Disable DMA Request */
4266 hfmpi2c
->Instance
->CR1
&= ~FMPI2C_CR1_TXDMAEN
;
4268 /* If last transfer, enable STOP interrupt */
4269 if(hfmpi2c
->XferCount
== 0U)
4271 /* Enable STOP interrupt */
4272 FMPI2C_Enable_IRQ(hfmpi2c
, FMPI2C_XFER_CPLT_IT
);
4274 /* else prepare a new DMA transfer and enable TCReload interrupt */
4277 /* Update Buffer pointer */
4278 hfmpi2c
->pBuffPtr
+= hfmpi2c
->XferSize
;
4280 /* Set the XferSize to transfer */
4281 if(hfmpi2c
->XferCount
> MAX_NBYTE_SIZE
)
4283 hfmpi2c
->XferSize
= MAX_NBYTE_SIZE
;
4287 hfmpi2c
->XferSize
= hfmpi2c
->XferCount
;
4290 /* Enable the DMA channel */
4291 HAL_DMA_Start_IT(hfmpi2c
->hdmatx
, (uint32_t)hfmpi2c
->pBuffPtr
, (uint32_t)&hfmpi2c
->Instance
->TXDR
, hfmpi2c
->XferSize
);
4293 /* Enable TC interrupts */
4294 FMPI2C_Enable_IRQ(hfmpi2c
, FMPI2C_XFER_RELOAD_IT
);
4299 * @brief DMA FMPI2C slave transmit process complete callback.
4300 * @param hdma DMA handle
4303 static void FMPI2C_DMASlaveTransmitCplt(DMA_HandleTypeDef
*hdma
)
4305 /* No specific action, Master fully manage the generation of STOP condition */
4306 /* Mean that this generation can arrive at any time, at the end or during DMA process */
4307 /* So STOP condition should be manage through Interrupt treatment */
4311 * @brief DMA FMPI2C master receive process complete callback.
4312 * @param hdma DMA handle
4315 static void FMPI2C_DMAMasterReceiveCplt(DMA_HandleTypeDef
*hdma
)
4317 FMPI2C_HandleTypeDef
* hfmpi2c
= (FMPI2C_HandleTypeDef
*)((DMA_HandleTypeDef
*)hdma
)->Parent
;
4319 /* Disable DMA Request */
4320 hfmpi2c
->Instance
->CR1
&= ~FMPI2C_CR1_RXDMAEN
;
4322 /* If last transfer, enable STOP interrupt */
4323 if(hfmpi2c
->XferCount
== 0U)
4325 /* Enable STOP interrupt */
4326 FMPI2C_Enable_IRQ(hfmpi2c
, FMPI2C_XFER_CPLT_IT
);
4328 /* else prepare a new DMA transfer and enable TCReload interrupt */
4331 /* Update Buffer pointer */
4332 hfmpi2c
->pBuffPtr
+= hfmpi2c
->XferSize
;
4334 /* Set the XferSize to transfer */
4335 if(hfmpi2c
->XferCount
> MAX_NBYTE_SIZE
)
4337 hfmpi2c
->XferSize
= MAX_NBYTE_SIZE
;
4341 hfmpi2c
->XferSize
= hfmpi2c
->XferCount
;
4344 /* Enable the DMA channel */
4345 HAL_DMA_Start_IT(hfmpi2c
->hdmarx
, (uint32_t)&hfmpi2c
->Instance
->RXDR
, (uint32_t)hfmpi2c
->pBuffPtr
, hfmpi2c
->XferSize
);
4347 /* Enable TC interrupts */
4348 FMPI2C_Enable_IRQ(hfmpi2c
, FMPI2C_XFER_RELOAD_IT
);
4353 * @brief DMA FMPI2C slave receive process complete callback.
4354 * @param hdma DMA handle
4357 static void FMPI2C_DMASlaveReceiveCplt(DMA_HandleTypeDef
*hdma
)
4359 /* No specific action, Master fully manage the generation of STOP condition */
4360 /* Mean that this generation can arrive at any time, at the end or during DMA process */
4361 /* So STOP condition should be manage through Interrupt treatment */
4365 * @brief DMA FMPI2C communication error callback.
4366 * @param hdma DMA handle
4369 static void FMPI2C_DMAError(DMA_HandleTypeDef
*hdma
)
4371 FMPI2C_HandleTypeDef
* hfmpi2c
= ( FMPI2C_HandleTypeDef
* )((DMA_HandleTypeDef
* )hdma
)->Parent
;
4373 /* Disable Acknowledge */
4374 hfmpi2c
->Instance
->CR2
|= FMPI2C_CR2_NACK
;
4376 /* Call the corresponding callback to inform upper layer of End of Transfer */
4377 FMPI2C_ITError(hfmpi2c
, HAL_FMPI2C_ERROR_DMA
);
4381 * @brief DMA FMPI2C communication abort callback
4382 * (To be called at end of DMA Abort procedure).
4383 * @param hdma: DMA handle.
4386 static void FMPI2C_DMAAbort(DMA_HandleTypeDef
*hdma
)
4388 FMPI2C_HandleTypeDef
* hfmpi2c
= ( FMPI2C_HandleTypeDef
* )((DMA_HandleTypeDef
* )hdma
)->Parent
;
4390 /* Disable Acknowledge */
4391 hfmpi2c
->Instance
->CR2
|= FMPI2C_CR2_NACK
;
4393 /* Reset AbortCpltCallback */
4394 hfmpi2c
->hdmatx
->XferAbortCallback
= NULL
;
4395 hfmpi2c
->hdmarx
->XferAbortCallback
= NULL
;
4397 /* Check if come from abort from user */
4398 if(hfmpi2c
->State
== HAL_FMPI2C_STATE_ABORT
)
4400 hfmpi2c
->State
= HAL_FMPI2C_STATE_READY
;
4402 /* Call the corresponding callback to inform upper layer of End of Transfer */
4403 HAL_FMPI2C_AbortCpltCallback(hfmpi2c
);
4407 /* Call the corresponding callback to inform upper layer of End of Transfer */
4408 HAL_FMPI2C_ErrorCallback(hfmpi2c
);
4413 * @brief This function handles FMPI2C Communication Timeout.
4414 * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains
4415 * the configuration information for the specified FMPI2C.
4416 * @param Flag Specifies the FMPI2C flag to check.
4417 * @param Status The new Flag status (SET or RESET).
4418 * @param Timeout Timeout duration
4419 * @param Tickstart Tick start value
4420 * @retval HAL status
4422 static HAL_StatusTypeDef
FMPI2C_WaitOnFlagUntilTimeout(FMPI2C_HandleTypeDef
*hfmpi2c
, uint32_t Flag
, FlagStatus Status
, uint32_t Timeout
, uint32_t Tickstart
)
4424 while(__HAL_FMPI2C_GET_FLAG(hfmpi2c
, Flag
) == Status
)
4426 /* Check for the Timeout */
4427 if(Timeout
!= HAL_MAX_DELAY
)
4429 if((Timeout
== 0U)||((HAL_GetTick() - Tickstart
) > Timeout
))
4431 hfmpi2c
->State
= HAL_FMPI2C_STATE_READY
;
4432 hfmpi2c
->Mode
= HAL_FMPI2C_MODE_NONE
;
4434 /* Process Unlocked */
4435 __HAL_UNLOCK(hfmpi2c
);
4444 * @brief This function handles FMPI2C Communication Timeout for specific usage of TXIS flag.
4445 * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains
4446 * the configuration information for the specified FMPI2C.
4447 * @param Timeout Timeout duration
4448 * @param Tickstart Tick start value
4449 * @retval HAL status
4451 static HAL_StatusTypeDef
FMPI2C_WaitOnTXISFlagUntilTimeout(FMPI2C_HandleTypeDef
*hfmpi2c
, uint32_t Timeout
, uint32_t Tickstart
)
4453 while(__HAL_FMPI2C_GET_FLAG(hfmpi2c
, FMPI2C_FLAG_TXIS
) == RESET
)
4455 /* Check if a NACK is detected */
4456 if(FMPI2C_IsAcknowledgeFailed(hfmpi2c
, Timeout
, Tickstart
) != HAL_OK
)
4461 /* Check for the Timeout */
4462 if(Timeout
!= HAL_MAX_DELAY
)
4464 if((Timeout
== 0U)||((HAL_GetTick() - Tickstart
) > Timeout
))
4466 hfmpi2c
->ErrorCode
|= HAL_FMPI2C_ERROR_TIMEOUT
;
4467 hfmpi2c
->State
= HAL_FMPI2C_STATE_READY
;
4468 hfmpi2c
->Mode
= HAL_FMPI2C_MODE_NONE
;
4470 /* Process Unlocked */
4471 __HAL_UNLOCK(hfmpi2c
);
4481 * @brief This function handles FMPI2C Communication Timeout for specific usage of STOP flag.
4482 * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains
4483 * the configuration information for the specified FMPI2C.
4484 * @param Timeout Timeout duration
4485 * @param Tickstart Tick start value
4486 * @retval HAL status
4488 static HAL_StatusTypeDef
FMPI2C_WaitOnSTOPFlagUntilTimeout(FMPI2C_HandleTypeDef
*hfmpi2c
, uint32_t Timeout
, uint32_t Tickstart
)
4490 while(__HAL_FMPI2C_GET_FLAG(hfmpi2c
, FMPI2C_FLAG_STOPF
) == RESET
)
4492 /* Check if a NACK is detected */
4493 if(FMPI2C_IsAcknowledgeFailed(hfmpi2c
, Timeout
, Tickstart
) != HAL_OK
)
4498 /* Check for the Timeout */
4499 if((Timeout
== 0U)||((HAL_GetTick() - Tickstart
) > Timeout
))
4501 hfmpi2c
->ErrorCode
|= HAL_FMPI2C_ERROR_TIMEOUT
;
4502 hfmpi2c
->State
= HAL_FMPI2C_STATE_READY
;
4503 hfmpi2c
->Mode
= HAL_FMPI2C_MODE_NONE
;
4505 /* Process Unlocked */
4506 __HAL_UNLOCK(hfmpi2c
);
4515 * @brief This function handles FMPI2C Communication Timeout for specific usage of RXNE flag.
4516 * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains
4517 * the configuration information for the specified FMPI2C.
4518 * @param Timeout Timeout duration
4519 * @param Tickstart Tick start value
4520 * @retval HAL status
4522 static HAL_StatusTypeDef
FMPI2C_WaitOnRXNEFlagUntilTimeout(FMPI2C_HandleTypeDef
*hfmpi2c
, uint32_t Timeout
, uint32_t Tickstart
)
4524 while(__HAL_FMPI2C_GET_FLAG(hfmpi2c
, FMPI2C_FLAG_RXNE
) == RESET
)
4526 /* Check if a NACK is detected */
4527 if(FMPI2C_IsAcknowledgeFailed(hfmpi2c
, Timeout
, Tickstart
) != HAL_OK
)
4532 /* Check if a STOPF is detected */
4533 if(__HAL_FMPI2C_GET_FLAG(hfmpi2c
, FMPI2C_FLAG_STOPF
) == SET
)
4535 /* Clear STOP Flag */
4536 __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c
, FMPI2C_FLAG_STOPF
);
4538 /* Clear Configuration Register 2 */
4539 FMPI2C_RESET_CR2(hfmpi2c
);
4541 hfmpi2c
->ErrorCode
= HAL_FMPI2C_ERROR_NONE
;
4542 hfmpi2c
->State
= HAL_FMPI2C_STATE_READY
;
4543 hfmpi2c
->Mode
= HAL_FMPI2C_MODE_NONE
;
4545 /* Process Unlocked */
4546 __HAL_UNLOCK(hfmpi2c
);
4551 /* Check for the Timeout */
4552 if((Timeout
== 0U)||((HAL_GetTick() - Tickstart
) > Timeout
))
4554 hfmpi2c
->ErrorCode
|= HAL_FMPI2C_ERROR_TIMEOUT
;
4555 hfmpi2c
->State
= HAL_FMPI2C_STATE_READY
;
4557 /* Process Unlocked */
4558 __HAL_UNLOCK(hfmpi2c
);
4567 * @brief This function handles Acknowledge failed detection during an FMPI2C Communication.
4568 * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains
4569 * the configuration information for the specified FMPI2C.
4570 * @param Timeout Timeout duration
4571 * @param Tickstart Tick start value
4572 * @retval HAL status
4574 static HAL_StatusTypeDef
FMPI2C_IsAcknowledgeFailed(FMPI2C_HandleTypeDef
*hfmpi2c
, uint32_t Timeout
, uint32_t Tickstart
)
4576 if(__HAL_FMPI2C_GET_FLAG(hfmpi2c
, FMPI2C_FLAG_AF
) == SET
)
4578 /* Wait until STOP Flag is reset */
4579 /* AutoEnd should be initiate after AF */
4580 while(__HAL_FMPI2C_GET_FLAG(hfmpi2c
, FMPI2C_FLAG_STOPF
) == RESET
)
4582 /* Check for the Timeout */
4583 if(Timeout
!= HAL_MAX_DELAY
)
4585 if((Timeout
== 0U)||((HAL_GetTick() - Tickstart
) > Timeout
))
4587 hfmpi2c
->State
= HAL_FMPI2C_STATE_READY
;
4588 hfmpi2c
->Mode
= HAL_FMPI2C_MODE_NONE
;
4590 /* Process Unlocked */
4591 __HAL_UNLOCK(hfmpi2c
);
4597 /* Clear NACKF Flag */
4598 __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c
, FMPI2C_FLAG_AF
);
4600 /* Clear STOP Flag */
4601 __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c
, FMPI2C_FLAG_STOPF
);
4603 /* Flush TX register */
4604 FMPI2C_Flush_TXDR(hfmpi2c
);
4606 /* Clear Configuration Register 2 */
4607 FMPI2C_RESET_CR2(hfmpi2c
);
4609 hfmpi2c
->ErrorCode
= HAL_FMPI2C_ERROR_AF
;
4610 hfmpi2c
->State
= HAL_FMPI2C_STATE_READY
;
4611 hfmpi2c
->Mode
= HAL_FMPI2C_MODE_NONE
;
4613 /* Process Unlocked */
4614 __HAL_UNLOCK(hfmpi2c
);
4622 * @brief Handles FMPI2Cx communication when starting transfer or during transfer (TC or TCR flag are set).
4623 * @param hfmpi2c FMPI2C handle.
4624 * @param DevAddress Specifies the slave address to be programmed.
4625 * @param Size Specifies the number of bytes to be programmed.
4626 * This parameter must be a value between 0 and 255.
4627 * @param Mode New state of the FMPI2C START condition generation.
4628 * This parameter can be one of the following values:
4629 * @arg @ref FMPI2C_RELOAD_MODE Enable Reload mode .
4630 * @arg @ref FMPI2C_AUTOEND_MODE Enable Automatic end mode.
4631 * @arg @ref FMPI2C_SOFTEND_MODE Enable Software end mode.
4632 * @param Request New state of the FMPI2C START condition generation.
4633 * This parameter can be one of the following values:
4634 * @arg @ref FMPI2C_NO_STARTSTOP Don't Generate stop and start condition.
4635 * @arg @ref FMPI2C_GENERATE_STOP Generate stop condition (Size should be set to 0).
4636 * @arg @ref FMPI2C_GENERATE_START_READ Generate Restart for read request.
4637 * @arg @ref FMPI2C_GENERATE_START_WRITE Generate Restart for write request.
4640 static void FMPI2C_TransferConfig(FMPI2C_HandleTypeDef
*hfmpi2c
, uint16_t DevAddress
, uint8_t Size
, uint32_t Mode
, uint32_t Request
)
4642 uint32_t tmpreg
= 0U;
4644 /* Check the parameters */
4645 assert_param(IS_FMPI2C_ALL_INSTANCE(hfmpi2c
->Instance
));
4646 assert_param(IS_TRANSFER_MODE(Mode
));
4647 assert_param(IS_TRANSFER_REQUEST(Request
));
4649 /* Get the CR2 register value */
4650 tmpreg
= hfmpi2c
->Instance
->CR2
;
4652 /* clear tmpreg specific bits */
4653 tmpreg
&= (uint32_t)~((uint32_t)(FMPI2C_CR2_SADD
| FMPI2C_CR2_NBYTES
| FMPI2C_CR2_RELOAD
| FMPI2C_CR2_AUTOEND
| FMPI2C_CR2_RD_WRN
| FMPI2C_CR2_START
| FMPI2C_CR2_STOP
));
4656 tmpreg
|= (uint32_t)(((uint32_t)DevAddress
& FMPI2C_CR2_SADD
) | (((uint32_t)Size
<< 16U) & FMPI2C_CR2_NBYTES
) | \
4657 (uint32_t)Mode
| (uint32_t)Request
);
4659 /* update CR2 register */
4660 hfmpi2c
->Instance
->CR2
= tmpreg
;
4664 * @brief Manage the enabling of Interrupts.
4665 * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains
4666 * the configuration information for the specified FMPI2C.
4667 * @param InterruptRequest Value of @ref FMPI2C_Interrupt_configuration_definition.
4668 * @retval HAL status
4670 static HAL_StatusTypeDef
FMPI2C_Enable_IRQ(FMPI2C_HandleTypeDef
*hfmpi2c
, uint16_t InterruptRequest
)
4672 uint32_t tmpisr
= 0U;
4674 if((hfmpi2c
->XferISR
== FMPI2C_Master_ISR_DMA
) || \
4675 (hfmpi2c
->XferISR
== FMPI2C_Slave_ISR_DMA
))
4677 if((InterruptRequest
& FMPI2C_XFER_LISTEN_IT
) == FMPI2C_XFER_LISTEN_IT
)
4679 /* Enable ERR, STOP, NACK and ADDR interrupts */
4680 tmpisr
|= FMPI2C_IT_ADDRI
| FMPI2C_IT_STOPI
| FMPI2C_IT_NACKI
| FMPI2C_IT_ERRI
;
4683 if((InterruptRequest
& FMPI2C_XFER_ERROR_IT
) == FMPI2C_XFER_ERROR_IT
)
4685 /* Enable ERR and NACK interrupts */
4686 tmpisr
|= FMPI2C_IT_ERRI
| FMPI2C_IT_NACKI
;
4689 if((InterruptRequest
& FMPI2C_XFER_CPLT_IT
) == FMPI2C_XFER_CPLT_IT
)
4691 /* Enable STOP interrupts */
4692 tmpisr
|= FMPI2C_IT_STOPI
;
4695 if((InterruptRequest
& FMPI2C_XFER_RELOAD_IT
) == FMPI2C_XFER_RELOAD_IT
)
4697 /* Enable TC interrupts */
4698 tmpisr
|= FMPI2C_IT_TCI
;
4703 if((InterruptRequest
& FMPI2C_XFER_LISTEN_IT
) == FMPI2C_XFER_LISTEN_IT
)
4705 /* Enable ERR, STOP, NACK, and ADDR interrupts */
4706 tmpisr
|= FMPI2C_IT_ADDRI
| FMPI2C_IT_STOPI
| FMPI2C_IT_NACKI
| FMPI2C_IT_ERRI
;
4709 if((InterruptRequest
& FMPI2C_XFER_TX_IT
) == FMPI2C_XFER_TX_IT
)
4711 /* Enable ERR, TC, STOP, NACK and RXI interrupts */
4712 tmpisr
|= FMPI2C_IT_ERRI
| FMPI2C_IT_TCI
| FMPI2C_IT_STOPI
| FMPI2C_IT_NACKI
| FMPI2C_IT_TXI
;
4715 if((InterruptRequest
& FMPI2C_XFER_RX_IT
) == FMPI2C_XFER_RX_IT
)
4717 /* Enable ERR, TC, STOP, NACK and TXI interrupts */
4718 tmpisr
|= FMPI2C_IT_ERRI
| FMPI2C_IT_TCI
| FMPI2C_IT_STOPI
| FMPI2C_IT_NACKI
| FMPI2C_IT_RXI
;
4721 if((InterruptRequest
& FMPI2C_XFER_CPLT_IT
) == FMPI2C_XFER_CPLT_IT
)
4723 /* Enable STOP interrupts */
4724 tmpisr
|= FMPI2C_IT_STOPI
;
4728 /* Enable interrupts only at the end */
4729 /* to avoid the risk of FMPI2C interrupt handle execution before */
4730 /* all interrupts requested done */
4731 __HAL_FMPI2C_ENABLE_IT(hfmpi2c
, tmpisr
);
4737 * @brief Manage the disabling of Interrupts.
4738 * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains
4739 * the configuration information for the specified FMPI2C.
4740 * @param InterruptRequest Value of @ref FMPI2C_Interrupt_configuration_definition.
4741 * @retval HAL status
4743 static HAL_StatusTypeDef
FMPI2C_Disable_IRQ(FMPI2C_HandleTypeDef
*hfmpi2c
, uint16_t InterruptRequest
)
4745 uint32_t tmpisr
= 0U;
4747 if((InterruptRequest
& FMPI2C_XFER_TX_IT
) == FMPI2C_XFER_TX_IT
)
4749 /* Disable TC and TXI interrupts */
4750 tmpisr
|= FMPI2C_IT_TCI
| FMPI2C_IT_TXI
;
4752 if((hfmpi2c
->State
& HAL_FMPI2C_STATE_LISTEN
) != HAL_FMPI2C_STATE_LISTEN
)
4754 /* Disable NACK and STOP interrupts */
4755 tmpisr
|= FMPI2C_IT_STOPI
| FMPI2C_IT_NACKI
| FMPI2C_IT_ERRI
;
4759 if((InterruptRequest
& FMPI2C_XFER_RX_IT
) == FMPI2C_XFER_RX_IT
)
4761 /* Disable TC and RXI interrupts */
4762 tmpisr
|= FMPI2C_IT_TCI
| FMPI2C_IT_RXI
;
4764 if((hfmpi2c
->State
& HAL_FMPI2C_STATE_LISTEN
) != HAL_FMPI2C_STATE_LISTEN
)
4766 /* Disable NACK and STOP interrupts */
4767 tmpisr
|= FMPI2C_IT_STOPI
| FMPI2C_IT_NACKI
| FMPI2C_IT_ERRI
;
4771 if((InterruptRequest
& FMPI2C_XFER_LISTEN_IT
) == FMPI2C_XFER_LISTEN_IT
)
4773 /* Disable ADDR, NACK and STOP interrupts */
4774 tmpisr
|= FMPI2C_IT_ADDRI
| FMPI2C_IT_STOPI
| FMPI2C_IT_NACKI
| FMPI2C_IT_ERRI
;
4777 if((InterruptRequest
& FMPI2C_XFER_ERROR_IT
) == FMPI2C_XFER_ERROR_IT
)
4779 /* Enable ERR and NACK interrupts */
4780 tmpisr
|= FMPI2C_IT_ERRI
| FMPI2C_IT_NACKI
;
4783 if((InterruptRequest
& FMPI2C_XFER_CPLT_IT
) == FMPI2C_XFER_CPLT_IT
)
4785 /* Enable STOP interrupts */
4786 tmpisr
|= FMPI2C_IT_STOPI
;
4789 if((InterruptRequest
& FMPI2C_XFER_RELOAD_IT
) == FMPI2C_XFER_RELOAD_IT
)
4791 /* Enable TC interrupts */
4792 tmpisr
|= FMPI2C_IT_TCI
;
4795 /* Disable interrupts only at the end */
4796 /* to avoid a breaking situation like at "t" time */
4797 /* all disable interrupts request are not done */
4798 __HAL_FMPI2C_DISABLE_IT(hfmpi2c
, tmpisr
);
4806 #endif /* STM32F410xx || STM32F446xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */
4807 #endif /* HAL_FMPI2C_MODULE_ENABLED */
4816 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/