2 ******************************************************************************
3 * @file stm32f7xx_hal_smbus.c
4 * @author MCD Application Team
7 * @brief SMBUS HAL module driver.
8 * This file provides firmware functions to manage the following
9 * functionalities of the System Management Bus (SMBus) peripheral,
10 * based on I2C principles of operation :
11 * + Initialization and de-initialization functions
12 * + IO operation functions
13 * + Peripheral State and Errors functions
16 ==============================================================================
17 ##### How to use this driver #####
18 ==============================================================================
20 The SMBUS HAL driver can be used as follows:
22 (#) Declare a SMBUS_HandleTypeDef handle structure, for example:
23 SMBUS_HandleTypeDef hsmbus;
25 (#)Initialize the SMBUS low level resources by implementing the HAL_SMBUS_MspInit() API:
26 (##) Enable the SMBUSx interface clock
27 (##) SMBUS pins configuration
28 (+++) Enable the clock for the SMBUS GPIOs
29 (+++) Configure SMBUS pins as alternate function open-drain
30 (##) NVIC configuration if you need to use interrupt process
31 (+++) Configure the SMBUSx interrupt priority
32 (+++) Enable the NVIC SMBUS IRQ Channel
34 (#) Configure the Communication Clock Timing, Bus Timeout, Own Address1, Master Addressing mode,
35 Dual Addressing mode, Own Address2, Own Address2 Mask, General call, Nostretch mode,
36 Peripheral mode and Packet Error Check mode in the hsmbus Init structure.
38 (#) Initialize the SMBUS registers by calling the HAL_SMBUS_Init() API:
39 (++) These API's configures also the low level Hardware GPIO, CLOCK, CORTEX...etc)
40 by calling the customized HAL_SMBUS_MspInit(&hsmbus) API.
42 (#) To check if target device is ready for communication, use the function HAL_SMBUS_IsDeviceReady()
44 (#) For SMBUS IO operations, only one mode of operations is available within this driver
46 *** Interrupt mode IO operation ***
47 ===================================
49 (+) Transmit in master/host SMBUS mode an amount of data in non-blocking mode using HAL_SMBUS_Master_Transmit_IT()
50 (++) At transmission end of transfer HAL_SMBUS_MasterTxCpltCallback() is executed and user can
51 add his own code by customization of function pointer HAL_SMBUS_MasterTxCpltCallback()
52 (+) Receive in master/host SMBUS mode an amount of data in non-blocking mode using HAL_SMBUS_Master_Receive_IT()
53 (++) At reception end of transfer HAL_SMBUS_MasterRxCpltCallback() is executed and user can
54 add his own code by customization of function pointer HAL_SMBUS_MasterRxCpltCallback()
55 (+) Abort a master/host SMBUS process communication with Interrupt using HAL_SMBUS_Master_Abort_IT()
56 (++) The associated previous transfer callback is called at the end of abort process
57 (++) mean HAL_SMBUS_MasterTxCpltCallback() in case of previous state was master transmit
58 (++) mean HAL_SMBUS_MasterRxCpltCallback() in case of previous state was master receive
59 (+) Enable/disable the Address listen mode in slave/device or host/slave SMBUS mode
60 using HAL_SMBUS_EnableListen_IT() HAL_SMBUS_DisableListen_IT()
61 (++) When address slave/device SMBUS match, HAL_SMBUS_AddrCallback() is executed and user can
62 add his own code to check the Address Match Code and the transmission direction request by master/host (Write/Read).
63 (++) At Listen mode end HAL_SMBUS_ListenCpltCallback() is executed and user can
64 add his own code by customization of function pointer HAL_SMBUS_ListenCpltCallback()
65 (+) Transmit in slave/device SMBUS mode an amount of data in non-blocking mode using HAL_SMBUS_Slave_Transmit_IT()
66 (++) At transmission end of transfer HAL_SMBUS_SlaveTxCpltCallback() is executed and user can
67 add his own code by customization of function pointer HAL_SMBUS_SlaveTxCpltCallback()
68 (+) Receive in slave/device SMBUS mode an amount of data in non-blocking mode using HAL_SMBUS_Slave_Receive_IT()
69 (++) At reception end of transfer HAL_SMBUS_SlaveRxCpltCallback() is executed and user can
70 add his own code by customization of function pointer HAL_SMBUS_SlaveRxCpltCallback()
71 (+) Enable/Disable the SMBUS alert mode using HAL_SMBUS_EnableAlert_IT() HAL_SMBUS_DisableAlert_IT()
72 (++) When SMBUS Alert is generated HAL_SMBUS_ErrorCallback() is executed and user can
73 add his own code by customization of function pointer HAL_SMBUS_ErrorCallback()
74 to check the Alert Error Code using function HAL_SMBUS_GetError()
75 (+) Get HAL state machine or error values using HAL_SMBUS_GetState() or HAL_SMBUS_GetError()
76 (+) In case of transfer Error, HAL_SMBUS_ErrorCallback() function is executed and user can
77 add his own code by customization of function pointer HAL_SMBUS_ErrorCallback()
78 to check the Error Code using function HAL_SMBUS_GetError()
80 *** SMBUS HAL driver macros list ***
81 ==================================
83 Below the list of most used macros in SMBUS HAL driver.
85 (+) __HAL_SMBUS_ENABLE: Enable the SMBUS peripheral
86 (+) __HAL_SMBUS_DISABLE: Disable the SMBUS peripheral
87 (+) __HAL_SMBUS_GET_FLAG: Check whether the specified SMBUS flag is set or not
88 (+) __HAL_SMBUS_CLEAR_FLAG: Clear the specified SMBUS pending flag
89 (+) __HAL_SMBUS_ENABLE_IT: Enable the specified SMBUS interrupt
90 (+) __HAL_SMBUS_DISABLE_IT: Disable the specified SMBUS interrupt
93 (@) You can refer to the SMBUS HAL driver header file for more useful macros
97 ******************************************************************************
100 * <h2><center>© COPYRIGHT(c) 2017 STMicroelectronics</center></h2>
102 * Redistribution and use in source and binary forms, with or without modification,
103 * are permitted provided that the following conditions are met:
104 * 1. Redistributions of source code must retain the above copyright notice,
105 * this list of conditions and the following disclaimer.
106 * 2. Redistributions in binary form must reproduce the above copyright notice,
107 * this list of conditions and the following disclaimer in the documentation
108 * and/or other materials provided with the distribution.
109 * 3. Neither the name of STMicroelectronics nor the names of its contributors
110 * may be used to endorse or promote products derived from this software
111 * without specific prior written permission.
113 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
114 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
115 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
116 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
117 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
118 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
119 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
120 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
121 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
122 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
124 ******************************************************************************
127 /* Includes ------------------------------------------------------------------*/
128 #include "stm32f7xx_hal.h"
130 /** @addtogroup STM32F7xx_HAL_Driver
134 /** @defgroup SMBUS SMBUS
135 * @brief SMBUS HAL module driver
139 #ifdef HAL_SMBUS_MODULE_ENABLED
141 /* Private typedef -----------------------------------------------------------*/
142 /* Private constants ---------------------------------------------------------*/
143 /** @defgroup SMBUS_Private_Define SMBUS Private Constants
146 #define TIMING_CLEAR_MASK (0xF0FFFFFFU) /*!< SMBUS TIMING clear register Mask */
147 #define HAL_TIMEOUT_ADDR (10000U) /*!< 10 s */
148 #define HAL_TIMEOUT_BUSY (25U) /*!< 25 ms */
149 #define HAL_TIMEOUT_DIR (25U) /*!< 25 ms */
150 #define HAL_TIMEOUT_RXNE (25U) /*!< 25 ms */
151 #define HAL_TIMEOUT_STOPF (25U) /*!< 25 ms */
152 #define HAL_TIMEOUT_TC (25U) /*!< 25 ms */
153 #define HAL_TIMEOUT_TCR (25U) /*!< 25 ms */
154 #define HAL_TIMEOUT_TXIS (25U) /*!< 25 ms */
155 #define MAX_NBYTE_SIZE 255U
160 /* Private macro -------------------------------------------------------------*/
161 /* Private variables ---------------------------------------------------------*/
162 /* Private function prototypes -----------------------------------------------*/
163 /** @addtogroup SMBUS_Private_Functions SMBUS Private Functions
166 static HAL_StatusTypeDef
SMBUS_WaitOnFlagUntilTimeout(SMBUS_HandleTypeDef
*hsmbus
, uint32_t Flag
, FlagStatus Status
, uint32_t Timeout
);
168 static HAL_StatusTypeDef
SMBUS_Enable_IRQ(SMBUS_HandleTypeDef
*hsmbus
, uint16_t InterruptRequest
);
169 static HAL_StatusTypeDef
SMBUS_Disable_IRQ(SMBUS_HandleTypeDef
*hsmbus
, uint16_t InterruptRequest
);
170 static HAL_StatusTypeDef
SMBUS_Master_ISR(SMBUS_HandleTypeDef
*hsmbus
);
171 static HAL_StatusTypeDef
SMBUS_Slave_ISR(SMBUS_HandleTypeDef
*hsmbus
);
173 static void SMBUS_ConvertOtherXferOptions(SMBUS_HandleTypeDef
*hsmbus
);
175 static void SMBUS_TransferConfig(SMBUS_HandleTypeDef
*hsmbus
, uint16_t DevAddress
, uint8_t Size
, uint32_t Mode
, uint32_t Request
);
180 /* Exported functions --------------------------------------------------------*/
182 /** @defgroup SMBUS_Exported_Functions SMBUS Exported Functions
186 /** @defgroup SMBUS_Exported_Functions_Group1 Initialization and de-initialization functions
187 * @brief Initialization and Configuration functions
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:
203 (++) Analog Filer mode
205 (++) Addressing mode (Master, Slave)
206 (++) Dual Addressing mode
208 (++) Own Address 2 Mask
209 (++) General call mode
211 (++) Packet Error Check mode
215 (+) Call the function HAL_SMBUS_DeInit() to restore the default configuration
216 of the selected SMBUSx peripheral.
223 * @brief Initialize the SMBUS according to the specified parameters
224 * in the SMBUS_InitTypeDef and initialize the associated handle.
225 * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains
226 * the configuration information for the specified SMBUS.
229 HAL_StatusTypeDef
HAL_SMBUS_Init(SMBUS_HandleTypeDef
*hsmbus
)
231 /* Check the SMBUS handle allocation */
237 /* Check the parameters */
238 assert_param(IS_SMBUS_ALL_INSTANCE(hsmbus
->Instance
));
239 assert_param(IS_SMBUS_ANALOG_FILTER(hsmbus
->Init
.AnalogFilter
));
240 assert_param(IS_SMBUS_OWN_ADDRESS1(hsmbus
->Init
.OwnAddress1
));
241 assert_param(IS_SMBUS_ADDRESSING_MODE(hsmbus
->Init
.AddressingMode
));
242 assert_param(IS_SMBUS_DUAL_ADDRESS(hsmbus
->Init
.DualAddressMode
));
243 assert_param(IS_SMBUS_OWN_ADDRESS2(hsmbus
->Init
.OwnAddress2
));
244 assert_param(IS_SMBUS_OWN_ADDRESS2_MASK(hsmbus
->Init
.OwnAddress2Masks
));
245 assert_param(IS_SMBUS_GENERAL_CALL(hsmbus
->Init
.GeneralCallMode
));
246 assert_param(IS_SMBUS_NO_STRETCH(hsmbus
->Init
.NoStretchMode
));
247 assert_param(IS_SMBUS_PEC(hsmbus
->Init
.PacketErrorCheckMode
));
248 assert_param(IS_SMBUS_PERIPHERAL_MODE(hsmbus
->Init
.PeripheralMode
));
250 if(hsmbus
->State
== HAL_SMBUS_STATE_RESET
)
252 /* Allocate lock resource and initialize it */
253 hsmbus
->Lock
= HAL_UNLOCKED
;
255 /* Init the low level hardware : GPIO, CLOCK, NVIC */
256 HAL_SMBUS_MspInit(hsmbus
);
259 hsmbus
->State
= HAL_SMBUS_STATE_BUSY
;
261 /* Disable the selected SMBUS peripheral */
262 __HAL_SMBUS_DISABLE(hsmbus
);
264 /*---------------------------- SMBUSx TIMINGR Configuration ------------------------*/
265 /* Configure SMBUSx: Frequency range */
266 hsmbus
->Instance
->TIMINGR
= hsmbus
->Init
.Timing
& TIMING_CLEAR_MASK
;
268 /*---------------------------- SMBUSx TIMEOUTR Configuration ------------------------*/
269 /* Configure SMBUSx: Bus Timeout */
270 hsmbus
->Instance
->TIMEOUTR
&= ~I2C_TIMEOUTR_TIMOUTEN
;
271 hsmbus
->Instance
->TIMEOUTR
&= ~I2C_TIMEOUTR_TEXTEN
;
272 hsmbus
->Instance
->TIMEOUTR
= hsmbus
->Init
.SMBusTimeout
;
274 /*---------------------------- SMBUSx OAR1 Configuration -----------------------*/
275 /* Configure SMBUSx: Own Address1 and ack own address1 mode */
276 hsmbus
->Instance
->OAR1
&= ~I2C_OAR1_OA1EN
;
278 if(hsmbus
->Init
.OwnAddress1
!= 0U)
280 if(hsmbus
->Init
.AddressingMode
== SMBUS_ADDRESSINGMODE_7BIT
)
282 hsmbus
->Instance
->OAR1
= (I2C_OAR1_OA1EN
| hsmbus
->Init
.OwnAddress1
);
284 else /* SMBUS_ADDRESSINGMODE_10BIT */
286 hsmbus
->Instance
->OAR1
= (I2C_OAR1_OA1EN
| I2C_OAR1_OA1MODE
| hsmbus
->Init
.OwnAddress1
);
290 /*---------------------------- SMBUSx CR2 Configuration ------------------------*/
291 /* Configure SMBUSx: Addressing Master mode */
292 if(hsmbus
->Init
.AddressingMode
== SMBUS_ADDRESSINGMODE_10BIT
)
294 hsmbus
->Instance
->CR2
= (I2C_CR2_ADD10
);
296 /* Enable the AUTOEND by default, and enable NACK (should be disable only during Slave process) */
297 /* AUTOEND and NACK bit will be manage during Transfer process */
298 hsmbus
->Instance
->CR2
|= (I2C_CR2_AUTOEND
| I2C_CR2_NACK
);
300 /*---------------------------- SMBUSx OAR2 Configuration -----------------------*/
301 /* Configure SMBUSx: Dual mode and Own Address2 */
302 hsmbus
->Instance
->OAR2
= (hsmbus
->Init
.DualAddressMode
| hsmbus
->Init
.OwnAddress2
| (hsmbus
->Init
.OwnAddress2Masks
<< 8U));
304 /*---------------------------- SMBUSx CR1 Configuration ------------------------*/
305 /* Configure SMBUSx: Generalcall and NoStretch mode */
306 hsmbus
->Instance
->CR1
= (hsmbus
->Init
.GeneralCallMode
| hsmbus
->Init
.NoStretchMode
| hsmbus
->Init
.PacketErrorCheckMode
| hsmbus
->Init
.PeripheralMode
| hsmbus
->Init
.AnalogFilter
);
308 /* Enable Slave Byte Control only in case of Packet Error Check is enabled and SMBUS Peripheral is set in Slave mode */
309 if( (hsmbus
->Init
.PacketErrorCheckMode
== SMBUS_PEC_ENABLE
)
310 && ( (hsmbus
->Init
.PeripheralMode
== SMBUS_PERIPHERAL_MODE_SMBUS_SLAVE
) || (hsmbus
->Init
.PeripheralMode
== SMBUS_PERIPHERAL_MODE_SMBUS_SLAVE_ARP
) ) )
312 hsmbus
->Instance
->CR1
|= I2C_CR1_SBC
;
315 /* Enable the selected SMBUS peripheral */
316 __HAL_SMBUS_ENABLE(hsmbus
);
318 hsmbus
->ErrorCode
= HAL_SMBUS_ERROR_NONE
;
319 hsmbus
->PreviousState
= HAL_SMBUS_STATE_READY
;
320 hsmbus
->State
= HAL_SMBUS_STATE_READY
;
326 * @brief DeInitialize the SMBUS peripheral.
327 * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains
328 * the configuration information for the specified SMBUS.
331 HAL_StatusTypeDef
HAL_SMBUS_DeInit(SMBUS_HandleTypeDef
*hsmbus
)
333 /* Check the SMBUS handle allocation */
339 /* Check the parameters */
340 assert_param(IS_SMBUS_ALL_INSTANCE(hsmbus
->Instance
));
342 hsmbus
->State
= HAL_SMBUS_STATE_BUSY
;
344 /* Disable the SMBUS Peripheral Clock */
345 __HAL_SMBUS_DISABLE(hsmbus
);
347 /* DeInit the low level hardware: GPIO, CLOCK, NVIC */
348 HAL_SMBUS_MspDeInit(hsmbus
);
350 hsmbus
->ErrorCode
= HAL_SMBUS_ERROR_NONE
;
351 hsmbus
->PreviousState
= HAL_SMBUS_STATE_RESET
;
352 hsmbus
->State
= HAL_SMBUS_STATE_RESET
;
355 __HAL_UNLOCK(hsmbus
);
361 * @brief Initialize the SMBUS MSP.
362 * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains
363 * the configuration information for the specified SMBUS.
366 __weak
void HAL_SMBUS_MspInit(SMBUS_HandleTypeDef
*hsmbus
)
368 /* Prevent unused argument(s) compilation warning */
371 /* NOTE : This function should not be modified, when the callback is needed,
372 the HAL_SMBUS_MspInit could be implemented in the user file
377 * @brief DeInitialize the SMBUS MSP.
378 * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains
379 * the configuration information for the specified SMBUS.
382 __weak
void HAL_SMBUS_MspDeInit(SMBUS_HandleTypeDef
*hsmbus
)
384 /* Prevent unused argument(s) compilation warning */
387 /* NOTE : This function should not be modified, when the callback is needed,
388 the HAL_SMBUS_MspDeInit could be implemented in the user file
396 /** @defgroup SMBUS_Exported_Functions_Group2 Input and Output operation functions
397 * @brief Data transfers functions
400 ===============================================================================
401 ##### IO operation functions #####
402 ===============================================================================
404 This subsection provides a set of functions allowing to manage the SMBUS data
407 (#) Blocking mode function to check if device is ready for usage is :
408 (++) HAL_SMBUS_IsDeviceReady()
410 (#) There is only one mode of transfer:
411 (++) Non-Blocking mode : The communication is performed using Interrupts.
412 These functions return the status of the transfer startup.
413 The end of the data processing will be indicated through the
414 dedicated SMBUS IRQ when using Interrupt mode.
416 (#) Non-Blocking mode functions with Interrupt are :
417 (++) HAL_SMBUS_Master_Transmit_IT()
418 (++) HAL_SMBUS_Master_Receive_IT()
419 (++) HAL_SMBUS_Slave_Transmit_IT()
420 (++) HAL_SMBUS_Slave_Receive_IT()
421 (++) HAL_SMBUS_EnableListen_IT()
422 (++) HAL_SMBUS_DisableListen_IT()
423 (++) HAL_SMBUS_EnableAlert_IT()
424 (++) HAL_SMBUS_DisableAlert_IT()
426 (#) A set of Transfer Complete Callbacks are provided in non-Blocking mode:
427 (++) HAL_SMBUS_MasterTxCpltCallback()
428 (++) HAL_SMBUS_MasterRxCpltCallback()
429 (++) HAL_SMBUS_SlaveTxCpltCallback()
430 (++) HAL_SMBUS_SlaveRxCpltCallback()
431 (++) HAL_SMBUS_AddrCallback()
432 (++) HAL_SMBUS_ListenCpltCallback()
433 (++) HAL_SMBUS_ErrorCallback()
440 * @brief Transmit in master/host SMBUS mode an amount of data in non-blocking mode with Interrupt.
441 * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains
442 * the configuration information for the specified SMBUS.
443 * @param DevAddress Target device address: The device 7 bits address value
444 * in datasheet must be shift at right before call interface
445 * @param pData Pointer to data buffer
446 * @param Size Amount of data to be sent
447 * @param XferOptions Options of Transfer, value of @ref SMBUS_XferOptions_definition
450 HAL_StatusTypeDef
HAL_SMBUS_Master_Transmit_IT(SMBUS_HandleTypeDef
*hsmbus
, uint16_t DevAddress
, uint8_t *pData
, uint16_t Size
, uint32_t XferOptions
)
452 /* Check the parameters */
453 assert_param(IS_SMBUS_TRANSFER_OPTIONS_REQUEST(XferOptions
));
455 if(hsmbus
->State
== HAL_SMBUS_STATE_READY
)
460 hsmbus
->State
= HAL_SMBUS_STATE_MASTER_BUSY_TX
;
461 hsmbus
->ErrorCode
= HAL_SMBUS_ERROR_NONE
;
462 /* Prepare transfer parameters */
463 hsmbus
->pBuffPtr
= pData
;
464 hsmbus
->XferCount
= Size
;
465 hsmbus
->XferOptions
= XferOptions
;
467 /* In case of Quick command, remove autoend mode */
468 /* Manage the stop generation by software */
469 if(hsmbus
->pBuffPtr
== NULL
)
471 hsmbus
->XferOptions
&= ~SMBUS_AUTOEND_MODE
;
474 if(Size
> MAX_NBYTE_SIZE
)
476 hsmbus
->XferSize
= MAX_NBYTE_SIZE
;
480 hsmbus
->XferSize
= Size
;
483 /* Send Slave Address */
484 /* Set NBYTES to write and reload if size > MAX_NBYTE_SIZE and generate RESTART */
485 if( (hsmbus
->XferSize
== MAX_NBYTE_SIZE
) && (hsmbus
->XferSize
< hsmbus
->XferCount
) )
487 SMBUS_TransferConfig(hsmbus
,DevAddress
,hsmbus
->XferSize
, SMBUS_RELOAD_MODE
| (hsmbus
->XferOptions
& SMBUS_SENDPEC_MODE
), SMBUS_GENERATE_START_WRITE
);
491 /* If transfer direction not change, do not generate Restart Condition */
492 /* Mean Previous state is same as current state */
493 if((hsmbus
->PreviousState
== HAL_SMBUS_STATE_MASTER_BUSY_TX
) && (IS_SMBUS_TRANSFER_OTHER_OPTIONS_REQUEST(hsmbus
->XferOptions
) == 0))
495 SMBUS_TransferConfig(hsmbus
,DevAddress
,hsmbus
->XferSize
, hsmbus
->XferOptions
, SMBUS_NO_STARTSTOP
);
497 /* Else transfer direction change, so generate Restart with new transfer direction */
500 /* Convert OTHER_xxx XferOptions if any */
501 SMBUS_ConvertOtherXferOptions(hsmbus
);
503 /* Handle Transfer */
504 SMBUS_TransferConfig(hsmbus
,DevAddress
,hsmbus
->XferSize
, hsmbus
->XferOptions
, SMBUS_GENERATE_START_WRITE
);
507 /* If PEC mode is enable, size to transmit manage by SW part should be Size-1 byte, corresponding to PEC byte */
508 /* PEC byte is automatically sent by HW block, no need to manage it in Transmit process */
509 if(SMBUS_GET_PEC_MODE(hsmbus
) != RESET
)
516 /* Process Unlocked */
517 __HAL_UNLOCK(hsmbus
);
519 /* Note : The SMBUS interrupts must be enabled after unlocking current process
520 to avoid the risk of SMBUS interrupt handle execution before current
522 SMBUS_Enable_IRQ(hsmbus
, SMBUS_IT_TX
);
533 * @brief Receive in master/host SMBUS mode an amount of data in non-blocking mode with Interrupt.
534 * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains
535 * the configuration information for the specified SMBUS.
536 * @param DevAddress Target device address: The device 7 bits address value
537 * in datasheet must be shift at right before call interface
538 * @param pData Pointer to data buffer
539 * @param Size Amount of data to be sent
540 * @param XferOptions Options of Transfer, value of @ref SMBUS_XferOptions_definition
543 HAL_StatusTypeDef
HAL_SMBUS_Master_Receive_IT(SMBUS_HandleTypeDef
*hsmbus
, uint16_t DevAddress
, uint8_t *pData
, uint16_t Size
, uint32_t XferOptions
)
545 /* Check the parameters */
546 assert_param(IS_SMBUS_TRANSFER_OPTIONS_REQUEST(XferOptions
));
548 if(hsmbus
->State
== HAL_SMBUS_STATE_READY
)
553 hsmbus
->State
= HAL_SMBUS_STATE_MASTER_BUSY_RX
;
554 hsmbus
->ErrorCode
= HAL_SMBUS_ERROR_NONE
;
556 /* Prepare transfer parameters */
557 hsmbus
->pBuffPtr
= pData
;
558 hsmbus
->XferCount
= Size
;
559 hsmbus
->XferOptions
= XferOptions
;
561 /* In case of Quick command, remove autoend mode */
562 /* Manage the stop generation by software */
563 if(hsmbus
->pBuffPtr
== NULL
)
565 hsmbus
->XferOptions
&= ~SMBUS_AUTOEND_MODE
;
568 if(Size
> MAX_NBYTE_SIZE
)
570 hsmbus
->XferSize
= MAX_NBYTE_SIZE
;
574 hsmbus
->XferSize
= Size
;
577 /* Send Slave Address */
578 /* Set NBYTES to write and reload if size > MAX_NBYTE_SIZE and generate RESTART */
579 if( (hsmbus
->XferSize
== MAX_NBYTE_SIZE
) && (hsmbus
->XferSize
< hsmbus
->XferCount
) )
581 SMBUS_TransferConfig(hsmbus
,DevAddress
,hsmbus
->XferSize
, SMBUS_RELOAD_MODE
| (hsmbus
->XferOptions
& SMBUS_SENDPEC_MODE
), SMBUS_GENERATE_START_READ
);
585 /* If transfer direction not change, do not generate Restart Condition */
586 /* Mean Previous state is same as current state */
587 if((hsmbus
->PreviousState
== HAL_SMBUS_STATE_MASTER_BUSY_RX
) && (IS_SMBUS_TRANSFER_OTHER_OPTIONS_REQUEST(hsmbus
->XferOptions
) == 0))
589 SMBUS_TransferConfig(hsmbus
,DevAddress
,hsmbus
->XferSize
, hsmbus
->XferOptions
, SMBUS_NO_STARTSTOP
);
591 /* Else transfer direction change, so generate Restart with new transfer direction */
594 /* Convert OTHER_xxx XferOptions if any */
595 SMBUS_ConvertOtherXferOptions(hsmbus
);
597 /* Handle Transfer */
598 SMBUS_TransferConfig(hsmbus
,DevAddress
,hsmbus
->XferSize
, hsmbus
->XferOptions
, SMBUS_GENERATE_START_READ
);
602 /* Process Unlocked */
603 __HAL_UNLOCK(hsmbus
);
605 /* Note : The SMBUS interrupts must be enabled after unlocking current process
606 to avoid the risk of SMBUS interrupt handle execution before current
608 SMBUS_Enable_IRQ(hsmbus
, SMBUS_IT_RX
);
619 * @brief Abort a master/host SMBUS process communication with Interrupt.
620 * @note This abort can be called only if state is ready
621 * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains
622 * the configuration information for the specified SMBUS.
623 * @param DevAddress Target device address: The device 7 bits address value
624 * in datasheet must be shift at right before call interface
627 HAL_StatusTypeDef
HAL_SMBUS_Master_Abort_IT(SMBUS_HandleTypeDef
*hsmbus
, uint16_t DevAddress
)
629 if(hsmbus
->State
== HAL_SMBUS_STATE_READY
)
634 /* Keep the same state as previous */
635 /* to perform as well the call of the corresponding end of transfer callback */
636 if(hsmbus
->PreviousState
== HAL_SMBUS_STATE_MASTER_BUSY_TX
)
638 hsmbus
->State
= HAL_SMBUS_STATE_MASTER_BUSY_TX
;
640 else if(hsmbus
->PreviousState
== HAL_SMBUS_STATE_MASTER_BUSY_RX
)
642 hsmbus
->State
= HAL_SMBUS_STATE_MASTER_BUSY_RX
;
646 /* Wrong usage of abort function */
647 /* This function should be used only in case of abort monitored by master device */
650 hsmbus
->ErrorCode
= HAL_SMBUS_ERROR_NONE
;
652 /* Set NBYTES to 1 to generate a dummy read on SMBUS peripheral */
653 /* Set AUTOEND mode, this will generate a NACK then STOP condition to abort the current transfer */
654 SMBUS_TransferConfig(hsmbus
, DevAddress
, 1U, SMBUS_AUTOEND_MODE
, SMBUS_NO_STARTSTOP
);
656 /* Process Unlocked */
657 __HAL_UNLOCK(hsmbus
);
659 /* Note : The SMBUS interrupts must be enabled after unlocking current process
660 to avoid the risk of SMBUS interrupt handle execution before current
662 if(hsmbus
->State
== HAL_SMBUS_STATE_MASTER_BUSY_TX
)
664 SMBUS_Enable_IRQ(hsmbus
, SMBUS_IT_TX
);
666 else if(hsmbus
->State
== HAL_SMBUS_STATE_MASTER_BUSY_RX
)
668 SMBUS_Enable_IRQ(hsmbus
, SMBUS_IT_RX
);
680 * @brief Transmit in slave/device SMBUS mode an amount of data in non-blocking mode with Interrupt.
681 * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains
682 * the configuration information for the specified SMBUS.
683 * @param pData Pointer to data buffer
684 * @param Size Amount of data to be sent
685 * @param XferOptions Options of Transfer, value of @ref SMBUS_XferOptions_definition
688 HAL_StatusTypeDef
HAL_SMBUS_Slave_Transmit_IT(SMBUS_HandleTypeDef
*hsmbus
, uint8_t *pData
, uint16_t Size
, uint32_t XferOptions
)
690 /* Check the parameters */
691 assert_param(IS_SMBUS_TRANSFER_OPTIONS_REQUEST(XferOptions
));
693 if(hsmbus
->State
== HAL_SMBUS_STATE_LISTEN
)
695 if((pData
== NULL
) || (Size
== 0U))
700 /* Disable Interrupts, to prevent preemption during treatment in case of multicall */
701 SMBUS_Disable_IRQ(hsmbus
, SMBUS_IT_ADDR
| SMBUS_IT_TX
);
706 hsmbus
->State
|= HAL_SMBUS_STATE_SLAVE_BUSY_TX
;
707 hsmbus
->ErrorCode
= HAL_SMBUS_ERROR_NONE
;
709 /* Set SBC bit to manage Acknowledge at each bit */
710 hsmbus
->Instance
->CR1
|= I2C_CR1_SBC
;
712 /* Enable Address Acknowledge */
713 hsmbus
->Instance
->CR2
&= ~I2C_CR2_NACK
;
715 /* Prepare transfer parameters */
716 hsmbus
->pBuffPtr
= pData
;
717 hsmbus
->XferCount
= Size
;
718 hsmbus
->XferOptions
= XferOptions
;
720 /* Convert OTHER_xxx XferOptions if any */
721 SMBUS_ConvertOtherXferOptions(hsmbus
);
723 if(Size
> MAX_NBYTE_SIZE
)
725 hsmbus
->XferSize
= MAX_NBYTE_SIZE
;
729 hsmbus
->XferSize
= Size
;
732 /* Set NBYTES to write and reload if size > MAX_NBYTE_SIZE and generate RESTART */
733 if( (hsmbus
->XferSize
== MAX_NBYTE_SIZE
) && (hsmbus
->XferSize
< hsmbus
->XferCount
) )
735 SMBUS_TransferConfig(hsmbus
, 0U,hsmbus
->XferSize
, SMBUS_RELOAD_MODE
| (hsmbus
->XferOptions
& SMBUS_SENDPEC_MODE
), SMBUS_NO_STARTSTOP
);
739 /* Set NBYTE to transmit */
740 SMBUS_TransferConfig(hsmbus
, 0U,hsmbus
->XferSize
, hsmbus
->XferOptions
, SMBUS_NO_STARTSTOP
);
742 /* If PEC mode is enable, size to transmit should be Size-1 byte, corresponding to PEC byte */
743 /* PEC byte is automatically sent by HW block, no need to manage it in Transmit process */
744 if(SMBUS_GET_PEC_MODE(hsmbus
) != RESET
)
751 /* Clear ADDR flag after prepare the transfer parameters */
752 /* This action will generate an acknowledge to the HOST */
753 __HAL_SMBUS_CLEAR_FLAG(hsmbus
,SMBUS_FLAG_ADDR
);
755 /* Process Unlocked */
756 __HAL_UNLOCK(hsmbus
);
758 /* Note : The SMBUS interrupts must be enabled after unlocking current process
759 to avoid the risk of SMBUS interrupt handle execution before current
761 /* REnable ADDR interrupt */
762 SMBUS_Enable_IRQ(hsmbus
, SMBUS_IT_TX
| SMBUS_IT_ADDR
);
773 * @brief Receive in slave/device SMBUS mode an amount of data in non-blocking mode with Interrupt.
774 * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains
775 * the configuration information for the specified SMBUS.
776 * @param pData Pointer to data buffer
777 * @param Size Amount of data to be sent
778 * @param XferOptions Options of Transfer, value of @ref SMBUS_XferOptions_definition
781 HAL_StatusTypeDef
HAL_SMBUS_Slave_Receive_IT(SMBUS_HandleTypeDef
*hsmbus
, uint8_t *pData
, uint16_t Size
, uint32_t XferOptions
)
783 /* Check the parameters */
784 assert_param(IS_SMBUS_TRANSFER_OPTIONS_REQUEST(XferOptions
));
786 if(hsmbus
->State
== HAL_SMBUS_STATE_LISTEN
)
788 if((pData
== NULL
) || (Size
== 0U))
793 /* Disable Interrupts, to prevent preemption during treatment in case of multicall */
794 SMBUS_Disable_IRQ(hsmbus
, SMBUS_IT_ADDR
| SMBUS_IT_RX
);
799 hsmbus
->State
|= HAL_SMBUS_STATE_SLAVE_BUSY_RX
;
800 hsmbus
->ErrorCode
= HAL_SMBUS_ERROR_NONE
;
802 /* Set SBC bit to manage Acknowledge at each bit */
803 hsmbus
->Instance
->CR1
|= I2C_CR1_SBC
;
805 /* Enable Address Acknowledge */
806 hsmbus
->Instance
->CR2
&= ~I2C_CR2_NACK
;
808 /* Prepare transfer parameters */
809 hsmbus
->pBuffPtr
= pData
;
810 hsmbus
->XferSize
= Size
;
811 hsmbus
->XferCount
= Size
;
812 hsmbus
->XferOptions
= XferOptions
;
814 /* Convert OTHER_xxx XferOptions if any */
815 SMBUS_ConvertOtherXferOptions(hsmbus
);
817 /* Set NBYTE to receive */
818 /* If XferSize equal "1", or XferSize equal "2" with PEC requested (mean 1 data byte + 1 PEC byte */
819 /* no need to set RELOAD bit mode, a ACK will be automatically generated in that case */
820 /* else need to set RELOAD bit mode to generate an automatic ACK at each byte Received */
821 /* This RELOAD bit will be reset for last BYTE to be receive in SMBUS_Slave_ISR */
822 if((hsmbus
->XferSize
== 1U) || ((hsmbus
->XferSize
== 2U) && (SMBUS_GET_PEC_MODE(hsmbus
) != RESET
)))
824 SMBUS_TransferConfig(hsmbus
, 0U, hsmbus
->XferSize
, hsmbus
->XferOptions
, SMBUS_NO_STARTSTOP
);
828 SMBUS_TransferConfig(hsmbus
, 0U, 1U, hsmbus
->XferOptions
| SMBUS_RELOAD_MODE
, SMBUS_NO_STARTSTOP
);
831 /* Clear ADDR flag after prepare the transfer parameters */
832 /* This action will generate an acknowledge to the HOST */
833 __HAL_SMBUS_CLEAR_FLAG(hsmbus
,SMBUS_FLAG_ADDR
);
835 /* Process Unlocked */
836 __HAL_UNLOCK(hsmbus
);
838 /* Note : The SMBUS interrupts must be enabled after unlocking current process
839 to avoid the risk of SMBUS interrupt handle execution before current
841 /* REnable ADDR interrupt */
842 SMBUS_Enable_IRQ(hsmbus
, SMBUS_IT_RX
| SMBUS_IT_ADDR
);
853 * @brief Enable the Address listen mode with Interrupt.
854 * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains
855 * the configuration information for the specified SMBUS.
858 HAL_StatusTypeDef
HAL_SMBUS_EnableListen_IT(SMBUS_HandleTypeDef
*hsmbus
)
860 hsmbus
->State
= HAL_SMBUS_STATE_LISTEN
;
862 /* Enable the Address Match interrupt */
863 SMBUS_Enable_IRQ(hsmbus
, SMBUS_IT_ADDR
);
869 * @brief Disable the Address listen mode with Interrupt.
870 * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains
871 * the configuration information for the specified SMBUS.
874 HAL_StatusTypeDef
HAL_SMBUS_DisableListen_IT(SMBUS_HandleTypeDef
*hsmbus
)
876 /* Disable Address listen mode only if a transfer is not ongoing */
877 if(hsmbus
->State
== HAL_SMBUS_STATE_LISTEN
)
879 hsmbus
->State
= HAL_SMBUS_STATE_READY
;
881 /* Disable the Address Match interrupt */
882 SMBUS_Disable_IRQ(hsmbus
, SMBUS_IT_ADDR
);
893 * @brief Enable the SMBUS alert mode with Interrupt.
894 * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains
895 * the configuration information for the specified SMBUSx peripheral.
898 HAL_StatusTypeDef
HAL_SMBUS_EnableAlert_IT(SMBUS_HandleTypeDef
*hsmbus
)
900 /* Enable SMBus alert */
901 hsmbus
->Instance
->CR1
|= I2C_CR1_ALERTEN
;
903 /* Clear ALERT flag */
904 __HAL_SMBUS_CLEAR_FLAG(hsmbus
, SMBUS_FLAG_ALERT
);
906 /* Enable Alert Interrupt */
907 SMBUS_Enable_IRQ(hsmbus
, SMBUS_IT_ALERT
);
912 * @brief Disable the SMBUS alert mode with Interrupt.
913 * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains
914 * the configuration information for the specified SMBUSx peripheral.
917 HAL_StatusTypeDef
HAL_SMBUS_DisableAlert_IT(SMBUS_HandleTypeDef
*hsmbus
)
919 /* Enable SMBus alert */
920 hsmbus
->Instance
->CR1
&= ~I2C_CR1_ALERTEN
;
922 /* Disable Alert Interrupt */
923 SMBUS_Disable_IRQ(hsmbus
, SMBUS_IT_ALERT
);
929 * @brief Check if target device is ready for communication.
930 * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains
931 * the configuration information for the specified SMBUS.
932 * @param DevAddress Target device address: The device 7 bits address value
933 * in datasheet must be shift at right before call interface
934 * @param Trials Number of trials
935 * @param Timeout Timeout duration
938 HAL_StatusTypeDef
HAL_SMBUS_IsDeviceReady(SMBUS_HandleTypeDef
*hsmbus
, uint16_t DevAddress
, uint32_t Trials
, uint32_t Timeout
)
940 uint32_t tickstart
= 0U;
942 __IO
uint32_t SMBUS_Trials
= 0U;
944 if(hsmbus
->State
== HAL_SMBUS_STATE_READY
)
946 if(__HAL_SMBUS_GET_FLAG(hsmbus
, SMBUS_FLAG_BUSY
) != RESET
)
954 hsmbus
->State
= HAL_SMBUS_STATE_BUSY
;
955 hsmbus
->ErrorCode
= HAL_SMBUS_ERROR_NONE
;
960 hsmbus
->Instance
->CR2
= SMBUS_GENERATE_START(hsmbus
->Init
.AddressingMode
,DevAddress
);
962 /* No need to Check TC flag, with AUTOEND mode the stop is automatically generated */
963 /* Wait until STOPF flag is set or a NACK flag is set*/
964 tickstart
= HAL_GetTick();
965 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
))
967 if(Timeout
!= HAL_MAX_DELAY
)
969 if((Timeout
== 0U) || ((HAL_GetTick() - tickstart
) > Timeout
))
971 /* Device is ready */
972 hsmbus
->State
= HAL_SMBUS_STATE_READY
;
974 /* Process Unlocked */
975 __HAL_UNLOCK(hsmbus
);
981 /* Check if the NACKF flag has not been set */
982 if (__HAL_SMBUS_GET_FLAG(hsmbus
, SMBUS_FLAG_AF
) == RESET
)
984 /* Wait until STOPF flag is reset */
985 if(SMBUS_WaitOnFlagUntilTimeout(hsmbus
, SMBUS_FLAG_STOPF
, RESET
, Timeout
) != HAL_OK
)
990 /* Clear STOP Flag */
991 __HAL_SMBUS_CLEAR_FLAG(hsmbus
, SMBUS_FLAG_STOPF
);
993 /* Device is ready */
994 hsmbus
->State
= HAL_SMBUS_STATE_READY
;
996 /* Process Unlocked */
997 __HAL_UNLOCK(hsmbus
);
1003 /* Wait until STOPF flag is reset */
1004 if(SMBUS_WaitOnFlagUntilTimeout(hsmbus
, SMBUS_FLAG_STOPF
, RESET
, Timeout
) != HAL_OK
)
1009 /* Clear NACK Flag */
1010 __HAL_SMBUS_CLEAR_FLAG(hsmbus
, SMBUS_FLAG_AF
);
1012 /* Clear STOP Flag, auto generated with autoend*/
1013 __HAL_SMBUS_CLEAR_FLAG(hsmbus
, SMBUS_FLAG_STOPF
);
1016 /* Check if the maximum allowed number of trials has been reached */
1017 if (SMBUS_Trials
++ == Trials
)
1020 hsmbus
->Instance
->CR2
|= I2C_CR2_STOP
;
1022 /* Wait until STOPF flag is reset */
1023 if(SMBUS_WaitOnFlagUntilTimeout(hsmbus
, SMBUS_FLAG_STOPF
, RESET
, Timeout
) != HAL_OK
)
1028 /* Clear STOP Flag */
1029 __HAL_SMBUS_CLEAR_FLAG(hsmbus
, SMBUS_FLAG_STOPF
);
1031 }while(SMBUS_Trials
< Trials
);
1033 hsmbus
->State
= HAL_SMBUS_STATE_READY
;
1035 /* Process Unlocked */
1036 __HAL_UNLOCK(hsmbus
);
1049 /** @defgroup SMBUS_IRQ_Handler_and_Callbacks IRQ Handler and Callbacks
1054 * @brief Handle SMBUS event interrupt request.
1055 * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains
1056 * the configuration information for the specified SMBUS.
1059 void HAL_SMBUS_EV_IRQHandler(SMBUS_HandleTypeDef
*hsmbus
)
1061 uint32_t tmpisrvalue
= 0U;
1063 /* Use a local variable to store the current ISR flags */
1064 /* This action will avoid a wrong treatment due to ISR flags change during interrupt handler */
1065 tmpisrvalue
= SMBUS_GET_ISR_REG(hsmbus
);
1067 /* SMBUS in mode Transmitter ---------------------------------------------------*/
1068 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
))
1070 /* Slave mode selected */
1071 if ((hsmbus
->State
& HAL_SMBUS_STATE_SLAVE_BUSY_TX
) == HAL_SMBUS_STATE_SLAVE_BUSY_TX
)
1073 SMBUS_Slave_ISR(hsmbus
);
1075 /* Master mode selected */
1076 else if((hsmbus
->State
& HAL_SMBUS_STATE_MASTER_BUSY_TX
) == HAL_SMBUS_STATE_MASTER_BUSY_TX
)
1078 SMBUS_Master_ISR(hsmbus
);
1082 /* SMBUS in mode Receiver ----------------------------------------------------*/
1083 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
))
1085 /* Slave mode selected */
1086 if ((hsmbus
->State
& HAL_SMBUS_STATE_SLAVE_BUSY_RX
) == HAL_SMBUS_STATE_SLAVE_BUSY_RX
)
1088 SMBUS_Slave_ISR(hsmbus
);
1090 /* Master mode selected */
1091 else if((hsmbus
->State
& HAL_SMBUS_STATE_MASTER_BUSY_RX
) == HAL_SMBUS_STATE_MASTER_BUSY_RX
)
1093 SMBUS_Master_ISR(hsmbus
);
1097 /* SMBUS in mode Listener Only --------------------------------------------------*/
1098 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
))
1099 && ((__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
)))
1101 if (hsmbus
->State
== HAL_SMBUS_STATE_LISTEN
)
1103 SMBUS_Slave_ISR(hsmbus
);
1109 * @brief Handle SMBUS error interrupt request.
1110 * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains
1111 * the configuration information for the specified SMBUS.
1114 void HAL_SMBUS_ER_IRQHandler(SMBUS_HandleTypeDef
*hsmbus
)
1116 /* SMBUS Bus error interrupt occurred ------------------------------------*/
1117 if((__HAL_SMBUS_GET_FLAG(hsmbus
, SMBUS_FLAG_BERR
) != RESET
) && (__HAL_SMBUS_GET_IT_SOURCE(hsmbus
, SMBUS_IT_ERRI
) != RESET
))
1119 hsmbus
->ErrorCode
|= HAL_SMBUS_ERROR_BERR
;
1121 /* Clear BERR flag */
1122 __HAL_SMBUS_CLEAR_FLAG(hsmbus
, SMBUS_FLAG_BERR
);
1125 /* SMBUS Over-Run/Under-Run interrupt occurred ----------------------------------------*/
1126 if((__HAL_SMBUS_GET_FLAG(hsmbus
, SMBUS_FLAG_OVR
) != RESET
) && (__HAL_SMBUS_GET_IT_SOURCE(hsmbus
, SMBUS_IT_ERRI
) != RESET
))
1128 hsmbus
->ErrorCode
|= HAL_SMBUS_ERROR_OVR
;
1130 /* Clear OVR flag */
1131 __HAL_SMBUS_CLEAR_FLAG(hsmbus
, SMBUS_FLAG_OVR
);
1134 /* SMBUS Arbitration Loss error interrupt occurred ------------------------------------*/
1135 if((__HAL_SMBUS_GET_FLAG(hsmbus
, SMBUS_FLAG_ARLO
) != RESET
) && (__HAL_SMBUS_GET_IT_SOURCE(hsmbus
, SMBUS_IT_ERRI
) != RESET
))
1137 hsmbus
->ErrorCode
|= HAL_SMBUS_ERROR_ARLO
;
1139 /* Clear ARLO flag */
1140 __HAL_SMBUS_CLEAR_FLAG(hsmbus
, SMBUS_FLAG_ARLO
);
1143 /* SMBUS Timeout error interrupt occurred ---------------------------------------------*/
1144 if((__HAL_SMBUS_GET_FLAG(hsmbus
, SMBUS_FLAG_TIMEOUT
) != RESET
) && (__HAL_SMBUS_GET_IT_SOURCE(hsmbus
, SMBUS_IT_ERRI
) != RESET
))
1146 hsmbus
->ErrorCode
|= HAL_SMBUS_ERROR_BUSTIMEOUT
;
1148 /* Clear TIMEOUT flag */
1149 __HAL_SMBUS_CLEAR_FLAG(hsmbus
, SMBUS_FLAG_TIMEOUT
);
1152 /* SMBUS Alert error interrupt occurred -----------------------------------------------*/
1153 if((__HAL_SMBUS_GET_FLAG(hsmbus
, SMBUS_FLAG_ALERT
) != RESET
) && (__HAL_SMBUS_GET_IT_SOURCE(hsmbus
, SMBUS_IT_ERRI
) != RESET
))
1155 hsmbus
->ErrorCode
|= HAL_SMBUS_ERROR_ALERT
;
1157 /* Clear ALERT flag */
1158 __HAL_SMBUS_CLEAR_FLAG(hsmbus
, SMBUS_FLAG_ALERT
);
1161 /* SMBUS Packet Error Check error interrupt occurred ----------------------------------*/
1162 if((__HAL_SMBUS_GET_FLAG(hsmbus
, SMBUS_FLAG_PECERR
) != RESET
) && (__HAL_SMBUS_GET_IT_SOURCE(hsmbus
, SMBUS_IT_ERRI
) != RESET
))
1164 hsmbus
->ErrorCode
|= HAL_SMBUS_ERROR_PECERR
;
1166 /* Clear PEC error flag */
1167 __HAL_SMBUS_CLEAR_FLAG(hsmbus
, SMBUS_FLAG_PECERR
);
1170 /* Call the Error Callback in case of Error detected */
1171 if((hsmbus
->ErrorCode
!= HAL_SMBUS_ERROR_NONE
)&&(hsmbus
->ErrorCode
!= HAL_SMBUS_ERROR_ACKF
))
1173 /* Do not Reset the HAL state in case of ALERT error */
1174 if((hsmbus
->ErrorCode
& HAL_SMBUS_ERROR_ALERT
) != HAL_SMBUS_ERROR_ALERT
)
1176 if(((hsmbus
->State
& HAL_SMBUS_STATE_SLAVE_BUSY_TX
) == HAL_SMBUS_STATE_SLAVE_BUSY_TX
)
1177 || ((hsmbus
->State
& HAL_SMBUS_STATE_SLAVE_BUSY_RX
) == HAL_SMBUS_STATE_SLAVE_BUSY_RX
))
1179 /* Reset only HAL_SMBUS_STATE_SLAVE_BUSY_XX */
1180 /* keep HAL_SMBUS_STATE_LISTEN if set */
1181 hsmbus
->PreviousState
= HAL_SMBUS_STATE_READY
;
1182 hsmbus
->State
= HAL_SMBUS_STATE_LISTEN
;
1186 /* Call the Error callback to prevent upper layer */
1187 HAL_SMBUS_ErrorCallback(hsmbus
);
1192 * @brief Master Tx Transfer completed callback.
1193 * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains
1194 * the configuration information for the specified SMBUS.
1197 __weak
void HAL_SMBUS_MasterTxCpltCallback(SMBUS_HandleTypeDef
*hsmbus
)
1199 /* Prevent unused argument(s) compilation warning */
1202 /* NOTE : This function should not be modified, when the callback is needed,
1203 the HAL_SMBUS_MasterTxCpltCallback() could be implemented in the user file
1208 * @brief Master Rx Transfer completed callback.
1209 * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains
1210 * the configuration information for the specified SMBUS.
1213 __weak
void HAL_SMBUS_MasterRxCpltCallback(SMBUS_HandleTypeDef
*hsmbus
)
1215 /* Prevent unused argument(s) compilation warning */
1218 /* NOTE : This function should not be modified, when the callback is needed,
1219 the HAL_SMBUS_MasterRxCpltCallback() could be implemented in the user file
1223 /** @brief Slave Tx Transfer completed callback.
1224 * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains
1225 * the configuration information for the specified SMBUS.
1228 __weak
void HAL_SMBUS_SlaveTxCpltCallback(SMBUS_HandleTypeDef
*hsmbus
)
1230 /* Prevent unused argument(s) compilation warning */
1233 /* NOTE : This function should not be modified, when the callback is needed,
1234 the HAL_SMBUS_SlaveTxCpltCallback() could be implemented in the user file
1239 * @brief Slave Rx Transfer completed callback.
1240 * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains
1241 * the configuration information for the specified SMBUS.
1244 __weak
void HAL_SMBUS_SlaveRxCpltCallback(SMBUS_HandleTypeDef
*hsmbus
)
1246 /* Prevent unused argument(s) compilation warning */
1249 /* NOTE : This function should not be modified, when the callback is needed,
1250 the HAL_SMBUS_SlaveRxCpltCallback() could be implemented in the user file
1255 * @brief Slave Address Match callback.
1256 * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains
1257 * the configuration information for the specified SMBUS.
1258 * @param TransferDirection: Master request Transfer Direction (Write/Read)
1259 * @param AddrMatchCode: Address Match Code
1262 __weak
void HAL_SMBUS_AddrCallback(SMBUS_HandleTypeDef
*hsmbus
, uint8_t TransferDirection
, uint16_t AddrMatchCode
)
1264 /* Prevent unused argument(s) compilation warning */
1266 UNUSED(TransferDirection
);
1267 UNUSED(AddrMatchCode
);
1269 /* NOTE : This function should not be modified, when the callback is needed,
1270 the HAL_SMBUS_AddrCallback() could be implemented in the user file
1275 * @brief Listen Complete callback.
1276 * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains
1277 * the configuration information for the specified SMBUS.
1280 __weak
void HAL_SMBUS_ListenCpltCallback(SMBUS_HandleTypeDef
*hsmbus
)
1282 /* Prevent unused argument(s) compilation warning */
1285 /* NOTE : This function should not be modified, when the callback is needed,
1286 the HAL_SMBUS_ListenCpltCallback() could be implemented in the user file
1291 * @brief SMBUS error callback.
1292 * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains
1293 * the configuration information for the specified SMBUS.
1296 __weak
void HAL_SMBUS_ErrorCallback(SMBUS_HandleTypeDef
*hsmbus
)
1298 /* Prevent unused argument(s) compilation warning */
1301 /* NOTE : This function should not be modified, when the callback is needed,
1302 the HAL_SMBUS_ErrorCallback() could be implemented in the user file
1310 /** @defgroup SMBUS_Exported_Functions_Group3 Peripheral State and Errors functions
1311 * @brief Peripheral State and Errors functions
1314 ===============================================================================
1315 ##### Peripheral State and Errors functions #####
1316 ===============================================================================
1318 This subsection permits to get in run-time the status of the peripheral
1326 * @brief Return the SMBUS handle state.
1327 * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains
1328 * the configuration information for the specified SMBUS.
1331 uint32_t HAL_SMBUS_GetState(SMBUS_HandleTypeDef
*hsmbus
)
1333 /* Return SMBUS handle state */
1334 return hsmbus
->State
;
1338 * @brief Return the SMBUS error code.
1339 * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains
1340 * the configuration information for the specified SMBUS.
1341 * @retval SMBUS Error Code
1343 uint32_t HAL_SMBUS_GetError(SMBUS_HandleTypeDef
*hsmbus
)
1345 return hsmbus
->ErrorCode
;
1356 /** @addtogroup SMBUS_Private_Functions SMBUS Private Functions
1357 * @brief Data transfers Private functions
1362 * @brief Interrupt Sub-Routine which handle the Interrupt Flags Master Mode.
1363 * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains
1364 * the configuration information for the specified SMBUS.
1365 * @retval HAL status
1367 static HAL_StatusTypeDef
SMBUS_Master_ISR(SMBUS_HandleTypeDef
*hsmbus
)
1369 uint16_t DevAddress
;
1371 /* Process Locked */
1374 if(__HAL_SMBUS_GET_FLAG(hsmbus
, SMBUS_FLAG_AF
) != RESET
)
1376 /* Clear NACK Flag */
1377 __HAL_SMBUS_CLEAR_FLAG(hsmbus
, SMBUS_FLAG_AF
);
1379 /* Set corresponding Error Code */
1380 /* No need to generate STOP, it is automatically done */
1381 hsmbus
->ErrorCode
|= HAL_SMBUS_ERROR_ACKF
;
1383 /* Process Unlocked */
1384 __HAL_UNLOCK(hsmbus
);
1386 /* Call the Error callback to prevent upper layer */
1387 HAL_SMBUS_ErrorCallback(hsmbus
);
1389 else if(__HAL_SMBUS_GET_FLAG(hsmbus
, SMBUS_FLAG_STOPF
) != RESET
)
1391 /* Call the corresponding callback to inform upper layer of End of Transfer */
1392 if(hsmbus
->State
== HAL_SMBUS_STATE_MASTER_BUSY_TX
)
1394 /* Disable Interrupt */
1395 SMBUS_Disable_IRQ(hsmbus
, SMBUS_IT_TX
);
1397 /* Clear STOP Flag */
1398 __HAL_SMBUS_CLEAR_FLAG(hsmbus
, SMBUS_FLAG_STOPF
);
1400 /* Clear Configuration Register 2 */
1401 SMBUS_RESET_CR2(hsmbus
);
1403 /* Flush remaining data in Fifo register in case of error occurs before TXEmpty */
1404 /* Disable the selected SMBUS peripheral */
1405 __HAL_SMBUS_DISABLE(hsmbus
);
1407 hsmbus
->PreviousState
= HAL_SMBUS_STATE_READY
;
1408 hsmbus
->State
= HAL_SMBUS_STATE_READY
;
1410 /* Process Unlocked */
1411 __HAL_UNLOCK(hsmbus
);
1413 /* REenable the selected SMBUS peripheral */
1414 __HAL_SMBUS_ENABLE(hsmbus
);
1416 HAL_SMBUS_MasterTxCpltCallback(hsmbus
);
1418 else if(hsmbus
->State
== HAL_SMBUS_STATE_MASTER_BUSY_RX
)
1420 /* Store Last receive data if any */
1421 if(__HAL_SMBUS_GET_FLAG(hsmbus
, SMBUS_FLAG_RXNE
) != RESET
)
1423 /* Read data from RXDR */
1424 (*hsmbus
->pBuffPtr
++) = hsmbus
->Instance
->RXDR
;
1426 if((hsmbus
->XferSize
> 0U))
1429 hsmbus
->XferCount
--;
1433 /* Disable Interrupt */
1434 SMBUS_Disable_IRQ(hsmbus
, SMBUS_IT_RX
);
1436 /* Clear STOP Flag */
1437 __HAL_SMBUS_CLEAR_FLAG(hsmbus
, SMBUS_FLAG_STOPF
);
1439 /* Clear Configuration Register 2 */
1440 SMBUS_RESET_CR2(hsmbus
);
1442 hsmbus
->PreviousState
= HAL_SMBUS_STATE_READY
;
1443 hsmbus
->State
= HAL_SMBUS_STATE_READY
;
1445 /* Process Unlocked */
1446 __HAL_UNLOCK(hsmbus
);
1448 HAL_SMBUS_MasterRxCpltCallback(hsmbus
);
1451 else if(__HAL_SMBUS_GET_FLAG(hsmbus
, SMBUS_FLAG_RXNE
) != RESET
)
1453 /* Read data from RXDR */
1454 (*hsmbus
->pBuffPtr
++) = hsmbus
->Instance
->RXDR
;
1456 hsmbus
->XferCount
--;
1458 else if(__HAL_SMBUS_GET_FLAG(hsmbus
, SMBUS_FLAG_TXIS
) != RESET
)
1460 /* Write data to TXDR */
1461 hsmbus
->Instance
->TXDR
= (*hsmbus
->pBuffPtr
++);
1463 hsmbus
->XferCount
--;
1465 else if(__HAL_SMBUS_GET_FLAG(hsmbus
, SMBUS_FLAG_TCR
) != RESET
)
1467 if((hsmbus
->XferSize
== 0U)&&(hsmbus
->XferCount
!= 0U))
1469 DevAddress
= (hsmbus
->Instance
->CR2
& I2C_CR2_SADD
);
1471 if(hsmbus
->XferCount
> MAX_NBYTE_SIZE
)
1473 SMBUS_TransferConfig(hsmbus
, DevAddress
, MAX_NBYTE_SIZE
, (SMBUS_RELOAD_MODE
| (hsmbus
->XferOptions
& SMBUS_SENDPEC_MODE
)), SMBUS_NO_STARTSTOP
);
1474 hsmbus
->XferSize
= MAX_NBYTE_SIZE
;
1478 hsmbus
->XferSize
= hsmbus
->XferCount
;
1479 SMBUS_TransferConfig(hsmbus
,DevAddress
,hsmbus
->XferSize
, hsmbus
->XferOptions
, SMBUS_NO_STARTSTOP
);
1480 /* If PEC mode is enable, size to transmit should be Size-1 byte, corresponding to PEC byte */
1481 /* PEC byte is automatically sent by HW block, no need to manage it in Transmit process */
1482 if(SMBUS_GET_PEC_MODE(hsmbus
) != RESET
)
1485 hsmbus
->XferCount
--;
1489 else if((hsmbus
->XferSize
== 0U)&&(hsmbus
->XferCount
== 0U))
1491 /* Call TxCpltCallback() if no stop mode is set */
1492 if(SMBUS_GET_STOP_MODE(hsmbus
) != SMBUS_AUTOEND_MODE
)
1494 /* Call the corresponding callback to inform upper layer of End of Transfer */
1495 if(hsmbus
->State
== HAL_SMBUS_STATE_MASTER_BUSY_TX
)
1497 /* Disable Interrupt */
1498 SMBUS_Disable_IRQ(hsmbus
, SMBUS_IT_TX
);
1499 hsmbus
->PreviousState
= hsmbus
->State
;
1500 hsmbus
->State
= HAL_SMBUS_STATE_READY
;
1502 /* Process Unlocked */
1503 __HAL_UNLOCK(hsmbus
);
1505 HAL_SMBUS_MasterTxCpltCallback(hsmbus
);
1507 else if(hsmbus
->State
== HAL_SMBUS_STATE_MASTER_BUSY_RX
)
1509 SMBUS_Disable_IRQ(hsmbus
, SMBUS_IT_RX
);
1510 hsmbus
->PreviousState
= hsmbus
->State
;
1511 hsmbus
->State
= HAL_SMBUS_STATE_READY
;
1513 /* Process Unlocked */
1514 __HAL_UNLOCK(hsmbus
);
1516 HAL_SMBUS_MasterRxCpltCallback(hsmbus
);
1521 else if(__HAL_SMBUS_GET_FLAG(hsmbus
, SMBUS_FLAG_TC
) != RESET
)
1523 if(hsmbus
->XferCount
== 0U)
1525 /* Specific use case for Quick command */
1526 if(hsmbus
->pBuffPtr
== NULL
)
1528 /* Generate a Stop command */
1529 hsmbus
->Instance
->CR2
|= I2C_CR2_STOP
;
1531 /* Call TxCpltCallback() if no stop mode is set */
1532 else if(SMBUS_GET_STOP_MODE(hsmbus
) != SMBUS_AUTOEND_MODE
)
1534 /* No Generate Stop, to permit restart mode */
1535 /* The stop will be done at the end of transfer, when SMBUS_AUTOEND_MODE enable */
1537 /* Call the corresponding callback to inform upper layer of End of Transfer */
1538 if(hsmbus
->State
== HAL_SMBUS_STATE_MASTER_BUSY_TX
)
1540 /* Disable Interrupt */
1541 SMBUS_Disable_IRQ(hsmbus
, SMBUS_IT_TX
);
1542 hsmbus
->PreviousState
= hsmbus
->State
;
1543 hsmbus
->State
= HAL_SMBUS_STATE_READY
;
1545 /* Process Unlocked */
1546 __HAL_UNLOCK(hsmbus
);
1548 HAL_SMBUS_MasterTxCpltCallback(hsmbus
);
1550 else if(hsmbus
->State
== HAL_SMBUS_STATE_MASTER_BUSY_RX
)
1552 SMBUS_Disable_IRQ(hsmbus
, SMBUS_IT_RX
);
1553 hsmbus
->PreviousState
= hsmbus
->State
;
1554 hsmbus
->State
= HAL_SMBUS_STATE_READY
;
1556 /* Process Unlocked */
1557 __HAL_UNLOCK(hsmbus
);
1559 HAL_SMBUS_MasterRxCpltCallback(hsmbus
);
1565 /* Process Unlocked */
1566 __HAL_UNLOCK(hsmbus
);
1571 * @brief Interrupt Sub-Routine which handle the Interrupt Flags Slave Mode.
1572 * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains
1573 * the configuration information for the specified SMBUS.
1574 * @retval HAL status
1576 static HAL_StatusTypeDef
SMBUS_Slave_ISR(SMBUS_HandleTypeDef
*hsmbus
)
1578 uint8_t TransferDirection
= 0U;
1579 uint16_t SlaveAddrCode
= 0U;
1581 /* Process Locked */
1584 if(__HAL_SMBUS_GET_FLAG(hsmbus
, SMBUS_FLAG_AF
) != RESET
)
1586 /* Check that SMBUS transfer finished */
1587 /* if yes, normal usecase, a NACK is sent by the HOST when Transfer is finished */
1588 /* Mean XferCount == 0*/
1589 /* So clear Flag NACKF only */
1590 if(hsmbus
->XferCount
== 0U)
1592 /* Clear NACK Flag */
1593 __HAL_SMBUS_CLEAR_FLAG(hsmbus
, SMBUS_FLAG_AF
);
1595 /* Process Unlocked */
1596 __HAL_UNLOCK(hsmbus
);
1600 /* if no, error usecase, a Non-Acknowledge of last Data is generated by the HOST*/
1601 /* Clear NACK Flag */
1602 __HAL_SMBUS_CLEAR_FLAG(hsmbus
, SMBUS_FLAG_AF
);
1604 /* Set HAL State to "Idle" State, mean to LISTEN state */
1605 /* So reset Slave Busy state */
1606 hsmbus
->PreviousState
= hsmbus
->State
;
1607 hsmbus
->State
&= ~((uint32_t)HAL_SMBUS_STATE_SLAVE_BUSY_TX
);
1608 hsmbus
->State
&= ~((uint32_t)HAL_SMBUS_STATE_SLAVE_BUSY_RX
);
1610 /* Disable RX/TX Interrupts, keep only ADDR Interrupt */
1611 SMBUS_Disable_IRQ(hsmbus
, SMBUS_IT_RX
| SMBUS_IT_TX
);
1613 /* Set ErrorCode corresponding to a Non-Acknowledge */
1614 hsmbus
->ErrorCode
|= HAL_SMBUS_ERROR_ACKF
;
1616 /* Process Unlocked */
1617 __HAL_UNLOCK(hsmbus
);
1619 /* Call the Error callback to prevent upper layer */
1620 HAL_SMBUS_ErrorCallback(hsmbus
);
1623 else if(__HAL_SMBUS_GET_FLAG(hsmbus
, SMBUS_FLAG_ADDR
) != RESET
)
1625 TransferDirection
= SMBUS_GET_DIR(hsmbus
);
1626 SlaveAddrCode
= SMBUS_GET_ADDR_MATCH(hsmbus
);
1628 /* Disable ADDR interrupt to prevent multiple ADDRInterrupt*/
1629 /* Other ADDRInterrupt will be treat in next Listen usecase */
1630 __HAL_SMBUS_DISABLE_IT(hsmbus
, SMBUS_IT_ADDRI
);
1632 /* Process Unlocked */
1633 __HAL_UNLOCK(hsmbus
);
1635 /* Call Slave Addr callback */
1636 HAL_SMBUS_AddrCallback(hsmbus
, TransferDirection
, SlaveAddrCode
);
1638 else if((__HAL_SMBUS_GET_FLAG(hsmbus
, SMBUS_FLAG_RXNE
) != RESET
) || (__HAL_SMBUS_GET_FLAG(hsmbus
, SMBUS_FLAG_TCR
) != RESET
))
1640 if( (hsmbus
->State
& HAL_SMBUS_STATE_SLAVE_BUSY_RX
) == HAL_SMBUS_STATE_SLAVE_BUSY_RX
)
1642 /* Read data from RXDR */
1643 (*hsmbus
->pBuffPtr
++) = hsmbus
->Instance
->RXDR
;
1645 hsmbus
->XferCount
--;
1647 if(hsmbus
->XferCount
== 1U)
1649 /* Receive last Byte, can be PEC byte in case of PEC BYTE enabled */
1650 /* or only the last Byte of Transfer */
1651 /* So reset the RELOAD bit mode */
1652 hsmbus
->XferOptions
&= ~SMBUS_RELOAD_MODE
;
1653 SMBUS_TransferConfig(hsmbus
, 0U ,1U , hsmbus
->XferOptions
, SMBUS_NO_STARTSTOP
);
1655 else if(hsmbus
->XferCount
== 0U)
1657 /* Last Byte is received, disable Interrupt */
1658 SMBUS_Disable_IRQ(hsmbus
, SMBUS_IT_RX
);
1660 /* Remove HAL_SMBUS_STATE_SLAVE_BUSY_RX, keep only HAL_SMBUS_STATE_LISTEN */
1661 hsmbus
->PreviousState
= hsmbus
->State
;
1662 hsmbus
->State
&= ~((uint32_t)HAL_SMBUS_STATE_SLAVE_BUSY_RX
);
1664 /* Process Unlocked */
1665 __HAL_UNLOCK(hsmbus
);
1667 /* Call the Rx complete callback to inform upper layer of the end of receive process */
1668 HAL_SMBUS_SlaveRxCpltCallback(hsmbus
);
1672 /* Set Reload for next Bytes */
1673 SMBUS_TransferConfig(hsmbus
, 0U, 1U, SMBUS_RELOAD_MODE
| (hsmbus
->XferOptions
& SMBUS_SENDPEC_MODE
), SMBUS_NO_STARTSTOP
);
1675 /* Ack last Byte Read */
1676 hsmbus
->Instance
->CR2
&= ~I2C_CR2_NACK
;
1679 else if( (hsmbus
->State
& HAL_SMBUS_STATE_SLAVE_BUSY_TX
) == HAL_SMBUS_STATE_SLAVE_BUSY_TX
)
1681 if((hsmbus
->XferSize
== 0U)&&(hsmbus
->XferCount
!= 0U))
1683 if(hsmbus
->XferCount
> MAX_NBYTE_SIZE
)
1685 SMBUS_TransferConfig(hsmbus
, 0U, MAX_NBYTE_SIZE
, (SMBUS_RELOAD_MODE
| (hsmbus
->XferOptions
& SMBUS_SENDPEC_MODE
)), SMBUS_NO_STARTSTOP
);
1686 hsmbus
->XferSize
= MAX_NBYTE_SIZE
;
1690 hsmbus
->XferSize
= hsmbus
->XferCount
;
1691 SMBUS_TransferConfig(hsmbus
, 0U, hsmbus
->XferSize
, hsmbus
->XferOptions
, SMBUS_NO_STARTSTOP
);
1692 /* If PEC mode is enable, size to transmit should be Size-1 byte, corresponding to PEC byte */
1693 /* PEC byte is automatically sent by HW block, no need to manage it in Transmit process */
1694 if(SMBUS_GET_PEC_MODE(hsmbus
) != RESET
)
1697 hsmbus
->XferCount
--;
1703 else if(__HAL_SMBUS_GET_FLAG(hsmbus
, SMBUS_FLAG_TXIS
) != RESET
)
1705 /* Write data to TXDR only if XferCount not reach "0" */
1706 /* A TXIS flag can be set, during STOP treatment */
1707 /* Check if all Data have already been sent */
1708 /* If it is the case, this last write in TXDR is not sent, correspond to a dummy TXIS event */
1709 if(hsmbus
->XferCount
> 0U)
1711 /* Write data to TXDR */
1712 hsmbus
->Instance
->TXDR
= (*hsmbus
->pBuffPtr
++);
1713 hsmbus
->XferCount
--;
1717 if(hsmbus
->XferCount
== 0U)
1719 /* Last Byte is Transmitted */
1720 /* Remove HAL_SMBUS_STATE_SLAVE_BUSY_TX, keep only HAL_SMBUS_STATE_LISTEN */
1721 SMBUS_Disable_IRQ(hsmbus
, SMBUS_IT_TX
);
1722 hsmbus
->PreviousState
= hsmbus
->State
;
1723 hsmbus
->State
&= ~((uint32_t)HAL_SMBUS_STATE_SLAVE_BUSY_TX
);
1725 /* Process Unlocked */
1726 __HAL_UNLOCK(hsmbus
);
1728 /* Call the Tx complete callback to inform upper layer of the end of transmit process */
1729 HAL_SMBUS_SlaveTxCpltCallback(hsmbus
);
1733 /* Check if STOPF is set */
1734 if(__HAL_SMBUS_GET_FLAG(hsmbus
, SMBUS_FLAG_STOPF
) != RESET
)
1736 if((hsmbus
->State
& HAL_SMBUS_STATE_LISTEN
) == HAL_SMBUS_STATE_LISTEN
)
1738 /* Store Last receive data if any */
1739 if(__HAL_SMBUS_GET_FLAG(hsmbus
, SMBUS_FLAG_RXNE
) != RESET
)
1741 /* Read data from RXDR */
1742 (*hsmbus
->pBuffPtr
++) = hsmbus
->Instance
->RXDR
;
1744 if((hsmbus
->XferSize
> 0U))
1747 hsmbus
->XferCount
--;
1751 /* Disable RX and TX Interrupts */
1752 SMBUS_Disable_IRQ(hsmbus
, SMBUS_IT_RX
| SMBUS_IT_TX
);
1754 /* Disable ADDR Interrupt */
1755 SMBUS_Disable_IRQ(hsmbus
, SMBUS_IT_ADDR
);
1757 /* Disable Address Acknowledge */
1758 hsmbus
->Instance
->CR2
|= I2C_CR2_NACK
;
1760 /* Clear Configuration Register 2 */
1761 SMBUS_RESET_CR2(hsmbus
);
1763 /* Clear STOP Flag */
1764 __HAL_SMBUS_CLEAR_FLAG(hsmbus
, SMBUS_FLAG_STOPF
);
1766 /* Clear ADDR flag */
1767 __HAL_SMBUS_CLEAR_FLAG(hsmbus
,SMBUS_FLAG_ADDR
);
1769 hsmbus
->XferOptions
= 0U;
1770 hsmbus
->PreviousState
= hsmbus
->State
;
1771 hsmbus
->State
= HAL_SMBUS_STATE_READY
;
1773 /* Process Unlocked */
1774 __HAL_UNLOCK(hsmbus
);
1776 /* Call the Listen Complete callback, to prevent upper layer of the end of Listen usecase */
1777 HAL_SMBUS_ListenCpltCallback(hsmbus
);
1781 /* Process Unlocked */
1782 __HAL_UNLOCK(hsmbus
);
1787 * @brief Manage the enabling of Interrupts.
1788 * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains
1789 * the configuration information for the specified SMBUS.
1790 * @param InterruptRequest Value of @ref SMBUS_Interrupt_configuration_definition.
1791 * @retval HAL status
1793 static HAL_StatusTypeDef
SMBUS_Enable_IRQ(SMBUS_HandleTypeDef
*hsmbus
, uint16_t InterruptRequest
)
1795 uint32_t tmpisr
= 0U;
1797 if((InterruptRequest
& SMBUS_IT_ALERT
) == SMBUS_IT_ALERT
)
1799 /* Enable ERR interrupt */
1800 tmpisr
|= SMBUS_IT_ERRI
;
1803 if((InterruptRequest
& SMBUS_IT_ADDR
) == SMBUS_IT_ADDR
)
1805 /* Enable ADDR, STOP interrupt */
1806 tmpisr
|= SMBUS_IT_ADDRI
| SMBUS_IT_STOPI
| SMBUS_IT_NACKI
| SMBUS_IT_ERRI
;
1809 if((InterruptRequest
& SMBUS_IT_TX
) == SMBUS_IT_TX
)
1811 /* Enable ERR, TC, STOP, NACK, RXI interrupt */
1812 tmpisr
|= SMBUS_IT_ERRI
| SMBUS_IT_TCI
| SMBUS_IT_STOPI
| SMBUS_IT_NACKI
| SMBUS_IT_TXI
;
1815 if((InterruptRequest
& SMBUS_IT_RX
) == SMBUS_IT_RX
)
1817 /* Enable ERR, TC, STOP, NACK, TXI interrupt */
1818 tmpisr
|= SMBUS_IT_ERRI
| SMBUS_IT_TCI
| SMBUS_IT_STOPI
| SMBUS_IT_NACKI
| SMBUS_IT_RXI
;
1821 /* Enable interrupts only at the end */
1822 /* to avoid the risk of SMBUS interrupt handle execution before */
1823 /* all interrupts requested done */
1824 __HAL_SMBUS_ENABLE_IT(hsmbus
, tmpisr
);
1829 * @brief Manage the disabling of Interrupts.
1830 * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains
1831 * the configuration information for the specified SMBUS.
1832 * @param InterruptRequest Value of @ref SMBUS_Interrupt_configuration_definition.
1833 * @retval HAL status
1835 static HAL_StatusTypeDef
SMBUS_Disable_IRQ(SMBUS_HandleTypeDef
*hsmbus
, uint16_t InterruptRequest
)
1837 uint32_t tmpisr
= 0U;
1839 if( ((InterruptRequest
& SMBUS_IT_ALERT
) == SMBUS_IT_ALERT
) && (hsmbus
->State
== HAL_SMBUS_STATE_READY
) )
1841 /* Disable ERR interrupt */
1842 tmpisr
|= SMBUS_IT_ERRI
;
1845 if((InterruptRequest
& SMBUS_IT_TX
) == SMBUS_IT_TX
)
1847 /* Disable TC, STOP, NACK, TXI interrupt */
1848 tmpisr
|= SMBUS_IT_TCI
| SMBUS_IT_TXI
;
1850 if((SMBUS_GET_ALERT_ENABLED(hsmbus
) == RESET
)
1851 && ((hsmbus
->State
& HAL_SMBUS_STATE_LISTEN
) != HAL_SMBUS_STATE_LISTEN
))
1853 /* Disable ERR interrupt */
1854 tmpisr
|= SMBUS_IT_ERRI
;
1857 if((hsmbus
->State
& HAL_SMBUS_STATE_LISTEN
) != HAL_SMBUS_STATE_LISTEN
)
1859 /* Disable STOPI, NACKI */
1860 tmpisr
|= SMBUS_IT_STOPI
| SMBUS_IT_NACKI
;
1864 if((InterruptRequest
& SMBUS_IT_RX
) == SMBUS_IT_RX
)
1866 /* Disable TC, STOP, NACK, RXI interrupt */
1867 tmpisr
|= SMBUS_IT_TCI
| SMBUS_IT_RXI
;
1869 if((SMBUS_GET_ALERT_ENABLED(hsmbus
) == RESET
)
1870 && ((hsmbus
->State
& HAL_SMBUS_STATE_LISTEN
) != HAL_SMBUS_STATE_LISTEN
))
1872 /* Disable ERR interrupt */
1873 tmpisr
|= SMBUS_IT_ERRI
;
1876 if((hsmbus
->State
& HAL_SMBUS_STATE_LISTEN
) != HAL_SMBUS_STATE_LISTEN
)
1878 /* Disable STOPI, NACKI */
1879 tmpisr
|= SMBUS_IT_STOPI
| SMBUS_IT_NACKI
;
1883 if((InterruptRequest
& SMBUS_IT_ADDR
) == SMBUS_IT_ADDR
)
1885 /* Enable ADDR, STOP interrupt */
1886 tmpisr
|= SMBUS_IT_ADDRI
| SMBUS_IT_STOPI
| SMBUS_IT_NACKI
;
1888 if(SMBUS_GET_ALERT_ENABLED(hsmbus
) == RESET
)
1890 /* Disable ERR interrupt */
1891 tmpisr
|= SMBUS_IT_ERRI
;
1895 /* Disable interrupts only at the end */
1896 /* to avoid a breaking situation like at "t" time */
1897 /* all disable interrupts request are not done */
1898 __HAL_SMBUS_DISABLE_IT(hsmbus
, tmpisr
);
1903 * @brief Handle SMBUS Communication Timeout.
1904 * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains
1905 * the configuration information for the specified SMBUS.
1906 * @param Flag Specifies the SMBUS flag to check.
1907 * @param Status The new Flag status (SET or RESET).
1908 * @param Timeout Timeout duration
1909 * @retval HAL status
1911 static HAL_StatusTypeDef
SMBUS_WaitOnFlagUntilTimeout(SMBUS_HandleTypeDef
*hsmbus
, uint32_t Flag
, FlagStatus Status
, uint32_t Timeout
)
1913 uint32_t tickstart
= HAL_GetTick();
1915 /* Wait until flag is set */
1918 while(__HAL_SMBUS_GET_FLAG(hsmbus
, Flag
) == RESET
)
1920 /* Check for the Timeout */
1921 if(Timeout
!= HAL_MAX_DELAY
)
1923 if((Timeout
== 0U) || ((HAL_GetTick() - tickstart
) > Timeout
))
1925 hsmbus
->PreviousState
= hsmbus
->State
;
1926 hsmbus
->State
= HAL_SMBUS_STATE_READY
;
1928 /* Process Unlocked */
1929 __HAL_UNLOCK(hsmbus
);
1938 while(__HAL_SMBUS_GET_FLAG(hsmbus
, Flag
) != RESET
)
1940 /* Check for the Timeout */
1941 if(Timeout
!= HAL_MAX_DELAY
)
1943 if((Timeout
== 0U) || ((HAL_GetTick() - tickstart
) > Timeout
))
1945 hsmbus
->PreviousState
= hsmbus
->State
;
1946 hsmbus
->State
= HAL_SMBUS_STATE_READY
;
1948 /* Process Unlocked */
1949 __HAL_UNLOCK(hsmbus
);
1960 * @brief Handle SMBUSx communication when starting transfer or during transfer (TC or TCR flag are set).
1961 * @param hsmbus SMBUS handle.
1962 * @param DevAddress specifies the slave address to be programmed.
1963 * @param Size specifies the number of bytes to be programmed.
1964 * This parameter must be a value between 0 and 255.
1965 * @param Mode New state of the SMBUS START condition generation.
1966 * This parameter can be one or a combination of the following values:
1967 * @arg @ref SMBUS_RELOAD_MODE Enable Reload mode.
1968 * @arg @ref SMBUS_AUTOEND_MODE Enable Automatic end mode.
1969 * @arg @ref SMBUS_SOFTEND_MODE Enable Software end mode and Reload mode.
1970 * @arg @ref SMBUS_SENDPEC_MODE Enable Packet Error Calculation mode.
1971 * @param Request New state of the SMBUS START condition generation.
1972 * This parameter can be one of the following values:
1973 * @arg @ref SMBUS_NO_STARTSTOP Don't Generate stop and start condition.
1974 * @arg @ref SMBUS_GENERATE_STOP Generate stop condition (Size should be set to 0).
1975 * @arg @ref SMBUS_GENERATE_START_READ Generate Restart for read request.
1976 * @arg @ref SMBUS_GENERATE_START_WRITE Generate Restart for write request.
1979 static void SMBUS_TransferConfig(SMBUS_HandleTypeDef
*hsmbus
, uint16_t DevAddress
, uint8_t Size
, uint32_t Mode
, uint32_t Request
)
1981 uint32_t tmpreg
= 0U;
1983 /* Check the parameters */
1984 assert_param(IS_SMBUS_ALL_INSTANCE(hsmbus
->Instance
));
1985 assert_param(IS_SMBUS_TRANSFER_MODE(Mode
));
1986 assert_param(IS_SMBUS_TRANSFER_REQUEST(Request
));
1988 /* Get the CR2 register value */
1989 tmpreg
= hsmbus
->Instance
->CR2
;
1991 /* clear tmpreg specific bits */
1992 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
));
1995 tmpreg
|= (uint32_t)(((uint32_t)DevAddress
& I2C_CR2_SADD
) | (((uint32_t)Size
<< 16U ) & I2C_CR2_NBYTES
) | \
1996 (uint32_t)Mode
| (uint32_t)Request
);
1998 /* update CR2 register */
1999 hsmbus
->Instance
->CR2
= tmpreg
;
2003 * @brief Convert SMBUSx OTHER_xxx XferOptions to functionnal XferOptions.
2004 * @param hsmbus SMBUS handle.
2007 static void SMBUS_ConvertOtherXferOptions(SMBUS_HandleTypeDef
*hsmbus
)
2009 /* if user set XferOptions to SMBUS_OTHER_FRAME_NO_PEC */
2010 /* it request implicitly to generate a restart condition */
2011 /* set XferOptions to SMBUS_FIRST_FRAME */
2012 if(hsmbus
->XferOptions
== SMBUS_OTHER_FRAME_NO_PEC
)
2014 hsmbus
->XferOptions
= SMBUS_FIRST_FRAME
;
2016 /* else if user set XferOptions to SMBUS_OTHER_FRAME_WITH_PEC */
2017 /* it request implicitly to generate a restart condition */
2018 /* set XferOptions to SMBUS_FIRST_FRAME | SMBUS_SENDPEC_MODE */
2019 else if(hsmbus
->XferOptions
== SMBUS_OTHER_FRAME_WITH_PEC
)
2021 hsmbus
->XferOptions
= SMBUS_FIRST_FRAME
| SMBUS_SENDPEC_MODE
;
2023 /* else if user set XferOptions to SMBUS_OTHER_AND_LAST_FRAME_NO_PEC */
2024 /* it request implicitly to generate a restart condition */
2025 /* then generate a stop condition at the end of transfer */
2026 /* set XferOptions to SMBUS_FIRST_AND_LAST_FRAME_NO_PEC */
2027 else if(hsmbus
->XferOptions
== SMBUS_OTHER_AND_LAST_FRAME_NO_PEC
)
2029 hsmbus
->XferOptions
= SMBUS_FIRST_AND_LAST_FRAME_NO_PEC
;
2031 /* else if user set XferOptions to SMBUS_OTHER_AND_LAST_FRAME_WITH_PEC */
2032 /* it request implicitly to generate a restart condition */
2033 /* then generate a stop condition at the end of transfer */
2034 /* set XferOptions to SMBUS_FIRST_AND_LAST_FRAME_WITH_PEC */
2035 else if(hsmbus
->XferOptions
== SMBUS_OTHER_AND_LAST_FRAME_WITH_PEC
)
2037 hsmbus
->XferOptions
= SMBUS_FIRST_AND_LAST_FRAME_WITH_PEC
;
2044 #endif /* HAL_SMBUS_MODULE_ENABLED */
2053 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/