Merge pull request #11189 from klutvott123/move-telemetry-displayport-init
[betaflight.git] / lib / main / STM32G4 / Drivers / STM32G4xx_HAL_Driver / Src / stm32g4xx_ll_fmc.c
blob39ec52b8d73dd53c6edf0abda8dbf29190696ff4
1 /**
2 ******************************************************************************
3 * @file stm32g4xx_ll_fmc.c
4 * @author MCD Application Team
5 * @brief FMC Low Layer HAL module driver.
7 * This file provides firmware functions to manage the following
8 * functionalities of the Flexible Memory Controller (FMC) peripheral memories:
9 * + Initialization/de-initialization functions
10 * + Peripheral Control functions
11 * + Peripheral State functions
13 @verbatim
14 ==============================================================================
15 ##### FMC peripheral features #####
16 ==============================================================================
17 [..] The Flexible memory controller (FMC) includes following memory controllers:
18 (+) The NOR/PSRAM memory controller
19 (+) The NAND memory controller
21 [..] The FMC functional block makes the interface with synchronous and asynchronous static
22 memories. Its main purposes are:
23 (+) to translate AHB transactions into the appropriate external device protocol
24 (+) to meet the access time requirements of the external memory devices
26 [..] All external memories share the addresses, data and control signals with the controller.
27 Each external device is accessed by means of a unique Chip Select. The FMC performs
28 only one access at a time to an external device.
29 The main features of the FMC controller are the following:
30 (+) Interface with static-memory mapped devices including:
31 (++) Static random access memory (SRAM)
32 (++) Read-only memory (ROM)
33 (++) NOR Flash memory/OneNAND Flash memory
34 (++) PSRAM (4 memory banks)
35 (++) Two banks of NAND Flash memory with ECC hardware to check up to 8 Kbytes of
36 data
37 (+) Independent Chip Select control for each memory bank
38 (+) Independent configuration for each memory bank
40 @endverbatim
41 ******************************************************************************
42 * @attention
44 * <h2><center>&copy; Copyright (c) 2017 STMicroelectronics.
45 * All rights reserved.</center></h2>
47 * This software component is licensed by ST under BSD 3-Clause license,
48 * the "License"; You may not use this file except in compliance with the
49 * License. You may obtain a copy of the License at:
50 * opensource.org/licenses/BSD-3-Clause
52 ******************************************************************************
55 /* Includes ------------------------------------------------------------------*/
56 #include "stm32g4xx_hal.h"
58 /** @addtogroup STM32G4xx_HAL_Driver
59 * @{
62 /** @defgroup FMC_LL FMC Low Layer
63 * @brief FMC driver modules
64 * @{
67 /* Private typedef -----------------------------------------------------------*/
68 /* Private define ------------------------------------------------------------*/
70 /** @defgroup FMC_LL_Private_Constants FMC Low Layer Private Constants
71 * @{
74 /* ----------------------- FMC registers bit mask --------------------------- */
76 #if defined(FMC_BANK1)
77 /* --- BCR Register ---*/
78 /* BCR register clear mask */
80 /* --- BTR Register ---*/
81 /* BTR register clear mask */
82 #define BTR_CLEAR_MASK ((uint32_t)(FMC_BTRx_ADDSET | FMC_BTRx_ADDHLD |\
83 FMC_BTRx_DATAST | FMC_BTRx_BUSTURN |\
84 FMC_BTRx_CLKDIV | FMC_BTRx_DATLAT |\
85 FMC_BTRx_ACCMOD | FMC_BTRx_DATAHLD))
87 /* --- BWTR Register ---*/
88 /* BWTR register clear mask */
89 #define BWTR_CLEAR_MASK ((uint32_t)(FMC_BWTRx_ADDSET | FMC_BWTRx_ADDHLD |\
90 FMC_BWTRx_DATAST | FMC_BWTRx_BUSTURN |\
91 FMC_BWTRx_ACCMOD | FMC_BWTRx_DATAHLD))
92 #endif /* FMC_BANK1 */
93 #if defined(FMC_BANK3)
95 /* --- PCR Register ---*/
96 /* PCR register clear mask */
97 #define PCR_CLEAR_MASK ((uint32_t)(FMC_PCR_PWAITEN | FMC_PCR_PBKEN | \
98 FMC_PCR_PTYP | FMC_PCR_PWID | \
99 FMC_PCR_ECCEN | FMC_PCR_TCLR | \
100 FMC_PCR_TAR | FMC_PCR_ECCPS))
101 /* --- PMEM Register ---*/
102 /* PMEM register clear mask */
103 #define PMEM_CLEAR_MASK ((uint32_t)(FMC_PMEM_MEMSET | FMC_PMEM_MEMWAIT |\
104 FMC_PMEM_MEMHOLD | FMC_PMEM_MEMHIZ))
106 /* --- PATT Register ---*/
107 /* PATT register clear mask */
108 #define PATT_CLEAR_MASK ((uint32_t)(FMC_PATT_ATTSET | FMC_PATT_ATTWAIT |\
109 FMC_PATT_ATTHOLD | FMC_PATT_ATTHIZ))
111 #endif /* FMC_BANK3 */
114 * @}
117 /* Private macro -------------------------------------------------------------*/
118 /* Private variables ---------------------------------------------------------*/
119 /* Private function prototypes -----------------------------------------------*/
120 /* Exported functions --------------------------------------------------------*/
122 /** @defgroup FMC_LL_Exported_Functions FMC Low Layer Exported Functions
123 * @{
126 #if defined(FMC_BANK1)
128 /** @defgroup FMC_LL_Exported_Functions_NORSRAM FMC Low Layer NOR SRAM Exported Functions
129 * @brief NORSRAM Controller functions
131 @verbatim
132 ==============================================================================
133 ##### How to use NORSRAM device driver #####
134 ==============================================================================
136 [..]
137 This driver contains a set of APIs to interface with the FMC NORSRAM banks in order
138 to run the NORSRAM external devices.
140 (+) FMC NORSRAM bank reset using the function FMC_NORSRAM_DeInit()
141 (+) FMC NORSRAM bank control configuration using the function FMC_NORSRAM_Init()
142 (+) FMC NORSRAM bank timing configuration using the function FMC_NORSRAM_Timing_Init()
143 (+) FMC NORSRAM bank extended timing configuration using the function
144 FMC_NORSRAM_Extended_Timing_Init()
145 (+) FMC NORSRAM bank enable/disable write operation using the functions
146 FMC_NORSRAM_WriteOperation_Enable()/FMC_NORSRAM_WriteOperation_Disable()
148 @endverbatim
149 * @{
152 /** @defgroup FMC_LL_NORSRAM_Exported_Functions_Group1 Initialization and de-initialization functions
153 * @brief Initialization and Configuration functions
155 @verbatim
156 ==============================================================================
157 ##### Initialization and de_initialization functions #####
158 ==============================================================================
159 [..]
160 This section provides functions allowing to:
161 (+) Initialize and configure the FMC NORSRAM interface
162 (+) De-initialize the FMC NORSRAM interface
163 (+) Configure the FMC clock and associated GPIOs
165 @endverbatim
166 * @{
170 * @brief Initialize the FMC_NORSRAM device according to the specified
171 * control parameters in the FMC_NORSRAM_InitTypeDef
172 * @param Device Pointer to NORSRAM device instance
173 * @param Init Pointer to NORSRAM Initialization structure
174 * @retval HAL status
176 HAL_StatusTypeDef FMC_NORSRAM_Init(FMC_NORSRAM_TypeDef *Device, FMC_NORSRAM_InitTypeDef *Init)
178 uint32_t flashaccess;
180 /* Check the parameters */
181 assert_param(IS_FMC_NORSRAM_DEVICE(Device));
182 assert_param(IS_FMC_NORSRAM_BANK(Init->NSBank));
183 assert_param(IS_FMC_MUX(Init->DataAddressMux));
184 assert_param(IS_FMC_MEMORY(Init->MemoryType));
185 assert_param(IS_FMC_NORSRAM_MEMORY_WIDTH(Init->MemoryDataWidth));
186 assert_param(IS_FMC_BURSTMODE(Init->BurstAccessMode));
187 assert_param(IS_FMC_WAIT_POLARITY(Init->WaitSignalPolarity));
188 assert_param(IS_FMC_WAIT_SIGNAL_ACTIVE(Init->WaitSignalActive));
189 assert_param(IS_FMC_WRITE_OPERATION(Init->WriteOperation));
190 assert_param(IS_FMC_WAITE_SIGNAL(Init->WaitSignal));
191 assert_param(IS_FMC_EXTENDED_MODE(Init->ExtendedMode));
192 assert_param(IS_FMC_ASYNWAIT(Init->AsynchronousWait));
193 assert_param(IS_FMC_WRITE_BURST(Init->WriteBurst));
194 assert_param(IS_FMC_CONTINOUS_CLOCK(Init->ContinuousClock));
195 assert_param(IS_FMC_WRITE_FIFO(Init->WriteFifo));
196 assert_param(IS_FMC_PAGESIZE(Init->PageSize));
197 assert_param(IS_FMC_NBL_SETUPTIME(Init->NBLSetupTime));
198 assert_param(IS_FUNCTIONAL_STATE(Init->MaxChipSelectPulse));
200 /* Disable NORSRAM Device */
201 __FMC_NORSRAM_DISABLE(Device, Init->NSBank);
203 /* Set NORSRAM device control parameters */
204 if (Init->MemoryType == FMC_MEMORY_TYPE_NOR)
206 flashaccess = FMC_NORSRAM_FLASH_ACCESS_ENABLE;
208 else
210 flashaccess = FMC_NORSRAM_FLASH_ACCESS_DISABLE;
213 MODIFY_REG(Device->BTCR[Init->NSBank],
214 (FMC_BCRx_MBKEN |
215 FMC_BCRx_MUXEN |
216 FMC_BCRx_MTYP |
217 FMC_BCRx_MWID |
218 FMC_BCRx_FACCEN |
219 FMC_BCRx_BURSTEN |
220 FMC_BCRx_WAITPOL |
221 FMC_BCRx_WAITCFG |
222 FMC_BCRx_WREN |
223 FMC_BCRx_WAITEN |
224 FMC_BCRx_EXTMOD |
225 FMC_BCRx_ASYNCWAIT |
226 FMC_BCRx_CBURSTRW |
227 FMC_BCR1_CCLKEN |
228 FMC_BCR1_WFDIS |
229 FMC_BCRx_NBLSET |
230 FMC_BCRx_CPSIZE),
231 (flashaccess |
232 Init->DataAddressMux |
233 Init->MemoryType |
234 Init->MemoryDataWidth |
235 Init->BurstAccessMode |
236 Init->WaitSignalPolarity |
237 Init->WaitSignalActive |
238 Init->WriteOperation |
239 Init->WaitSignal |
240 Init->ExtendedMode |
241 Init->AsynchronousWait |
242 Init->WriteBurst |
243 Init->ContinuousClock |
244 Init->WriteFifo |
245 Init->NBLSetupTime |
246 Init->PageSize));
248 /* Configure synchronous mode when Continuous clock is enabled for bank2..4 */
249 if ((Init->ContinuousClock == FMC_CONTINUOUS_CLOCK_SYNC_ASYNC) && (Init->NSBank != FMC_NORSRAM_BANK1))
251 MODIFY_REG(Device->BTCR[FMC_NORSRAM_BANK1], FMC_BCR1_CCLKEN, Init->ContinuousClock);
254 if (Init->NSBank != FMC_NORSRAM_BANK1)
256 /* Configure Write FIFO mode when Write Fifo is enabled for bank2..4 */
257 SET_BIT(Device->BTCR[FMC_NORSRAM_BANK1], (uint32_t)(Init->WriteFifo));
260 /* Check PSRAM chip select counter state */
261 if(Init->MaxChipSelectPulse == ENABLE)
263 /* Check the parameters */
264 assert_param(IS_FMC_MAX_CHIP_SELECT_PULSE_TIME(Init->MaxChipSelectPulseTime));
266 /* Configure PSRAM chip select counter value */
267 MODIFY_REG(Device->PCSCNTR, FMC_PCSCNTR_CSCOUNT, (uint32_t)(Init->MaxChipSelectPulseTime));
269 /* Enable PSRAM chip select counter for the bank */
270 switch (Init->NSBank)
272 case FMC_NORSRAM_BANK1 :
273 SET_BIT(Device->PCSCNTR, FMC_PCSCNTR_CNTB1EN);
274 break;
276 case FMC_NORSRAM_BANK2 :
277 SET_BIT(Device->PCSCNTR, FMC_PCSCNTR_CNTB2EN);
278 break;
280 case FMC_NORSRAM_BANK3 :
281 SET_BIT(Device->PCSCNTR, FMC_PCSCNTR_CNTB3EN);
282 break;
284 case FMC_NORSRAM_BANK4 :
285 SET_BIT(Device->PCSCNTR, FMC_PCSCNTR_CNTB4EN);
286 break;
288 default :
289 break;
293 return HAL_OK;
298 * @brief DeInitialize the FMC_NORSRAM peripheral
299 * @param Device Pointer to NORSRAM device instance
300 * @param ExDevice Pointer to NORSRAM extended mode device instance
301 * @param Bank NORSRAM bank number
302 * @retval HAL status
304 HAL_StatusTypeDef FMC_NORSRAM_DeInit(FMC_NORSRAM_TypeDef *Device, FMC_NORSRAM_EXTENDED_TypeDef *ExDevice, uint32_t Bank)
306 /* Check the parameters */
307 assert_param(IS_FMC_NORSRAM_DEVICE(Device));
308 assert_param(IS_FMC_NORSRAM_EXTENDED_DEVICE(ExDevice));
309 assert_param(IS_FMC_NORSRAM_BANK(Bank));
311 /* Disable the FMC_NORSRAM device */
312 __FMC_NORSRAM_DISABLE(Device, Bank);
314 /* De-initialize the FMC_NORSRAM device */
315 /* FMC_NORSRAM_BANK1 */
316 if (Bank == FMC_NORSRAM_BANK1)
318 Device->BTCR[Bank] = 0x000030DBU;
320 /* FMC_NORSRAM_BANK2, FMC_NORSRAM_BANK3 or FMC_NORSRAM_BANK4 */
321 else
323 Device->BTCR[Bank] = 0x000030D2U;
326 Device->BTCR[Bank + 1U] = 0x0FFFFFFFU;
327 ExDevice->BWTR[Bank] = 0x0FFFFFFFU;
329 /* De-initialize PSRAM chip select counter */
330 switch (Bank)
332 case FMC_NORSRAM_BANK1 :
333 CLEAR_BIT(Device->PCSCNTR, FMC_PCSCNTR_CNTB1EN);
334 break;
336 case FMC_NORSRAM_BANK2 :
337 CLEAR_BIT(Device->PCSCNTR, FMC_PCSCNTR_CNTB2EN);
338 break;
340 case FMC_NORSRAM_BANK3 :
341 CLEAR_BIT(Device->PCSCNTR, FMC_PCSCNTR_CNTB3EN);
342 break;
344 case FMC_NORSRAM_BANK4 :
345 CLEAR_BIT(Device->PCSCNTR, FMC_PCSCNTR_CNTB4EN);
346 break;
348 default :
349 break;
352 return HAL_OK;
357 * @brief Initialize the FMC_NORSRAM Timing according to the specified
358 * parameters in the FMC_NORSRAM_TimingTypeDef
359 * @param Device Pointer to NORSRAM device instance
360 * @param Timing Pointer to NORSRAM Timing structure
361 * @param Bank NORSRAM bank number
362 * @retval HAL status
364 HAL_StatusTypeDef FMC_NORSRAM_Timing_Init(FMC_NORSRAM_TypeDef *Device, FMC_NORSRAM_TimingTypeDef *Timing, uint32_t Bank)
366 uint32_t tmpr;
368 /* Check the parameters */
369 assert_param(IS_FMC_NORSRAM_DEVICE(Device));
370 assert_param(IS_FMC_ADDRESS_SETUP_TIME(Timing->AddressSetupTime));
371 assert_param(IS_FMC_ADDRESS_HOLD_TIME(Timing->AddressHoldTime));
372 assert_param(IS_FMC_DATAHOLD_DURATION(Timing->DataHoldTime));
373 assert_param(IS_FMC_DATASETUP_TIME(Timing->DataSetupTime));
374 assert_param(IS_FMC_TURNAROUND_TIME(Timing->BusTurnAroundDuration));
375 assert_param(IS_FMC_CLK_DIV(Timing->CLKDivision));
376 assert_param(IS_FMC_DATA_LATENCY(Timing->DataLatency));
377 assert_param(IS_FMC_ACCESS_MODE(Timing->AccessMode));
378 assert_param(IS_FMC_NORSRAM_BANK(Bank));
380 /* Set FMC_NORSRAM device timing parameters */
381 MODIFY_REG(Device->BTCR[Bank + 1U], BTR_CLEAR_MASK, (Timing->AddressSetupTime |
382 ((Timing->AddressHoldTime) << FMC_BTRx_ADDHLD_Pos) |
383 ((Timing->DataSetupTime) << FMC_BTRx_DATAST_Pos) |
384 ((Timing->DataHoldTime) << FMC_BTRx_DATAHLD_Pos) |
385 ((Timing->BusTurnAroundDuration) << FMC_BTRx_BUSTURN_Pos) |
386 (((Timing->CLKDivision) - 1U) << FMC_BTRx_CLKDIV_Pos) |
387 (((Timing->DataLatency) - 2U) << FMC_BTRx_DATLAT_Pos) |
388 (Timing->AccessMode)));
390 /* Configure Clock division value (in NORSRAM bank 1) when continuous clock is enabled */
391 if (HAL_IS_BIT_SET(Device->BTCR[FMC_NORSRAM_BANK1], FMC_BCR1_CCLKEN))
393 tmpr = (uint32_t)(Device->BTCR[FMC_NORSRAM_BANK1 + 1U] & ~(((uint32_t)0x0F) << FMC_BTRx_CLKDIV_Pos));
394 tmpr |= (uint32_t)(((Timing->CLKDivision) - 1U) << FMC_BTRx_CLKDIV_Pos);
395 MODIFY_REG(Device->BTCR[FMC_NORSRAM_BANK1 + 1U], FMC_BTRx_CLKDIV, tmpr);
398 return HAL_OK;
402 * @brief Initialize the FMC_NORSRAM Extended mode Timing according to the specified
403 * parameters in the FMC_NORSRAM_TimingTypeDef
404 * @param Device Pointer to NORSRAM device instance
405 * @param Timing Pointer to NORSRAM Timing structure
406 * @param Bank NORSRAM bank number
407 * @param ExtendedMode FMC Extended Mode
408 * This parameter can be one of the following values:
409 * @arg FMC_EXTENDED_MODE_DISABLE
410 * @arg FMC_EXTENDED_MODE_ENABLE
411 * @retval HAL status
413 HAL_StatusTypeDef FMC_NORSRAM_Extended_Timing_Init(FMC_NORSRAM_EXTENDED_TypeDef *Device, FMC_NORSRAM_TimingTypeDef *Timing, uint32_t Bank, uint32_t ExtendedMode)
415 /* Check the parameters */
416 assert_param(IS_FMC_EXTENDED_MODE(ExtendedMode));
418 /* Set NORSRAM device timing register for write configuration, if extended mode is used */
419 if (ExtendedMode == FMC_EXTENDED_MODE_ENABLE)
421 /* Check the parameters */
422 assert_param(IS_FMC_NORSRAM_EXTENDED_DEVICE(Device));
423 assert_param(IS_FMC_ADDRESS_SETUP_TIME(Timing->AddressSetupTime));
424 assert_param(IS_FMC_ADDRESS_HOLD_TIME(Timing->AddressHoldTime));
425 assert_param(IS_FMC_DATASETUP_TIME(Timing->DataSetupTime));
426 assert_param(IS_FMC_DATAHOLD_DURATION(Timing->DataHoldTime));
427 assert_param(IS_FMC_TURNAROUND_TIME(Timing->BusTurnAroundDuration));
428 assert_param(IS_FMC_ACCESS_MODE(Timing->AccessMode));
429 assert_param(IS_FMC_NORSRAM_BANK(Bank));
431 /* Set NORSRAM device timing register for write configuration, if extended mode is used */
432 MODIFY_REG(Device->BWTR[Bank], BWTR_CLEAR_MASK, (Timing->AddressSetupTime |
433 ((Timing->AddressHoldTime) << FMC_BWTRx_ADDHLD_Pos) |
434 ((Timing->DataSetupTime) << FMC_BWTRx_DATAST_Pos) |
435 ((Timing->DataHoldTime) << FMC_BWTRx_DATAHLD_Pos) |
436 Timing->AccessMode |
437 ((Timing->BusTurnAroundDuration) << FMC_BWTRx_BUSTURN_Pos)));
439 else
441 Device->BWTR[Bank] = 0x0FFFFFFFU;
444 return HAL_OK;
447 * @}
450 /** @addtogroup FMC_LL_NORSRAM_Private_Functions_Group2
451 * @brief management functions
453 @verbatim
454 ==============================================================================
455 ##### FMC_NORSRAM Control functions #####
456 ==============================================================================
457 [..]
458 This subsection provides a set of functions allowing to control dynamically
459 the FMC NORSRAM interface.
461 @endverbatim
462 * @{
466 * @brief Enables dynamically FMC_NORSRAM write operation.
467 * @param Device Pointer to NORSRAM device instance
468 * @param Bank NORSRAM bank number
469 * @retval HAL status
471 HAL_StatusTypeDef FMC_NORSRAM_WriteOperation_Enable(FMC_NORSRAM_TypeDef *Device, uint32_t Bank)
473 /* Check the parameters */
474 assert_param(IS_FMC_NORSRAM_DEVICE(Device));
475 assert_param(IS_FMC_NORSRAM_BANK(Bank));
477 /* Enable write operation */
478 SET_BIT(Device->BTCR[Bank], FMC_WRITE_OPERATION_ENABLE);
480 return HAL_OK;
484 * @brief Disables dynamically FMC_NORSRAM write operation.
485 * @param Device Pointer to NORSRAM device instance
486 * @param Bank NORSRAM bank number
487 * @retval HAL status
489 HAL_StatusTypeDef FMC_NORSRAM_WriteOperation_Disable(FMC_NORSRAM_TypeDef *Device, uint32_t Bank)
491 /* Check the parameters */
492 assert_param(IS_FMC_NORSRAM_DEVICE(Device));
493 assert_param(IS_FMC_NORSRAM_BANK(Bank));
495 /* Disable write operation */
496 CLEAR_BIT(Device->BTCR[Bank], FMC_WRITE_OPERATION_ENABLE);
498 return HAL_OK;
502 * @}
506 * @}
508 #endif /* FMC_BANK1 */
510 #if defined(FMC_BANK3)
512 /** @defgroup FMC_LL_Exported_Functions_NAND FMC Low Layer NAND Exported Functions
513 * @brief NAND Controller functions
515 @verbatim
516 ==============================================================================
517 ##### How to use NAND device driver #####
518 ==============================================================================
519 [..]
520 This driver contains a set of APIs to interface with the FMC NAND banks in order
521 to run the NAND external devices.
523 (+) FMC NAND bank reset using the function FMC_NAND_DeInit()
524 (+) FMC NAND bank control configuration using the function FMC_NAND_Init()
525 (+) FMC NAND bank common space timing configuration using the function
526 FMC_NAND_CommonSpace_Timing_Init()
527 (+) FMC NAND bank attribute space timing configuration using the function
528 FMC_NAND_AttributeSpace_Timing_Init()
529 (+) FMC NAND bank enable/disable ECC correction feature using the functions
530 FMC_NAND_ECC_Enable()/FMC_NAND_ECC_Disable()
531 (+) FMC NAND bank get ECC correction code using the function FMC_NAND_GetECC()
533 @endverbatim
534 * @{
537 /** @defgroup FMC_LL_NAND_Exported_Functions_Group1 Initialization and de-initialization functions
538 * @brief Initialization and Configuration functions
540 @verbatim
541 ==============================================================================
542 ##### Initialization and de_initialization functions #####
543 ==============================================================================
544 [..]
545 This section provides functions allowing to:
546 (+) Initialize and configure the FMC NAND interface
547 (+) De-initialize the FMC NAND interface
548 (+) Configure the FMC clock and associated GPIOs
550 @endverbatim
551 * @{
555 * @brief Initializes the FMC_NAND device according to the specified
556 * control parameters in the FMC_NAND_HandleTypeDef
557 * @param Device Pointer to NAND device instance
558 * @param Init Pointer to NAND Initialization structure
559 * @retval HAL status
561 HAL_StatusTypeDef FMC_NAND_Init(FMC_NAND_TypeDef *Device, FMC_NAND_InitTypeDef *Init)
563 /* Check the parameters */
564 assert_param(IS_FMC_NAND_DEVICE(Device));
565 assert_param(IS_FMC_NAND_BANK(Init->NandBank));
566 assert_param(IS_FMC_WAIT_FEATURE(Init->Waitfeature));
567 assert_param(IS_FMC_NAND_MEMORY_WIDTH(Init->MemoryDataWidth));
568 assert_param(IS_FMC_ECC_STATE(Init->EccComputation));
569 assert_param(IS_FMC_ECCPAGE_SIZE(Init->ECCPageSize));
570 assert_param(IS_FMC_TCLR_TIME(Init->TCLRSetupTime));
571 assert_param(IS_FMC_TAR_TIME(Init->TARSetupTime));
573 /* NAND bank 3 registers configuration */
574 MODIFY_REG(Device->PCR, PCR_CLEAR_MASK, (Init->Waitfeature |
575 FMC_PCR_MEMORY_TYPE_NAND |
576 Init->MemoryDataWidth |
577 Init->EccComputation |
578 Init->ECCPageSize |
579 ((Init->TCLRSetupTime) << FMC_PCR_TCLR_Pos) |
580 ((Init->TARSetupTime) << FMC_PCR_TAR_Pos)));
582 return HAL_OK;
586 * @brief Initializes the FMC_NAND Common space Timing according to the specified
587 * parameters in the FMC_NAND_PCC_TimingTypeDef
588 * @param Device Pointer to NAND device instance
589 * @param Timing Pointer to NAND timing structure
590 * @param Bank NAND bank number
591 * @retval HAL status
593 HAL_StatusTypeDef FMC_NAND_CommonSpace_Timing_Init(FMC_NAND_TypeDef *Device, FMC_NAND_PCC_TimingTypeDef *Timing, uint32_t Bank)
595 /* Check the parameters */
596 assert_param(IS_FMC_NAND_DEVICE(Device));
597 assert_param(IS_FMC_SETUP_TIME(Timing->SetupTime));
598 assert_param(IS_FMC_WAIT_TIME(Timing->WaitSetupTime));
599 assert_param(IS_FMC_HOLD_TIME(Timing->HoldSetupTime));
600 assert_param(IS_FMC_HIZ_TIME(Timing->HiZSetupTime));
601 assert_param(IS_FMC_NAND_BANK(Bank));
603 /* NAND bank 3 registers configuration */
604 MODIFY_REG(Device->PMEM, PMEM_CLEAR_MASK, (Timing->SetupTime |
605 ((Timing->WaitSetupTime) << FMC_PMEM_MEMWAIT_Pos) |
606 ((Timing->HoldSetupTime) << FMC_PMEM_MEMHOLD_Pos) |
607 ((Timing->HiZSetupTime) << FMC_PMEM_MEMHIZ_Pos)));
609 return HAL_OK;
613 * @brief Initializes the FMC_NAND Attribute space Timing according to the specified
614 * parameters in the FMC_NAND_PCC_TimingTypeDef
615 * @param Device Pointer to NAND device instance
616 * @param Timing Pointer to NAND timing structure
617 * @param Bank NAND bank number
618 * @retval HAL status
620 HAL_StatusTypeDef FMC_NAND_AttributeSpace_Timing_Init(FMC_NAND_TypeDef *Device, FMC_NAND_PCC_TimingTypeDef *Timing, uint32_t Bank)
622 /* Check the parameters */
623 assert_param(IS_FMC_NAND_DEVICE(Device));
624 assert_param(IS_FMC_SETUP_TIME(Timing->SetupTime));
625 assert_param(IS_FMC_WAIT_TIME(Timing->WaitSetupTime));
626 assert_param(IS_FMC_HOLD_TIME(Timing->HoldSetupTime));
627 assert_param(IS_FMC_HIZ_TIME(Timing->HiZSetupTime));
628 assert_param(IS_FMC_NAND_BANK(Bank));
630 /* NAND bank 3 registers configuration */
631 MODIFY_REG(Device->PATT, PATT_CLEAR_MASK, (Timing->SetupTime |
632 ((Timing->WaitSetupTime) << FMC_PATT_ATTWAIT_Pos) |
633 ((Timing->HoldSetupTime) << FMC_PATT_ATTHOLD_Pos) |
634 ((Timing->HiZSetupTime) << FMC_PATT_ATTHIZ_Pos)));
636 return HAL_OK;
640 * @brief DeInitializes the FMC_NAND device
641 * @param Device Pointer to NAND device instance
642 * @param Bank NAND bank number
643 * @retval HAL status
645 HAL_StatusTypeDef FMC_NAND_DeInit(FMC_NAND_TypeDef *Device, uint32_t Bank)
647 /* Check the parameters */
648 assert_param(IS_FMC_NAND_DEVICE(Device));
649 assert_param(IS_FMC_NAND_BANK(Bank));
651 /* Disable the NAND Bank */
652 __FMC_NAND_DISABLE(Device, Bank);
654 /* De-initialize the NAND Bank */
655 /* Set the FMC_NAND_BANK3 registers to their reset values */
656 WRITE_REG(Device->PCR, 0x00000018U);
657 WRITE_REG(Device->SR, 0x00000040U);
658 WRITE_REG(Device->PMEM, 0xFCFCFCFCU);
659 WRITE_REG(Device->PATT, 0xFCFCFCFCU);
661 return HAL_OK;
665 * @}
668 /** @defgroup HAL_FMC_NAND_Group2 Peripheral Control functions
669 * @brief management functions
671 @verbatim
672 ==============================================================================
673 ##### FMC_NAND Control functions #####
674 ==============================================================================
675 [..]
676 This subsection provides a set of functions allowing to control dynamically
677 the FMC NAND interface.
679 @endverbatim
680 * @{
685 * @brief Enables dynamically FMC_NAND ECC feature.
686 * @param Device Pointer to NAND device instance
687 * @param Bank NAND bank number
688 * @retval HAL status
690 HAL_StatusTypeDef FMC_NAND_ECC_Enable(FMC_NAND_TypeDef *Device, uint32_t Bank)
692 /* Check the parameters */
693 assert_param(IS_FMC_NAND_DEVICE(Device));
694 assert_param(IS_FMC_NAND_BANK(Bank));
696 /* Enable ECC feature */
697 SET_BIT(Device->PCR, FMC_PCR_ECCEN);
699 return HAL_OK;
704 * @brief Disables dynamically FMC_NAND ECC feature.
705 * @param Device Pointer to NAND device instance
706 * @param Bank NAND bank number
707 * @retval HAL status
709 HAL_StatusTypeDef FMC_NAND_ECC_Disable(FMC_NAND_TypeDef *Device, uint32_t Bank)
711 /* Check the parameters */
712 assert_param(IS_FMC_NAND_DEVICE(Device));
713 assert_param(IS_FMC_NAND_BANK(Bank));
715 /* Disable ECC feature */
716 CLEAR_BIT(Device->PCR, FMC_PCR_ECCEN);
718 return HAL_OK;
722 * @brief Disables dynamically FMC_NAND ECC feature.
723 * @param Device Pointer to NAND device instance
724 * @param ECCval Pointer to ECC value
725 * @param Bank NAND bank number
726 * @param Timeout Timeout wait value
727 * @retval HAL status
729 HAL_StatusTypeDef FMC_NAND_GetECC(FMC_NAND_TypeDef *Device, uint32_t *ECCval, uint32_t Bank, uint32_t Timeout)
731 uint32_t tickstart;
733 /* Check the parameters */
734 assert_param(IS_FMC_NAND_DEVICE(Device));
735 assert_param(IS_FMC_NAND_BANK(Bank));
737 /* Get tick */
738 tickstart = HAL_GetTick();
740 /* Wait until FIFO is empty */
741 while (__FMC_NAND_GET_FLAG(Device, Bank, FMC_FLAG_FEMPT) == RESET)
743 /* Check for the Timeout */
744 if (Timeout != HAL_MAX_DELAY)
746 if (((HAL_GetTick() - tickstart) > Timeout) || (Timeout == 0U))
748 return HAL_TIMEOUT;
753 /* Get the ECCR register value */
754 *ECCval = (uint32_t)Device->ECCR;
756 return HAL_OK;
760 * @}
762 #endif /* FMC_BANK3 */
767 * @}
771 * @}
775 * @}
778 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/