2 ******************************************************************************
3 * @file stm32f4xx_ll_fmc.c
4 * @author MCD Application Team
7 * @brief FMC Low Layer HAL module driver.
9 * This file provides firmware functions to manage the following
10 * functionalities of the Flexible Memory Controller (FMC) peripheral memories:
11 * + Initialization/de-initialization functions
12 * + Peripheral Control functions
13 * + Peripheral State functions
16 ==============================================================================
17 ##### FMC peripheral features #####
18 ==============================================================================
19 [..] The Flexible memory controller (FMC) includes three memory controllers:
20 (+) The NOR/PSRAM memory controller
21 (+) The NAND/PC Card memory controller
22 (+) The Synchronous DRAM (SDRAM) controller
24 [..] The FMC functional block makes the interface with synchronous and asynchronous static
25 memories, SDRAM memories, and 16-bit PC memory cards. Its main purposes are:
26 (+) to translate AHB transactions into the appropriate external device protocol
27 (+) to meet the access time requirements of the external memory devices
29 [..] All external memories share the addresses, data and control signals with the controller.
30 Each external device is accessed by means of a unique Chip Select. The FMC performs
31 only one access at a time to an external device.
32 The main features of the FMC controller are the following:
33 (+) Interface with static-memory mapped devices including:
34 (++) Static random access memory (SRAM)
35 (++) Read-only memory (ROM)
36 (++) NOR Flash memory/OneNAND Flash memory
37 (++) PSRAM (4 memory banks)
38 (++) 16-bit PC Card compatible devices
39 (++) Two banks of NAND Flash memory with ECC hardware to check up to 8 Kbytes of
41 (+) Interface with synchronous DRAM (SDRAM) memories
42 (+) Independent Chip Select control for each memory bank
43 (+) Independent configuration for each memory bank
46 ******************************************************************************
49 * <h2><center>© COPYRIGHT(c) 2017 STMicroelectronics</center></h2>
51 * Redistribution and use in source and binary forms, with or without modification,
52 * are permitted provided that the following conditions are met:
53 * 1. Redistributions of source code must retain the above copyright notice,
54 * this list of conditions and the following disclaimer.
55 * 2. Redistributions in binary form must reproduce the above copyright notice,
56 * this list of conditions and the following disclaimer in the documentation
57 * and/or other materials provided with the distribution.
58 * 3. Neither the name of STMicroelectronics nor the names of its contributors
59 * may be used to endorse or promote products derived from this software
60 * without specific prior written permission.
62 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
63 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
64 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
65 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
66 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
67 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
68 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
69 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
70 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
71 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
73 ******************************************************************************
76 /* Includes ------------------------------------------------------------------*/
77 #include "stm32f4xx_hal.h"
79 /** @addtogroup STM32F4xx_HAL_Driver
83 /** @defgroup FMC_LL FMC Low Layer
84 * @brief FMC driver modules
88 #if defined (HAL_SRAM_MODULE_ENABLED) || defined(HAL_NOR_MODULE_ENABLED) || defined(HAL_NAND_MODULE_ENABLED) || defined(HAL_PCCARD_MODULE_ENABLED) || defined(HAL_SDRAM_MODULE_ENABLED)
90 #if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx)
92 /* Private typedef -----------------------------------------------------------*/
93 /* Private define ------------------------------------------------------------*/
94 /* Private macro -------------------------------------------------------------*/
95 /* Private variables ---------------------------------------------------------*/
96 /* Private function prototypes -----------------------------------------------*/
97 /* Private functions ---------------------------------------------------------*/
98 /** @addtogroup FMC_LL_Private_Functions
102 /** @addtogroup FMC_LL_NORSRAM
103 * @brief NORSRAM Controller functions
106 ==============================================================================
107 ##### How to use NORSRAM device driver #####
108 ==============================================================================
111 This driver contains a set of APIs to interface with the FMC NORSRAM banks in order
112 to run the NORSRAM external devices.
114 (+) FMC NORSRAM bank reset using the function FMC_NORSRAM_DeInit()
115 (+) FMC NORSRAM bank control configuration using the function FMC_NORSRAM_Init()
116 (+) FMC NORSRAM bank timing configuration using the function FMC_NORSRAM_Timing_Init()
117 (+) FMC NORSRAM bank extended timing configuration using the function
118 FMC_NORSRAM_Extended_Timing_Init()
119 (+) FMC NORSRAM bank enable/disable write operation using the functions
120 FMC_NORSRAM_WriteOperation_Enable()/FMC_NORSRAM_WriteOperation_Disable()
127 /** @addtogroup FMC_LL_NORSRAM_Private_Functions_Group1
128 * @brief Initialization and Configuration functions
131 ==============================================================================
132 ##### Initialization and de_initialization functions #####
133 ==============================================================================
135 This section provides functions allowing to:
136 (+) Initialize and configure the FMC NORSRAM interface
137 (+) De-initialize the FMC NORSRAM interface
138 (+) Configure the FMC clock and associated GPIOs
145 * @brief Initialize the FMC_NORSRAM device according to the specified
146 * control parameters in the FMC_NORSRAM_InitTypeDef
147 * @param Device: Pointer to NORSRAM device instance
148 * @param Init: Pointer to NORSRAM Initialization structure
151 HAL_StatusTypeDef
FMC_NORSRAM_Init(FMC_NORSRAM_TypeDef
*Device
, FMC_NORSRAM_InitTypeDef
* Init
)
155 /* Check the parameters */
156 assert_param(IS_FMC_NORSRAM_DEVICE(Device
));
157 assert_param(IS_FMC_NORSRAM_BANK(Init
->NSBank
));
158 assert_param(IS_FMC_MUX(Init
->DataAddressMux
));
159 assert_param(IS_FMC_MEMORY(Init
->MemoryType
));
160 assert_param(IS_FMC_NORSRAM_MEMORY_WIDTH(Init
->MemoryDataWidth
));
161 assert_param(IS_FMC_BURSTMODE(Init
->BurstAccessMode
));
162 assert_param(IS_FMC_WAIT_POLARITY(Init
->WaitSignalPolarity
));
163 #if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx)
164 assert_param(IS_FMC_WRAP_MODE(Init
->WrapMode
));
165 #endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx */
166 assert_param(IS_FMC_WAIT_SIGNAL_ACTIVE(Init
->WaitSignalActive
));
167 assert_param(IS_FMC_WRITE_OPERATION(Init
->WriteOperation
));
168 assert_param(IS_FMC_WAITE_SIGNAL(Init
->WaitSignal
));
169 assert_param(IS_FMC_EXTENDED_MODE(Init
->ExtendedMode
));
170 assert_param(IS_FMC_ASYNWAIT(Init
->AsynchronousWait
));
171 assert_param(IS_FMC_WRITE_BURST(Init
->WriteBurst
));
172 assert_param(IS_FMC_CONTINOUS_CLOCK(Init
->ContinuousClock
));
173 assert_param(IS_FMC_PAGESIZE(Init
->PageSize
));
174 #if defined (STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx)
175 assert_param(IS_FMC_WRITE_FIFO(Init
->WriteFifo
));
176 #endif /* STM32F446xx || STM32F469xx || STM32F479xx */
178 /* Get the BTCR register value */
179 tmpr
= Device
->BTCR
[Init
->NSBank
];
181 #if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx)
182 /* Clear MBKEN, MUXEN, MTYP, MWID, FACCEN, BURSTEN, WAITPOL, WRAPMOD, WAITCFG, WREN,
183 WAITEN, EXTMOD, ASYNCWAIT, CPSIZE, CBURSTRW and CCLKEN bits */
184 tmpr
&= ((uint32_t)~(FMC_BCR1_MBKEN
| FMC_BCR1_MUXEN
| FMC_BCR1_MTYP
| \
185 FMC_BCR1_MWID
| FMC_BCR1_FACCEN
| FMC_BCR1_BURSTEN
| \
186 FMC_BCR1_WAITPOL
| FMC_BCR1_WRAPMOD
| FMC_BCR1_WAITCFG
| \
187 FMC_BCR1_WREN
| FMC_BCR1_WAITEN
| FMC_BCR1_EXTMOD
| \
188 FMC_BCR1_ASYNCWAIT
| FMC_BCR1_CPSIZE
| FMC_BCR1_CBURSTRW
| \
191 /* Set NORSRAM device control parameters */
192 tmpr
|= (uint32_t)(Init
->DataAddressMux
|\
194 Init
->MemoryDataWidth
|\
195 Init
->BurstAccessMode
|\
196 Init
->WaitSignalPolarity
|\
198 Init
->WaitSignalActive
|\
199 Init
->WriteOperation
|\
201 Init
->ExtendedMode
|\
202 Init
->AsynchronousWait
|\
205 Init
->ContinuousClock
);
206 #else /* defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) */
207 /* Clear MBKEN, MUXEN, MTYP, MWID, FACCEN, BURSTEN, WAITPOL, CPSIZE, WAITCFG, WREN,
208 WAITEN, EXTMOD, ASYNCWAIT, CBURSTRW, CCLKEN and WFDIS bits */
209 tmpr
&= ((uint32_t)~(FMC_BCR1_MBKEN
| FMC_BCR1_MUXEN
| FMC_BCR1_MTYP
| \
210 FMC_BCR1_MWID
| FMC_BCR1_FACCEN
| FMC_BCR1_BURSTEN
| \
211 FMC_BCR1_WAITPOL
| FMC_BCR1_WAITCFG
| FMC_BCR1_CPSIZE
| \
212 FMC_BCR1_WREN
| FMC_BCR1_WAITEN
| FMC_BCR1_EXTMOD
| \
213 FMC_BCR1_ASYNCWAIT
| FMC_BCR1_CBURSTRW
| FMC_BCR1_CCLKEN
| \
216 /* Set NORSRAM device control parameters */
217 tmpr
|= (uint32_t)(Init
->DataAddressMux
|\
219 Init
->MemoryDataWidth
|\
220 Init
->BurstAccessMode
|\
221 Init
->WaitSignalPolarity
|\
222 Init
->WaitSignalActive
|\
223 Init
->WriteOperation
|\
225 Init
->ExtendedMode
|\
226 Init
->AsynchronousWait
|\
228 Init
->ContinuousClock
|\
231 #endif /* defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) */
233 if(Init
->MemoryType
== FMC_MEMORY_TYPE_NOR
)
235 tmpr
|= (uint32_t)FMC_NORSRAM_FLASH_ACCESS_ENABLE
;
238 Device
->BTCR
[Init
->NSBank
] = tmpr
;
240 /* Configure synchronous mode when Continuous clock is enabled for bank2..4 */
241 if((Init
->ContinuousClock
== FMC_CONTINUOUS_CLOCK_SYNC_ASYNC
) && (Init
->NSBank
!= FMC_NORSRAM_BANK1
))
243 Device
->BTCR
[FMC_NORSRAM_BANK1
] |= (uint32_t)(Init
->ContinuousClock
);
246 #if defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx)
247 if(Init
->NSBank
!= FMC_NORSRAM_BANK1
)
249 Device
->BTCR
[FMC_NORSRAM_BANK1
] |= (uint32_t)(Init
->WriteFifo
);
251 #endif /* STM32F446xx || STM32F469xx || STM32F479xx */
257 * @brief DeInitialize the FMC_NORSRAM peripheral
258 * @param Device: Pointer to NORSRAM device instance
259 * @param ExDevice: Pointer to NORSRAM extended mode device instance
260 * @param Bank: NORSRAM bank number
263 HAL_StatusTypeDef
FMC_NORSRAM_DeInit(FMC_NORSRAM_TypeDef
*Device
, FMC_NORSRAM_EXTENDED_TypeDef
*ExDevice
, uint32_t Bank
)
265 /* Check the parameters */
266 assert_param(IS_FMC_NORSRAM_DEVICE(Device
));
267 assert_param(IS_FMC_NORSRAM_EXTENDED_DEVICE(ExDevice
));
268 assert_param(IS_FMC_NORSRAM_BANK(Bank
));
270 /* Disable the FMC_NORSRAM device */
271 __FMC_NORSRAM_DISABLE(Device
, Bank
);
273 /* De-initialize the FMC_NORSRAM device */
274 /* FMC_NORSRAM_BANK1 */
275 if(Bank
== FMC_NORSRAM_BANK1
)
277 Device
->BTCR
[Bank
] = 0x000030DBU
;
279 /* FMC_NORSRAM_BANK2, FMC_NORSRAM_BANK3 or FMC_NORSRAM_BANK4 */
282 Device
->BTCR
[Bank
] = 0x000030D2U
;
285 Device
->BTCR
[Bank
+ 1U] = 0x0FFFFFFFU
;
286 ExDevice
->BWTR
[Bank
] = 0x0FFFFFFFU
;
292 * @brief Initialize the FMC_NORSRAM Timing according to the specified
293 * parameters in the FMC_NORSRAM_TimingTypeDef
294 * @param Device: Pointer to NORSRAM device instance
295 * @param Timing: Pointer to NORSRAM Timing structure
296 * @param Bank: NORSRAM bank number
299 HAL_StatusTypeDef
FMC_NORSRAM_Timing_Init(FMC_NORSRAM_TypeDef
*Device
, FMC_NORSRAM_TimingTypeDef
*Timing
, uint32_t Bank
)
303 /* Check the parameters */
304 assert_param(IS_FMC_NORSRAM_DEVICE(Device
));
305 assert_param(IS_FMC_ADDRESS_SETUP_TIME(Timing
->AddressSetupTime
));
306 assert_param(IS_FMC_ADDRESS_HOLD_TIME(Timing
->AddressHoldTime
));
307 assert_param(IS_FMC_DATASETUP_TIME(Timing
->DataSetupTime
));
308 assert_param(IS_FMC_TURNAROUND_TIME(Timing
->BusTurnAroundDuration
));
309 assert_param(IS_FMC_CLK_DIV(Timing
->CLKDivision
));
310 assert_param(IS_FMC_DATA_LATENCY(Timing
->DataLatency
));
311 assert_param(IS_FMC_ACCESS_MODE(Timing
->AccessMode
));
312 assert_param(IS_FMC_NORSRAM_BANK(Bank
));
314 /* Get the BTCR register value */
315 tmpr
= Device
->BTCR
[Bank
+ 1U];
317 /* Clear ADDSET, ADDHLD, DATAST, BUSTURN, CLKDIV, DATLAT and ACCMOD bits */
318 tmpr
&= ((uint32_t)~(FMC_BTR1_ADDSET
| FMC_BTR1_ADDHLD
| FMC_BTR1_DATAST
| \
319 FMC_BTR1_BUSTURN
| FMC_BTR1_CLKDIV
| FMC_BTR1_DATLAT
| \
322 /* Set FMC_NORSRAM device timing parameters */
323 tmpr
|= (uint32_t)(Timing
->AddressSetupTime
|\
324 ((Timing
->AddressHoldTime
) << 4U) |\
325 ((Timing
->DataSetupTime
) << 8U) |\
326 ((Timing
->BusTurnAroundDuration
) << 16U) |\
327 (((Timing
->CLKDivision
) - 1U) << 20U) |\
328 (((Timing
->DataLatency
) - 2U) << 24U) |\
329 (Timing
->AccessMode
));
331 Device
->BTCR
[Bank
+ 1U] = tmpr
;
333 /* Configure Clock division value (in NORSRAM bank 1) when continuous clock is enabled */
334 if(HAL_IS_BIT_SET(Device
->BTCR
[FMC_NORSRAM_BANK1
], FMC_BCR1_CCLKEN
))
336 tmpr
= (uint32_t)(Device
->BTCR
[FMC_NORSRAM_BANK1
+ 1U] & ~(0x0FU
<< 20U));
337 tmpr
|= (uint32_t)(((Timing
->CLKDivision
) - 1U) << 20U);
338 Device
->BTCR
[FMC_NORSRAM_BANK1
+ 1U] = tmpr
;
345 * @brief Initialize the FMC_NORSRAM Extended mode Timing according to the specified
346 * parameters in the FMC_NORSRAM_TimingTypeDef
347 * @param Device: Pointer to NORSRAM device instance
348 * @param Timing: Pointer to NORSRAM Timing structure
349 * @param Bank: NORSRAM bank number
352 HAL_StatusTypeDef
FMC_NORSRAM_Extended_Timing_Init(FMC_NORSRAM_EXTENDED_TypeDef
*Device
, FMC_NORSRAM_TimingTypeDef
*Timing
, uint32_t Bank
, uint32_t ExtendedMode
)
356 /* Check the parameters */
357 assert_param(IS_FMC_EXTENDED_MODE(ExtendedMode
));
359 /* Set NORSRAM device timing register for write configuration, if extended mode is used */
360 if(ExtendedMode
== FMC_EXTENDED_MODE_ENABLE
)
362 /* Check the parameters */
363 assert_param(IS_FMC_NORSRAM_EXTENDED_DEVICE(Device
));
364 assert_param(IS_FMC_ADDRESS_SETUP_TIME(Timing
->AddressSetupTime
));
365 assert_param(IS_FMC_ADDRESS_HOLD_TIME(Timing
->AddressHoldTime
));
366 assert_param(IS_FMC_DATASETUP_TIME(Timing
->DataSetupTime
));
367 assert_param(IS_FMC_TURNAROUND_TIME(Timing
->BusTurnAroundDuration
));
368 assert_param(IS_FMC_ACCESS_MODE(Timing
->AccessMode
));
369 assert_param(IS_FMC_NORSRAM_BANK(Bank
));
371 /* Get the BWTR register value */
372 tmpr
= Device
->BWTR
[Bank
];
374 /* Clear ADDSET, ADDHLD, DATAST, BUSTURN and ACCMOD bits */
375 tmpr
&= ((uint32_t)~(FMC_BWTR1_ADDSET
| FMC_BWTR1_ADDHLD
| FMC_BWTR1_DATAST
| \
376 FMC_BWTR1_BUSTURN
| FMC_BWTR1_ACCMOD
));
378 tmpr
|= (uint32_t)(Timing
->AddressSetupTime
|\
379 ((Timing
->AddressHoldTime
) << 4U) |\
380 ((Timing
->DataSetupTime
) << 8U) |\
381 ((Timing
->BusTurnAroundDuration
) << 16U) |\
382 (Timing
->AccessMode
));
384 Device
->BWTR
[Bank
] = tmpr
;
388 Device
->BWTR
[Bank
] = 0x0FFFFFFFU
;
397 /** @addtogroup FMC_LL_NORSRAM_Private_Functions_Group2
398 * @brief management functions
401 ==============================================================================
402 ##### FMC_NORSRAM Control functions #####
403 ==============================================================================
405 This subsection provides a set of functions allowing to control dynamically
406 the FMC NORSRAM interface.
412 * @brief Enables dynamically FMC_NORSRAM write operation.
413 * @param Device: Pointer to NORSRAM device instance
414 * @param Bank: NORSRAM bank number
417 HAL_StatusTypeDef
FMC_NORSRAM_WriteOperation_Enable(FMC_NORSRAM_TypeDef
*Device
, uint32_t Bank
)
419 /* Check the parameters */
420 assert_param(IS_FMC_NORSRAM_DEVICE(Device
));
421 assert_param(IS_FMC_NORSRAM_BANK(Bank
));
423 /* Enable write operation */
424 Device
->BTCR
[Bank
] |= FMC_WRITE_OPERATION_ENABLE
;
430 * @brief Disables dynamically FMC_NORSRAM write operation.
431 * @param Device: Pointer to NORSRAM device instance
432 * @param Bank: NORSRAM bank number
435 HAL_StatusTypeDef
FMC_NORSRAM_WriteOperation_Disable(FMC_NORSRAM_TypeDef
*Device
, uint32_t Bank
)
437 /* Check the parameters */
438 assert_param(IS_FMC_NORSRAM_DEVICE(Device
));
439 assert_param(IS_FMC_NORSRAM_BANK(Bank
));
441 /* Disable write operation */
442 Device
->BTCR
[Bank
] &= ~FMC_WRITE_OPERATION_ENABLE
;
455 /** @addtogroup FMC_LL_NAND
456 * @brief NAND Controller functions
459 ==============================================================================
460 ##### How to use NAND device driver #####
461 ==============================================================================
463 This driver contains a set of APIs to interface with the FMC NAND banks in order
464 to run the NAND external devices.
466 (+) FMC NAND bank reset using the function FMC_NAND_DeInit()
467 (+) FMC NAND bank control configuration using the function FMC_NAND_Init()
468 (+) FMC NAND bank common space timing configuration using the function
469 FMC_NAND_CommonSpace_Timing_Init()
470 (+) FMC NAND bank attribute space timing configuration using the function
471 FMC_NAND_AttributeSpace_Timing_Init()
472 (+) FMC NAND bank enable/disable ECC correction feature using the functions
473 FMC_NAND_ECC_Enable()/FMC_NAND_ECC_Disable()
474 (+) FMC NAND bank get ECC correction code using the function FMC_NAND_GetECC()
480 #if defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx)
481 /** @defgroup HAL_FMC_NAND_Group1 Initialization/de-initialization functions
482 * @brief Initialization and Configuration functions
485 ==============================================================================
486 ##### Initialization and de_initialization functions #####
487 ==============================================================================
489 This section provides functions allowing to:
490 (+) Initialize and configure the FMC NAND interface
491 (+) De-initialize the FMC NAND interface
492 (+) Configure the FMC clock and associated GPIOs
499 * @brief Initializes the FMC_NAND device according to the specified
500 * control parameters in the FMC_NAND_HandleTypeDef
501 * @param Device: Pointer to NAND device instance
502 * @param Init: Pointer to NAND Initialization structure
505 HAL_StatusTypeDef
FMC_NAND_Init(FMC_NAND_TypeDef
*Device
, FMC_NAND_InitTypeDef
*Init
)
509 /* Check the parameters */
510 assert_param(IS_FMC_NAND_DEVICE(Device
));
511 assert_param(IS_FMC_NAND_BANK(Init
->NandBank
));
512 assert_param(IS_FMC_WAIT_FEATURE(Init
->Waitfeature
));
513 assert_param(IS_FMC_NAND_MEMORY_WIDTH(Init
->MemoryDataWidth
));
514 assert_param(IS_FMC_ECC_STATE(Init
->EccComputation
));
515 assert_param(IS_FMC_ECCPAGE_SIZE(Init
->ECCPageSize
));
516 assert_param(IS_FMC_TCLR_TIME(Init
->TCLRSetupTime
));
517 assert_param(IS_FMC_TAR_TIME(Init
->TARSetupTime
));
519 /* Get the NAND bank register value */
522 /* Clear PWAITEN, PBKEN, PTYP, PWID, ECCEN, TCLR, TAR and ECCPS bits */
523 tmpr
&= ((uint32_t)~(FMC_PCR_PWAITEN
| FMC_PCR_PBKEN
| FMC_PCR_PTYP
| \
524 FMC_PCR_PWID
| FMC_PCR_ECCEN
| FMC_PCR_TCLR
| \
525 FMC_PCR_TAR
| FMC_PCR_ECCPS
));
527 /* Set NAND device control parameters */
528 tmpr
|= (uint32_t)(Init
->Waitfeature
|\
529 FMC_PCR_MEMORY_TYPE_NAND
|\
530 Init
->MemoryDataWidth
|\
531 Init
->EccComputation
|\
533 ((Init
->TCLRSetupTime
) << 9U) |\
534 ((Init
->TARSetupTime
) << 13U));
536 /* NAND bank registers configuration */
543 * @brief Initializes the FMC_NAND Common space Timing according to the specified
544 * parameters in the FMC_NAND_PCC_TimingTypeDef
545 * @param Device: Pointer to NAND device instance
546 * @param Timing: Pointer to NAND timing structure
547 * @param Bank: NAND bank number
550 HAL_StatusTypeDef
FMC_NAND_CommonSpace_Timing_Init(FMC_NAND_TypeDef
*Device
, FMC_NAND_PCC_TimingTypeDef
*Timing
, uint32_t Bank
)
554 /* Check the parameters */
555 assert_param(IS_FMC_NAND_DEVICE(Device
));
556 assert_param(IS_FMC_SETUP_TIME(Timing
->SetupTime
));
557 assert_param(IS_FMC_WAIT_TIME(Timing
->WaitSetupTime
));
558 assert_param(IS_FMC_HOLD_TIME(Timing
->HoldSetupTime
));
559 assert_param(IS_FMC_HIZ_TIME(Timing
->HiZSetupTime
));
560 assert_param(IS_FMC_NAND_BANK(Bank
));
562 /* Get the NAND bank 2 register value */
566 /* Clear MEMSETx, MEMWAITx, MEMHOLDx and MEMHIZx bits */
567 tmpr
&= ((uint32_t)~(FMC_PMEM_MEMSET2
| FMC_PMEM_MEMWAIT2
| FMC_PMEM_MEMHOLD2
| \
570 /* Set FMC_NAND device timing parameters */
571 tmpr
|= (uint32_t)(Timing
->SetupTime
|\
572 ((Timing
->WaitSetupTime
) << 8U) |\
573 ((Timing
->HoldSetupTime
) << 16U) |\
574 ((Timing
->HiZSetupTime
) << 24U)
577 /* NAND bank registers configuration */
584 * @brief Initializes the FMC_NAND Attribute space Timing according to the specified
585 * parameters in the FMC_NAND_PCC_TimingTypeDef
586 * @param Device: Pointer to NAND device instance
587 * @param Timing: Pointer to NAND timing structure
588 * @param Bank: NAND bank number
591 HAL_StatusTypeDef
FMC_NAND_AttributeSpace_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 /* Get the NAND bank register value */
606 /* Clear ATTSETx, ATTWAITx, ATTHOLDx and ATTHIZx bits */
607 tmpr
&= ((uint32_t)~(FMC_PATT_ATTSET2
| FMC_PATT_ATTWAIT2
| FMC_PATT_ATTHOLD2
| \
610 /* Set FMC_NAND device timing parameters */
611 tmpr
|= (uint32_t)(Timing
->SetupTime
|\
612 ((Timing
->WaitSetupTime
) << 8U) |\
613 ((Timing
->HoldSetupTime
) << 16U) |\
614 ((Timing
->HiZSetupTime
) << 24U));
616 /* NAND bank registers configuration */
624 * @brief DeInitializes the FMC_NAND device
625 * @param Device: Pointer to NAND device instance
626 * @param Bank: NAND bank number
629 HAL_StatusTypeDef
FMC_NAND_DeInit(FMC_NAND_TypeDef
*Device
, uint32_t Bank
)
631 /* Check the parameters */
632 assert_param(IS_FMC_NAND_DEVICE(Device
));
633 assert_param(IS_FMC_NAND_BANK(Bank
));
635 /* Disable the NAND Bank */
636 __FMC_NAND_DISABLE(Device
, Bank
);
638 /* De-initialize the NAND Bank */
639 /* Set the FMC_NAND_BANK registers to their reset values */
640 Device
->PCR
= 0x00000018U
;
641 Device
->SR
= 0x00000040U
;
642 Device
->PMEM
= 0xFCFCFCFCU
;
643 Device
->PATT
= 0xFCFCFCFCU
;
653 /** @defgroup HAL_FMC_NAND_Group2 Control functions
654 * @brief management functions
657 ==============================================================================
658 ##### FMC_NAND Control functions #####
659 ==============================================================================
661 This subsection provides a set of functions allowing to control dynamically
662 the FMC NAND interface.
670 * @brief Enables dynamically FMC_NAND ECC feature.
671 * @param Device: Pointer to NAND device instance
672 * @param Bank: NAND bank number
675 HAL_StatusTypeDef
FMC_NAND_ECC_Enable(FMC_NAND_TypeDef
*Device
, uint32_t Bank
)
677 /* Check the parameters */
678 assert_param(IS_FMC_NAND_DEVICE(Device
));
679 assert_param(IS_FMC_NAND_BANK(Bank
));
681 /* Enable ECC feature */
682 Device
->PCR
|= FMC_PCR_ECCEN
;
689 * @brief Disables dynamically FMC_NAND ECC feature.
690 * @param Device: Pointer to NAND device instance
691 * @param Bank: NAND bank number
694 HAL_StatusTypeDef
FMC_NAND_ECC_Disable(FMC_NAND_TypeDef
*Device
, uint32_t Bank
)
696 /* Check the parameters */
697 assert_param(IS_FMC_NAND_DEVICE(Device
));
698 assert_param(IS_FMC_NAND_BANK(Bank
));
700 /* Disable ECC feature */
701 Device
->PCR
&= ~FMC_PCR_ECCEN
;
707 * @brief Disables dynamically FMC_NAND ECC feature.
708 * @param Device: Pointer to NAND device instance
709 * @param ECCval: Pointer to ECC value
710 * @param Bank: NAND bank number
711 * @param Timeout: Timeout wait value
714 HAL_StatusTypeDef
FMC_NAND_GetECC(FMC_NAND_TypeDef
*Device
, uint32_t *ECCval
, uint32_t Bank
, uint32_t Timeout
)
716 uint32_t tickstart
= 0U;
718 /* Check the parameters */
719 assert_param(IS_FMC_NAND_DEVICE(Device
));
720 assert_param(IS_FMC_NAND_BANK(Bank
));
723 tickstart
= HAL_GetTick();
725 /* Wait until FIFO is empty */
726 while(__FMC_NAND_GET_FLAG(Device
, Bank
, FMC_FLAG_FEMPT
) == RESET
)
728 /* Check for the Timeout */
729 if(Timeout
!= HAL_MAX_DELAY
)
731 if((Timeout
== 0U)||((HAL_GetTick() - tickstart
) > Timeout
))
738 /* Get the ECCR register value */
739 *ECCval
= (uint32_t)Device
->ECCR
;
748 #else /* defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) */
749 /** @defgroup HAL_FMC_NAND_Group1 Initialization/de-initialization functions
750 * @brief Initialization and Configuration functions
753 ==============================================================================
754 ##### Initialization and de_initialization functions #####
755 ==============================================================================
757 This section provides functions allowing to:
758 (+) Initialize and configure the FMC NAND interface
759 (+) De-initialize the FMC NAND interface
760 (+) Configure the FMC clock and associated GPIOs
766 * @brief Initializes the FMC_NAND device according to the specified
767 * control parameters in the FMC_NAND_HandleTypeDef
768 * @param Device: Pointer to NAND device instance
769 * @param Init: Pointer to NAND Initialization structure
772 HAL_StatusTypeDef
FMC_NAND_Init(FMC_NAND_TypeDef
*Device
, FMC_NAND_InitTypeDef
*Init
)
776 /* Check the parameters */
777 assert_param(IS_FMC_NAND_DEVICE(Device
));
778 assert_param(IS_FMC_NAND_BANK(Init
->NandBank
));
779 assert_param(IS_FMC_WAIT_FEATURE(Init
->Waitfeature
));
780 assert_param(IS_FMC_NAND_MEMORY_WIDTH(Init
->MemoryDataWidth
));
781 assert_param(IS_FMC_ECC_STATE(Init
->EccComputation
));
782 assert_param(IS_FMC_ECCPAGE_SIZE(Init
->ECCPageSize
));
783 assert_param(IS_FMC_TCLR_TIME(Init
->TCLRSetupTime
));
784 assert_param(IS_FMC_TAR_TIME(Init
->TARSetupTime
));
786 if(Init
->NandBank
== FMC_NAND_BANK2
)
788 /* Get the NAND bank 2 register value */
793 /* Get the NAND bank 3 register value */
797 /* Clear PWAITEN, PBKEN, PTYP, PWID, ECCEN, TCLR, TAR and ECCPS bits */
798 tmpr
&= ((uint32_t)~(FMC_PCR2_PWAITEN
| FMC_PCR2_PBKEN
| FMC_PCR2_PTYP
| \
799 FMC_PCR2_PWID
| FMC_PCR2_ECCEN
| FMC_PCR2_TCLR
| \
800 FMC_PCR2_TAR
| FMC_PCR2_ECCPS
));
802 /* Set NAND device control parameters */
803 tmpr
|= (uint32_t)(Init
->Waitfeature
|\
804 FMC_PCR_MEMORY_TYPE_NAND
|\
805 Init
->MemoryDataWidth
|\
806 Init
->EccComputation
|\
808 ((Init
->TCLRSetupTime
) << 9U) |\
809 ((Init
->TARSetupTime
) << 13U));
811 if(Init
->NandBank
== FMC_NAND_BANK2
)
813 /* NAND bank 2 registers configuration */
818 /* NAND bank 3 registers configuration */
827 * @brief Initializes the FMC_NAND Common space Timing according to the specified
828 * parameters in the FMC_NAND_PCC_TimingTypeDef
829 * @param Device: Pointer to NAND device instance
830 * @param Timing: Pointer to NAND timing structure
831 * @param Bank: NAND bank number
834 HAL_StatusTypeDef
FMC_NAND_CommonSpace_Timing_Init(FMC_NAND_TypeDef
*Device
, FMC_NAND_PCC_TimingTypeDef
*Timing
, uint32_t Bank
)
838 /* Check the parameters */
839 assert_param(IS_FMC_NAND_DEVICE(Device
));
840 assert_param(IS_FMC_SETUP_TIME(Timing
->SetupTime
));
841 assert_param(IS_FMC_WAIT_TIME(Timing
->WaitSetupTime
));
842 assert_param(IS_FMC_HOLD_TIME(Timing
->HoldSetupTime
));
843 assert_param(IS_FMC_HIZ_TIME(Timing
->HiZSetupTime
));
844 assert_param(IS_FMC_NAND_BANK(Bank
));
846 if(Bank
== FMC_NAND_BANK2
)
848 /* Get the NAND bank 2 register value */
849 tmpr
= Device
->PMEM2
;
853 /* Get the NAND bank 3 register value */
854 tmpr
= Device
->PMEM3
;
857 /* Clear MEMSETx, MEMWAITx, MEMHOLDx and MEMHIZx bits */
858 tmpr
&= ((uint32_t)~(FMC_PMEM2_MEMSET2
| FMC_PMEM2_MEMWAIT2
| FMC_PMEM2_MEMHOLD2
| \
861 /* Set FMC_NAND device timing parameters */
862 tmpr
|= (uint32_t)(Timing
->SetupTime
|\
863 ((Timing
->WaitSetupTime
) << 8U) |\
864 ((Timing
->HoldSetupTime
) << 16U) |\
865 ((Timing
->HiZSetupTime
) << 24U)
868 if(Bank
== FMC_NAND_BANK2
)
870 /* NAND bank 2 registers configuration */
871 Device
->PMEM2
= tmpr
;
875 /* NAND bank 3 registers configuration */
876 Device
->PMEM3
= tmpr
;
883 * @brief Initializes the FMC_NAND Attribute space Timing according to the specified
884 * parameters in the FMC_NAND_PCC_TimingTypeDef
885 * @param Device: Pointer to NAND device instance
886 * @param Timing: Pointer to NAND timing structure
887 * @param Bank: NAND bank number
890 HAL_StatusTypeDef
FMC_NAND_AttributeSpace_Timing_Init(FMC_NAND_TypeDef
*Device
, FMC_NAND_PCC_TimingTypeDef
*Timing
, uint32_t Bank
)
894 /* Check the parameters */
895 assert_param(IS_FMC_NAND_DEVICE(Device
));
896 assert_param(IS_FMC_SETUP_TIME(Timing
->SetupTime
));
897 assert_param(IS_FMC_WAIT_TIME(Timing
->WaitSetupTime
));
898 assert_param(IS_FMC_HOLD_TIME(Timing
->HoldSetupTime
));
899 assert_param(IS_FMC_HIZ_TIME(Timing
->HiZSetupTime
));
900 assert_param(IS_FMC_NAND_BANK(Bank
));
902 if(Bank
== FMC_NAND_BANK2
)
904 /* Get the NAND bank 2 register value */
905 tmpr
= Device
->PATT2
;
909 /* Get the NAND bank 3 register value */
910 tmpr
= Device
->PATT3
;
913 /* Clear ATTSETx, ATTWAITx, ATTHOLDx and ATTHIZx bits */
914 tmpr
&= ((uint32_t)~(FMC_PATT2_ATTSET2
| FMC_PATT2_ATTWAIT2
| FMC_PATT2_ATTHOLD2
| \
917 /* Set FMC_NAND device timing parameters */
918 tmpr
|= (uint32_t)(Timing
->SetupTime
|\
919 ((Timing
->WaitSetupTime
) << 8U) |\
920 ((Timing
->HoldSetupTime
) << 16U) |\
921 ((Timing
->HiZSetupTime
) << 24U));
923 if(Bank
== FMC_NAND_BANK2
)
925 /* NAND bank 2 registers configuration */
926 Device
->PATT2
= tmpr
;
930 /* NAND bank 3 registers configuration */
931 Device
->PATT3
= tmpr
;
938 * @brief DeInitializes the FMC_NAND device
939 * @param Device: Pointer to NAND device instance
940 * @param Bank: NAND bank number
943 HAL_StatusTypeDef
FMC_NAND_DeInit(FMC_NAND_TypeDef
*Device
, uint32_t Bank
)
945 /* Check the parameters */
946 assert_param(IS_FMC_NAND_DEVICE(Device
));
947 assert_param(IS_FMC_NAND_BANK(Bank
));
949 /* Disable the NAND Bank */
950 __FMC_NAND_DISABLE(Device
, Bank
);
952 /* De-initialize the NAND Bank */
953 if(Bank
== FMC_NAND_BANK2
)
955 /* Set the FMC_NAND_BANK2 registers to their reset values */
956 Device
->PCR2
= 0x00000018U
;
957 Device
->SR2
= 0x00000040U
;
958 Device
->PMEM2
= 0xFCFCFCFCU
;
959 Device
->PATT2
= 0xFCFCFCFCU
;
964 /* Set the FMC_NAND_BANK3 registers to their reset values */
965 Device
->PCR3
= 0x00000018U
;
966 Device
->SR3
= 0x00000040U
;
967 Device
->PMEM3
= 0xFCFCFCFCU
;
968 Device
->PATT3
= 0xFCFCFCFCU
;
978 /** @addtogroup FMC_LL_NAND_Private_Functions_Group2
979 * @brief management functions
982 ==============================================================================
983 ##### FMC_NAND Control functions #####
984 ==============================================================================
986 This subsection provides a set of functions allowing to control dynamically
987 the FMC NAND interface.
993 * @brief Enables dynamically FMC_NAND ECC feature.
994 * @param Device: Pointer to NAND device instance
995 * @param Bank: NAND bank number
998 HAL_StatusTypeDef
FMC_NAND_ECC_Enable(FMC_NAND_TypeDef
*Device
, uint32_t Bank
)
1000 /* Check the parameters */
1001 assert_param(IS_FMC_NAND_DEVICE(Device
));
1002 assert_param(IS_FMC_NAND_BANK(Bank
));
1004 /* Enable ECC feature */
1005 if(Bank
== FMC_NAND_BANK2
)
1007 Device
->PCR2
|= FMC_PCR2_ECCEN
;
1011 Device
->PCR3
|= FMC_PCR3_ECCEN
;
1018 * @brief Disables dynamically FMC_NAND ECC feature.
1019 * @param Device: Pointer to NAND device instance
1020 * @param Bank: NAND bank number
1021 * @retval HAL status
1023 HAL_StatusTypeDef
FMC_NAND_ECC_Disable(FMC_NAND_TypeDef
*Device
, uint32_t Bank
)
1025 /* Check the parameters */
1026 assert_param(IS_FMC_NAND_DEVICE(Device
));
1027 assert_param(IS_FMC_NAND_BANK(Bank
));
1029 /* Disable ECC feature */
1030 if(Bank
== FMC_NAND_BANK2
)
1032 Device
->PCR2
&= ~FMC_PCR2_ECCEN
;
1036 Device
->PCR3
&= ~FMC_PCR3_ECCEN
;
1043 * @brief Disables dynamically FMC_NAND ECC feature.
1044 * @param Device: Pointer to NAND device instance
1045 * @param ECCval: Pointer to ECC value
1046 * @param Bank: NAND bank number
1047 * @param Timeout: Timeout wait value
1048 * @retval HAL status
1050 HAL_StatusTypeDef
FMC_NAND_GetECC(FMC_NAND_TypeDef
*Device
, uint32_t *ECCval
, uint32_t Bank
, uint32_t Timeout
)
1052 uint32_t tickstart
= 0U;
1054 /* Check the parameters */
1055 assert_param(IS_FMC_NAND_DEVICE(Device
));
1056 assert_param(IS_FMC_NAND_BANK(Bank
));
1059 tickstart
= HAL_GetTick();
1061 /* Wait until FIFO is empty */
1062 while(__FMC_NAND_GET_FLAG(Device
, Bank
, FMC_FLAG_FEMPT
) == RESET
)
1064 /* Check for the Timeout */
1065 if(Timeout
!= HAL_MAX_DELAY
)
1067 if((Timeout
== 0U)||((HAL_GetTick() - tickstart
) > Timeout
))
1074 if(Bank
== FMC_NAND_BANK2
)
1076 /* Get the ECCR2 register value */
1077 *ECCval
= (uint32_t)Device
->ECCR2
;
1081 /* Get the ECCR3 register value */
1082 *ECCval
= (uint32_t)Device
->ECCR3
;
1092 #endif /* defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) */
1097 #if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx)
1098 /** @addtogroup FMC_LL_PCCARD
1099 * @brief PCCARD Controller functions
1102 ==============================================================================
1103 ##### How to use PCCARD device driver #####
1104 ==============================================================================
1106 This driver contains a set of APIs to interface with the FMC PCCARD bank in order
1107 to run the PCCARD/compact flash external devices.
1109 (+) FMC PCCARD bank reset using the function FMC_PCCARD_DeInit()
1110 (+) FMC PCCARD bank control configuration using the function FMC_PCCARD_Init()
1111 (+) FMC PCCARD bank common space timing configuration using the function
1112 FMC_PCCARD_CommonSpace_Timing_Init()
1113 (+) FMC PCCARD bank attribute space timing configuration using the function
1114 FMC_PCCARD_AttributeSpace_Timing_Init()
1115 (+) FMC PCCARD bank IO space timing configuration using the function
1116 FMC_PCCARD_IOSpace_Timing_Init()
1121 /** @addtogroup FMC_LL_PCCARD_Private_Functions_Group1
1122 * @brief Initialization and Configuration functions
1125 ==============================================================================
1126 ##### Initialization and de_initialization functions #####
1127 ==============================================================================
1129 This section provides functions allowing to:
1130 (+) Initialize and configure the FMC PCCARD interface
1131 (+) De-initialize the FMC PCCARD interface
1132 (+) Configure the FMC clock and associated GPIOs
1139 * @brief Initializes the FMC_PCCARD device according to the specified
1140 * control parameters in the FMC_PCCARD_HandleTypeDef
1141 * @param Device: Pointer to PCCARD device instance
1142 * @param Init: Pointer to PCCARD Initialization structure
1143 * @retval HAL status
1145 HAL_StatusTypeDef
FMC_PCCARD_Init(FMC_PCCARD_TypeDef
*Device
, FMC_PCCARD_InitTypeDef
*Init
)
1149 /* Check the parameters */
1150 assert_param(IS_FMC_PCCARD_DEVICE(Device
));
1151 assert_param(IS_FMC_WAIT_FEATURE(Init
->Waitfeature
));
1152 assert_param(IS_FMC_TCLR_TIME(Init
->TCLRSetupTime
));
1153 assert_param(IS_FMC_TAR_TIME(Init
->TARSetupTime
));
1155 /* Get PCCARD control register value */
1156 tmpr
= Device
->PCR4
;
1158 /* Clear TAR, TCLR, PWAITEN and PWID bits */
1159 tmpr
&= ((uint32_t)~(FMC_PCR4_TAR
| FMC_PCR4_TCLR
| FMC_PCR4_PWAITEN
| \
1162 /* Set FMC_PCCARD device control parameters */
1163 tmpr
|= (uint32_t)(Init
->Waitfeature
|\
1164 FMC_NAND_PCC_MEM_BUS_WIDTH_16
|\
1165 (Init
->TCLRSetupTime
<< 9U) |\
1166 (Init
->TARSetupTime
<< 13U));
1168 Device
->PCR4
= tmpr
;
1174 * @brief Initializes the FMC_PCCARD Common space Timing according to the specified
1175 * parameters in the FMC_NAND_PCC_TimingTypeDef
1176 * @param Device: Pointer to PCCARD device instance
1177 * @param Timing: Pointer to PCCARD timing structure
1178 * @retval HAL status
1180 HAL_StatusTypeDef
FMC_PCCARD_CommonSpace_Timing_Init(FMC_PCCARD_TypeDef
*Device
, FMC_NAND_PCC_TimingTypeDef
*Timing
)
1184 /* Check the parameters */
1185 assert_param(IS_FMC_PCCARD_DEVICE(Device
));
1186 assert_param(IS_FMC_SETUP_TIME(Timing
->SetupTime
));
1187 assert_param(IS_FMC_WAIT_TIME(Timing
->WaitSetupTime
));
1188 assert_param(IS_FMC_HOLD_TIME(Timing
->HoldSetupTime
));
1189 assert_param(IS_FMC_HIZ_TIME(Timing
->HiZSetupTime
));
1191 /* Get PCCARD common space timing register value */
1192 tmpr
= Device
->PMEM4
;
1194 /* Clear MEMSETx, MEMWAITx, MEMHOLDx and MEMHIZx bits */
1195 tmpr
&= ((uint32_t)~(FMC_PMEM4_MEMSET4
| FMC_PMEM4_MEMWAIT4
| FMC_PMEM4_MEMHOLD4
| \
1196 FMC_PMEM4_MEMHIZ4
));
1197 /* Set PCCARD timing parameters */
1198 tmpr
|= (uint32_t)(Timing
->SetupTime
|\
1199 ((Timing
->WaitSetupTime
) << 8U) |\
1200 ((Timing
->HoldSetupTime
) << 16U) |\
1201 ((Timing
->HiZSetupTime
) << 24U));
1203 Device
->PMEM4
= tmpr
;
1209 * @brief Initializes the FMC_PCCARD Attribute space Timing according to the specified
1210 * parameters in the FMC_NAND_PCC_TimingTypeDef
1211 * @param Device: Pointer to PCCARD device instance
1212 * @param Timing: Pointer to PCCARD timing structure
1213 * @retval HAL status
1215 HAL_StatusTypeDef
FMC_PCCARD_AttributeSpace_Timing_Init(FMC_PCCARD_TypeDef
*Device
, FMC_NAND_PCC_TimingTypeDef
*Timing
)
1219 /* Check the parameters */
1220 assert_param(IS_FMC_PCCARD_DEVICE(Device
));
1221 assert_param(IS_FMC_SETUP_TIME(Timing
->SetupTime
));
1222 assert_param(IS_FMC_WAIT_TIME(Timing
->WaitSetupTime
));
1223 assert_param(IS_FMC_HOLD_TIME(Timing
->HoldSetupTime
));
1224 assert_param(IS_FMC_HIZ_TIME(Timing
->HiZSetupTime
));
1226 /* Get PCCARD timing parameters */
1227 tmpr
= Device
->PATT4
;
1229 /* Clear ATTSETx, ATTWAITx, ATTHOLDx and ATTHIZx bits */
1230 tmpr
&= ((uint32_t)~(FMC_PATT4_ATTSET4
| FMC_PATT4_ATTWAIT4
| FMC_PATT4_ATTHOLD4
| \
1231 FMC_PATT4_ATTHIZ4
));
1233 /* Set PCCARD timing parameters */
1234 tmpr
|= (uint32_t)(Timing
->SetupTime
|\
1235 ((Timing
->WaitSetupTime
) << 8U) |\
1236 ((Timing
->HoldSetupTime
) << 16U) |\
1237 ((Timing
->HiZSetupTime
) << 24U));
1238 Device
->PATT4
= tmpr
;
1244 * @brief Initializes the FMC_PCCARD IO space Timing according to the specified
1245 * parameters in the FMC_NAND_PCC_TimingTypeDef
1246 * @param Device: Pointer to PCCARD device instance
1247 * @param Timing: Pointer to PCCARD timing structure
1248 * @retval HAL status
1250 HAL_StatusTypeDef
FMC_PCCARD_IOSpace_Timing_Init(FMC_PCCARD_TypeDef
*Device
, FMC_NAND_PCC_TimingTypeDef
*Timing
)
1254 /* Check the parameters */
1255 assert_param(IS_FMC_PCCARD_DEVICE(Device
));
1256 assert_param(IS_FMC_SETUP_TIME(Timing
->SetupTime
));
1257 assert_param(IS_FMC_WAIT_TIME(Timing
->WaitSetupTime
));
1258 assert_param(IS_FMC_HOLD_TIME(Timing
->HoldSetupTime
));
1259 assert_param(IS_FMC_HIZ_TIME(Timing
->HiZSetupTime
));
1261 /* Get FMC_PCCARD device timing parameters */
1262 tmpr
= Device
->PIO4
;
1264 /* Clear IOSET4, IOWAIT4, IOHOLD4 and IOHIZ4 bits */
1265 tmpr
&= ((uint32_t)~(FMC_PIO4_IOSET4
| FMC_PIO4_IOWAIT4
| FMC_PIO4_IOHOLD4
| \
1268 /* Set FMC_PCCARD device timing parameters */
1269 tmpr
|= (uint32_t)(Timing
->SetupTime
|\
1270 ((Timing
->WaitSetupTime
) << 8U) |\
1271 ((Timing
->HoldSetupTime
) << 16U) |\
1272 ((Timing
->HiZSetupTime
) << 24U));
1274 Device
->PIO4
= tmpr
;
1280 * @brief DeInitializes the FMC_PCCARD device
1281 * @param Device: Pointer to PCCARD device instance
1282 * @retval HAL status
1284 HAL_StatusTypeDef
FMC_PCCARD_DeInit(FMC_PCCARD_TypeDef
*Device
)
1286 /* Check the parameters */
1287 assert_param(IS_FMC_PCCARD_DEVICE(Device
));
1289 /* Disable the FMC_PCCARD device */
1290 __FMC_PCCARD_DISABLE(Device
);
1292 /* De-initialize the FMC_PCCARD device */
1293 Device
->PCR4
= 0x00000018U
;
1294 Device
->SR4
= 0x00000000U
;
1295 Device
->PMEM4
= 0xFCFCFCFCU
;
1296 Device
->PATT4
= 0xFCFCFCFCU
;
1297 Device
->PIO4
= 0xFCFCFCFCU
;
1305 #endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx */
1308 /** @addtogroup FMC_LL_SDRAM
1309 * @brief SDRAM Controller functions
1312 ==============================================================================
1313 ##### How to use SDRAM device driver #####
1314 ==============================================================================
1316 This driver contains a set of APIs to interface with the FMC SDRAM banks in order
1317 to run the SDRAM external devices.
1319 (+) FMC SDRAM bank reset using the function FMC_SDRAM_DeInit()
1320 (+) FMC SDRAM bank control configuration using the function FMC_SDRAM_Init()
1321 (+) FMC SDRAM bank timing configuration using the function FMC_SDRAM_Timing_Init()
1322 (+) FMC SDRAM bank enable/disable write operation using the functions
1323 FMC_SDRAM_WriteOperation_Enable()/FMC_SDRAM_WriteOperation_Disable()
1324 (+) FMC SDRAM bank send command using the function FMC_SDRAM_SendCommand()
1330 /** @addtogroup FMC_LL_SDRAM_Private_Functions_Group1
1331 * @brief Initialization and Configuration functions
1334 ==============================================================================
1335 ##### Initialization and de_initialization functions #####
1336 ==============================================================================
1338 This section provides functions allowing to:
1339 (+) Initialize and configure the FMC SDRAM interface
1340 (+) De-initialize the FMC SDRAM interface
1341 (+) Configure the FMC clock and associated GPIOs
1348 * @brief Initializes the FMC_SDRAM device according to the specified
1349 * control parameters in the FMC_SDRAM_InitTypeDef
1350 * @param Device: Pointer to SDRAM device instance
1351 * @param Init: Pointer to SDRAM Initialization structure
1352 * @retval HAL status
1354 HAL_StatusTypeDef
FMC_SDRAM_Init(FMC_SDRAM_TypeDef
*Device
, FMC_SDRAM_InitTypeDef
*Init
)
1356 uint32_t tmpr1
= 0U;
1357 uint32_t tmpr2
= 0U;
1359 /* Check the parameters */
1360 assert_param(IS_FMC_SDRAM_DEVICE(Device
));
1361 assert_param(IS_FMC_SDRAM_BANK(Init
->SDBank
));
1362 assert_param(IS_FMC_COLUMNBITS_NUMBER(Init
->ColumnBitsNumber
));
1363 assert_param(IS_FMC_ROWBITS_NUMBER(Init
->RowBitsNumber
));
1364 assert_param(IS_FMC_SDMEMORY_WIDTH(Init
->MemoryDataWidth
));
1365 assert_param(IS_FMC_INTERNALBANK_NUMBER(Init
->InternalBankNumber
));
1366 assert_param(IS_FMC_CAS_LATENCY(Init
->CASLatency
));
1367 assert_param(IS_FMC_WRITE_PROTECTION(Init
->WriteProtection
));
1368 assert_param(IS_FMC_SDCLOCK_PERIOD(Init
->SDClockPeriod
));
1369 assert_param(IS_FMC_READ_BURST(Init
->ReadBurst
));
1370 assert_param(IS_FMC_READPIPE_DELAY(Init
->ReadPipeDelay
));
1372 /* Set SDRAM bank configuration parameters */
1373 if (Init
->SDBank
!= FMC_SDRAM_BANK2
)
1375 tmpr1
= Device
->SDCR
[FMC_SDRAM_BANK1
];
1377 /* Clear NC, NR, MWID, NB, CAS, WP, SDCLK, RBURST, and RPIPE bits */
1378 tmpr1
&= ((uint32_t)~(FMC_SDCR1_NC
| FMC_SDCR1_NR
| FMC_SDCR1_MWID
| \
1379 FMC_SDCR1_NB
| FMC_SDCR1_CAS
| FMC_SDCR1_WP
| \
1380 FMC_SDCR1_SDCLK
| FMC_SDCR1_RBURST
| FMC_SDCR1_RPIPE
));
1383 tmpr1
|= (uint32_t)(Init
->ColumnBitsNumber
|\
1384 Init
->RowBitsNumber
|\
1385 Init
->MemoryDataWidth
|\
1386 Init
->InternalBankNumber
|\
1388 Init
->WriteProtection
|\
1389 Init
->SDClockPeriod
|\
1393 Device
->SDCR
[FMC_SDRAM_BANK1
] = tmpr1
;
1395 else /* FMC_Bank2_SDRAM */
1397 tmpr1
= Device
->SDCR
[FMC_SDRAM_BANK1
];
1399 /* Clear NC, NR, MWID, NB, CAS, WP, SDCLK, RBURST, and RPIPE bits */
1400 tmpr1
&= ((uint32_t)~(FMC_SDCR1_SDCLK
| FMC_SDCR1_RBURST
| FMC_SDCR1_RPIPE
));
1402 tmpr1
|= (uint32_t)(Init
->SDClockPeriod
|\
1404 Init
->ReadPipeDelay
);
1406 tmpr2
= Device
->SDCR
[FMC_SDRAM_BANK2
];
1408 /* Clear NC, NR, MWID, NB, CAS, WP, SDCLK, RBURST, and RPIPE bits */
1409 tmpr2
&= ((uint32_t)~(FMC_SDCR1_NC
| FMC_SDCR1_NR
| FMC_SDCR1_MWID
| \
1410 FMC_SDCR1_NB
| FMC_SDCR1_CAS
| FMC_SDCR1_WP
| \
1411 FMC_SDCR1_SDCLK
| FMC_SDCR1_RBURST
| FMC_SDCR1_RPIPE
));
1413 tmpr2
|= (uint32_t)(Init
->ColumnBitsNumber
|\
1414 Init
->RowBitsNumber
|\
1415 Init
->MemoryDataWidth
|\
1416 Init
->InternalBankNumber
|\
1418 Init
->WriteProtection
);
1420 Device
->SDCR
[FMC_SDRAM_BANK1
] = tmpr1
;
1421 Device
->SDCR
[FMC_SDRAM_BANK2
] = tmpr2
;
1428 * @brief Initializes the FMC_SDRAM device timing according to the specified
1429 * parameters in the FMC_SDRAM_TimingTypeDef
1430 * @param Device: Pointer to SDRAM device instance
1431 * @param Timing: Pointer to SDRAM Timing structure
1432 * @param Bank: SDRAM bank number
1433 * @retval HAL status
1435 HAL_StatusTypeDef
FMC_SDRAM_Timing_Init(FMC_SDRAM_TypeDef
*Device
, FMC_SDRAM_TimingTypeDef
*Timing
, uint32_t Bank
)
1437 uint32_t tmpr1
= 0U;
1438 uint32_t tmpr2
= 0U;
1440 /* Check the parameters */
1441 assert_param(IS_FMC_SDRAM_DEVICE(Device
));
1442 assert_param(IS_FMC_LOADTOACTIVE_DELAY(Timing
->LoadToActiveDelay
));
1443 assert_param(IS_FMC_EXITSELFREFRESH_DELAY(Timing
->ExitSelfRefreshDelay
));
1444 assert_param(IS_FMC_SELFREFRESH_TIME(Timing
->SelfRefreshTime
));
1445 assert_param(IS_FMC_ROWCYCLE_DELAY(Timing
->RowCycleDelay
));
1446 assert_param(IS_FMC_WRITE_RECOVERY_TIME(Timing
->WriteRecoveryTime
));
1447 assert_param(IS_FMC_RP_DELAY(Timing
->RPDelay
));
1448 assert_param(IS_FMC_RCD_DELAY(Timing
->RCDDelay
));
1449 assert_param(IS_FMC_SDRAM_BANK(Bank
));
1451 /* Set SDRAM device timing parameters */
1452 if (Bank
!= FMC_SDRAM_BANK2
)
1454 tmpr1
= Device
->SDTR
[FMC_SDRAM_BANK1
];
1456 /* Clear TMRD, TXSR, TRAS, TRC, TWR, TRP and TRCD bits */
1457 tmpr1
&= ((uint32_t)~(FMC_SDTR1_TMRD
| FMC_SDTR1_TXSR
| FMC_SDTR1_TRAS
| \
1458 FMC_SDTR1_TRC
| FMC_SDTR1_TWR
| FMC_SDTR1_TRP
| \
1461 tmpr1
|= (uint32_t)(((Timing
->LoadToActiveDelay
)-1U) |\
1462 (((Timing
->ExitSelfRefreshDelay
)-1U) << 4U) |\
1463 (((Timing
->SelfRefreshTime
)-1U) << 8U) |\
1464 (((Timing
->RowCycleDelay
)-1U) << 12U) |\
1465 (((Timing
->WriteRecoveryTime
)-1U) <<16U) |\
1466 (((Timing
->RPDelay
)-1U) << 20U) |\
1467 (((Timing
->RCDDelay
)-1U) << 24U));
1468 Device
->SDTR
[FMC_SDRAM_BANK1
] = tmpr1
;
1470 else /* FMC_Bank2_SDRAM */
1472 tmpr1
= Device
->SDTR
[FMC_SDRAM_BANK1
];
1474 /* Clear TRC and TRP bits */
1475 tmpr1
&= ((uint32_t)~(FMC_SDTR1_TRC
| FMC_SDTR1_TRP
));
1477 tmpr1
|= (uint32_t)((((Timing
->RowCycleDelay
)-1U) << 12U) |\
1478 (((Timing
->RPDelay
)-1U) << 20U));
1480 tmpr2
= Device
->SDTR
[FMC_SDRAM_BANK2
];
1482 /* Clear TMRD, TXSR, TRAS, TRC, TWR, TRP and TRCD bits */
1483 tmpr2
&= ((uint32_t)~(FMC_SDTR1_TMRD
| FMC_SDTR1_TXSR
| FMC_SDTR1_TRAS
| \
1484 FMC_SDTR1_TRC
| FMC_SDTR1_TWR
| FMC_SDTR1_TRP
| \
1487 tmpr2
|= (uint32_t)((((Timing
->LoadToActiveDelay
)-1U) |\
1488 (((Timing
->ExitSelfRefreshDelay
)-1U) << 4U) |\
1489 (((Timing
->SelfRefreshTime
)-1U) << 8U) |\
1490 (((Timing
->WriteRecoveryTime
)-1U) <<16U) |\
1491 (((Timing
->RCDDelay
)-1U) << 24U)));
1493 Device
->SDTR
[FMC_SDRAM_BANK1
] = tmpr1
;
1494 Device
->SDTR
[FMC_SDRAM_BANK2
] = tmpr2
;
1500 * @brief DeInitializes the FMC_SDRAM peripheral
1501 * @param Device: Pointer to SDRAM device instance
1502 * @retval HAL status
1504 HAL_StatusTypeDef
FMC_SDRAM_DeInit(FMC_SDRAM_TypeDef
*Device
, uint32_t Bank
)
1506 /* Check the parameters */
1507 assert_param(IS_FMC_SDRAM_DEVICE(Device
));
1508 assert_param(IS_FMC_SDRAM_BANK(Bank
));
1510 /* De-initialize the SDRAM device */
1511 Device
->SDCR
[Bank
] = 0x000002D0U
;
1512 Device
->SDTR
[Bank
] = 0x0FFFFFFFU
;
1513 Device
->SDCMR
= 0x00000000U
;
1514 Device
->SDRTR
= 0x00000000U
;
1515 Device
->SDSR
= 0x00000000U
;
1524 /** @addtogroup FMC_LL_SDRAMPrivate_Functions_Group2
1525 * @brief management functions
1528 ==============================================================================
1529 ##### FMC_SDRAM Control functions #####
1530 ==============================================================================
1532 This subsection provides a set of functions allowing to control dynamically
1533 the FMC SDRAM interface.
1539 * @brief Enables dynamically FMC_SDRAM write protection.
1540 * @param Device: Pointer to SDRAM device instance
1541 * @param Bank: SDRAM bank number
1542 * @retval HAL status
1544 HAL_StatusTypeDef
FMC_SDRAM_WriteProtection_Enable(FMC_SDRAM_TypeDef
*Device
, uint32_t Bank
)
1546 /* Check the parameters */
1547 assert_param(IS_FMC_SDRAM_DEVICE(Device
));
1548 assert_param(IS_FMC_SDRAM_BANK(Bank
));
1550 /* Enable write protection */
1551 Device
->SDCR
[Bank
] |= FMC_SDRAM_WRITE_PROTECTION_ENABLE
;
1557 * @brief Disables dynamically FMC_SDRAM write protection.
1558 * @param hsdram: FMC_SDRAM handle
1559 * @retval HAL status
1561 HAL_StatusTypeDef
FMC_SDRAM_WriteProtection_Disable(FMC_SDRAM_TypeDef
*Device
, uint32_t Bank
)
1563 /* Check the parameters */
1564 assert_param(IS_FMC_SDRAM_DEVICE(Device
));
1565 assert_param(IS_FMC_SDRAM_BANK(Bank
));
1567 /* Disable write protection */
1568 Device
->SDCR
[Bank
] &= ~FMC_SDRAM_WRITE_PROTECTION_ENABLE
;
1574 * @brief Send Command to the FMC SDRAM bank
1575 * @param Device: Pointer to SDRAM device instance
1576 * @param Command: Pointer to SDRAM command structure
1577 * @param Timing: Pointer to SDRAM Timing structure
1578 * @param Timeout: Timeout wait value
1581 HAL_StatusTypeDef
FMC_SDRAM_SendCommand(FMC_SDRAM_TypeDef
*Device
, FMC_SDRAM_CommandTypeDef
*Command
, uint32_t Timeout
)
1583 __IO
uint32_t tmpr
= 0U;
1584 uint32_t tickstart
= 0U;
1586 /* Check the parameters */
1587 assert_param(IS_FMC_SDRAM_DEVICE(Device
));
1588 assert_param(IS_FMC_COMMAND_MODE(Command
->CommandMode
));
1589 assert_param(IS_FMC_COMMAND_TARGET(Command
->CommandTarget
));
1590 assert_param(IS_FMC_AUTOREFRESH_NUMBER(Command
->AutoRefreshNumber
));
1591 assert_param(IS_FMC_MODE_REGISTER(Command
->ModeRegisterDefinition
));
1593 /* Set command register */
1594 tmpr
= (uint32_t)((Command
->CommandMode
) |\
1595 (Command
->CommandTarget
) |\
1596 (((Command
->AutoRefreshNumber
)-1U) << 5U) |\
1597 ((Command
->ModeRegisterDefinition
) << 9U)
1600 Device
->SDCMR
= tmpr
;
1603 tickstart
= HAL_GetTick();
1605 /* Wait until command is send */
1606 while(HAL_IS_BIT_SET(Device
->SDSR
, FMC_SDSR_BUSY
))
1608 /* Check for the Timeout */
1609 if(Timeout
!= HAL_MAX_DELAY
)
1611 if((Timeout
== 0U)||((HAL_GetTick() - tickstart
) > Timeout
))
1622 * @brief Program the SDRAM Memory Refresh rate.
1623 * @param Device: Pointer to SDRAM device instance
1624 * @param RefreshRate: The SDRAM refresh rate value.
1627 HAL_StatusTypeDef
FMC_SDRAM_ProgramRefreshRate(FMC_SDRAM_TypeDef
*Device
, uint32_t RefreshRate
)
1629 /* Check the parameters */
1630 assert_param(IS_FMC_SDRAM_DEVICE(Device
));
1631 assert_param(IS_FMC_REFRESH_RATE(RefreshRate
));
1633 /* Set the refresh rate in command register */
1634 Device
->SDRTR
|= (RefreshRate
<<1U);
1640 * @brief Set the Number of consecutive SDRAM Memory auto Refresh commands.
1641 * @param Device: Pointer to SDRAM device instance
1642 * @param AutoRefreshNumber: Specifies the auto Refresh number.
1645 HAL_StatusTypeDef
FMC_SDRAM_SetAutoRefreshNumber(FMC_SDRAM_TypeDef
*Device
, uint32_t AutoRefreshNumber
)
1647 /* Check the parameters */
1648 assert_param(IS_FMC_SDRAM_DEVICE(Device
));
1649 assert_param(IS_FMC_AUTOREFRESH_NUMBER(AutoRefreshNumber
));
1651 /* Set the Auto-refresh number in command register */
1652 Device
->SDCMR
|= (AutoRefreshNumber
<< 5U);
1658 * @brief Returns the indicated FMC SDRAM bank mode status.
1659 * @param Device: Pointer to SDRAM device instance
1660 * @param Bank: Defines the FMC SDRAM bank. This parameter can be
1661 * FMC_Bank1_SDRAM or FMC_Bank2_SDRAM.
1662 * @retval The FMC SDRAM bank mode status, could be on of the following values:
1663 * FMC_SDRAM_NORMAL_MODE, FMC_SDRAM_SELF_REFRESH_MODE or
1664 * FMC_SDRAM_POWER_DOWN_MODE.
1666 uint32_t FMC_SDRAM_GetModeStatus(FMC_SDRAM_TypeDef
*Device
, uint32_t Bank
)
1668 uint32_t tmpreg
= 0U;
1670 /* Check the parameters */
1671 assert_param(IS_FMC_SDRAM_DEVICE(Device
));
1672 assert_param(IS_FMC_SDRAM_BANK(Bank
));
1674 /* Get the corresponding bank mode */
1675 if(Bank
== FMC_SDRAM_BANK1
)
1677 tmpreg
= (uint32_t)(Device
->SDSR
& FMC_SDSR_MODES1
);
1681 tmpreg
= ((uint32_t)(Device
->SDSR
& FMC_SDSR_MODES2
) >> 2U);
1684 /* Return the mode status */
1699 #endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */
1700 #endif /* HAL_SRAM_MODULE_ENABLED || HAL_NOR_MODULE_ENABLED || HAL_NAND_MODULE_ENABLED || HAL_PCCARD_MODULE_ENABLED || HAL_SDRAM_MODULE_ENABLED */
1710 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/