2 ******************************************************************************
3 * @file stm32h7xx_hal_ramecc.c
4 * @author MCD Application Team
5 * @brief RAMECC HAL module driver.
6 * This file provides firmware functions to manage the following
7 * functionalities of the RAM ECC monitoring (RAMECC) peripheral:
8 * + Initialization and de-initialization functions
9 * + Monitoring operation functions
10 * + Error informations functions
11 * + State and error functions
13 ==============================================================================
14 ##### How to use this driver #####
15 ==============================================================================
17 (#) Enable and latch error informations through HAL_RAMECC_Init().
19 (#) For a given Monitor, enable and disable interrupt through
20 HAL_RAMECC_EnableNotifiaction().
21 To enable a notification for a given RAMECC instance, use global
23 To enable a notification for only RAMECC monitor, use monitor interrupts.
24 All possible notifications are defined in the driver header file under
25 RAMECC_Interrupt group.
30 (+) Use HAL_RAMECC_StartMonitor() to start RAMECC latch failing
31 information without enabling any notification.
33 *** Interrupt mode ***
34 ======================
36 (+) Use HAL_RAMECC_EnableNotifiaction() to enable interrupts for a
38 (+) Configure the RAMECC interrupt priority using
39 HAL_NVIC_SetPriority().
40 (+) Enable the RAMECC IRQ handler using HAL_NVIC_EnableIRQ().
42 *** Failing informations ***
43 ======================
45 (#) Use HAL_RAMECC_GetFailingAddress() function to return the RAMECC
47 (#) Use HAL_RAMECC_GetFailingDataLow() function to return the RAMECC
49 (#) Use HAL_RAMECC_GetFailingDataHigh() function to return the RAMECC
51 (#) Use HAL_RAMECC_GetHammingErrorCode() function to return the RAMECC
52 Hamming bits injected.
53 (#) Use HAL_RAMECC_IsECCSingleErrorDetected() function to check if a single
54 error was detected and corrected.
55 (#) Use HAL_RAMECC_IsECCDoubleErrorDetected() function to check if a double
58 *** RAMECC HAL driver macros list ***
59 =============================================
61 Below the list of used macros in RAMECC HAL driver.
63 (+) __HAL_RAMECC_ENABLE_IT : Enable the specified ECCRAM Monitor
65 (+) __HAL_RAMECC_DISABLE_IT : Disable the specified ECCRAM Monitor
67 (+) __HAL_RAMECC_GET_FLAG : Return the current RAMECC Monitor selected
69 (+) __HAL_RAMECC_CLEAR_FLAG : Clear the current RAMECC Monitor selected
72 ******************************************************************************
75 * <h2><center>© COPYRIGHT(c) 2017 STMicroelectronics.
76 * All rights reserved.</center></h2>
78 * This software component is licensed by ST under BSD 3-Clause license,
79 * the "License"; You may not use this file except in compliance with the
80 * License. You may obtain a copy of the License at:
81 * opensource.org/licenses/BSD-3-Clause
83 ******************************************************************************
86 /* Includes ------------------------------------------------------------------*/
87 #include "stm32h7xx_hal.h"
89 /** @addtogroup STM32H7xx_HAL_Driver
93 /** @defgroup RAMECC RAMECC
94 * @brief RAMECC HAL module driver
98 #ifdef HAL_RAMECC_MODULE_ENABLED
100 /* Private types -------------------------------------------------------------*/
101 /* Private variables ---------------------------------------------------------*/
102 /* Private constants ---------------------------------------------------------*/
103 /* Private macros ------------------------------------------------------------*/
104 /* Private functions ---------------------------------------------------------*/
105 /* Exported functions --------------------------------------------------------*/
107 /** @addtogroup RAMECC_Exported_Functions
111 /** @addtogroup RAMECC_Exported_Functions_Group1
114 ===============================================================================
115 ##### Initialization and de-initialization functions #####
116 ===============================================================================
118 This section provides functions allowing to initialize the RAMECC Monitor.
120 The HAL_RAMECC_Init() function follows the RAMECC configuration procedures
121 as described in reference manual.
122 The HAL_RAMECC_DeInit() function allows to deinitialize the RAMECC monitor.
129 * @brief Initialize the RAMECC by clearing flags and disabling interrupts.
130 * @param hramecc Pointer to a RAMECC_HandleTypeDef structure that contains
131 * the configuration information for the specified RAMECC
133 * @retval HAL status.
135 HAL_StatusTypeDef
HAL_RAMECC_Init (RAMECC_HandleTypeDef
*hramecc
)
137 /* Check the RAMECC peripheral handle */
140 /* Return HAL status */
144 /* Check the parameters */
145 assert_param (IS_RAMECC_MONITOR_ALL_INSTANCE (hramecc
->Instance
));
147 /* Change RAMECC peripheral state */
148 hramecc
->State
= HAL_RAMECC_STATE_BUSY
;
150 /* Disable RAMECC monitor */
151 hramecc
->Instance
->CR
&= ~RAMECC_CR_ECCELEN
;
153 /* Disable all global interrupts */
154 ((RAMECC_TypeDef
*)((uint32_t)hramecc
->Instance
& 0xFFFFFF00U
))->IER
&= \
155 ~(RAMECC_IER_GIE
| RAMECC_IER_GECCSEIE
| RAMECC_IER_GECCDEIE
| RAMECC_IER_GECCDEBWIE
);
157 /* Disable all interrupts monitor */
158 hramecc
->Instance
->CR
&= ~(RAMECC_CR_ECCSEIE
| RAMECC_CR_ECCDEIE
| RAMECC_CR_ECCDEBWIE
);
160 /* Clear RAMECC monitor flags */
161 __HAL_RAMECC_CLEAR_FLAG (hramecc
, RAMECC_FLAGS_ALL
);
163 /* Initialise the RAMECC error code */
164 hramecc
->ErrorCode
= HAL_RAMECC_ERROR_NONE
;
166 /* Update the RAMECC state */
167 hramecc
->State
= HAL_RAMECC_STATE_READY
;
169 /* Return HAL status */
175 * @brief DeInitializes the RAMECC peripheral.
176 * @param hramecc Pointer to a RAMECC_HandleTypeDef structure that contains
177 * the configuration information for the specified RAMECC
179 * @retval HAL status.
181 HAL_StatusTypeDef
HAL_RAMECC_DeInit (RAMECC_HandleTypeDef
*hramecc
)
183 /* Check the RAMECC peripheral handle */
186 /* Return HAL status */
190 /* Check the parameters */
191 assert_param (IS_RAMECC_MONITOR_ALL_INSTANCE (hramecc
->Instance
));
193 /* Disable RAMECC monitor */
194 hramecc
->Instance
->CR
&= ~RAMECC_CR_ECCELEN
;
196 /* Disable all global interrupts */
197 ((RAMECC_TypeDef
*)((uint32_t)hramecc
->Instance
& 0xFFFFFF00U
))->IER
&= \
198 ~(RAMECC_IER_GIE
| RAMECC_IER_GECCSEIE
| RAMECC_IER_GECCDEIE
| RAMECC_IER_GECCDEBWIE
);
200 /* Disable all interrupts monitor */
201 hramecc
->Instance
->CR
&= ~(RAMECC_CR_ECCSEIE
| RAMECC_CR_ECCDEIE
| RAMECC_CR_ECCDEBWIE
);
203 /* Clear RAMECC monitor flags */
204 __HAL_RAMECC_CLEAR_FLAG (hramecc
, RAMECC_FLAGS_ALL
);
207 hramecc
->DetectErrorCallback
= NULL
;
209 /* Initialise the RAMECC error code */
210 hramecc
->ErrorCode
= HAL_RAMECC_ERROR_NONE
;
212 /* Change RAMECC peripheral state */
213 hramecc
->State
= HAL_RAMECC_STATE_RESET
;
215 /* Return HAL status */
226 /** @addtogroup RAMECC_Exported_Functions_Group2
229 ===============================================================================
230 ##### Monitoring operation functions #####
231 ===============================================================================
232 [..] This section provides functions allowing to:
233 (+) Configure latching error informations.
234 (+) Configure RAMECC Global/Monitor interrupts.
235 (+) Register and Unregister RAMECC callbacks
236 (+) Handle RAMECC interrupt request
243 * @brief Starts the RAMECC latching error information.
244 * @param hramecc Pointer to a RAMECC_HandleTypeDef structure that contains
245 * the configuration information for the specified RAMECC
247 * @retval HAL status.
249 HAL_StatusTypeDef
HAL_RAMECC_StartMonitor (RAMECC_HandleTypeDef
*hramecc
)
251 /* Check the parameters */
252 assert_param (IS_RAMECC_MONITOR_ALL_INSTANCE (hramecc
->Instance
));
254 /* Check RAMECC state */
255 if (hramecc
->State
== HAL_RAMECC_STATE_READY
)
257 /* Change RAMECC peripheral state */
258 hramecc
->State
= HAL_RAMECC_STATE_BUSY
;
260 /* Enable RAMECC monitor */
261 hramecc
->Instance
->CR
|= RAMECC_CR_ECCELEN
;
263 /* Change RAMECC peripheral state */
264 hramecc
->State
= HAL_RAMECC_STATE_READY
;
268 /* Update the error code */
269 hramecc
->ErrorCode
= HAL_RAMECC_ERROR_BUSY
;
271 /* Return HAL status */
275 /* Return HAL status */
281 * @brief Stop the RAMECC latching error informations.
282 * @param hramecc Pointer to a RAMECC_HandleTypeDef structure that contains
283 * the configuration information for the specified RAMECC
285 * @retval HAL status.
287 HAL_StatusTypeDef
HAL_RAMECC_StopMonitor (RAMECC_HandleTypeDef
*hramecc
)
289 /* Check the parameters */
290 assert_param (IS_RAMECC_MONITOR_ALL_INSTANCE (hramecc
->Instance
));
292 /* Check RAMECC state */
293 if (hramecc
->State
== HAL_RAMECC_STATE_READY
)
295 /* Change RAMECC peripheral state */
296 hramecc
->State
= HAL_RAMECC_STATE_BUSY
;
298 /* Disable RAMECC monitor */
299 hramecc
->Instance
->CR
&= ~RAMECC_CR_ECCELEN
;
301 /* Change RAMECC peripheral state */
302 hramecc
->State
= HAL_RAMECC_STATE_READY
;
306 /* Update the error code */
307 hramecc
->ErrorCode
= HAL_RAMECC_ERROR_BUSY
;
309 /* Return HAL status */
313 /* Return HAL status */
319 * @brief Enable the RAMECC error interrupts.
320 * @param hramecc Pointer to a RAMECC_HandleTypeDef structure that
321 * contains the configuration information for the
322 * specified RAMECC Monitor.
323 * @param Notifications Select the notification.
324 * @retval HAL status.
326 HAL_StatusTypeDef
HAL_RAMECC_EnableNotification (RAMECC_HandleTypeDef
*hramecc
, uint32_t Notifications
)
328 /* Check the parameters */
329 assert_param (IS_RAMECC_MONITOR_ALL_INSTANCE (hramecc
->Instance
));
330 assert_param (IS_RAMECC_INTERRUPT (Notifications
));
332 /* Check RAMECC state */
333 if (hramecc
->State
== HAL_RAMECC_STATE_READY
)
335 /* Change RAMECC peripheral state */
336 hramecc
->State
= HAL_RAMECC_STATE_BUSY
;
338 /* Enable RAMECC interrupts */
339 __HAL_RAMECC_ENABLE_IT (hramecc
, Notifications
);
341 /* Change RAMECC peripheral state */
342 hramecc
->State
= HAL_RAMECC_STATE_READY
;
346 /* Update the error code */
347 hramecc
->ErrorCode
= HAL_RAMECC_ERROR_BUSY
;
349 /* Return HAL status */
353 /* Return HAL status */
359 * @brief Disable the RAMECC error interrupts.
360 * @param hramecc Pointer to a RAMECC_HandleTypeDef structure that
361 * contains the configuration information for the
362 * specified RAMECC Monitor.
363 * @param Notifications Select the notification.
364 * @retval HAL status.
366 HAL_StatusTypeDef
HAL_RAMECC_DisableNotification (RAMECC_HandleTypeDef
*hramecc
, uint32_t Notifications
)
368 /* Check the parameters */
369 assert_param (IS_RAMECC_MONITOR_ALL_INSTANCE (hramecc
->Instance
));
370 assert_param (IS_RAMECC_INTERRUPT (Notifications
));
372 /* Check RAMECC state */
373 if (hramecc
->State
== HAL_RAMECC_STATE_READY
)
375 /* Change RAMECC peripheral state */
376 hramecc
->State
= HAL_RAMECC_STATE_BUSY
;
378 /* Disable RAMECC interrupts */
379 __HAL_RAMECC_DISABLE_IT (hramecc
, Notifications
);
381 /* Change RAMECC peripheral state */
382 hramecc
->State
= HAL_RAMECC_STATE_READY
;
386 /* Update the error code */
387 hramecc
->ErrorCode
= HAL_RAMECC_ERROR_BUSY
;
389 /* Return HAL status */
393 /* Return HAL status */
399 * @brief Register callbacks.
400 * @param hramecc Pointer to a RAMECC_HandleTypeDef structure that contains
401 * the configuration information for the specified RAMECC
403 * @param pCallback pointer to private callbacsk function which has pointer to
404 * a RAMECC_HandleTypeDef structure as parameter.
405 * @retval HAL status.
407 HAL_StatusTypeDef
HAL_RAMECC_RegisterCallback (RAMECC_HandleTypeDef
*hramecc
, void (* pCallback
)(RAMECC_HandleTypeDef
*_hramecc
))
409 HAL_StatusTypeDef status
= HAL_OK
;
411 if (pCallback
== NULL
)
413 /* Update the error code */
414 hramecc
->ErrorCode
|= HAL_RAMECC_ERROR_INVALID_CALLBACK
;
416 /* Return HAL status */
420 /* Check the parameters */
421 assert_param (IS_RAMECC_MONITOR_ALL_INSTANCE (hramecc
->Instance
));
423 /* Check RAMECC state */
424 if (hramecc
->State
== HAL_RAMECC_STATE_READY
)
426 hramecc
->DetectErrorCallback
= pCallback
;
430 /* Update the error code */
431 hramecc
->ErrorCode
= HAL_RAMECC_ERROR_INVALID_CALLBACK
;
433 /* Update HAL status */
437 /* Return HAL status */
443 * @brief UnRegister callbacks.
444 * @param hramecc Pointer to a RAMECC_HandleTypeDef structure that contains
445 * the configuration information for the specified RAMECC
447 * @retval HAL status.
449 HAL_StatusTypeDef
HAL_RAMECC_UnRegisterCallback (RAMECC_HandleTypeDef
*hramecc
)
451 HAL_StatusTypeDef status
= HAL_OK
;
453 /* Check the parameters */
454 assert_param (IS_RAMECC_MONITOR_ALL_INSTANCE (hramecc
->Instance
));
456 /* Check RAMECC state */
457 if(hramecc
->State
== HAL_RAMECC_STATE_READY
)
459 hramecc
->DetectErrorCallback
= NULL
;
463 /* Update the error code */
464 hramecc
->ErrorCode
= HAL_RAMECC_ERROR_INVALID_CALLBACK
;
466 /* Update HAL status */
470 /* Return HAL status */
476 * @brief Handles RAMECC interrupt request.
477 * @param hramecc Pointer to a RAMECC_HandleTypeDef structure that contains
478 * the configuration information for the specified RAMECC
482 void HAL_RAMECC_IRQHandler (RAMECC_HandleTypeDef
*hramecc
)
484 uint32_t ier_reg
= ((RAMECC_TypeDef
*)((uint32_t)hramecc
->Instance
& 0xFFFFFF00U
))->IER
;
485 uint32_t cr_reg
= hramecc
->Instance
->CR
>> 1U;
486 uint32_t sr_reg
= hramecc
->Instance
->SR
<< 1U;
488 /* Update global interrupt variables */
489 if ((ier_reg
& RAMECC_IER_GIE
) == RAMECC_IER_GIE
)
491 ier_reg
= RAMECC_IT_GLOBAL_ALL
;
494 /* Clear active flags */
495 __HAL_RAMECC_CLEAR_FLAG (hramecc
, (((ier_reg
| cr_reg
) & sr_reg
) >> 1U));
497 /* Check if a valid double error callback is registred */
498 if (hramecc
->DetectErrorCallback
!= NULL
)
500 /* Error detection callback */
501 hramecc
->DetectErrorCallback(hramecc
);
506 /** @addtogroup RAMECC_Exported_Functions_Group3
509 ===============================================================================
510 ##### Error informations functions #####
511 ===============================================================================
512 [..] This section provides functions allowing to:
513 (+) Get failing address.
514 (+) Get failing data low.
515 (+) Get failing data high.
516 (+) Get hamming bits injected.
517 (+) Check single error flag.
518 (+) Check double error flag.
525 * @brief Return the RAMECC failing address.
526 * @param hramecc Pointer to a RAMECC_HandleTypeDef structure that contains
527 * the configuration information for the specified RAMECC
529 * @retval Failing address offset.
531 uint32_t HAL_RAMECC_GetFailingAddress (RAMECC_HandleTypeDef
*hramecc
)
533 /* Check the parameters */
534 assert_param (IS_RAMECC_MONITOR_ALL_INSTANCE (hramecc
->Instance
));
536 /* Return failing address */
537 return hramecc
->Instance
->FAR
;
542 * @brief Return the RAMECC data low.
543 * @param hramecc Pointer to a RAMECC_HandleTypeDef structure that contains
544 * the configuration information for the specified RAMECC
546 * @retval Failing data low.
548 uint32_t HAL_RAMECC_GetFailingDataLow (RAMECC_HandleTypeDef
*hramecc
)
550 /* Check the parameters */
551 assert_param (IS_RAMECC_MONITOR_ALL_INSTANCE (hramecc
->Instance
));
553 /* Return failing data low */
554 return hramecc
->Instance
->FDRL
;
559 * @brief Return the RAMECC data high.
560 * @param hramecc Pointer to a RAMECC_HandleTypeDef structure that contains
561 * the configuration information for the specified RAMECC
563 * @retval Failing data high.
565 uint32_t HAL_RAMECC_GetFailingDataHigh (RAMECC_HandleTypeDef
*hramecc
)
567 /* Check the parameters */
568 assert_param (IS_RAMECC_MONITOR_ALL_INSTANCE (hramecc
->Instance
));
570 /* Return failing data high */
571 return hramecc
->Instance
->FDRH
;
576 * @brief Return the RAMECC Hamming bits injected.
577 * @param hramecc Pointer to a RAMECC_HandleTypeDef structure that contains
578 * the configuration information for the specified RAMECC
580 * @retval Hamming bits injected.
582 uint32_t HAL_RAMECC_GetHammingErrorCode (RAMECC_HandleTypeDef
*hramecc
)
584 /* Check the parameters */
585 assert_param (IS_RAMECC_MONITOR_ALL_INSTANCE (hramecc
->Instance
));
587 /* Return hamming bits injected */
588 return hramecc
->Instance
->FECR
;
592 * @brief Check if an ECC single error was occured.
593 * @param hramecc Pointer to a RAMECC_HandleTypeDef structure that contains
594 * the configuration information for the specified RAMECC
596 * @retval State of bit (1 or 0).
598 uint32_t HAL_RAMECC_IsECCSingleErrorDetected (RAMECC_HandleTypeDef
*hramecc
)
600 /* Check the parameters */
601 assert_param (IS_RAMECC_MONITOR_ALL_INSTANCE (hramecc
->Instance
));
603 /* Return the state of SEDC flag */
604 return ((READ_BIT(hramecc
->Instance
->SR
, RAMECC_SR_SEDCF
) == (RAMECC_SR_SEDCF
)) ? 1UL : 0UL);
608 * @brief Check if an ECC double error was occured.
609 * @param hramecc Pointer to a RAMECC_HandleTypeDef structure that contains
610 * the configuration information for the specified RAMECC
612 * @retval State of bit (1 or 0).
614 uint32_t HAL_RAMECC_IsECCDoubleErrorDetected (RAMECC_HandleTypeDef
*hramecc
)
616 /* Check the parameters */
617 assert_param (IS_RAMECC_MONITOR_ALL_INSTANCE (hramecc
->Instance
));
619 /* Return the state of DEDF | DEBWDF flags */
620 return ((READ_BIT(hramecc
->Instance
->SR
, (RAMECC_SR_DEDF
| RAMECC_SR_DEBWDF
)) != 0U) ? 1UL : 0UL);
627 /** @addtogroup RAMECC_Exported_Functions_Group4
630 ===============================================================================
631 ##### State and Error Functions #####
632 ===============================================================================
634 This section provides functions allowing to check and get the RAMECC state
637 The HAL_RAMECC_GetState() function allows to get the RAMECC peripheral
639 The HAL_RAMECC_GetError() function allows to Get the RAMECC peripheral error
647 * @brief Get the RAMECC peripheral state.
648 * @param hramecc : Pointer to a RAMECC_HandleTypeDef structure that
649 * contains the configuration information for the
650 * specified RAMECC instance.
651 * @retval RAMECC state.
653 HAL_RAMECC_StateTypeDef
HAL_RAMECC_GetState (RAMECC_HandleTypeDef
*hramecc
)
655 /* Return the RAMECC state */
656 return hramecc
->State
;
660 * @brief Get the RAMECC peripheral error code.
661 * @param hramecc : Pointer to a RAMECC_HandleTypeDef structure that
662 * contains the configuration information for the
663 * specified RAMECC instance.
664 * @retval RAMECC error code.
666 uint32_t HAL_RAMECC_GetError (RAMECC_HandleTypeDef
*hramecc
)
668 /* Return the RAMECC error code */
669 return hramecc
->ErrorCode
;
674 #endif /* HAL_RAMECC_MODULE_ENABLED */
692 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/