Merge pull request #11189 from klutvott123/move-telemetry-displayport-init
[betaflight.git] / lib / main / STM32F3 / Drivers / STM32F3xx_HAL_Driver / Src / stm32f3xx_hal_smbus.c
blob3fb3f739b23aca83dbdec28003c046ca385f97a7
1 /**
2 ******************************************************************************
3 * @file stm32f3xx_hal_smbus.c
4 * @author MCD Application Team
5 * @brief SMBUS HAL module driver.
6 * This file provides firmware functions to manage the following
7 * functionalities of the System Management Bus (SMBus) peripheral,
8 * based on I2C principles of operation :
9 * + Initialization and de-initialization functions
10 * + IO operation functions
11 * + Peripheral State and Errors functions
13 @verbatim
14 ==============================================================================
15 ##### How to use this driver #####
16 ==============================================================================
17 [..]
18 The SMBUS HAL driver can be used as follows:
20 (#) Declare a SMBUS_HandleTypeDef handle structure, for example:
21 SMBUS_HandleTypeDef hsmbus;
23 (#)Initialize the SMBUS low level resources by implementing the HAL_SMBUS_MspInit() API:
24 (##) Enable the SMBUSx interface clock
25 (##) SMBUS pins configuration
26 (+++) Enable the clock for the SMBUS GPIOs
27 (+++) Configure SMBUS pins as alternate function open-drain
28 (##) NVIC configuration if you need to use interrupt process
29 (+++) Configure the SMBUSx interrupt priority
30 (+++) Enable the NVIC SMBUS IRQ Channel
32 (#) Configure the Communication Clock Timing, Bus Timeout, Own Address1, Master Addressing mode,
33 Dual Addressing mode, Own Address2, Own Address2 Mask, General call, Nostretch mode,
34 Peripheral mode and Packet Error Check mode in the hsmbus Init structure.
36 (#) Initialize the SMBUS registers by calling the HAL_SMBUS_Init() API:
37 (++) These API's configures also the low level Hardware GPIO, CLOCK, CORTEX...etc)
38 by calling the customized HAL_SMBUS_MspInit(&hsmbus) API.
40 (#) To check if target device is ready for communication, use the function HAL_SMBUS_IsDeviceReady()
42 (#) For SMBUS IO operations, only one mode of operations is available within this driver
44 *** Interrupt mode IO operation ***
45 ===================================
46 [..]
47 (+) Transmit in master/host SMBUS mode an amount of data in non-blocking mode using HAL_SMBUS_Master_Transmit_IT()
48 (++) At transmission end of transfer HAL_SMBUS_MasterTxCpltCallback() is executed and user can
49 add his own code by customization of function pointer HAL_SMBUS_MasterTxCpltCallback()
50 (+) Receive in master/host SMBUS mode an amount of data in non-blocking mode using HAL_SMBUS_Master_Receive_IT()
51 (++) At reception end of transfer HAL_SMBUS_MasterRxCpltCallback() is executed and user can
52 add his own code by customization of function pointer HAL_SMBUS_MasterRxCpltCallback()
53 (+) Abort a master/host SMBUS process communication with Interrupt using HAL_SMBUS_Master_Abort_IT()
54 (++) The associated previous transfer callback is called at the end of abort process
55 (++) mean HAL_SMBUS_MasterTxCpltCallback() in case of previous state was master transmit
56 (++) mean HAL_SMBUS_MasterRxCpltCallback() in case of previous state was master receive
57 (+) Enable/disable the Address listen mode in slave/device or host/slave SMBUS mode
58 using HAL_SMBUS_EnableListen_IT() HAL_SMBUS_DisableListen_IT()
59 (++) When address slave/device SMBUS match, HAL_SMBUS_AddrCallback() is executed and user can
60 add his own code to check the Address Match Code and the transmission direction request by master/host (Write/Read).
61 (++) At Listen mode end HAL_SMBUS_ListenCpltCallback() is executed and user can
62 add his own code by customization of function pointer HAL_SMBUS_ListenCpltCallback()
63 (+) Transmit in slave/device SMBUS mode an amount of data in non-blocking mode using HAL_SMBUS_Slave_Transmit_IT()
64 (++) At transmission end of transfer HAL_SMBUS_SlaveTxCpltCallback() is executed and user can
65 add his own code by customization of function pointer HAL_SMBUS_SlaveTxCpltCallback()
66 (+) Receive in slave/device SMBUS mode an amount of data in non-blocking mode using HAL_SMBUS_Slave_Receive_IT()
67 (++) At reception end of transfer HAL_SMBUS_SlaveRxCpltCallback() is executed and user can
68 add his own code by customization of function pointer HAL_SMBUS_SlaveRxCpltCallback()
69 (+) Enable/Disable the SMBUS alert mode using HAL_SMBUS_EnableAlert_IT() HAL_SMBUS_DisableAlert_IT()
70 (++) When SMBUS Alert is generated HAL_SMBUS_ErrorCallback() is executed and user can
71 add his own code by customization of function pointer HAL_SMBUS_ErrorCallback()
72 to check the Alert Error Code using function HAL_SMBUS_GetError()
73 (+) Get HAL state machine or error values using HAL_SMBUS_GetState() or HAL_SMBUS_GetError()
74 (+) In case of transfer Error, HAL_SMBUS_ErrorCallback() function is executed and user can
75 add his own code by customization of function pointer HAL_SMBUS_ErrorCallback()
76 to check the Error Code using function HAL_SMBUS_GetError()
78 *** SMBUS HAL driver macros list ***
79 ==================================
80 [..]
81 Below the list of most used macros in SMBUS HAL driver.
83 (+) __HAL_SMBUS_ENABLE: Enable the SMBUS peripheral
84 (+) __HAL_SMBUS_DISABLE: Disable the SMBUS peripheral
85 (+) __HAL_SMBUS_GET_FLAG: Check whether the specified SMBUS flag is set or not
86 (+) __HAL_SMBUS_CLEAR_FLAG: Clear the specified SMBUS pending flag
87 (+) __HAL_SMBUS_ENABLE_IT: Enable the specified SMBUS interrupt
88 (+) __HAL_SMBUS_DISABLE_IT: Disable the specified SMBUS interrupt
90 [..]
91 (@) You can refer to the SMBUS HAL driver header file for more useful macros
94 @endverbatim
95 ******************************************************************************
96 * @attention
98 * <h2><center>&copy; COPYRIGHT(c) 2016 STMicroelectronics</center></h2>
100 * Redistribution and use in source and binary forms, with or without modification,
101 * are permitted provided that the following conditions are met:
102 * 1. Redistributions of source code must retain the above copyright notice,
103 * this list of conditions and the following disclaimer.
104 * 2. Redistributions in binary form must reproduce the above copyright notice,
105 * this list of conditions and the following disclaimer in the documentation
106 * and/or other materials provided with the distribution.
107 * 3. Neither the name of STMicroelectronics nor the names of its contributors
108 * may be used to endorse or promote products derived from this software
109 * without specific prior written permission.
111 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
112 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
113 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
114 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
115 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
116 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
117 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
118 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
119 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
120 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
122 ******************************************************************************
125 /* Includes ------------------------------------------------------------------*/
126 #include "stm32f3xx_hal.h"
128 /** @addtogroup STM32F3xx_HAL_Driver
129 * @{
132 /** @defgroup SMBUS SMBUS
133 * @brief SMBUS HAL module driver
134 * @{
137 #ifdef HAL_SMBUS_MODULE_ENABLED
139 /* Private typedef -----------------------------------------------------------*/
140 /* Private constants ---------------------------------------------------------*/
141 /** @defgroup SMBUS_Private_Define SMBUS Private Constants
142 * @{
144 #define TIMING_CLEAR_MASK (0xF0FFFFFFU) /*!< SMBUS TIMING clear register Mask */
145 #define HAL_TIMEOUT_ADDR (10000U) /*!< 10 s */
146 #define HAL_TIMEOUT_BUSY (25U) /*!< 25 ms */
147 #define HAL_TIMEOUT_DIR (25U) /*!< 25 ms */
148 #define HAL_TIMEOUT_RXNE (25U) /*!< 25 ms */
149 #define HAL_TIMEOUT_STOPF (25U) /*!< 25 ms */
150 #define HAL_TIMEOUT_TC (25U) /*!< 25 ms */
151 #define HAL_TIMEOUT_TCR (25U) /*!< 25 ms */
152 #define HAL_TIMEOUT_TXIS (25U) /*!< 25 ms */
153 #define MAX_NBYTE_SIZE 255U
155 * @}
158 /* Private macro -------------------------------------------------------------*/
159 /* Private variables ---------------------------------------------------------*/
160 /* Private function prototypes -----------------------------------------------*/
161 /** @addtogroup SMBUS_Private_Functions SMBUS Private Functions
162 * @{
164 static HAL_StatusTypeDef SMBUS_WaitOnFlagUntilTimeout(SMBUS_HandleTypeDef *hsmbus, uint32_t Flag, FlagStatus Status, uint32_t Timeout);
166 static HAL_StatusTypeDef SMBUS_Enable_IRQ(SMBUS_HandleTypeDef *hsmbus, uint16_t InterruptRequest);
167 static HAL_StatusTypeDef SMBUS_Disable_IRQ(SMBUS_HandleTypeDef *hsmbus, uint16_t InterruptRequest);
168 static HAL_StatusTypeDef SMBUS_Master_ISR(SMBUS_HandleTypeDef *hsmbus);
169 static HAL_StatusTypeDef SMBUS_Slave_ISR(SMBUS_HandleTypeDef *hsmbus);
171 static void SMBUS_ConvertOtherXferOptions(SMBUS_HandleTypeDef *hsmbus);
173 static void SMBUS_ITErrorHandler(SMBUS_HandleTypeDef *hsmbus);
175 static void SMBUS_TransferConfig(SMBUS_HandleTypeDef *hsmbus, uint16_t DevAddress, uint8_t Size, uint32_t Mode, uint32_t Request);
177 * @}
180 /* Exported functions --------------------------------------------------------*/
182 /** @defgroup SMBUS_Exported_Functions SMBUS Exported Functions
183 * @{
186 /** @defgroup SMBUS_Exported_Functions_Group1 Initialization and de-initialization functions
187 * @brief Initialization and Configuration functions
189 @verbatim
190 ===============================================================================
191 ##### Initialization and de-initialization functions #####
192 ===============================================================================
193 [..] This subsection provides a set of functions allowing to initialize and
194 deinitialize the SMBUSx peripheral:
196 (+) User must Implement HAL_SMBUS_MspInit() function in which he configures
197 all related peripherals resources (CLOCK, GPIO, IT and NVIC ).
199 (+) Call the function HAL_SMBUS_Init() to configure the selected device with
200 the selected configuration:
201 (++) Clock Timing
202 (++) Bus Timeout
203 (++) Analog Filer mode
204 (++) Own Address 1
205 (++) Addressing mode (Master, Slave)
206 (++) Dual Addressing mode
207 (++) Own Address 2
208 (++) Own Address 2 Mask
209 (++) General call mode
210 (++) Nostretch mode
211 (++) Packet Error Check mode
212 (++) Peripheral mode
215 (+) Call the function HAL_SMBUS_DeInit() to restore the default configuration
216 of the selected SMBUSx peripheral.
218 (+) Enable/Disable Analog/Digital filters with HAL_SMBUS_ConfigAnalogFilter() and
219 HAL_SMBUS_ConfigDigitalFilter().
221 @endverbatim
222 * @{
226 * @brief Initialize the SMBUS according to the specified parameters
227 * in the SMBUS_InitTypeDef and initialize the associated handle.
228 * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains
229 * the configuration information for the specified SMBUS.
230 * @retval HAL status
232 HAL_StatusTypeDef HAL_SMBUS_Init(SMBUS_HandleTypeDef *hsmbus)
234 /* Check the SMBUS handle allocation */
235 if (hsmbus == NULL)
237 return HAL_ERROR;
240 /* Check the parameters */
241 assert_param(IS_SMBUS_ALL_INSTANCE(hsmbus->Instance));
242 assert_param(IS_SMBUS_ANALOG_FILTER(hsmbus->Init.AnalogFilter));
243 assert_param(IS_SMBUS_OWN_ADDRESS1(hsmbus->Init.OwnAddress1));
244 assert_param(IS_SMBUS_ADDRESSING_MODE(hsmbus->Init.AddressingMode));
245 assert_param(IS_SMBUS_DUAL_ADDRESS(hsmbus->Init.DualAddressMode));
246 assert_param(IS_SMBUS_OWN_ADDRESS2(hsmbus->Init.OwnAddress2));
247 assert_param(IS_SMBUS_OWN_ADDRESS2_MASK(hsmbus->Init.OwnAddress2Masks));
248 assert_param(IS_SMBUS_GENERAL_CALL(hsmbus->Init.GeneralCallMode));
249 assert_param(IS_SMBUS_NO_STRETCH(hsmbus->Init.NoStretchMode));
250 assert_param(IS_SMBUS_PEC(hsmbus->Init.PacketErrorCheckMode));
251 assert_param(IS_SMBUS_PERIPHERAL_MODE(hsmbus->Init.PeripheralMode));
253 if (hsmbus->State == HAL_SMBUS_STATE_RESET)
255 /* Allocate lock resource and initialize it */
256 hsmbus->Lock = HAL_UNLOCKED;
258 /* Init the low level hardware : GPIO, CLOCK, NVIC */
259 HAL_SMBUS_MspInit(hsmbus);
262 hsmbus->State = HAL_SMBUS_STATE_BUSY;
264 /* Disable the selected SMBUS peripheral */
265 __HAL_SMBUS_DISABLE(hsmbus);
267 /*---------------------------- SMBUSx TIMINGR Configuration ------------------------*/
268 /* Configure SMBUSx: Frequency range */
269 hsmbus->Instance->TIMINGR = hsmbus->Init.Timing & TIMING_CLEAR_MASK;
271 /*---------------------------- SMBUSx TIMEOUTR Configuration ------------------------*/
272 /* Configure SMBUSx: Bus Timeout */
273 hsmbus->Instance->TIMEOUTR &= ~I2C_TIMEOUTR_TIMOUTEN;
274 hsmbus->Instance->TIMEOUTR &= ~I2C_TIMEOUTR_TEXTEN;
275 hsmbus->Instance->TIMEOUTR = hsmbus->Init.SMBusTimeout;
277 /*---------------------------- SMBUSx OAR1 Configuration -----------------------*/
278 /* Configure SMBUSx: Own Address1 and ack own address1 mode */
279 hsmbus->Instance->OAR1 &= ~I2C_OAR1_OA1EN;
281 if (hsmbus->Init.OwnAddress1 != 0U)
283 if (hsmbus->Init.AddressingMode == SMBUS_ADDRESSINGMODE_7BIT)
285 hsmbus->Instance->OAR1 = (I2C_OAR1_OA1EN | hsmbus->Init.OwnAddress1);
287 else /* SMBUS_ADDRESSINGMODE_10BIT */
289 hsmbus->Instance->OAR1 = (I2C_OAR1_OA1EN | I2C_OAR1_OA1MODE | hsmbus->Init.OwnAddress1);
293 /*---------------------------- SMBUSx CR2 Configuration ------------------------*/
294 /* Configure SMBUSx: Addressing Master mode */
295 if (hsmbus->Init.AddressingMode == SMBUS_ADDRESSINGMODE_10BIT)
297 hsmbus->Instance->CR2 = (I2C_CR2_ADD10);
299 /* Enable the AUTOEND by default, and enable NACK (should be disable only during Slave process) */
300 /* AUTOEND and NACK bit will be manage during Transfer process */
301 hsmbus->Instance->CR2 |= (I2C_CR2_AUTOEND | I2C_CR2_NACK);
303 /*---------------------------- SMBUSx OAR2 Configuration -----------------------*/
304 /* Configure SMBUSx: Dual mode and Own Address2 */
305 hsmbus->Instance->OAR2 = (hsmbus->Init.DualAddressMode | hsmbus->Init.OwnAddress2 | (hsmbus->Init.OwnAddress2Masks << 8U));
307 /*---------------------------- SMBUSx CR1 Configuration ------------------------*/
308 /* Configure SMBUSx: Generalcall and NoStretch mode */
309 hsmbus->Instance->CR1 = (hsmbus->Init.GeneralCallMode | hsmbus->Init.NoStretchMode | hsmbus->Init.PacketErrorCheckMode | hsmbus->Init.PeripheralMode | hsmbus->Init.AnalogFilter);
311 /* Enable Slave Byte Control only in case of Packet Error Check is enabled and SMBUS Peripheral is set in Slave mode */
312 if ((hsmbus->Init.PacketErrorCheckMode == SMBUS_PEC_ENABLE)
313 && ((hsmbus->Init.PeripheralMode == SMBUS_PERIPHERAL_MODE_SMBUS_SLAVE) || (hsmbus->Init.PeripheralMode == SMBUS_PERIPHERAL_MODE_SMBUS_SLAVE_ARP)))
315 hsmbus->Instance->CR1 |= I2C_CR1_SBC;
318 /* Enable the selected SMBUS peripheral */
319 __HAL_SMBUS_ENABLE(hsmbus);
321 hsmbus->ErrorCode = HAL_SMBUS_ERROR_NONE;
322 hsmbus->PreviousState = HAL_SMBUS_STATE_READY;
323 hsmbus->State = HAL_SMBUS_STATE_READY;
325 return HAL_OK;
329 * @brief DeInitialize the SMBUS peripheral.
330 * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains
331 * the configuration information for the specified SMBUS.
332 * @retval HAL status
334 HAL_StatusTypeDef HAL_SMBUS_DeInit(SMBUS_HandleTypeDef *hsmbus)
336 /* Check the SMBUS handle allocation */
337 if (hsmbus == NULL)
339 return HAL_ERROR;
342 /* Check the parameters */
343 assert_param(IS_SMBUS_ALL_INSTANCE(hsmbus->Instance));
345 hsmbus->State = HAL_SMBUS_STATE_BUSY;
347 /* Disable the SMBUS Peripheral Clock */
348 __HAL_SMBUS_DISABLE(hsmbus);
350 /* DeInit the low level hardware: GPIO, CLOCK, NVIC */
351 HAL_SMBUS_MspDeInit(hsmbus);
353 hsmbus->ErrorCode = HAL_SMBUS_ERROR_NONE;
354 hsmbus->PreviousState = HAL_SMBUS_STATE_RESET;
355 hsmbus->State = HAL_SMBUS_STATE_RESET;
357 /* Release Lock */
358 __HAL_UNLOCK(hsmbus);
360 return HAL_OK;
364 * @brief Initialize the SMBUS MSP.
365 * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains
366 * the configuration information for the specified SMBUS.
367 * @retval None
369 __weak void HAL_SMBUS_MspInit(SMBUS_HandleTypeDef *hsmbus)
371 /* Prevent unused argument(s) compilation warning */
372 UNUSED(hsmbus);
374 /* NOTE : This function should not be modified, when the callback is needed,
375 the HAL_SMBUS_MspInit could be implemented in the user file
380 * @brief DeInitialize the SMBUS MSP.
381 * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains
382 * the configuration information for the specified SMBUS.
383 * @retval None
385 __weak void HAL_SMBUS_MspDeInit(SMBUS_HandleTypeDef *hsmbus)
387 /* Prevent unused argument(s) compilation warning */
388 UNUSED(hsmbus);
390 /* NOTE : This function should not be modified, when the callback is needed,
391 the HAL_SMBUS_MspDeInit could be implemented in the user file
396 * @brief Configure Analog noise filter.
397 * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains
398 * the configuration information for the specified SMBUS.
399 * @param AnalogFilter This parameter can be one of the following values:
400 * @arg @ref SMBUS_ANALOGFILTER_ENABLE
401 * @arg @ref SMBUS_ANALOGFILTER_DISABLE
402 * @retval HAL status
404 HAL_StatusTypeDef HAL_SMBUS_ConfigAnalogFilter(SMBUS_HandleTypeDef *hsmbus, uint32_t AnalogFilter)
406 /* Check the parameters */
407 assert_param(IS_SMBUS_ALL_INSTANCE(hsmbus->Instance));
408 assert_param(IS_SMBUS_ANALOG_FILTER(AnalogFilter));
410 if (hsmbus->State == HAL_SMBUS_STATE_READY)
412 /* Process Locked */
413 __HAL_LOCK(hsmbus);
415 hsmbus->State = HAL_SMBUS_STATE_BUSY;
417 /* Disable the selected SMBUS peripheral */
418 __HAL_SMBUS_DISABLE(hsmbus);
420 /* Reset ANOFF bit */
421 hsmbus->Instance->CR1 &= ~(I2C_CR1_ANFOFF);
423 /* Set analog filter bit*/
424 hsmbus->Instance->CR1 |= AnalogFilter;
426 __HAL_SMBUS_ENABLE(hsmbus);
428 hsmbus->State = HAL_SMBUS_STATE_READY;
430 /* Process Unlocked */
431 __HAL_UNLOCK(hsmbus);
433 return HAL_OK;
435 else
437 return HAL_BUSY;
442 * @brief Configure Digital noise filter.
443 * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains
444 * the configuration information for the specified SMBUS.
445 * @param DigitalFilter Coefficient of digital noise filter between Min_Data=0x00 and Max_Data=0x0F.
446 * @retval HAL status
448 HAL_StatusTypeDef HAL_SMBUS_ConfigDigitalFilter(SMBUS_HandleTypeDef *hsmbus, uint32_t DigitalFilter)
450 uint32_t tmpreg = 0U;
452 /* Check the parameters */
453 assert_param(IS_SMBUS_ALL_INSTANCE(hsmbus->Instance));
454 assert_param(IS_SMBUS_DIGITAL_FILTER(DigitalFilter));
456 if (hsmbus->State == HAL_SMBUS_STATE_READY)
458 /* Process Locked */
459 __HAL_LOCK(hsmbus);
461 hsmbus->State = HAL_SMBUS_STATE_BUSY;
463 /* Disable the selected SMBUS peripheral */
464 __HAL_SMBUS_DISABLE(hsmbus);
466 /* Get the old register value */
467 tmpreg = hsmbus->Instance->CR1;
469 /* Reset I2C DNF bits [11:8] */
470 tmpreg &= ~(I2C_CR1_DNF);
472 /* Set I2Cx DNF coefficient */
473 tmpreg |= DigitalFilter << I2C_CR1_DNF_Pos;
475 /* Store the new register value */
476 hsmbus->Instance->CR1 = tmpreg;
478 __HAL_SMBUS_ENABLE(hsmbus);
480 hsmbus->State = HAL_SMBUS_STATE_READY;
482 /* Process Unlocked */
483 __HAL_UNLOCK(hsmbus);
485 return HAL_OK;
487 else
489 return HAL_BUSY;
494 * @}
497 /** @defgroup SMBUS_Exported_Functions_Group2 Input and Output operation functions
498 * @brief Data transfers functions
500 @verbatim
501 ===============================================================================
502 ##### IO operation functions #####
503 ===============================================================================
504 [..]
505 This subsection provides a set of functions allowing to manage the SMBUS data
506 transfers.
508 (#) Blocking mode function to check if device is ready for usage is :
509 (++) HAL_SMBUS_IsDeviceReady()
511 (#) There is only one mode of transfer:
512 (++) Non-Blocking mode : The communication is performed using Interrupts.
513 These functions return the status of the transfer startup.
514 The end of the data processing will be indicated through the
515 dedicated SMBUS IRQ when using Interrupt mode.
517 (#) Non-Blocking mode functions with Interrupt are :
518 (++) HAL_SMBUS_Master_Transmit_IT()
519 (++) HAL_SMBUS_Master_Receive_IT()
520 (++) HAL_SMBUS_Slave_Transmit_IT()
521 (++) HAL_SMBUS_Slave_Receive_IT()
522 (++) HAL_SMBUS_EnableListen_IT() or alias HAL_SMBUS_EnableListen_IT()
523 (++) HAL_SMBUS_DisableListen_IT()
524 (++) HAL_SMBUS_EnableAlert_IT()
525 (++) HAL_SMBUS_DisableAlert_IT()
527 (#) A set of Transfer Complete Callbacks are provided in non-Blocking mode:
528 (++) HAL_SMBUS_MasterTxCpltCallback()
529 (++) HAL_SMBUS_MasterRxCpltCallback()
530 (++) HAL_SMBUS_SlaveTxCpltCallback()
531 (++) HAL_SMBUS_SlaveRxCpltCallback()
532 (++) HAL_SMBUS_AddrCallback()
533 (++) HAL_SMBUS_ListenCpltCallback()
534 (++) HAL_SMBUS_ErrorCallback()
536 @endverbatim
537 * @{
541 * @brief Transmit in master/host SMBUS mode an amount of data in non-blocking mode with Interrupt.
542 * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains
543 * the configuration information for the specified SMBUS.
544 * @param DevAddress Target device address: The device 7 bits address value
545 * in datasheet must be shift at right before call interface
546 * @param pData Pointer to data buffer
547 * @param Size Amount of data to be sent
548 * @param XferOptions Options of Transfer, value of @ref SMBUS_XferOptions_definition
549 * @retval HAL status
551 HAL_StatusTypeDef HAL_SMBUS_Master_Transmit_IT(SMBUS_HandleTypeDef *hsmbus, uint16_t DevAddress, uint8_t *pData, uint16_t Size, uint32_t XferOptions)
553 /* Check the parameters */
554 assert_param(IS_SMBUS_TRANSFER_OPTIONS_REQUEST(XferOptions));
556 if (hsmbus->State == HAL_SMBUS_STATE_READY)
558 /* Process Locked */
559 __HAL_LOCK(hsmbus);
561 hsmbus->State = HAL_SMBUS_STATE_MASTER_BUSY_TX;
562 hsmbus->ErrorCode = HAL_SMBUS_ERROR_NONE;
563 /* Prepare transfer parameters */
564 hsmbus->pBuffPtr = pData;
565 hsmbus->XferCount = Size;
566 hsmbus->XferOptions = XferOptions;
568 /* In case of Quick command, remove autoend mode */
569 /* Manage the stop generation by software */
570 if (hsmbus->pBuffPtr == NULL)
572 hsmbus->XferOptions &= ~SMBUS_AUTOEND_MODE;
575 if (Size > MAX_NBYTE_SIZE)
577 hsmbus->XferSize = MAX_NBYTE_SIZE;
579 else
581 hsmbus->XferSize = Size;
584 /* Send Slave Address */
585 /* Set NBYTES to write and reload if size > MAX_NBYTE_SIZE and generate RESTART */
586 if ((hsmbus->XferSize == MAX_NBYTE_SIZE) && (hsmbus->XferSize < hsmbus->XferCount))
588 SMBUS_TransferConfig(hsmbus, DevAddress, hsmbus->XferSize, SMBUS_RELOAD_MODE | (hsmbus->XferOptions & SMBUS_SENDPEC_MODE), SMBUS_GENERATE_START_WRITE);
590 else
592 /* If transfer direction not change, do not generate Restart Condition */
593 /* Mean Previous state is same as current state */
594 if ((hsmbus->PreviousState == HAL_SMBUS_STATE_MASTER_BUSY_TX) && (IS_SMBUS_TRANSFER_OTHER_OPTIONS_REQUEST(hsmbus->XferOptions) == 0))
596 SMBUS_TransferConfig(hsmbus, DevAddress, hsmbus->XferSize, hsmbus->XferOptions, SMBUS_NO_STARTSTOP);
598 /* Else transfer direction change, so generate Restart with new transfer direction */
599 else
601 /* Convert OTHER_xxx XferOptions if any */
602 SMBUS_ConvertOtherXferOptions(hsmbus);
604 /* Handle Transfer */
605 SMBUS_TransferConfig(hsmbus, DevAddress, hsmbus->XferSize, hsmbus->XferOptions, SMBUS_GENERATE_START_WRITE);
608 /* If PEC mode is enable, size to transmit manage by SW part should be Size-1 byte, corresponding to PEC byte */
609 /* PEC byte is automatically sent by HW block, no need to manage it in Transmit process */
610 if (SMBUS_GET_PEC_MODE(hsmbus) != RESET)
612 hsmbus->XferSize--;
613 hsmbus->XferCount--;
617 /* Process Unlocked */
618 __HAL_UNLOCK(hsmbus);
620 /* Note : The SMBUS interrupts must be enabled after unlocking current process
621 to avoid the risk of SMBUS interrupt handle execution before current
622 process unlock */
623 SMBUS_Enable_IRQ(hsmbus, SMBUS_IT_TX);
625 return HAL_OK;
627 else
629 return HAL_BUSY;
634 * @brief Receive in master/host SMBUS mode an amount of data in non-blocking mode with Interrupt.
635 * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains
636 * the configuration information for the specified SMBUS.
637 * @param DevAddress Target device address: The device 7 bits address value
638 * in datasheet must be shift at right before call interface
639 * @param pData Pointer to data buffer
640 * @param Size Amount of data to be sent
641 * @param XferOptions Options of Transfer, value of @ref SMBUS_XferOptions_definition
642 * @retval HAL status
644 HAL_StatusTypeDef HAL_SMBUS_Master_Receive_IT(SMBUS_HandleTypeDef *hsmbus, uint16_t DevAddress, uint8_t *pData, uint16_t Size, uint32_t XferOptions)
646 /* Check the parameters */
647 assert_param(IS_SMBUS_TRANSFER_OPTIONS_REQUEST(XferOptions));
649 if (hsmbus->State == HAL_SMBUS_STATE_READY)
651 /* Process Locked */
652 __HAL_LOCK(hsmbus);
654 hsmbus->State = HAL_SMBUS_STATE_MASTER_BUSY_RX;
655 hsmbus->ErrorCode = HAL_SMBUS_ERROR_NONE;
657 /* Prepare transfer parameters */
658 hsmbus->pBuffPtr = pData;
659 hsmbus->XferCount = Size;
660 hsmbus->XferOptions = XferOptions;
662 /* In case of Quick command, remove autoend mode */
663 /* Manage the stop generation by software */
664 if (hsmbus->pBuffPtr == NULL)
666 hsmbus->XferOptions &= ~SMBUS_AUTOEND_MODE;
669 if (Size > MAX_NBYTE_SIZE)
671 hsmbus->XferSize = MAX_NBYTE_SIZE;
673 else
675 hsmbus->XferSize = Size;
678 /* Send Slave Address */
679 /* Set NBYTES to write and reload if size > MAX_NBYTE_SIZE and generate RESTART */
680 if ((hsmbus->XferSize == MAX_NBYTE_SIZE) && (hsmbus->XferSize < hsmbus->XferCount))
682 SMBUS_TransferConfig(hsmbus, DevAddress, hsmbus->XferSize, SMBUS_RELOAD_MODE | (hsmbus->XferOptions & SMBUS_SENDPEC_MODE), SMBUS_GENERATE_START_READ);
684 else
686 /* If transfer direction not change, do not generate Restart Condition */
687 /* Mean Previous state is same as current state */
688 if ((hsmbus->PreviousState == HAL_SMBUS_STATE_MASTER_BUSY_RX) && (IS_SMBUS_TRANSFER_OTHER_OPTIONS_REQUEST(hsmbus->XferOptions) == 0))
690 SMBUS_TransferConfig(hsmbus, DevAddress, hsmbus->XferSize, hsmbus->XferOptions, SMBUS_NO_STARTSTOP);
692 /* Else transfer direction change, so generate Restart with new transfer direction */
693 else
695 /* Convert OTHER_xxx XferOptions if any */
696 SMBUS_ConvertOtherXferOptions(hsmbus);
698 /* Handle Transfer */
699 SMBUS_TransferConfig(hsmbus, DevAddress, hsmbus->XferSize, hsmbus->XferOptions, SMBUS_GENERATE_START_READ);
703 /* Process Unlocked */
704 __HAL_UNLOCK(hsmbus);
706 /* Note : The SMBUS interrupts must be enabled after unlocking current process
707 to avoid the risk of SMBUS interrupt handle execution before current
708 process unlock */
709 SMBUS_Enable_IRQ(hsmbus, SMBUS_IT_RX);
711 return HAL_OK;
713 else
715 return HAL_BUSY;
720 * @brief Abort a master/host SMBUS process communication with Interrupt.
721 * @note This abort can be called only if state is ready
722 * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains
723 * the configuration information for the specified SMBUS.
724 * @param DevAddress Target device address: The device 7 bits address value
725 * in datasheet must be shift at right before call interface
726 * @retval HAL status
728 HAL_StatusTypeDef HAL_SMBUS_Master_Abort_IT(SMBUS_HandleTypeDef *hsmbus, uint16_t DevAddress)
730 if (hsmbus->State == HAL_SMBUS_STATE_READY)
732 /* Process Locked */
733 __HAL_LOCK(hsmbus);
735 /* Keep the same state as previous */
736 /* to perform as well the call of the corresponding end of transfer callback */
737 if (hsmbus->PreviousState == HAL_SMBUS_STATE_MASTER_BUSY_TX)
739 hsmbus->State = HAL_SMBUS_STATE_MASTER_BUSY_TX;
741 else if (hsmbus->PreviousState == HAL_SMBUS_STATE_MASTER_BUSY_RX)
743 hsmbus->State = HAL_SMBUS_STATE_MASTER_BUSY_RX;
745 else
747 /* Wrong usage of abort function */
748 /* This function should be used only in case of abort monitored by master device */
749 return HAL_ERROR;
751 hsmbus->ErrorCode = HAL_SMBUS_ERROR_NONE;
753 /* Set NBYTES to 1 to generate a dummy read on SMBUS peripheral */
754 /* Set AUTOEND mode, this will generate a NACK then STOP condition to abort the current transfer */
755 SMBUS_TransferConfig(hsmbus, DevAddress, 1U, SMBUS_AUTOEND_MODE, SMBUS_NO_STARTSTOP);
757 /* Process Unlocked */
758 __HAL_UNLOCK(hsmbus);
760 /* Note : The SMBUS interrupts must be enabled after unlocking current process
761 to avoid the risk of SMBUS interrupt handle execution before current
762 process unlock */
763 if (hsmbus->State == HAL_SMBUS_STATE_MASTER_BUSY_TX)
765 SMBUS_Enable_IRQ(hsmbus, SMBUS_IT_TX);
767 else if (hsmbus->State == HAL_SMBUS_STATE_MASTER_BUSY_RX)
769 SMBUS_Enable_IRQ(hsmbus, SMBUS_IT_RX);
772 return HAL_OK;
774 else
776 return HAL_BUSY;
781 * @brief Transmit in slave/device SMBUS mode an amount of data in non-blocking mode with Interrupt.
782 * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains
783 * the configuration information for the specified SMBUS.
784 * @param pData Pointer to data buffer
785 * @param Size Amount of data to be sent
786 * @param XferOptions Options of Transfer, value of @ref SMBUS_XferOptions_definition
787 * @retval HAL status
789 HAL_StatusTypeDef HAL_SMBUS_Slave_Transmit_IT(SMBUS_HandleTypeDef *hsmbus, uint8_t *pData, uint16_t Size, uint32_t XferOptions)
791 /* Check the parameters */
792 assert_param(IS_SMBUS_TRANSFER_OPTIONS_REQUEST(XferOptions));
794 if (hsmbus->State == HAL_SMBUS_STATE_LISTEN)
796 if ((pData == NULL) || (Size == 0U))
798 return HAL_ERROR;
801 /* Disable Interrupts, to prevent preemption during treatment in case of multicall */
802 SMBUS_Disable_IRQ(hsmbus, SMBUS_IT_ADDR | SMBUS_IT_TX);
804 /* Process Locked */
805 __HAL_LOCK(hsmbus);
807 hsmbus->State |= HAL_SMBUS_STATE_SLAVE_BUSY_TX;
808 hsmbus->ErrorCode = HAL_SMBUS_ERROR_NONE;
810 /* Set SBC bit to manage Acknowledge at each bit */
811 hsmbus->Instance->CR1 |= I2C_CR1_SBC;
813 /* Enable Address Acknowledge */
814 hsmbus->Instance->CR2 &= ~I2C_CR2_NACK;
816 /* Prepare transfer parameters */
817 hsmbus->pBuffPtr = pData;
818 hsmbus->XferCount = Size;
819 hsmbus->XferOptions = XferOptions;
821 /* Convert OTHER_xxx XferOptions if any */
822 SMBUS_ConvertOtherXferOptions(hsmbus);
824 if (Size > MAX_NBYTE_SIZE)
826 hsmbus->XferSize = MAX_NBYTE_SIZE;
828 else
830 hsmbus->XferSize = Size;
833 /* Set NBYTES to write and reload if size > MAX_NBYTE_SIZE and generate RESTART */
834 if ((hsmbus->XferSize == MAX_NBYTE_SIZE) && (hsmbus->XferSize < hsmbus->XferCount))
836 SMBUS_TransferConfig(hsmbus, 0U, hsmbus->XferSize, SMBUS_RELOAD_MODE | (hsmbus->XferOptions & SMBUS_SENDPEC_MODE), SMBUS_NO_STARTSTOP);
838 else
840 /* Set NBYTE to transmit */
841 SMBUS_TransferConfig(hsmbus, 0U, hsmbus->XferSize, hsmbus->XferOptions, SMBUS_NO_STARTSTOP);
843 /* If PEC mode is enable, size to transmit should be Size-1 byte, corresponding to PEC byte */
844 /* PEC byte is automatically sent by HW block, no need to manage it in Transmit process */
845 if (SMBUS_GET_PEC_MODE(hsmbus) != RESET)
847 hsmbus->XferSize--;
848 hsmbus->XferCount--;
852 /* Clear ADDR flag after prepare the transfer parameters */
853 /* This action will generate an acknowledge to the HOST */
854 __HAL_SMBUS_CLEAR_FLAG(hsmbus, SMBUS_FLAG_ADDR);
856 /* Process Unlocked */
857 __HAL_UNLOCK(hsmbus);
859 /* Note : The SMBUS interrupts must be enabled after unlocking current process
860 to avoid the risk of SMBUS interrupt handle execution before current
861 process unlock */
862 /* REnable ADDR interrupt */
863 SMBUS_Enable_IRQ(hsmbus, SMBUS_IT_TX | SMBUS_IT_ADDR);
865 return HAL_OK;
867 else
869 return HAL_ERROR;
874 * @brief Receive in slave/device SMBUS mode an amount of data in non-blocking mode with Interrupt.
875 * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains
876 * the configuration information for the specified SMBUS.
877 * @param pData Pointer to data buffer
878 * @param Size Amount of data to be sent
879 * @param XferOptions Options of Transfer, value of @ref SMBUS_XferOptions_definition
880 * @retval HAL status
882 HAL_StatusTypeDef HAL_SMBUS_Slave_Receive_IT(SMBUS_HandleTypeDef *hsmbus, uint8_t *pData, uint16_t Size, uint32_t XferOptions)
884 /* Check the parameters */
885 assert_param(IS_SMBUS_TRANSFER_OPTIONS_REQUEST(XferOptions));
887 if (hsmbus->State == HAL_SMBUS_STATE_LISTEN)
889 if ((pData == NULL) || (Size == 0U))
891 return HAL_ERROR;
894 /* Disable Interrupts, to prevent preemption during treatment in case of multicall */
895 SMBUS_Disable_IRQ(hsmbus, SMBUS_IT_ADDR | SMBUS_IT_RX);
897 /* Process Locked */
898 __HAL_LOCK(hsmbus);
900 hsmbus->State |= HAL_SMBUS_STATE_SLAVE_BUSY_RX;
901 hsmbus->ErrorCode = HAL_SMBUS_ERROR_NONE;
903 /* Set SBC bit to manage Acknowledge at each bit */
904 hsmbus->Instance->CR1 |= I2C_CR1_SBC;
906 /* Enable Address Acknowledge */
907 hsmbus->Instance->CR2 &= ~I2C_CR2_NACK;
909 /* Prepare transfer parameters */
910 hsmbus->pBuffPtr = pData;
911 hsmbus->XferSize = Size;
912 hsmbus->XferCount = Size;
913 hsmbus->XferOptions = XferOptions;
915 /* Convert OTHER_xxx XferOptions if any */
916 SMBUS_ConvertOtherXferOptions(hsmbus);
918 /* Set NBYTE to receive */
919 /* If XferSize equal "1", or XferSize equal "2" with PEC requested (mean 1 data byte + 1 PEC byte */
920 /* no need to set RELOAD bit mode, a ACK will be automatically generated in that case */
921 /* else need to set RELOAD bit mode to generate an automatic ACK at each byte Received */
922 /* This RELOAD bit will be reset for last BYTE to be receive in SMBUS_Slave_ISR */
923 if ((hsmbus->XferSize == 1U) || ((hsmbus->XferSize == 2U) && (SMBUS_GET_PEC_MODE(hsmbus) != RESET)))
925 SMBUS_TransferConfig(hsmbus, 0U, hsmbus->XferSize, hsmbus->XferOptions, SMBUS_NO_STARTSTOP);
927 else
929 SMBUS_TransferConfig(hsmbus, 0U, 1U, hsmbus->XferOptions | SMBUS_RELOAD_MODE, SMBUS_NO_STARTSTOP);
932 /* Clear ADDR flag after prepare the transfer parameters */
933 /* This action will generate an acknowledge to the HOST */
934 __HAL_SMBUS_CLEAR_FLAG(hsmbus, SMBUS_FLAG_ADDR);
936 /* Process Unlocked */
937 __HAL_UNLOCK(hsmbus);
939 /* Note : The SMBUS interrupts must be enabled after unlocking current process
940 to avoid the risk of SMBUS interrupt handle execution before current
941 process unlock */
942 /* REnable ADDR interrupt */
943 SMBUS_Enable_IRQ(hsmbus, SMBUS_IT_RX | SMBUS_IT_ADDR);
945 return HAL_OK;
947 else
949 return HAL_ERROR;
954 * @brief Enable the Address listen mode with Interrupt.
955 * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains
956 * the configuration information for the specified SMBUS.
957 * @retval HAL status
959 HAL_StatusTypeDef HAL_SMBUS_EnableListen_IT(SMBUS_HandleTypeDef *hsmbus)
961 hsmbus->State = HAL_SMBUS_STATE_LISTEN;
963 /* Enable the Address Match interrupt */
964 SMBUS_Enable_IRQ(hsmbus, SMBUS_IT_ADDR);
966 return HAL_OK;
970 * @brief Disable the Address listen mode with Interrupt.
971 * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains
972 * the configuration information for the specified SMBUS.
973 * @retval HAL status
975 HAL_StatusTypeDef HAL_SMBUS_DisableListen_IT(SMBUS_HandleTypeDef *hsmbus)
977 /* Disable Address listen mode only if a transfer is not ongoing */
978 if (hsmbus->State == HAL_SMBUS_STATE_LISTEN)
980 hsmbus->State = HAL_SMBUS_STATE_READY;
982 /* Disable the Address Match interrupt */
983 SMBUS_Disable_IRQ(hsmbus, SMBUS_IT_ADDR);
985 return HAL_OK;
987 else
989 return HAL_BUSY;
994 * @brief Enable the SMBUS alert mode with Interrupt.
995 * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains
996 * the configuration information for the specified SMBUSx peripheral.
997 * @retval HAL status
999 HAL_StatusTypeDef HAL_SMBUS_EnableAlert_IT(SMBUS_HandleTypeDef *hsmbus)
1001 /* Enable SMBus alert */
1002 hsmbus->Instance->CR1 |= I2C_CR1_ALERTEN;
1004 /* Clear ALERT flag */
1005 __HAL_SMBUS_CLEAR_FLAG(hsmbus, SMBUS_FLAG_ALERT);
1007 /* Enable Alert Interrupt */
1008 SMBUS_Enable_IRQ(hsmbus, SMBUS_IT_ALERT);
1010 return HAL_OK;
1013 * @brief Disable the SMBUS alert mode with Interrupt.
1014 * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains
1015 * the configuration information for the specified SMBUSx peripheral.
1016 * @retval HAL status
1018 HAL_StatusTypeDef HAL_SMBUS_DisableAlert_IT(SMBUS_HandleTypeDef *hsmbus)
1020 /* Enable SMBus alert */
1021 hsmbus->Instance->CR1 &= ~I2C_CR1_ALERTEN;
1023 /* Disable Alert Interrupt */
1024 SMBUS_Disable_IRQ(hsmbus, SMBUS_IT_ALERT);
1026 return HAL_OK;
1030 * @brief Check if target device is ready for communication.
1031 * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains
1032 * the configuration information for the specified SMBUS.
1033 * @param DevAddress Target device address: The device 7 bits address value
1034 * in datasheet must be shift at right before call interface
1035 * @param Trials Number of trials
1036 * @param Timeout Timeout duration
1037 * @retval HAL status
1039 HAL_StatusTypeDef HAL_SMBUS_IsDeviceReady(SMBUS_HandleTypeDef *hsmbus, uint16_t DevAddress, uint32_t Trials, uint32_t Timeout)
1041 uint32_t tickstart = 0U;
1043 __IO uint32_t SMBUS_Trials = 0U;
1045 if (hsmbus->State == HAL_SMBUS_STATE_READY)
1047 if (__HAL_SMBUS_GET_FLAG(hsmbus, SMBUS_FLAG_BUSY) != RESET)
1049 return HAL_BUSY;
1052 /* Process Locked */
1053 __HAL_LOCK(hsmbus);
1055 hsmbus->State = HAL_SMBUS_STATE_BUSY;
1056 hsmbus->ErrorCode = HAL_SMBUS_ERROR_NONE;
1060 /* Generate Start */
1061 hsmbus->Instance->CR2 = SMBUS_GENERATE_START(hsmbus->Init.AddressingMode, DevAddress);
1063 /* No need to Check TC flag, with AUTOEND mode the stop is automatically generated */
1064 /* Wait until STOPF flag is set or a NACK flag is set*/
1065 tickstart = HAL_GetTick();
1066 while ((__HAL_SMBUS_GET_FLAG(hsmbus, SMBUS_FLAG_STOPF) == RESET) && (__HAL_SMBUS_GET_FLAG(hsmbus, SMBUS_FLAG_AF) == RESET) && (hsmbus->State != HAL_SMBUS_STATE_TIMEOUT))
1068 if (Timeout != HAL_MAX_DELAY)
1070 if ((Timeout == 0U) || ((HAL_GetTick() - tickstart) > Timeout))
1072 /* Device is ready */
1073 hsmbus->State = HAL_SMBUS_STATE_READY;
1075 /* Process Unlocked */
1076 __HAL_UNLOCK(hsmbus);
1077 return HAL_TIMEOUT;
1082 /* Check if the NACKF flag has not been set */
1083 if (__HAL_SMBUS_GET_FLAG(hsmbus, SMBUS_FLAG_AF) == RESET)
1085 /* Wait until STOPF flag is reset */
1086 if (SMBUS_WaitOnFlagUntilTimeout(hsmbus, SMBUS_FLAG_STOPF, RESET, Timeout) != HAL_OK)
1088 return HAL_TIMEOUT;
1091 /* Clear STOP Flag */
1092 __HAL_SMBUS_CLEAR_FLAG(hsmbus, SMBUS_FLAG_STOPF);
1094 /* Device is ready */
1095 hsmbus->State = HAL_SMBUS_STATE_READY;
1097 /* Process Unlocked */
1098 __HAL_UNLOCK(hsmbus);
1100 return HAL_OK;
1102 else
1104 /* Wait until STOPF flag is reset */
1105 if (SMBUS_WaitOnFlagUntilTimeout(hsmbus, SMBUS_FLAG_STOPF, RESET, Timeout) != HAL_OK)
1107 return HAL_TIMEOUT;
1110 /* Clear NACK Flag */
1111 __HAL_SMBUS_CLEAR_FLAG(hsmbus, SMBUS_FLAG_AF);
1113 /* Clear STOP Flag, auto generated with autoend*/
1114 __HAL_SMBUS_CLEAR_FLAG(hsmbus, SMBUS_FLAG_STOPF);
1117 /* Check if the maximum allowed number of trials has been reached */
1118 if (SMBUS_Trials++ == Trials)
1120 /* Generate Stop */
1121 hsmbus->Instance->CR2 |= I2C_CR2_STOP;
1123 /* Wait until STOPF flag is reset */
1124 if (SMBUS_WaitOnFlagUntilTimeout(hsmbus, SMBUS_FLAG_STOPF, RESET, Timeout) != HAL_OK)
1126 return HAL_TIMEOUT;
1129 /* Clear STOP Flag */
1130 __HAL_SMBUS_CLEAR_FLAG(hsmbus, SMBUS_FLAG_STOPF);
1133 while (SMBUS_Trials < Trials);
1135 hsmbus->State = HAL_SMBUS_STATE_READY;
1137 /* Process Unlocked */
1138 __HAL_UNLOCK(hsmbus);
1140 return HAL_TIMEOUT;
1142 else
1144 return HAL_BUSY;
1148 * @}
1151 /** @defgroup SMBUS_IRQ_Handler_and_Callbacks IRQ Handler and Callbacks
1152 * @{
1156 * @brief Handle SMBUS event interrupt request.
1157 * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains
1158 * the configuration information for the specified SMBUS.
1159 * @retval None
1161 void HAL_SMBUS_EV_IRQHandler(SMBUS_HandleTypeDef *hsmbus)
1163 uint32_t tmpisrvalue = 0U;
1165 /* Use a local variable to store the current ISR flags */
1166 /* This action will avoid a wrong treatment due to ISR flags change during interrupt handler */
1167 tmpisrvalue = SMBUS_GET_ISR_REG(hsmbus);
1169 /* SMBUS in mode Transmitter ---------------------------------------------------*/
1170 if (((SMBUS_CHECK_FLAG(tmpisrvalue, SMBUS_FLAG_TXIS) != RESET) || (SMBUS_CHECK_FLAG(tmpisrvalue, SMBUS_FLAG_TCR) != RESET) || (SMBUS_CHECK_FLAG(tmpisrvalue, SMBUS_FLAG_TC) != RESET) || (SMBUS_CHECK_FLAG(tmpisrvalue, SMBUS_FLAG_STOPF) != RESET) || (SMBUS_CHECK_FLAG(tmpisrvalue, SMBUS_FLAG_AF) != RESET)) && (__HAL_SMBUS_GET_IT_SOURCE(hsmbus, (SMBUS_IT_TCI | SMBUS_IT_STOPI | SMBUS_IT_NACKI | SMBUS_IT_TXI)) != RESET))
1172 /* Slave mode selected */
1173 if ((hsmbus->State & HAL_SMBUS_STATE_SLAVE_BUSY_TX) == HAL_SMBUS_STATE_SLAVE_BUSY_TX)
1175 SMBUS_Slave_ISR(hsmbus);
1177 /* Master mode selected */
1178 else if ((hsmbus->State & HAL_SMBUS_STATE_MASTER_BUSY_TX) == HAL_SMBUS_STATE_MASTER_BUSY_TX)
1180 SMBUS_Master_ISR(hsmbus);
1184 /* SMBUS in mode Receiver ----------------------------------------------------*/
1185 if (((SMBUS_CHECK_FLAG(tmpisrvalue, SMBUS_FLAG_RXNE) != RESET) || (SMBUS_CHECK_FLAG(tmpisrvalue, SMBUS_FLAG_TCR) != RESET) || (SMBUS_CHECK_FLAG(tmpisrvalue, SMBUS_FLAG_TC) != RESET) || (SMBUS_CHECK_FLAG(tmpisrvalue, SMBUS_FLAG_STOPF) != RESET) || (SMBUS_CHECK_FLAG(tmpisrvalue, SMBUS_FLAG_AF) != RESET)) && (__HAL_SMBUS_GET_IT_SOURCE(hsmbus, (SMBUS_IT_TCI | SMBUS_IT_STOPI | SMBUS_IT_NACKI | SMBUS_IT_RXI)) != RESET))
1187 /* Slave mode selected */
1188 if ((hsmbus->State & HAL_SMBUS_STATE_SLAVE_BUSY_RX) == HAL_SMBUS_STATE_SLAVE_BUSY_RX)
1190 SMBUS_Slave_ISR(hsmbus);
1192 /* Master mode selected */
1193 else if ((hsmbus->State & HAL_SMBUS_STATE_MASTER_BUSY_RX) == HAL_SMBUS_STATE_MASTER_BUSY_RX)
1195 SMBUS_Master_ISR(hsmbus);
1199 /* SMBUS in mode Listener Only --------------------------------------------------*/
1200 if (((SMBUS_CHECK_FLAG(tmpisrvalue, SMBUS_FLAG_ADDR) != RESET) || (SMBUS_CHECK_FLAG(tmpisrvalue, SMBUS_FLAG_STOPF) != RESET) || (SMBUS_CHECK_FLAG(tmpisrvalue, SMBUS_FLAG_AF) != RESET))
1201 && ((__HAL_SMBUS_GET_IT_SOURCE(hsmbus, SMBUS_IT_ADDRI) != RESET) || (__HAL_SMBUS_GET_IT_SOURCE(hsmbus, SMBUS_IT_STOPI) != RESET) || (__HAL_SMBUS_GET_IT_SOURCE(hsmbus, SMBUS_IT_NACKI) != RESET)))
1203 if (hsmbus->State == HAL_SMBUS_STATE_LISTEN)
1205 SMBUS_Slave_ISR(hsmbus);
1211 * @brief Handle SMBUS error interrupt request.
1212 * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains
1213 * the configuration information for the specified SMBUS.
1214 * @retval None
1216 void HAL_SMBUS_ER_IRQHandler(SMBUS_HandleTypeDef *hsmbus)
1218 SMBUS_ITErrorHandler(hsmbus);
1222 * @brief Master Tx Transfer completed callback.
1223 * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains
1224 * the configuration information for the specified SMBUS.
1225 * @retval None
1227 __weak void HAL_SMBUS_MasterTxCpltCallback(SMBUS_HandleTypeDef *hsmbus)
1229 /* Prevent unused argument(s) compilation warning */
1230 UNUSED(hsmbus);
1232 /* NOTE : This function should not be modified, when the callback is needed,
1233 the HAL_SMBUS_MasterTxCpltCallback() could be implemented in the user file
1238 * @brief Master Rx Transfer completed callback.
1239 * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains
1240 * the configuration information for the specified SMBUS.
1241 * @retval None
1243 __weak void HAL_SMBUS_MasterRxCpltCallback(SMBUS_HandleTypeDef *hsmbus)
1245 /* Prevent unused argument(s) compilation warning */
1246 UNUSED(hsmbus);
1248 /* NOTE : This function should not be modified, when the callback is needed,
1249 the HAL_SMBUS_MasterRxCpltCallback() could be implemented in the user file
1253 /** @brief Slave Tx Transfer completed callback.
1254 * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains
1255 * the configuration information for the specified SMBUS.
1256 * @retval None
1258 __weak void HAL_SMBUS_SlaveTxCpltCallback(SMBUS_HandleTypeDef *hsmbus)
1260 /* Prevent unused argument(s) compilation warning */
1261 UNUSED(hsmbus);
1263 /* NOTE : This function should not be modified, when the callback is needed,
1264 the HAL_SMBUS_SlaveTxCpltCallback() could be implemented in the user file
1269 * @brief Slave Rx Transfer completed callback.
1270 * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains
1271 * the configuration information for the specified SMBUS.
1272 * @retval None
1274 __weak void HAL_SMBUS_SlaveRxCpltCallback(SMBUS_HandleTypeDef *hsmbus)
1276 /* Prevent unused argument(s) compilation warning */
1277 UNUSED(hsmbus);
1279 /* NOTE : This function should not be modified, when the callback is needed,
1280 the HAL_SMBUS_SlaveRxCpltCallback() could be implemented in the user file
1285 * @brief Slave Address Match callback.
1286 * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains
1287 * the configuration information for the specified SMBUS.
1288 * @param TransferDirection Master request Transfer Direction (Write/Read)
1289 * @param AddrMatchCode Address Match Code
1290 * @retval None
1292 __weak void HAL_SMBUS_AddrCallback(SMBUS_HandleTypeDef *hsmbus, uint8_t TransferDirection, uint16_t AddrMatchCode)
1294 /* Prevent unused argument(s) compilation warning */
1295 UNUSED(hsmbus);
1296 UNUSED(TransferDirection);
1297 UNUSED(AddrMatchCode);
1299 /* NOTE : This function should not be modified, when the callback is needed,
1300 the HAL_SMBUS_AddrCallback() could be implemented in the user file
1305 * @brief Listen Complete callback.
1306 * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains
1307 * the configuration information for the specified SMBUS.
1308 * @retval None
1310 __weak void HAL_SMBUS_ListenCpltCallback(SMBUS_HandleTypeDef *hsmbus)
1312 /* Prevent unused argument(s) compilation warning */
1313 UNUSED(hsmbus);
1315 /* NOTE : This function should not be modified, when the callback is needed,
1316 the HAL_SMBUS_ListenCpltCallback() could be implemented in the user file
1321 * @brief SMBUS error callback.
1322 * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains
1323 * the configuration information for the specified SMBUS.
1324 * @retval None
1326 __weak void HAL_SMBUS_ErrorCallback(SMBUS_HandleTypeDef *hsmbus)
1328 /* Prevent unused argument(s) compilation warning */
1329 UNUSED(hsmbus);
1331 /* NOTE : This function should not be modified, when the callback is needed,
1332 the HAL_SMBUS_ErrorCallback() could be implemented in the user file
1337 * @}
1340 /** @defgroup SMBUS_Exported_Functions_Group3 Peripheral State and Errors functions
1341 * @brief Peripheral State and Errors functions
1343 @verbatim
1344 ===============================================================================
1345 ##### Peripheral State and Errors functions #####
1346 ===============================================================================
1347 [..]
1348 This subsection permits to get in run-time the status of the peripheral
1349 and the data flow.
1351 @endverbatim
1352 * @{
1356 * @brief Return the SMBUS handle state.
1357 * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains
1358 * the configuration information for the specified SMBUS.
1359 * @retval HAL state
1361 uint32_t HAL_SMBUS_GetState(SMBUS_HandleTypeDef *hsmbus)
1363 /* Return SMBUS handle state */
1364 return hsmbus->State;
1368 * @brief Return the SMBUS error code.
1369 * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains
1370 * the configuration information for the specified SMBUS.
1371 * @retval SMBUS Error Code
1373 uint32_t HAL_SMBUS_GetError(SMBUS_HandleTypeDef *hsmbus)
1375 return hsmbus->ErrorCode;
1379 * @}
1383 * @}
1386 /** @addtogroup SMBUS_Private_Functions SMBUS Private Functions
1387 * @brief Data transfers Private functions
1388 * @{
1392 * @brief Interrupt Sub-Routine which handle the Interrupt Flags Master Mode.
1393 * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains
1394 * the configuration information for the specified SMBUS.
1395 * @retval HAL status
1397 static HAL_StatusTypeDef SMBUS_Master_ISR(SMBUS_HandleTypeDef *hsmbus)
1399 uint16_t DevAddress;
1401 /* Process Locked */
1402 __HAL_LOCK(hsmbus);
1404 if (__HAL_SMBUS_GET_FLAG(hsmbus, SMBUS_FLAG_AF) != RESET)
1406 /* Clear NACK Flag */
1407 __HAL_SMBUS_CLEAR_FLAG(hsmbus, SMBUS_FLAG_AF);
1409 /* Set corresponding Error Code */
1410 /* No need to generate STOP, it is automatically done */
1411 hsmbus->ErrorCode |= HAL_SMBUS_ERROR_ACKF;
1413 /* Process Unlocked */
1414 __HAL_UNLOCK(hsmbus);
1416 /* Call the Error callback to inform upper layer */
1417 HAL_SMBUS_ErrorCallback(hsmbus);
1419 else if (__HAL_SMBUS_GET_FLAG(hsmbus, SMBUS_FLAG_STOPF) != RESET)
1421 /* Check and treat errors if errors occurs during STOP process */
1422 SMBUS_ITErrorHandler(hsmbus);
1424 /* Call the corresponding callback to inform upper layer of End of Transfer */
1425 if (hsmbus->State == HAL_SMBUS_STATE_MASTER_BUSY_TX)
1427 /* Disable Interrupt */
1428 SMBUS_Disable_IRQ(hsmbus, SMBUS_IT_TX);
1430 /* Clear STOP Flag */
1431 __HAL_SMBUS_CLEAR_FLAG(hsmbus, SMBUS_FLAG_STOPF);
1433 /* Clear Configuration Register 2 */
1434 SMBUS_RESET_CR2(hsmbus);
1436 /* Flush remaining data in Fifo register in case of error occurs before TXEmpty */
1437 /* Disable the selected SMBUS peripheral */
1438 __HAL_SMBUS_DISABLE(hsmbus);
1440 hsmbus->PreviousState = HAL_SMBUS_STATE_READY;
1441 hsmbus->State = HAL_SMBUS_STATE_READY;
1443 /* Process Unlocked */
1444 __HAL_UNLOCK(hsmbus);
1446 /* REenable the selected SMBUS peripheral */
1447 __HAL_SMBUS_ENABLE(hsmbus);
1449 HAL_SMBUS_MasterTxCpltCallback(hsmbus);
1451 else if (hsmbus->State == HAL_SMBUS_STATE_MASTER_BUSY_RX)
1453 /* Store Last receive data if any */
1454 if (__HAL_SMBUS_GET_FLAG(hsmbus, SMBUS_FLAG_RXNE) != RESET)
1456 /* Read data from RXDR */
1457 (*hsmbus->pBuffPtr++) = hsmbus->Instance->RXDR;
1459 if ((hsmbus->XferSize > 0U))
1461 hsmbus->XferSize--;
1462 hsmbus->XferCount--;
1466 /* Disable Interrupt */
1467 SMBUS_Disable_IRQ(hsmbus, SMBUS_IT_RX);
1469 /* Clear STOP Flag */
1470 __HAL_SMBUS_CLEAR_FLAG(hsmbus, SMBUS_FLAG_STOPF);
1472 /* Clear Configuration Register 2 */
1473 SMBUS_RESET_CR2(hsmbus);
1475 hsmbus->PreviousState = HAL_SMBUS_STATE_READY;
1476 hsmbus->State = HAL_SMBUS_STATE_READY;
1478 /* Process Unlocked */
1479 __HAL_UNLOCK(hsmbus);
1481 HAL_SMBUS_MasterRxCpltCallback(hsmbus);
1484 else if (__HAL_SMBUS_GET_FLAG(hsmbus, SMBUS_FLAG_RXNE) != RESET)
1486 /* Read data from RXDR */
1487 (*hsmbus->pBuffPtr++) = hsmbus->Instance->RXDR;
1488 hsmbus->XferSize--;
1489 hsmbus->XferCount--;
1491 else if (__HAL_SMBUS_GET_FLAG(hsmbus, SMBUS_FLAG_TXIS) != RESET)
1493 /* Write data to TXDR */
1494 hsmbus->Instance->TXDR = (*hsmbus->pBuffPtr++);
1495 hsmbus->XferSize--;
1496 hsmbus->XferCount--;
1498 else if (__HAL_SMBUS_GET_FLAG(hsmbus, SMBUS_FLAG_TCR) != RESET)
1500 if ((hsmbus->XferSize == 0U) && (hsmbus->XferCount != 0U))
1502 DevAddress = (hsmbus->Instance->CR2 & I2C_CR2_SADD);
1504 if (hsmbus->XferCount > MAX_NBYTE_SIZE)
1506 SMBUS_TransferConfig(hsmbus, DevAddress, MAX_NBYTE_SIZE, (SMBUS_RELOAD_MODE | (hsmbus->XferOptions & SMBUS_SENDPEC_MODE)), SMBUS_NO_STARTSTOP);
1507 hsmbus->XferSize = MAX_NBYTE_SIZE;
1509 else
1511 hsmbus->XferSize = hsmbus->XferCount;
1512 SMBUS_TransferConfig(hsmbus, DevAddress, hsmbus->XferSize, hsmbus->XferOptions, SMBUS_NO_STARTSTOP);
1513 /* If PEC mode is enable, size to transmit should be Size-1 byte, corresponding to PEC byte */
1514 /* PEC byte is automatically sent by HW block, no need to manage it in Transmit process */
1515 if (SMBUS_GET_PEC_MODE(hsmbus) != RESET)
1517 hsmbus->XferSize--;
1518 hsmbus->XferCount--;
1522 else if ((hsmbus->XferSize == 0U) && (hsmbus->XferCount == 0U))
1524 /* Call TxCpltCallback() if no stop mode is set */
1525 if (SMBUS_GET_STOP_MODE(hsmbus) != SMBUS_AUTOEND_MODE)
1527 /* Call the corresponding callback to inform upper layer of End of Transfer */
1528 if (hsmbus->State == HAL_SMBUS_STATE_MASTER_BUSY_TX)
1530 /* Disable Interrupt */
1531 SMBUS_Disable_IRQ(hsmbus, SMBUS_IT_TX);
1532 hsmbus->PreviousState = hsmbus->State;
1533 hsmbus->State = HAL_SMBUS_STATE_READY;
1535 /* Process Unlocked */
1536 __HAL_UNLOCK(hsmbus);
1538 HAL_SMBUS_MasterTxCpltCallback(hsmbus);
1540 else if (hsmbus->State == HAL_SMBUS_STATE_MASTER_BUSY_RX)
1542 SMBUS_Disable_IRQ(hsmbus, SMBUS_IT_RX);
1543 hsmbus->PreviousState = hsmbus->State;
1544 hsmbus->State = HAL_SMBUS_STATE_READY;
1546 /* Process Unlocked */
1547 __HAL_UNLOCK(hsmbus);
1549 HAL_SMBUS_MasterRxCpltCallback(hsmbus);
1554 else if (__HAL_SMBUS_GET_FLAG(hsmbus, SMBUS_FLAG_TC) != RESET)
1556 if (hsmbus->XferCount == 0U)
1558 /* Specific use case for Quick command */
1559 if (hsmbus->pBuffPtr == NULL)
1561 /* Generate a Stop command */
1562 hsmbus->Instance->CR2 |= I2C_CR2_STOP;
1564 /* Call TxCpltCallback() if no stop mode is set */
1565 else if (SMBUS_GET_STOP_MODE(hsmbus) != SMBUS_AUTOEND_MODE)
1567 /* No Generate Stop, to permit restart mode */
1568 /* The stop will be done at the end of transfer, when SMBUS_AUTOEND_MODE enable */
1570 /* Call the corresponding callback to inform upper layer of End of Transfer */
1571 if (hsmbus->State == HAL_SMBUS_STATE_MASTER_BUSY_TX)
1573 /* Disable Interrupt */
1574 SMBUS_Disable_IRQ(hsmbus, SMBUS_IT_TX);
1575 hsmbus->PreviousState = hsmbus->State;
1576 hsmbus->State = HAL_SMBUS_STATE_READY;
1578 /* Process Unlocked */
1579 __HAL_UNLOCK(hsmbus);
1581 HAL_SMBUS_MasterTxCpltCallback(hsmbus);
1583 else if (hsmbus->State == HAL_SMBUS_STATE_MASTER_BUSY_RX)
1585 SMBUS_Disable_IRQ(hsmbus, SMBUS_IT_RX);
1586 hsmbus->PreviousState = hsmbus->State;
1587 hsmbus->State = HAL_SMBUS_STATE_READY;
1589 /* Process Unlocked */
1590 __HAL_UNLOCK(hsmbus);
1592 HAL_SMBUS_MasterRxCpltCallback(hsmbus);
1598 /* Process Unlocked */
1599 __HAL_UNLOCK(hsmbus);
1601 return HAL_OK;
1604 * @brief Interrupt Sub-Routine which handle the Interrupt Flags Slave Mode.
1605 * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains
1606 * the configuration information for the specified SMBUS.
1607 * @retval HAL status
1609 static HAL_StatusTypeDef SMBUS_Slave_ISR(SMBUS_HandleTypeDef *hsmbus)
1611 uint8_t TransferDirection = 0U;
1612 uint16_t SlaveAddrCode = 0U;
1614 /* Process Locked */
1615 __HAL_LOCK(hsmbus);
1617 if (__HAL_SMBUS_GET_FLAG(hsmbus, SMBUS_FLAG_AF) != RESET)
1619 /* Check that SMBUS transfer finished */
1620 /* if yes, normal usecase, a NACK is sent by the HOST when Transfer is finished */
1621 /* Mean XferCount == 0*/
1622 /* So clear Flag NACKF only */
1623 if (hsmbus->XferCount == 0U)
1625 /* Clear NACK Flag */
1626 __HAL_SMBUS_CLEAR_FLAG(hsmbus, SMBUS_FLAG_AF);
1628 /* Process Unlocked */
1629 __HAL_UNLOCK(hsmbus);
1631 else
1633 /* if no, error usecase, a Non-Acknowledge of last Data is generated by the HOST*/
1634 /* Clear NACK Flag */
1635 __HAL_SMBUS_CLEAR_FLAG(hsmbus, SMBUS_FLAG_AF);
1637 /* Set HAL State to "Idle" State, mean to LISTEN state */
1638 /* So reset Slave Busy state */
1639 hsmbus->PreviousState = hsmbus->State;
1640 hsmbus->State &= ~((uint32_t)HAL_SMBUS_STATE_SLAVE_BUSY_TX);
1641 hsmbus->State &= ~((uint32_t)HAL_SMBUS_STATE_SLAVE_BUSY_RX);
1643 /* Disable RX/TX Interrupts, keep only ADDR Interrupt */
1644 SMBUS_Disable_IRQ(hsmbus, SMBUS_IT_RX | SMBUS_IT_TX);
1646 /* Set ErrorCode corresponding to a Non-Acknowledge */
1647 hsmbus->ErrorCode |= HAL_SMBUS_ERROR_ACKF;
1649 /* Process Unlocked */
1650 __HAL_UNLOCK(hsmbus);
1652 /* Call the Error callback to inform upper layer */
1653 HAL_SMBUS_ErrorCallback(hsmbus);
1656 else if (__HAL_SMBUS_GET_FLAG(hsmbus, SMBUS_FLAG_ADDR) != RESET)
1658 TransferDirection = SMBUS_GET_DIR(hsmbus);
1659 SlaveAddrCode = SMBUS_GET_ADDR_MATCH(hsmbus);
1661 /* Disable ADDR interrupt to prevent multiple ADDRInterrupt*/
1662 /* Other ADDRInterrupt will be treat in next Listen usecase */
1663 __HAL_SMBUS_DISABLE_IT(hsmbus, SMBUS_IT_ADDRI);
1665 /* Process Unlocked */
1666 __HAL_UNLOCK(hsmbus);
1668 /* Call Slave Addr callback */
1669 HAL_SMBUS_AddrCallback(hsmbus, TransferDirection, SlaveAddrCode);
1671 else if ((__HAL_SMBUS_GET_FLAG(hsmbus, SMBUS_FLAG_RXNE) != RESET) || (__HAL_SMBUS_GET_FLAG(hsmbus, SMBUS_FLAG_TCR) != RESET))
1673 if ((hsmbus->State & HAL_SMBUS_STATE_SLAVE_BUSY_RX) == HAL_SMBUS_STATE_SLAVE_BUSY_RX)
1675 /* Read data from RXDR */
1676 (*hsmbus->pBuffPtr++) = hsmbus->Instance->RXDR;
1677 hsmbus->XferSize--;
1678 hsmbus->XferCount--;
1680 if (hsmbus->XferCount == 1U)
1682 /* Receive last Byte, can be PEC byte in case of PEC BYTE enabled */
1683 /* or only the last Byte of Transfer */
1684 /* So reset the RELOAD bit mode */
1685 hsmbus->XferOptions &= ~SMBUS_RELOAD_MODE;
1686 SMBUS_TransferConfig(hsmbus, 0U , 1U , hsmbus->XferOptions, SMBUS_NO_STARTSTOP);
1688 else if (hsmbus->XferCount == 0U)
1690 /* Last Byte is received, disable Interrupt */
1691 SMBUS_Disable_IRQ(hsmbus, SMBUS_IT_RX);
1693 /* Remove HAL_SMBUS_STATE_SLAVE_BUSY_RX, keep only HAL_SMBUS_STATE_LISTEN */
1694 hsmbus->PreviousState = hsmbus->State;
1695 hsmbus->State &= ~((uint32_t)HAL_SMBUS_STATE_SLAVE_BUSY_RX);
1697 /* Process Unlocked */
1698 __HAL_UNLOCK(hsmbus);
1700 /* Call the Rx complete callback to inform upper layer of the end of receive process */
1701 HAL_SMBUS_SlaveRxCpltCallback(hsmbus);
1703 else
1705 /* Set Reload for next Bytes */
1706 SMBUS_TransferConfig(hsmbus, 0U, 1U, SMBUS_RELOAD_MODE | (hsmbus->XferOptions & SMBUS_SENDPEC_MODE), SMBUS_NO_STARTSTOP);
1708 /* Ack last Byte Read */
1709 hsmbus->Instance->CR2 &= ~I2C_CR2_NACK;
1712 else if ((hsmbus->State & HAL_SMBUS_STATE_SLAVE_BUSY_TX) == HAL_SMBUS_STATE_SLAVE_BUSY_TX)
1714 if ((hsmbus->XferSize == 0U) && (hsmbus->XferCount != 0U))
1716 if (hsmbus->XferCount > MAX_NBYTE_SIZE)
1718 SMBUS_TransferConfig(hsmbus, 0U, MAX_NBYTE_SIZE, (SMBUS_RELOAD_MODE | (hsmbus->XferOptions & SMBUS_SENDPEC_MODE)), SMBUS_NO_STARTSTOP);
1719 hsmbus->XferSize = MAX_NBYTE_SIZE;
1721 else
1723 hsmbus->XferSize = hsmbus->XferCount;
1724 SMBUS_TransferConfig(hsmbus, 0U, hsmbus->XferSize, hsmbus->XferOptions, SMBUS_NO_STARTSTOP);
1725 /* If PEC mode is enable, size to transmit should be Size-1 byte, corresponding to PEC byte */
1726 /* PEC byte is automatically sent by HW block, no need to manage it in Transmit process */
1727 if (SMBUS_GET_PEC_MODE(hsmbus) != RESET)
1729 hsmbus->XferSize--;
1730 hsmbus->XferCount--;
1736 else if (__HAL_SMBUS_GET_FLAG(hsmbus, SMBUS_FLAG_TXIS) != RESET)
1738 /* Write data to TXDR only if XferCount not reach "0" */
1739 /* A TXIS flag can be set, during STOP treatment */
1740 /* Check if all Data have already been sent */
1741 /* If it is the case, this last write in TXDR is not sent, correspond to a dummy TXIS event */
1742 if (hsmbus->XferCount > 0U)
1744 /* Write data to TXDR */
1745 hsmbus->Instance->TXDR = (*hsmbus->pBuffPtr++);
1746 hsmbus->XferCount--;
1747 hsmbus->XferSize--;
1750 if (hsmbus->XferCount == 0U)
1752 /* Last Byte is Transmitted */
1753 /* Remove HAL_SMBUS_STATE_SLAVE_BUSY_TX, keep only HAL_SMBUS_STATE_LISTEN */
1754 SMBUS_Disable_IRQ(hsmbus, SMBUS_IT_TX);
1755 hsmbus->PreviousState = hsmbus->State;
1756 hsmbus->State &= ~((uint32_t)HAL_SMBUS_STATE_SLAVE_BUSY_TX);
1758 /* Process Unlocked */
1759 __HAL_UNLOCK(hsmbus);
1761 /* Call the Tx complete callback to inform upper layer of the end of transmit process */
1762 HAL_SMBUS_SlaveTxCpltCallback(hsmbus);
1766 /* Check if STOPF is set */
1767 if (__HAL_SMBUS_GET_FLAG(hsmbus, SMBUS_FLAG_STOPF) != RESET)
1769 if ((hsmbus->State & HAL_SMBUS_STATE_LISTEN) == HAL_SMBUS_STATE_LISTEN)
1771 /* Store Last receive data if any */
1772 if (__HAL_SMBUS_GET_FLAG(hsmbus, SMBUS_FLAG_RXNE) != RESET)
1774 /* Read data from RXDR */
1775 (*hsmbus->pBuffPtr++) = hsmbus->Instance->RXDR;
1777 if ((hsmbus->XferSize > 0U))
1779 hsmbus->XferSize--;
1780 hsmbus->XferCount--;
1784 /* Disable RX and TX Interrupts */
1785 SMBUS_Disable_IRQ(hsmbus, SMBUS_IT_RX | SMBUS_IT_TX);
1787 /* Disable ADDR Interrupt */
1788 SMBUS_Disable_IRQ(hsmbus, SMBUS_IT_ADDR);
1790 /* Disable Address Acknowledge */
1791 hsmbus->Instance->CR2 |= I2C_CR2_NACK;
1793 /* Clear Configuration Register 2 */
1794 SMBUS_RESET_CR2(hsmbus);
1796 /* Clear STOP Flag */
1797 __HAL_SMBUS_CLEAR_FLAG(hsmbus, SMBUS_FLAG_STOPF);
1799 /* Clear ADDR flag */
1800 __HAL_SMBUS_CLEAR_FLAG(hsmbus, SMBUS_FLAG_ADDR);
1802 hsmbus->XferOptions = 0U;
1803 hsmbus->PreviousState = hsmbus->State;
1804 hsmbus->State = HAL_SMBUS_STATE_READY;
1806 /* Process Unlocked */
1807 __HAL_UNLOCK(hsmbus);
1809 /* Call the Listen Complete callback, to inform upper layer of the end of Listen usecase */
1810 HAL_SMBUS_ListenCpltCallback(hsmbus);
1814 /* Process Unlocked */
1815 __HAL_UNLOCK(hsmbus);
1817 return HAL_OK;
1820 * @brief Manage the enabling of Interrupts.
1821 * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains
1822 * the configuration information for the specified SMBUS.
1823 * @param InterruptRequest Value of @ref SMBUS_Interrupt_configuration_definition.
1824 * @retval HAL status
1826 static HAL_StatusTypeDef SMBUS_Enable_IRQ(SMBUS_HandleTypeDef *hsmbus, uint16_t InterruptRequest)
1828 uint32_t tmpisr = 0U;
1830 if ((InterruptRequest & SMBUS_IT_ALERT) == SMBUS_IT_ALERT)
1832 /* Enable ERR interrupt */
1833 tmpisr |= SMBUS_IT_ERRI;
1836 if ((InterruptRequest & SMBUS_IT_ADDR) == SMBUS_IT_ADDR)
1838 /* Enable ADDR, STOP interrupt */
1839 tmpisr |= SMBUS_IT_ADDRI | SMBUS_IT_STOPI | SMBUS_IT_NACKI | SMBUS_IT_ERRI;
1842 if ((InterruptRequest & SMBUS_IT_TX) == SMBUS_IT_TX)
1844 /* Enable ERR, TC, STOP, NACK, RXI interrupt */
1845 tmpisr |= SMBUS_IT_ERRI | SMBUS_IT_TCI | SMBUS_IT_STOPI | SMBUS_IT_NACKI | SMBUS_IT_TXI;
1848 if ((InterruptRequest & SMBUS_IT_RX) == SMBUS_IT_RX)
1850 /* Enable ERR, TC, STOP, NACK, TXI interrupt */
1851 tmpisr |= SMBUS_IT_ERRI | SMBUS_IT_TCI | SMBUS_IT_STOPI | SMBUS_IT_NACKI | SMBUS_IT_RXI;
1854 /* Enable interrupts only at the end */
1855 /* to avoid the risk of SMBUS interrupt handle execution before */
1856 /* all interrupts requested done */
1857 __HAL_SMBUS_ENABLE_IT(hsmbus, tmpisr);
1859 return HAL_OK;
1862 * @brief Manage the disabling of Interrupts.
1863 * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains
1864 * the configuration information for the specified SMBUS.
1865 * @param InterruptRequest Value of @ref SMBUS_Interrupt_configuration_definition.
1866 * @retval HAL status
1868 static HAL_StatusTypeDef SMBUS_Disable_IRQ(SMBUS_HandleTypeDef *hsmbus, uint16_t InterruptRequest)
1870 uint32_t tmpisr = 0U;
1872 if (((InterruptRequest & SMBUS_IT_ALERT) == SMBUS_IT_ALERT) && (hsmbus->State == HAL_SMBUS_STATE_READY))
1874 /* Disable ERR interrupt */
1875 tmpisr |= SMBUS_IT_ERRI;
1878 if ((InterruptRequest & SMBUS_IT_TX) == SMBUS_IT_TX)
1880 /* Disable TC, STOP, NACK, TXI interrupt */
1881 tmpisr |= SMBUS_IT_TCI | SMBUS_IT_TXI;
1883 if ((SMBUS_GET_ALERT_ENABLED(hsmbus) == RESET)
1884 && ((hsmbus->State & HAL_SMBUS_STATE_LISTEN) != HAL_SMBUS_STATE_LISTEN))
1886 /* Disable ERR interrupt */
1887 tmpisr |= SMBUS_IT_ERRI;
1890 if ((hsmbus->State & HAL_SMBUS_STATE_LISTEN) != HAL_SMBUS_STATE_LISTEN)
1892 /* Disable STOPI, NACKI */
1893 tmpisr |= SMBUS_IT_STOPI | SMBUS_IT_NACKI;
1897 if ((InterruptRequest & SMBUS_IT_RX) == SMBUS_IT_RX)
1899 /* Disable TC, STOP, NACK, RXI interrupt */
1900 tmpisr |= SMBUS_IT_TCI | SMBUS_IT_RXI;
1902 if ((SMBUS_GET_ALERT_ENABLED(hsmbus) == RESET)
1903 && ((hsmbus->State & HAL_SMBUS_STATE_LISTEN) != HAL_SMBUS_STATE_LISTEN))
1905 /* Disable ERR interrupt */
1906 tmpisr |= SMBUS_IT_ERRI;
1909 if ((hsmbus->State & HAL_SMBUS_STATE_LISTEN) != HAL_SMBUS_STATE_LISTEN)
1911 /* Disable STOPI, NACKI */
1912 tmpisr |= SMBUS_IT_STOPI | SMBUS_IT_NACKI;
1916 if ((InterruptRequest & SMBUS_IT_ADDR) == SMBUS_IT_ADDR)
1918 /* Enable ADDR, STOP interrupt */
1919 tmpisr |= SMBUS_IT_ADDRI | SMBUS_IT_STOPI | SMBUS_IT_NACKI;
1921 if (SMBUS_GET_ALERT_ENABLED(hsmbus) == RESET)
1923 /* Disable ERR interrupt */
1924 tmpisr |= SMBUS_IT_ERRI;
1928 /* Disable interrupts only at the end */
1929 /* to avoid a breaking situation like at "t" time */
1930 /* all disable interrupts request are not done */
1931 __HAL_SMBUS_DISABLE_IT(hsmbus, tmpisr);
1933 return HAL_OK;
1937 * @brief SMBUS interrupts error handler.
1938 * @param hsmbus SMBUS handle.
1939 * @retval None
1941 static void SMBUS_ITErrorHandler(SMBUS_HandleTypeDef *hsmbus)
1943 uint32_t itflags = READ_REG(hsmbus->Instance->ISR);
1944 uint32_t itsources = READ_REG(hsmbus->Instance->CR1);
1946 /* SMBUS Bus error interrupt occurred ------------------------------------*/
1947 if (((itflags & SMBUS_FLAG_BERR) != RESET) && ((itsources & SMBUS_IT_ERRI) != RESET))
1949 hsmbus->ErrorCode |= HAL_SMBUS_ERROR_BERR;
1951 /* Clear BERR flag */
1952 __HAL_SMBUS_CLEAR_FLAG(hsmbus, SMBUS_FLAG_BERR);
1955 /* SMBUS Over-Run/Under-Run interrupt occurred ----------------------------------------*/
1956 if (((itflags & SMBUS_FLAG_OVR) != RESET) && ((itsources & SMBUS_IT_ERRI) != RESET))
1958 hsmbus->ErrorCode |= HAL_SMBUS_ERROR_OVR;
1960 /* Clear OVR flag */
1961 __HAL_SMBUS_CLEAR_FLAG(hsmbus, SMBUS_FLAG_OVR);
1964 /* SMBUS Arbitration Loss error interrupt occurred ------------------------------------*/
1965 if (((itflags & SMBUS_FLAG_ARLO) != RESET) && ((itsources & SMBUS_IT_ERRI) != RESET))
1967 hsmbus->ErrorCode |= HAL_SMBUS_ERROR_ARLO;
1969 /* Clear ARLO flag */
1970 __HAL_SMBUS_CLEAR_FLAG(hsmbus, SMBUS_FLAG_ARLO);
1973 /* SMBUS Timeout error interrupt occurred ---------------------------------------------*/
1974 if (((itflags & SMBUS_FLAG_TIMEOUT) != RESET) && ((itsources & SMBUS_IT_ERRI) != RESET))
1976 hsmbus->ErrorCode |= HAL_SMBUS_ERROR_BUSTIMEOUT;
1978 /* Clear TIMEOUT flag */
1979 __HAL_SMBUS_CLEAR_FLAG(hsmbus, SMBUS_FLAG_TIMEOUT);
1982 /* SMBUS Alert error interrupt occurred -----------------------------------------------*/
1983 if (((itflags & SMBUS_FLAG_ALERT) != RESET) && ((itsources & SMBUS_IT_ERRI) != RESET))
1985 hsmbus->ErrorCode |= HAL_SMBUS_ERROR_ALERT;
1987 /* Clear ALERT flag */
1988 __HAL_SMBUS_CLEAR_FLAG(hsmbus, SMBUS_FLAG_ALERT);
1991 /* SMBUS Packet Error Check error interrupt occurred ----------------------------------*/
1992 if (((itflags & SMBUS_FLAG_PECERR) != RESET) && ((itsources & SMBUS_IT_ERRI) != RESET))
1994 hsmbus->ErrorCode |= HAL_SMBUS_ERROR_PECERR;
1996 /* Clear PEC error flag */
1997 __HAL_SMBUS_CLEAR_FLAG(hsmbus, SMBUS_FLAG_PECERR);
2000 /* Call the Error Callback in case of Error detected */
2001 if ((hsmbus->ErrorCode != HAL_SMBUS_ERROR_NONE) && (hsmbus->ErrorCode != HAL_SMBUS_ERROR_ACKF))
2003 /* Do not Reset the HAL state in case of ALERT error */
2004 if ((hsmbus->ErrorCode & HAL_SMBUS_ERROR_ALERT) != HAL_SMBUS_ERROR_ALERT)
2006 if (((hsmbus->State & HAL_SMBUS_STATE_SLAVE_BUSY_TX) == HAL_SMBUS_STATE_SLAVE_BUSY_TX)
2007 || ((hsmbus->State & HAL_SMBUS_STATE_SLAVE_BUSY_RX) == HAL_SMBUS_STATE_SLAVE_BUSY_RX))
2009 /* Reset only HAL_SMBUS_STATE_SLAVE_BUSY_XX */
2010 /* keep HAL_SMBUS_STATE_LISTEN if set */
2011 hsmbus->PreviousState = HAL_SMBUS_STATE_READY;
2012 hsmbus->State = HAL_SMBUS_STATE_LISTEN;
2016 /* Call the Error callback to inform upper layer */
2017 HAL_SMBUS_ErrorCallback(hsmbus);
2022 * @brief Handle SMBUS Communication Timeout.
2023 * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains
2024 * the configuration information for the specified SMBUS.
2025 * @param Flag Specifies the SMBUS flag to check.
2026 * @param Status The new Flag status (SET or RESET).
2027 * @param Timeout Timeout duration
2028 * @retval HAL status
2030 static HAL_StatusTypeDef SMBUS_WaitOnFlagUntilTimeout(SMBUS_HandleTypeDef *hsmbus, uint32_t Flag, FlagStatus Status, uint32_t Timeout)
2032 uint32_t tickstart = HAL_GetTick();
2034 /* Wait until flag is set */
2035 if (Status == RESET)
2037 while (__HAL_SMBUS_GET_FLAG(hsmbus, Flag) == RESET)
2039 /* Check for the Timeout */
2040 if (Timeout != HAL_MAX_DELAY)
2042 if ((Timeout == 0U) || ((HAL_GetTick() - tickstart) > Timeout))
2044 hsmbus->PreviousState = hsmbus->State;
2045 hsmbus->State = HAL_SMBUS_STATE_READY;
2047 /* Process Unlocked */
2048 __HAL_UNLOCK(hsmbus);
2050 return HAL_TIMEOUT;
2055 else
2057 while (__HAL_SMBUS_GET_FLAG(hsmbus, Flag) != RESET)
2059 /* Check for the Timeout */
2060 if (Timeout != HAL_MAX_DELAY)
2062 if ((Timeout == 0U) || ((HAL_GetTick() - tickstart) > Timeout))
2064 hsmbus->PreviousState = hsmbus->State;
2065 hsmbus->State = HAL_SMBUS_STATE_READY;
2067 /* Process Unlocked */
2068 __HAL_UNLOCK(hsmbus);
2070 return HAL_TIMEOUT;
2075 return HAL_OK;
2079 * @brief Handle SMBUSx communication when starting transfer or during transfer (TC or TCR flag are set).
2080 * @param hsmbus SMBUS handle.
2081 * @param DevAddress specifies the slave address to be programmed.
2082 * @param Size specifies the number of bytes to be programmed.
2083 * This parameter must be a value between 0 and 255.
2084 * @param Mode New state of the SMBUS START condition generation.
2085 * This parameter can be one or a combination of the following values:
2086 * @arg @ref SMBUS_RELOAD_MODE Enable Reload mode.
2087 * @arg @ref SMBUS_AUTOEND_MODE Enable Automatic end mode.
2088 * @arg @ref SMBUS_SOFTEND_MODE Enable Software end mode and Reload mode.
2089 * @arg @ref SMBUS_SENDPEC_MODE Enable Packet Error Calculation mode.
2090 * @param Request New state of the SMBUS START condition generation.
2091 * This parameter can be one of the following values:
2092 * @arg @ref SMBUS_NO_STARTSTOP Don't Generate stop and start condition.
2093 * @arg @ref SMBUS_GENERATE_STOP Generate stop condition (Size should be set to 0).
2094 * @arg @ref SMBUS_GENERATE_START_READ Generate Restart for read request.
2095 * @arg @ref SMBUS_GENERATE_START_WRITE Generate Restart for write request.
2096 * @retval None
2098 static void SMBUS_TransferConfig(SMBUS_HandleTypeDef *hsmbus, uint16_t DevAddress, uint8_t Size, uint32_t Mode, uint32_t Request)
2100 uint32_t tmpreg = 0U;
2102 /* Check the parameters */
2103 assert_param(IS_SMBUS_ALL_INSTANCE(hsmbus->Instance));
2104 assert_param(IS_SMBUS_TRANSFER_MODE(Mode));
2105 assert_param(IS_SMBUS_TRANSFER_REQUEST(Request));
2107 /* Get the CR2 register value */
2108 tmpreg = hsmbus->Instance->CR2;
2110 /* clear tmpreg specific bits */
2111 tmpreg &= (uint32_t)~((uint32_t)(I2C_CR2_SADD | I2C_CR2_NBYTES | I2C_CR2_RELOAD | I2C_CR2_AUTOEND | I2C_CR2_RD_WRN | I2C_CR2_START | I2C_CR2_STOP | I2C_CR2_PECBYTE));
2113 /* update tmpreg */
2114 tmpreg |= (uint32_t)(((uint32_t)DevAddress & I2C_CR2_SADD) | (((uint32_t)Size << 16U) & I2C_CR2_NBYTES) | \
2115 (uint32_t)Mode | (uint32_t)Request);
2117 /* update CR2 register */
2118 hsmbus->Instance->CR2 = tmpreg;
2122 * @brief Convert SMBUSx OTHER_xxx XferOptions to functionnal XferOptions.
2123 * @param hsmbus SMBUS handle.
2124 * @retval None
2126 static void SMBUS_ConvertOtherXferOptions(SMBUS_HandleTypeDef *hsmbus)
2128 /* if user set XferOptions to SMBUS_OTHER_FRAME_NO_PEC */
2129 /* it request implicitly to generate a restart condition */
2130 /* set XferOptions to SMBUS_FIRST_FRAME */
2131 if (hsmbus->XferOptions == SMBUS_OTHER_FRAME_NO_PEC)
2133 hsmbus->XferOptions = SMBUS_FIRST_FRAME;
2135 /* else if user set XferOptions to SMBUS_OTHER_FRAME_WITH_PEC */
2136 /* it request implicitly to generate a restart condition */
2137 /* set XferOptions to SMBUS_FIRST_FRAME | SMBUS_SENDPEC_MODE */
2138 else if (hsmbus->XferOptions == SMBUS_OTHER_FRAME_WITH_PEC)
2140 hsmbus->XferOptions = SMBUS_FIRST_FRAME | SMBUS_SENDPEC_MODE;
2142 /* else if user set XferOptions to SMBUS_OTHER_AND_LAST_FRAME_NO_PEC */
2143 /* it request implicitly to generate a restart condition */
2144 /* then generate a stop condition at the end of transfer */
2145 /* set XferOptions to SMBUS_FIRST_AND_LAST_FRAME_NO_PEC */
2146 else if (hsmbus->XferOptions == SMBUS_OTHER_AND_LAST_FRAME_NO_PEC)
2148 hsmbus->XferOptions = SMBUS_FIRST_AND_LAST_FRAME_NO_PEC;
2150 /* else if user set XferOptions to SMBUS_OTHER_AND_LAST_FRAME_WITH_PEC */
2151 /* it request implicitly to generate a restart condition */
2152 /* then generate a stop condition at the end of transfer */
2153 /* set XferOptions to SMBUS_FIRST_AND_LAST_FRAME_WITH_PEC */
2154 else if (hsmbus->XferOptions == SMBUS_OTHER_AND_LAST_FRAME_WITH_PEC)
2156 hsmbus->XferOptions = SMBUS_FIRST_AND_LAST_FRAME_WITH_PEC;
2160 * @}
2163 #endif /* HAL_SMBUS_MODULE_ENABLED */
2165 * @}
2169 * @}
2172 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/