before merging master
[inav.git] / lib / main / STM32F7 / Drivers / STM32F7xx_HAL_Driver / Src / stm32f7xx_ll_fmc.c
blob381c408354a12ef849317fa04a7839a5a0be81f2
1 /**
2 ******************************************************************************
3 * @file stm32f7xx_ll_fmc.c
4 * @author MCD Application Team
5 * @version V1.2.2
6 * @date 14-April-2017
7 * @brief FMC Low Layer HAL module driver.
8 *
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
15 @verbatim
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 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
40 data
41 (+) Interface with synchronous DRAM (SDRAM) memories
42 (+) Independent Chip Select control for each memory bank
43 (+) Independent configuration for each memory bank
45 @endverbatim
46 ******************************************************************************
47 * @attention
49 * <h2><center>&copy; 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 ******************************************************************************
74 */
76 /* Includes ------------------------------------------------------------------*/
77 #include "stm32f7xx_hal.h"
79 /** @addtogroup STM32F7xx_HAL_Driver
80 * @{
83 /** @defgroup FMC_LL FMC Low Layer
84 * @brief FMC driver modules
85 * @{
88 #if defined (HAL_SRAM_MODULE_ENABLED) || defined(HAL_NOR_MODULE_ENABLED) || defined(HAL_NAND_MODULE_ENABLED) || defined(HAL_SDRAM_MODULE_ENABLED)
90 /* Private typedef -----------------------------------------------------------*/
91 /* Private define ------------------------------------------------------------*/
92 /* Private macro -------------------------------------------------------------*/
93 /* Private variables ---------------------------------------------------------*/
94 /* Private function prototypes -----------------------------------------------*/
95 /* Exported functions --------------------------------------------------------*/
97 /** @defgroup FMC_LL_Exported_Functions FMC Low Layer Exported Functions
98 * @{
101 /** @defgroup FMC_LL_Exported_Functions_NORSRAM FMC Low Layer NOR SRAM Exported Functions
102 * @brief NORSRAM Controller functions
104 @verbatim
105 ==============================================================================
106 ##### How to use NORSRAM device driver #####
107 ==============================================================================
109 [..]
110 This driver contains a set of APIs to interface with the FMC NORSRAM banks in order
111 to run the NORSRAM external devices.
113 (+) FMC NORSRAM bank reset using the function FMC_NORSRAM_DeInit()
114 (+) FMC NORSRAM bank control configuration using the function FMC_NORSRAM_Init()
115 (+) FMC NORSRAM bank timing configuration using the function FMC_NORSRAM_Timing_Init()
116 (+) FMC NORSRAM bank extended timing configuration using the function
117 FMC_NORSRAM_Extended_Timing_Init()
118 (+) FMC NORSRAM bank enable/disable write operation using the functions
119 FMC_NORSRAM_WriteOperation_Enable()/FMC_NORSRAM_WriteOperation_Disable()
122 @endverbatim
123 * @{
126 /** @defgroup FMC_LL_NORSRAM_Exported_Functions_Group1 Initialization and de-initialization functions
127 * @brief Initialization and Configuration functions
129 @verbatim
130 ==============================================================================
131 ##### Initialization and de_initialization functions #####
132 ==============================================================================
133 [..]
134 This section provides functions allowing to:
135 (+) Initialize and configure the FMC NORSRAM interface
136 (+) De-initialize the FMC NORSRAM interface
137 (+) Configure the FMC clock and associated GPIOs
139 @endverbatim
140 * @{
144 * @brief Initialize the FMC_NORSRAM device according to the specified
145 * control parameters in the FMC_NORSRAM_InitTypeDef
146 * @param Device: Pointer to NORSRAM device instance
147 * @param Init: Pointer to NORSRAM Initialization structure
148 * @retval HAL status
150 HAL_StatusTypeDef FMC_NORSRAM_Init(FMC_NORSRAM_TypeDef *Device, FMC_NORSRAM_InitTypeDef* Init)
152 uint32_t tmpr = 0;
154 /* Check the parameters */
155 assert_param(IS_FMC_NORSRAM_DEVICE(Device));
156 assert_param(IS_FMC_NORSRAM_BANK(Init->NSBank));
157 assert_param(IS_FMC_MUX(Init->DataAddressMux));
158 assert_param(IS_FMC_MEMORY(Init->MemoryType));
159 assert_param(IS_FMC_NORSRAM_MEMORY_WIDTH(Init->MemoryDataWidth));
160 assert_param(IS_FMC_BURSTMODE(Init->BurstAccessMode));
161 assert_param(IS_FMC_WAIT_POLARITY(Init->WaitSignalPolarity));
162 assert_param(IS_FMC_WAIT_SIGNAL_ACTIVE(Init->WaitSignalActive));
163 assert_param(IS_FMC_WRITE_OPERATION(Init->WriteOperation));
164 assert_param(IS_FMC_WAITE_SIGNAL(Init->WaitSignal));
165 assert_param(IS_FMC_EXTENDED_MODE(Init->ExtendedMode));
166 assert_param(IS_FMC_ASYNWAIT(Init->AsynchronousWait));
167 assert_param(IS_FMC_WRITE_BURST(Init->WriteBurst));
168 assert_param(IS_FMC_CONTINOUS_CLOCK(Init->ContinuousClock));
169 assert_param(IS_FMC_WRITE_FIFO(Init->WriteFifo));
170 assert_param(IS_FMC_PAGESIZE(Init->PageSize));
172 /* Get the BTCR register value */
173 tmpr = Device->BTCR[Init->NSBank];
175 /* Clear MBKEN, MUXEN, MTYP, MWID, FACCEN, BURSTEN, WAITPOL, WAITCFG, WREN,
176 WAITEN, EXTMOD, ASYNCWAIT, CBURSTRW and CCLKEN bits */
177 tmpr &= ((uint32_t)~(FMC_BCR1_MBKEN | FMC_BCR1_MUXEN | FMC_BCR1_MTYP | \
178 FMC_BCR1_MWID | FMC_BCR1_FACCEN | FMC_BCR1_BURSTEN | \
179 FMC_BCR1_WAITPOL | FMC_BCR1_CPSIZE | FMC_BCR1_WAITCFG | \
180 FMC_BCR1_WREN | FMC_BCR1_WAITEN | FMC_BCR1_EXTMOD | \
181 FMC_BCR1_ASYNCWAIT | FMC_BCR1_CBURSTRW | FMC_BCR1_CCLKEN | FMC_BCR1_WFDIS));
183 /* Set NORSRAM device control parameters */
184 tmpr |= (uint32_t)(Init->DataAddressMux |\
185 Init->MemoryType |\
186 Init->MemoryDataWidth |\
187 Init->BurstAccessMode |\
188 Init->WaitSignalPolarity |\
189 Init->WaitSignalActive |\
190 Init->WriteOperation |\
191 Init->WaitSignal |\
192 Init->ExtendedMode |\
193 Init->AsynchronousWait |\
194 Init->WriteBurst |\
195 Init->ContinuousClock |\
196 Init->PageSize |\
197 Init->WriteFifo);
199 if(Init->MemoryType == FMC_MEMORY_TYPE_NOR)
201 tmpr |= (uint32_t)FMC_NORSRAM_FLASH_ACCESS_ENABLE;
204 Device->BTCR[Init->NSBank] = tmpr;
206 /* Configure synchronous mode when Continuous clock is enabled for bank2..4 */
207 if((Init->ContinuousClock == FMC_CONTINUOUS_CLOCK_SYNC_ASYNC) && (Init->NSBank != FMC_NORSRAM_BANK1))
209 Device->BTCR[FMC_NORSRAM_BANK1] |= (uint32_t)(Init->ContinuousClock);
211 if(Init->NSBank != FMC_NORSRAM_BANK1)
213 Device->BTCR[FMC_NORSRAM_BANK1] |= (uint32_t)(Init->WriteFifo);
216 return HAL_OK;
221 * @brief DeInitialize the FMC_NORSRAM peripheral
222 * @param Device: Pointer to NORSRAM device instance
223 * @param ExDevice: Pointer to NORSRAM extended mode device instance
224 * @param Bank: NORSRAM bank number
225 * @retval HAL status
227 HAL_StatusTypeDef FMC_NORSRAM_DeInit(FMC_NORSRAM_TypeDef *Device, FMC_NORSRAM_EXTENDED_TypeDef *ExDevice, uint32_t Bank)
229 /* Check the parameters */
230 assert_param(IS_FMC_NORSRAM_DEVICE(Device));
231 assert_param(IS_FMC_NORSRAM_EXTENDED_DEVICE(ExDevice));
232 assert_param(IS_FMC_NORSRAM_BANK(Bank));
234 /* Disable the FMC_NORSRAM device */
235 __FMC_NORSRAM_DISABLE(Device, Bank);
237 /* De-initialize the FMC_NORSRAM device */
238 /* FMC_NORSRAM_BANK1 */
239 if(Bank == FMC_NORSRAM_BANK1)
241 Device->BTCR[Bank] = 0x000030DB;
243 /* FMC_NORSRAM_BANK2, FMC_NORSRAM_BANK3 or FMC_NORSRAM_BANK4 */
244 else
246 Device->BTCR[Bank] = 0x000030D2;
249 Device->BTCR[Bank + 1] = 0x0FFFFFFF;
250 ExDevice->BWTR[Bank] = 0x0FFFFFFF;
252 return HAL_OK;
257 * @brief Initialize the FMC_NORSRAM Timing according to the specified
258 * parameters in the FMC_NORSRAM_TimingTypeDef
259 * @param Device: Pointer to NORSRAM device instance
260 * @param Timing: Pointer to NORSRAM Timing structure
261 * @param Bank: NORSRAM bank number
262 * @retval HAL status
264 HAL_StatusTypeDef FMC_NORSRAM_Timing_Init(FMC_NORSRAM_TypeDef *Device, FMC_NORSRAM_TimingTypeDef *Timing, uint32_t Bank)
266 uint32_t tmpr = 0;
268 /* Check the parameters */
269 assert_param(IS_FMC_NORSRAM_DEVICE(Device));
270 assert_param(IS_FMC_ADDRESS_SETUP_TIME(Timing->AddressSetupTime));
271 assert_param(IS_FMC_ADDRESS_HOLD_TIME(Timing->AddressHoldTime));
272 assert_param(IS_FMC_DATASETUP_TIME(Timing->DataSetupTime));
273 assert_param(IS_FMC_TURNAROUND_TIME(Timing->BusTurnAroundDuration));
274 assert_param(IS_FMC_CLK_DIV(Timing->CLKDivision));
275 assert_param(IS_FMC_DATA_LATENCY(Timing->DataLatency));
276 assert_param(IS_FMC_ACCESS_MODE(Timing->AccessMode));
277 assert_param(IS_FMC_NORSRAM_BANK(Bank));
279 /* Get the BTCR register value */
280 tmpr = Device->BTCR[Bank + 1];
282 /* Clear ADDSET, ADDHLD, DATAST, BUSTURN, CLKDIV, DATLAT and ACCMOD bits */
283 tmpr &= ((uint32_t)~(FMC_BTR1_ADDSET | FMC_BTR1_ADDHLD | FMC_BTR1_DATAST | \
284 FMC_BTR1_BUSTURN | FMC_BTR1_CLKDIV | FMC_BTR1_DATLAT | \
285 FMC_BTR1_ACCMOD));
287 /* Set FMC_NORSRAM device timing parameters */
288 tmpr |= (uint32_t)(Timing->AddressSetupTime |\
289 ((Timing->AddressHoldTime) << 4) |\
290 ((Timing->DataSetupTime) << 8) |\
291 ((Timing->BusTurnAroundDuration) << 16) |\
292 (((Timing->CLKDivision)-1) << 20) |\
293 (((Timing->DataLatency)-2) << 24) |\
294 (Timing->AccessMode)
297 Device->BTCR[Bank + 1] = tmpr;
299 /* Configure Clock division value (in NORSRAM bank 1) when continuous clock is enabled */
300 if(HAL_IS_BIT_SET(Device->BTCR[FMC_NORSRAM_BANK1], FMC_BCR1_CCLKEN))
302 tmpr = (uint32_t)(Device->BTCR[FMC_NORSRAM_BANK1 + 1] & ~(((uint32_t)0x0F) << 20));
303 tmpr |= (uint32_t)(((Timing->CLKDivision)-1) << 20);
304 Device->BTCR[FMC_NORSRAM_BANK1 + 1] = tmpr;
307 return HAL_OK;
311 * @brief Initialize the FMC_NORSRAM Extended mode Timing according to the specified
312 * parameters in the FMC_NORSRAM_TimingTypeDef
313 * @param Device: Pointer to NORSRAM device instance
314 * @param Timing: Pointer to NORSRAM Timing structure
315 * @param Bank: NORSRAM bank number
316 * @retval HAL status
318 HAL_StatusTypeDef FMC_NORSRAM_Extended_Timing_Init(FMC_NORSRAM_EXTENDED_TypeDef *Device, FMC_NORSRAM_TimingTypeDef *Timing, uint32_t Bank, uint32_t ExtendedMode)
320 uint32_t tmpr = 0;
322 /* Check the parameters */
323 assert_param(IS_FMC_EXTENDED_MODE(ExtendedMode));
325 /* Set NORSRAM device timing register for write configuration, if extended mode is used */
326 if(ExtendedMode == FMC_EXTENDED_MODE_ENABLE)
328 /* Check the parameters */
329 assert_param(IS_FMC_NORSRAM_EXTENDED_DEVICE(Device));
330 assert_param(IS_FMC_ADDRESS_SETUP_TIME(Timing->AddressSetupTime));
331 assert_param(IS_FMC_ADDRESS_HOLD_TIME(Timing->AddressHoldTime));
332 assert_param(IS_FMC_DATASETUP_TIME(Timing->DataSetupTime));
333 assert_param(IS_FMC_TURNAROUND_TIME(Timing->BusTurnAroundDuration));
334 assert_param(IS_FMC_CLK_DIV(Timing->CLKDivision));
335 assert_param(IS_FMC_DATA_LATENCY(Timing->DataLatency));
336 assert_param(IS_FMC_ACCESS_MODE(Timing->AccessMode));
337 assert_param(IS_FMC_NORSRAM_BANK(Bank));
339 /* Get the BWTR register value */
340 tmpr = Device->BWTR[Bank];
342 /* Clear ADDSET, ADDHLD, DATAST, BUSTURN, CLKDIV, DATLAT and ACCMOD bits */
343 tmpr &= ((uint32_t)~(FMC_BWTR1_ADDSET | FMC_BWTR1_ADDHLD | FMC_BWTR1_DATAST | \
344 FMC_BWTR1_BUSTURN | FMC_BWTR1_ACCMOD));
346 tmpr |= (uint32_t)(Timing->AddressSetupTime |\
347 ((Timing->AddressHoldTime) << 4) |\
348 ((Timing->DataSetupTime) << 8) |\
349 ((Timing->BusTurnAroundDuration) << 16) |\
350 (Timing->AccessMode));
352 Device->BWTR[Bank] = tmpr;
354 else
356 Device->BWTR[Bank] = 0x0FFFFFFF;
359 return HAL_OK;
362 * @}
365 /** @addtogroup FMC_LL_NORSRAM_Private_Functions_Group2
366 * @brief management functions
368 @verbatim
369 ==============================================================================
370 ##### FMC_NORSRAM Control functions #####
371 ==============================================================================
372 [..]
373 This subsection provides a set of functions allowing to control dynamically
374 the FMC NORSRAM interface.
376 @endverbatim
377 * @{
381 * @brief Enables dynamically FMC_NORSRAM write operation.
382 * @param Device: Pointer to NORSRAM device instance
383 * @param Bank: NORSRAM bank number
384 * @retval HAL status
386 HAL_StatusTypeDef FMC_NORSRAM_WriteOperation_Enable(FMC_NORSRAM_TypeDef *Device, uint32_t Bank)
388 /* Check the parameters */
389 assert_param(IS_FMC_NORSRAM_DEVICE(Device));
390 assert_param(IS_FMC_NORSRAM_BANK(Bank));
392 /* Enable write operation */
393 Device->BTCR[Bank] |= FMC_WRITE_OPERATION_ENABLE;
395 return HAL_OK;
399 * @brief Disables dynamically FMC_NORSRAM write operation.
400 * @param Device: Pointer to NORSRAM device instance
401 * @param Bank: NORSRAM bank number
402 * @retval HAL status
404 HAL_StatusTypeDef FMC_NORSRAM_WriteOperation_Disable(FMC_NORSRAM_TypeDef *Device, uint32_t Bank)
406 /* Check the parameters */
407 assert_param(IS_FMC_NORSRAM_DEVICE(Device));
408 assert_param(IS_FMC_NORSRAM_BANK(Bank));
410 /* Disable write operation */
411 Device->BTCR[Bank] &= ~FMC_WRITE_OPERATION_ENABLE;
413 return HAL_OK;
417 * @}
421 * @}
424 /** @defgroup FMC_LL_Exported_Functions_NAND FMC Low Layer NAND Exported Functions
425 * @brief NAND Controller functions
427 @verbatim
428 ==============================================================================
429 ##### How to use NAND device driver #####
430 ==============================================================================
431 [..]
432 This driver contains a set of APIs to interface with the FMC NAND banks in order
433 to run the NAND external devices.
435 (+) FMC NAND bank reset using the function FMC_NAND_DeInit()
436 (+) FMC NAND bank control configuration using the function FMC_NAND_Init()
437 (+) FMC NAND bank common space timing configuration using the function
438 FMC_NAND_CommonSpace_Timing_Init()
439 (+) FMC NAND bank attribute space timing configuration using the function
440 FMC_NAND_AttributeSpace_Timing_Init()
441 (+) FMC NAND bank enable/disable ECC correction feature using the functions
442 FMC_NAND_ECC_Enable()/FMC_NAND_ECC_Disable()
443 (+) FMC NAND bank get ECC correction code using the function FMC_NAND_GetECC()
445 @endverbatim
446 * @{
449 /** @defgroup FMC_LL_NAND_Exported_Functions_Group1 Initialization and de-initialization functions
450 * @brief Initialization and Configuration functions
452 @verbatim
453 ==============================================================================
454 ##### Initialization and de_initialization functions #####
455 ==============================================================================
456 [..]
457 This section provides functions allowing to:
458 (+) Initialize and configure the FMC NAND interface
459 (+) De-initialize the FMC NAND interface
460 (+) Configure the FMC clock and associated GPIOs
462 @endverbatim
463 * @{
467 * @brief Initializes the FMC_NAND device according to the specified
468 * control parameters in the FMC_NAND_HandleTypeDef
469 * @param Device: Pointer to NAND device instance
470 * @param Init: Pointer to NAND Initialization structure
471 * @retval HAL status
473 HAL_StatusTypeDef FMC_NAND_Init(FMC_NAND_TypeDef *Device, FMC_NAND_InitTypeDef *Init)
475 uint32_t tmpr = 0;
477 /* Check the parameters */
478 assert_param(IS_FMC_NAND_DEVICE(Device));
479 assert_param(IS_FMC_NAND_BANK(Init->NandBank));
480 assert_param(IS_FMC_WAIT_FEATURE(Init->Waitfeature));
481 assert_param(IS_FMC_NAND_MEMORY_WIDTH(Init->MemoryDataWidth));
482 assert_param(IS_FMC_ECC_STATE(Init->EccComputation));
483 assert_param(IS_FMC_ECCPAGE_SIZE(Init->ECCPageSize));
484 assert_param(IS_FMC_TCLR_TIME(Init->TCLRSetupTime));
485 assert_param(IS_FMC_TAR_TIME(Init->TARSetupTime));
487 /* Get the NAND bank 3 register value */
488 tmpr = Device->PCR;
490 /* Clear PWAITEN, PBKEN, PTYP, PWID, ECCEN, TCLR, TAR and ECCPS bits */
491 tmpr &= ((uint32_t)~(FMC_PCR_PWAITEN | FMC_PCR_PBKEN | FMC_PCR_PTYP | \
492 FMC_PCR_PWID | FMC_PCR_ECCEN | FMC_PCR_TCLR | \
493 FMC_PCR_TAR | FMC_PCR_ECCPS));
494 /* Set NAND device control parameters */
495 tmpr |= (uint32_t)(Init->Waitfeature |\
496 FMC_PCR_MEMORY_TYPE_NAND |\
497 Init->MemoryDataWidth |\
498 Init->EccComputation |\
499 Init->ECCPageSize |\
500 ((Init->TCLRSetupTime) << 9) |\
501 ((Init->TARSetupTime) << 13));
503 /* NAND bank 3 registers configuration */
504 Device->PCR = tmpr;
506 return HAL_OK;
511 * @brief Initializes the FMC_NAND Common space Timing according to the specified
512 * parameters in the FMC_NAND_PCC_TimingTypeDef
513 * @param Device: Pointer to NAND device instance
514 * @param Timing: Pointer to NAND timing structure
515 * @param Bank: NAND bank number
516 * @retval HAL status
518 HAL_StatusTypeDef FMC_NAND_CommonSpace_Timing_Init(FMC_NAND_TypeDef *Device, FMC_NAND_PCC_TimingTypeDef *Timing, uint32_t Bank)
520 uint32_t tmpr = 0;
522 /* Check the parameters */
523 assert_param(IS_FMC_NAND_DEVICE(Device));
524 assert_param(IS_FMC_SETUP_TIME(Timing->SetupTime));
525 assert_param(IS_FMC_WAIT_TIME(Timing->WaitSetupTime));
526 assert_param(IS_FMC_HOLD_TIME(Timing->HoldSetupTime));
527 assert_param(IS_FMC_HIZ_TIME(Timing->HiZSetupTime));
528 assert_param(IS_FMC_NAND_BANK(Bank));
530 /* Get the NAND bank 3 register value */
531 tmpr = Device->PMEM;
533 /* Clear MEMSETx, MEMWAITx, MEMHOLDx and MEMHIZx bits */
534 tmpr &= ((uint32_t)~(FMC_PMEM_MEMSET3 | FMC_PMEM_MEMWAIT3 | FMC_PMEM_MEMHOLD3 | \
535 FMC_PMEM_MEMHIZ3));
536 /* Set FMC_NAND device timing parameters */
537 tmpr |= (uint32_t)(Timing->SetupTime |\
538 ((Timing->WaitSetupTime) << 8) |\
539 ((Timing->HoldSetupTime) << 16) |\
540 ((Timing->HiZSetupTime) << 24)
543 /* NAND bank 3 registers configuration */
544 Device->PMEM = tmpr;
546 return HAL_OK;
550 * @brief Initializes the FMC_NAND Attribute space Timing according to the specified
551 * parameters in the FMC_NAND_PCC_TimingTypeDef
552 * @param Device: Pointer to NAND device instance
553 * @param Timing: Pointer to NAND timing structure
554 * @param Bank: NAND bank number
555 * @retval HAL status
557 HAL_StatusTypeDef FMC_NAND_AttributeSpace_Timing_Init(FMC_NAND_TypeDef *Device, FMC_NAND_PCC_TimingTypeDef *Timing, uint32_t Bank)
559 uint32_t tmpr = 0;
561 /* Check the parameters */
562 assert_param(IS_FMC_NAND_DEVICE(Device));
563 assert_param(IS_FMC_SETUP_TIME(Timing->SetupTime));
564 assert_param(IS_FMC_WAIT_TIME(Timing->WaitSetupTime));
565 assert_param(IS_FMC_HOLD_TIME(Timing->HoldSetupTime));
566 assert_param(IS_FMC_HIZ_TIME(Timing->HiZSetupTime));
567 assert_param(IS_FMC_NAND_BANK(Bank));
569 /* Get the NAND bank 3 register value */
570 tmpr = Device->PATT;
572 /* Clear ATTSETx, ATTWAITx, ATTHOLDx and ATTHIZx bits */
573 tmpr &= ((uint32_t)~(FMC_PATT_ATTSET3 | FMC_PATT_ATTWAIT3 | FMC_PATT_ATTHOLD3 | \
574 FMC_PATT_ATTHIZ3));
575 /* Set FMC_NAND device timing parameters */
576 tmpr |= (uint32_t)(Timing->SetupTime |\
577 ((Timing->WaitSetupTime) << 8) |\
578 ((Timing->HoldSetupTime) << 16) |\
579 ((Timing->HiZSetupTime) << 24));
581 /* NAND bank 3 registers configuration */
582 Device->PATT = tmpr;
584 return HAL_OK;
588 * @brief DeInitializes the FMC_NAND device
589 * @param Device: Pointer to NAND device instance
590 * @param Bank: NAND bank number
591 * @retval HAL status
593 HAL_StatusTypeDef FMC_NAND_DeInit(FMC_NAND_TypeDef *Device, uint32_t Bank)
595 /* Check the parameters */
596 assert_param(IS_FMC_NAND_DEVICE(Device));
597 assert_param(IS_FMC_NAND_BANK(Bank));
599 /* Disable the NAND Bank */
600 __FMC_NAND_DISABLE(Device);
602 /* Set the FMC_NAND_BANK3 registers to their reset values */
603 Device->PCR = 0x00000018U;
604 Device->SR = 0x00000040U;
605 Device->PMEM = 0xFCFCFCFCU;
606 Device->PATT = 0xFCFCFCFCU;
608 return HAL_OK;
612 * @}
615 /** @defgroup HAL_FMC_NAND_Group3 Control functions
616 * @brief management functions
618 @verbatim
619 ==============================================================================
620 ##### FMC_NAND Control functions #####
621 ==============================================================================
622 [..]
623 This subsection provides a set of functions allowing to control dynamically
624 the FMC NAND interface.
626 @endverbatim
627 * @{
632 * @brief Enables dynamically FMC_NAND ECC feature.
633 * @param Device: Pointer to NAND device instance
634 * @param Bank: NAND bank number
635 * @retval HAL status
637 HAL_StatusTypeDef FMC_NAND_ECC_Enable(FMC_NAND_TypeDef *Device, uint32_t Bank)
639 /* Check the parameters */
640 assert_param(IS_FMC_NAND_DEVICE(Device));
641 assert_param(IS_FMC_NAND_BANK(Bank));
643 /* Enable ECC feature */
644 Device->PCR |= FMC_PCR_ECCEN;
646 return HAL_OK;
651 * @brief Disables dynamically FMC_NAND ECC feature.
652 * @param Device: Pointer to NAND device instance
653 * @param Bank: NAND bank number
654 * @retval HAL status
656 HAL_StatusTypeDef FMC_NAND_ECC_Disable(FMC_NAND_TypeDef *Device, uint32_t Bank)
658 /* Check the parameters */
659 assert_param(IS_FMC_NAND_DEVICE(Device));
660 assert_param(IS_FMC_NAND_BANK(Bank));
662 /* Disable ECC feature */
663 Device->PCR &= ~FMC_PCR_ECCEN;
665 return HAL_OK;
669 * @brief Disables dynamically FMC_NAND ECC feature.
670 * @param Device: Pointer to NAND device instance
671 * @param ECCval: Pointer to ECC value
672 * @param Bank: NAND bank number
673 * @param Timeout: Timeout wait value
674 * @retval HAL status
676 HAL_StatusTypeDef FMC_NAND_GetECC(FMC_NAND_TypeDef *Device, uint32_t *ECCval, uint32_t Bank, uint32_t Timeout)
678 uint32_t tickstart = 0;
680 /* Check the parameters */
681 assert_param(IS_FMC_NAND_DEVICE(Device));
682 assert_param(IS_FMC_NAND_BANK(Bank));
684 /* Get tick */
685 tickstart = HAL_GetTick();
687 /* Wait until FIFO is empty */
688 while(__FMC_NAND_GET_FLAG(Device, Bank, FMC_FLAG_FEMPT) == RESET)
690 /* Check for the Timeout */
691 if(Timeout != HAL_MAX_DELAY)
693 if((Timeout == 0)||((HAL_GetTick() - tickstart ) > Timeout))
695 return HAL_TIMEOUT;
700 /* Get the ECCR register value */
701 *ECCval = (uint32_t)Device->ECCR;
703 return HAL_OK;
707 * @}
711 * @}
714 /** @defgroup FMC_LL_SDRAM
715 * @brief SDRAM Controller functions
717 @verbatim
718 ==============================================================================
719 ##### How to use SDRAM device driver #####
720 ==============================================================================
721 [..]
722 This driver contains a set of APIs to interface with the FMC SDRAM banks in order
723 to run the SDRAM external devices.
725 (+) FMC SDRAM bank reset using the function FMC_SDRAM_DeInit()
726 (+) FMC SDRAM bank control configuration using the function FMC_SDRAM_Init()
727 (+) FMC SDRAM bank timing configuration using the function FMC_SDRAM_Timing_Init()
728 (+) FMC SDRAM bank enable/disable write operation using the functions
729 FMC_SDRAM_WriteOperation_Enable()/FMC_SDRAM_WriteOperation_Disable()
730 (+) FMC SDRAM bank send command using the function FMC_SDRAM_SendCommand()
732 @endverbatim
733 * @{
736 /** @addtogroup FMC_LL_SDRAM_Private_Functions_Group1
737 * @brief Initialization and Configuration functions
739 @verbatim
740 ==============================================================================
741 ##### Initialization and de_initialization functions #####
742 ==============================================================================
743 [..]
744 This section provides functions allowing to:
745 (+) Initialize and configure the FMC SDRAM interface
746 (+) De-initialize the FMC SDRAM interface
747 (+) Configure the FMC clock and associated GPIOs
749 @endverbatim
750 * @{
754 * @brief Initializes the FMC_SDRAM device according to the specified
755 * control parameters in the FMC_SDRAM_InitTypeDef
756 * @param Device: Pointer to SDRAM device instance
757 * @param Init: Pointer to SDRAM Initialization structure
758 * @retval HAL status
760 HAL_StatusTypeDef FMC_SDRAM_Init(FMC_SDRAM_TypeDef *Device, FMC_SDRAM_InitTypeDef *Init)
762 uint32_t tmpr1 = 0;
763 uint32_t tmpr2 = 0;
765 /* Check the parameters */
766 assert_param(IS_FMC_SDRAM_DEVICE(Device));
767 assert_param(IS_FMC_SDRAM_BANK(Init->SDBank));
768 assert_param(IS_FMC_COLUMNBITS_NUMBER(Init->ColumnBitsNumber));
769 assert_param(IS_FMC_ROWBITS_NUMBER(Init->RowBitsNumber));
770 assert_param(IS_FMC_SDMEMORY_WIDTH(Init->MemoryDataWidth));
771 assert_param(IS_FMC_INTERNALBANK_NUMBER(Init->InternalBankNumber));
772 assert_param(IS_FMC_CAS_LATENCY(Init->CASLatency));
773 assert_param(IS_FMC_WRITE_PROTECTION(Init->WriteProtection));
774 assert_param(IS_FMC_SDCLOCK_PERIOD(Init->SDClockPeriod));
775 assert_param(IS_FMC_READ_BURST(Init->ReadBurst));
776 assert_param(IS_FMC_READPIPE_DELAY(Init->ReadPipeDelay));
778 /* Set SDRAM bank configuration parameters */
779 if (Init->SDBank != FMC_SDRAM_BANK2)
781 tmpr1 = Device->SDCR[FMC_SDRAM_BANK1];
783 /* Clear NC, NR, MWID, NB, CAS, WP, SDCLK, RBURST, and RPIPE bits */
784 tmpr1 &= ((uint32_t)~(FMC_SDCR1_NC | FMC_SDCR1_NR | FMC_SDCR1_MWID | \
785 FMC_SDCR1_NB | FMC_SDCR1_CAS | FMC_SDCR1_WP | \
786 FMC_SDCR1_SDCLK | FMC_SDCR1_RBURST | FMC_SDCR1_RPIPE));
788 tmpr1 |= (uint32_t)(Init->ColumnBitsNumber |\
789 Init->RowBitsNumber |\
790 Init->MemoryDataWidth |\
791 Init->InternalBankNumber |\
792 Init->CASLatency |\
793 Init->WriteProtection |\
794 Init->SDClockPeriod |\
795 Init->ReadBurst |\
796 Init->ReadPipeDelay
798 Device->SDCR[FMC_SDRAM_BANK1] = tmpr1;
800 else /* FMC_Bank2_SDRAM */
802 tmpr1 = Device->SDCR[FMC_SDRAM_BANK1];
804 /* Clear SDCLK, RBURST, and RPIPE bits */
805 tmpr1 &= ((uint32_t)~(FMC_SDCR1_SDCLK | FMC_SDCR1_RBURST | FMC_SDCR1_RPIPE));
807 tmpr1 |= (uint32_t)(Init->SDClockPeriod |\
808 Init->ReadBurst |\
809 Init->ReadPipeDelay);
811 tmpr2 = Device->SDCR[FMC_SDRAM_BANK2];
813 /* Clear NC, NR, MWID, NB, CAS, WP, SDCLK, RBURST, and RPIPE bits */
814 tmpr2 &= ((uint32_t)~(FMC_SDCR1_NC | FMC_SDCR1_NR | FMC_SDCR1_MWID | \
815 FMC_SDCR1_NB | FMC_SDCR1_CAS | FMC_SDCR1_WP | \
816 FMC_SDCR1_SDCLK | FMC_SDCR1_RBURST | FMC_SDCR1_RPIPE));
818 tmpr2 |= (uint32_t)(Init->ColumnBitsNumber |\
819 Init->RowBitsNumber |\
820 Init->MemoryDataWidth |\
821 Init->InternalBankNumber |\
822 Init->CASLatency |\
823 Init->WriteProtection);
825 Device->SDCR[FMC_SDRAM_BANK1] = tmpr1;
826 Device->SDCR[FMC_SDRAM_BANK2] = tmpr2;
829 return HAL_OK;
834 * @brief Initializes the FMC_SDRAM device timing according to the specified
835 * parameters in the FMC_SDRAM_TimingTypeDef
836 * @param Device: Pointer to SDRAM device instance
837 * @param Timing: Pointer to SDRAM Timing structure
838 * @param Bank: SDRAM bank number
839 * @retval HAL status
841 HAL_StatusTypeDef FMC_SDRAM_Timing_Init(FMC_SDRAM_TypeDef *Device, FMC_SDRAM_TimingTypeDef *Timing, uint32_t Bank)
843 uint32_t tmpr1 = 0;
844 uint32_t tmpr2 = 0;
846 /* Check the parameters */
847 assert_param(IS_FMC_SDRAM_DEVICE(Device));
848 assert_param(IS_FMC_LOADTOACTIVE_DELAY(Timing->LoadToActiveDelay));
849 assert_param(IS_FMC_EXITSELFREFRESH_DELAY(Timing->ExitSelfRefreshDelay));
850 assert_param(IS_FMC_SELFREFRESH_TIME(Timing->SelfRefreshTime));
851 assert_param(IS_FMC_ROWCYCLE_DELAY(Timing->RowCycleDelay));
852 assert_param(IS_FMC_WRITE_RECOVERY_TIME(Timing->WriteRecoveryTime));
853 assert_param(IS_FMC_RP_DELAY(Timing->RPDelay));
854 assert_param(IS_FMC_RCD_DELAY(Timing->RCDDelay));
855 assert_param(IS_FMC_SDRAM_BANK(Bank));
857 /* Set SDRAM device timing parameters */
858 if (Bank != FMC_SDRAM_BANK2)
860 tmpr1 = Device->SDTR[FMC_SDRAM_BANK1];
862 /* Clear TMRD, TXSR, TRAS, TRC, TWR, TRP and TRCD bits */
863 tmpr1 &= ((uint32_t)~(FMC_SDTR1_TMRD | FMC_SDTR1_TXSR | FMC_SDTR1_TRAS | \
864 FMC_SDTR1_TRC | FMC_SDTR1_TWR | FMC_SDTR1_TRP | \
865 FMC_SDTR1_TRCD));
867 tmpr1 |= (uint32_t)(((Timing->LoadToActiveDelay)-1) |\
868 (((Timing->ExitSelfRefreshDelay)-1) << 4) |\
869 (((Timing->SelfRefreshTime)-1) << 8) |\
870 (((Timing->RowCycleDelay)-1) << 12) |\
871 (((Timing->WriteRecoveryTime)-1) <<16) |\
872 (((Timing->RPDelay)-1) << 20) |\
873 (((Timing->RCDDelay)-1) << 24));
874 Device->SDTR[FMC_SDRAM_BANK1] = tmpr1;
876 else /* FMC_Bank2_SDRAM */
878 tmpr1 = Device->SDTR[FMC_SDRAM_BANK1];
880 /* Clear TRC and TRP bits */
881 tmpr1 &= ((uint32_t)~(FMC_SDTR1_TRC | FMC_SDTR1_TRP));
883 tmpr1 |= (uint32_t)((((Timing->RowCycleDelay)-1) << 12) |\
884 (((Timing->RPDelay)-1) << 20));
886 tmpr2 = Device->SDTR[FMC_SDRAM_BANK2];
888 /* Clear TMRD, TXSR, TRAS, TRC, TWR, TRP and TRCD bits */
889 tmpr2 &= ((uint32_t)~(FMC_SDTR1_TMRD | FMC_SDTR1_TXSR | FMC_SDTR1_TRAS | \
890 FMC_SDTR1_TRC | FMC_SDTR1_TWR | FMC_SDTR1_TRP | \
891 FMC_SDTR1_TRCD));
893 tmpr2 |= (uint32_t)(((Timing->LoadToActiveDelay)-1) |\
894 (((Timing->ExitSelfRefreshDelay)-1) << 4) |\
895 (((Timing->SelfRefreshTime)-1) << 8) |\
896 (((Timing->WriteRecoveryTime)-1) <<16) |\
897 (((Timing->RCDDelay)-1) << 24));
899 Device->SDTR[FMC_SDRAM_BANK1] = tmpr1;
900 Device->SDTR[FMC_SDRAM_BANK2] = tmpr2;
903 return HAL_OK;
907 * @brief DeInitializes the FMC_SDRAM peripheral
908 * @param Device: Pointer to SDRAM device instance
909 * @retval HAL status
911 HAL_StatusTypeDef FMC_SDRAM_DeInit(FMC_SDRAM_TypeDef *Device, uint32_t Bank)
913 /* Check the parameters */
914 assert_param(IS_FMC_SDRAM_DEVICE(Device));
915 assert_param(IS_FMC_SDRAM_BANK(Bank));
917 /* De-initialize the SDRAM device */
918 Device->SDCR[Bank] = 0x000002D0;
919 Device->SDTR[Bank] = 0x0FFFFFFF;
920 Device->SDCMR = 0x00000000;
921 Device->SDRTR = 0x00000000;
922 Device->SDSR = 0x00000000;
924 return HAL_OK;
928 * @}
931 /** @addtogroup FMC_LL_SDRAMPrivate_Functions_Group2
932 * @brief management functions
934 @verbatim
935 ==============================================================================
936 ##### FMC_SDRAM Control functions #####
937 ==============================================================================
938 [..]
939 This subsection provides a set of functions allowing to control dynamically
940 the FMC SDRAM interface.
942 @endverbatim
943 * @{
947 * @brief Enables dynamically FMC_SDRAM write protection.
948 * @param Device: Pointer to SDRAM device instance
949 * @param Bank: SDRAM bank number
950 * @retval HAL status
952 HAL_StatusTypeDef FMC_SDRAM_WriteProtection_Enable(FMC_SDRAM_TypeDef *Device, uint32_t Bank)
954 /* Check the parameters */
955 assert_param(IS_FMC_SDRAM_DEVICE(Device));
956 assert_param(IS_FMC_SDRAM_BANK(Bank));
958 /* Enable write protection */
959 Device->SDCR[Bank] |= FMC_SDRAM_WRITE_PROTECTION_ENABLE;
961 return HAL_OK;
965 * @brief Disables dynamically FMC_SDRAM write protection.
966 * @param hsdram: FMC_SDRAM handle
967 * @retval HAL status
969 HAL_StatusTypeDef FMC_SDRAM_WriteProtection_Disable(FMC_SDRAM_TypeDef *Device, uint32_t Bank)
971 /* Check the parameters */
972 assert_param(IS_FMC_SDRAM_DEVICE(Device));
973 assert_param(IS_FMC_SDRAM_BANK(Bank));
975 /* Disable write protection */
976 Device->SDCR[Bank] &= ~FMC_SDRAM_WRITE_PROTECTION_ENABLE;
978 return HAL_OK;
982 * @brief Send Command to the FMC SDRAM bank
983 * @param Device: Pointer to SDRAM device instance
984 * @param Command: Pointer to SDRAM command structure
985 * @param Timing: Pointer to SDRAM Timing structure
986 * @param Timeout: Timeout wait value
987 * @retval HAL state
989 HAL_StatusTypeDef FMC_SDRAM_SendCommand(FMC_SDRAM_TypeDef *Device, FMC_SDRAM_CommandTypeDef *Command, uint32_t Timeout)
991 __IO uint32_t tmpr = 0;
992 uint32_t tickstart = 0;
994 /* Check the parameters */
995 assert_param(IS_FMC_SDRAM_DEVICE(Device));
996 assert_param(IS_FMC_COMMAND_MODE(Command->CommandMode));
997 assert_param(IS_FMC_COMMAND_TARGET(Command->CommandTarget));
998 assert_param(IS_FMC_AUTOREFRESH_NUMBER(Command->AutoRefreshNumber));
999 assert_param(IS_FMC_MODE_REGISTER(Command->ModeRegisterDefinition));
1001 /* Set command register */
1002 tmpr = (uint32_t)((Command->CommandMode) |\
1003 (Command->CommandTarget) |\
1004 (((Command->AutoRefreshNumber)-1) << 5) |\
1005 ((Command->ModeRegisterDefinition) << 9)
1008 Device->SDCMR = tmpr;
1010 /* Get tick */
1011 tickstart = HAL_GetTick();
1013 /* wait until command is send */
1014 while(HAL_IS_BIT_SET(Device->SDSR, FMC_SDSR_BUSY))
1016 /* Check for the Timeout */
1017 if(Timeout != HAL_MAX_DELAY)
1019 if((Timeout == 0)||((HAL_GetTick() - tickstart ) > Timeout))
1021 return HAL_TIMEOUT;
1026 return HAL_OK;
1030 * @brief Program the SDRAM Memory Refresh rate.
1031 * @param Device: Pointer to SDRAM device instance
1032 * @param RefreshRate: The SDRAM refresh rate value.
1033 * @retval HAL state
1035 HAL_StatusTypeDef FMC_SDRAM_ProgramRefreshRate(FMC_SDRAM_TypeDef *Device, uint32_t RefreshRate)
1037 /* Check the parameters */
1038 assert_param(IS_FMC_SDRAM_DEVICE(Device));
1039 assert_param(IS_FMC_REFRESH_RATE(RefreshRate));
1041 /* Set the refresh rate in command register */
1042 Device->SDRTR |= (RefreshRate<<1);
1044 return HAL_OK;
1048 * @brief Set the Number of consecutive SDRAM Memory auto Refresh commands.
1049 * @param Device: Pointer to SDRAM device instance
1050 * @param AutoRefreshNumber: Specifies the auto Refresh number.
1051 * @retval None
1053 HAL_StatusTypeDef FMC_SDRAM_SetAutoRefreshNumber(FMC_SDRAM_TypeDef *Device, uint32_t AutoRefreshNumber)
1055 /* Check the parameters */
1056 assert_param(IS_FMC_SDRAM_DEVICE(Device));
1057 assert_param(IS_FMC_AUTOREFRESH_NUMBER(AutoRefreshNumber));
1059 /* Set the Auto-refresh number in command register */
1060 Device->SDCMR |= (AutoRefreshNumber << 5);
1062 return HAL_OK;
1066 * @brief Returns the indicated FMC SDRAM bank mode status.
1067 * @param Device: Pointer to SDRAM device instance
1068 * @param Bank: Defines the FMC SDRAM bank. This parameter can be
1069 * FMC_Bank1_SDRAM or FMC_Bank2_SDRAM.
1070 * @retval The FMC SDRAM bank mode status, could be on of the following values:
1071 * FMC_SDRAM_NORMAL_MODE, FMC_SDRAM_SELF_REFRESH_MODE or
1072 * FMC_SDRAM_POWER_DOWN_MODE.
1074 uint32_t FMC_SDRAM_GetModeStatus(FMC_SDRAM_TypeDef *Device, uint32_t Bank)
1076 uint32_t tmpreg = 0;
1078 /* Check the parameters */
1079 assert_param(IS_FMC_SDRAM_DEVICE(Device));
1080 assert_param(IS_FMC_SDRAM_BANK(Bank));
1082 /* Get the corresponding bank mode */
1083 if(Bank == FMC_SDRAM_BANK1)
1085 tmpreg = (uint32_t)(Device->SDSR & FMC_SDSR_MODES1);
1087 else
1089 tmpreg = ((uint32_t)(Device->SDSR & FMC_SDSR_MODES2) >> 2);
1092 /* Return the mode status */
1093 return tmpreg;
1097 * @}
1101 * @}
1105 * @}
1107 #endif /* HAL_SRAM_MODULE_ENABLED || HAL_NOR_MODULE_ENABLED || HAL_NAND_MODULE_ENABLED || HAL_SDRAM_MODULE_ENABLED */
1110 * @}
1114 * @}
1117 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/