summaryrefslogtreecommitdiff
path: root/nuttx/configs/sama5d3x-ek
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2013-08-01 16:58:55 -0600
committerGregory Nutt <gnutt@nuttx.org>2013-08-01 16:58:55 -0600
commit5b9a446aec5dfd38e1f4db42851137cf684d0d00 (patch)
tree52ff2a9d085669f03e593f3f11d40a44172c9b96 /nuttx/configs/sama5d3x-ek
parentc220e9234abb367ff8db2426a2563e3b124b1e97 (diff)
downloadpx4-nuttx-5b9a446aec5dfd38e1f4db42851137cf684d0d00.tar.gz
px4-nuttx-5b9a446aec5dfd38e1f4db42851137cf684d0d00.tar.bz2
px4-nuttx-5b9a446aec5dfd38e1f4db42851137cf684d0d00.zip
SAMA5: Add logic to initialize SAMA5D3x-EK on-board SDRAM
Diffstat (limited to 'nuttx/configs/sama5d3x-ek')
-rw-r--r--nuttx/configs/sama5d3x-ek/src/Makefile4
-rw-r--r--nuttx/configs/sama5d3x-ek/src/sam_norflash.c33
-rw-r--r--nuttx/configs/sama5d3x-ek/src/sam_sdram.c548
-rw-r--r--nuttx/configs/sama5d3x-ek/src/sama5d3x-ek.h31
4 files changed, 603 insertions, 13 deletions
diff --git a/nuttx/configs/sama5d3x-ek/src/Makefile b/nuttx/configs/sama5d3x-ek/src/Makefile
index 1ae5ae4cf..7e94a01ee 100644
--- a/nuttx/configs/sama5d3x-ek/src/Makefile
+++ b/nuttx/configs/sama5d3x-ek/src/Makefile
@@ -46,6 +46,10 @@ ifeq ($(CONFIG_HAVE_CXX),y)
CSRCS += sam_cxxinitialize.c
endif
+ifeq ($(CONFIG_SAMA5_DDRCS),y)
+CSRCS += sam_sdram.c
+endif
+
ifeq ($(CONFIG_SAMA5_BOOT_CS0FLASH),y)
CSRCS += sam_norflash.c
endif
diff --git a/nuttx/configs/sama5d3x-ek/src/sam_norflash.c b/nuttx/configs/sama5d3x-ek/src/sam_norflash.c
index 3604dcfc2..1b4ff0c3f 100644
--- a/nuttx/configs/sama5d3x-ek/src/sam_norflash.c
+++ b/nuttx/configs/sama5d3x-ek/src/sam_norflash.c
@@ -1,9 +1,16 @@
-/************************************************************************************
+/****************************************************************************
* configs/sama5d3x-ek/src/sam_norflash.c
*
* Copyright (C) 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
+ * Most of this file derives from Atmel sample code for the SAMA5D3x-EK
+ * board. That sample code has licensing that is compatible with the NuttX
+ * modified BSD license:
+ *
+ * Copyright (c) 2012, Atmel Corporation
+ * All rights reserved.
+ *
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
@@ -14,8 +21,8 @@
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
- * 3. Neither the name NuttX nor the names of its contributors may be
- * used to endorse or promote products derived from this software
+ * 3. Neither the name NuttX nor Atmel nor the names of its contributors may
+ * be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
@@ -31,11 +38,11 @@
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
- ************************************************************************************/
+ ****************************************************************************/
-/************************************************************************************
+/****************************************************************************
* Included Files
- ************************************************************************************/
+ ****************************************************************************/
#include <nuttx/config.h>
@@ -49,17 +56,17 @@
#ifdef CONFIG_SAMA5_BOOT_CS0FLASH
-/************************************************************************************
- * Definitions
- ************************************************************************************/
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
-/************************************************************************************
+/****************************************************************************
* Private Functions
- ************************************************************************************/
+ ****************************************************************************/
-/************************************************************************************
+/****************************************************************************
* Public Functions
- ************************************************************************************/
+ ****************************************************************************/
/****************************************************************************
* Name: board_norflash_config
diff --git a/nuttx/configs/sama5d3x-ek/src/sam_sdram.c b/nuttx/configs/sama5d3x-ek/src/sam_sdram.c
new file mode 100644
index 000000000..71b9748dd
--- /dev/null
+++ b/nuttx/configs/sama5d3x-ek/src/sam_sdram.c
@@ -0,0 +1,548 @@
+/****************************************************************************
+ * configs/sama5d3x-ek/src/sam_sdram.c
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Most of this file derives from Atmel sample code for the SAMA5D3x-E
+ * board. That sample code has licensing that is compatible with the NuttX
+ * modified BSD license:
+ *
+ * Copyright (c) 2012, Atmel Corporation
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor Atmel nor the names of its contributors may
+ * be used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <debug.h>
+
+#include "up_arch.h"
+
+#include "sam_periphclks.h"
+#incldue "chip/sam_memorymap.h"
+#include "chip/sam_pmc.h"
+#include "chip/sam_sfr.h"
+
+#include "sama5d3x-ek.h"
+
+/* This file requires:
+ *
+ * CONFIG_SAMA5_DDRCS -- DRAM support is enabled, and
+ * !CONFIG_SAMA5_BOOT_SDRAM - We did not boot into SRAM, and
+ * !CONFIG_BOOT_RUNFROMSDRAM - We are not running from SDRAM.
+ */
+
+#if defined(CONFIG_SAMA5_DDRCS) && !defined(CONFIG_SAMA5_BOOT_SDRAM) && \
+ !defined(CONFIG_BOOT_RUNFROMSDRAM)
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+/* Used for SDRAM command handshaking */
+
+#define DDR2_BA0(r) (1 << (25 + r))
+#define DDR2_BA1(r) (1 << (26 + r))
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: board_sdram_delay
+ *
+ * Description:
+ * Precision delay function for SDRAM configuration.
+ *
+ * This delay loop requires 6 core cycles per iteration. At 396MHz, that
+ * is equivalent to 15.1515 nanoseconds per iteration.
+ *
+ ****************************************************************************/
+
+static inline board_sdram_delay(unsigned int loops)
+{
+ volatile unsigned int i;
+
+ for (i = 0; i < loops; i++)
+ {
+ asm("nop");
+ }
+}
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: board_sdram_config
+ *
+ * Description:
+ * Configures DDR2 (MT47H128M16RT 128MB/ MT47H64M16HR)
+ *
+ * MT47H64M16HR : 8 Meg x 16 x 8 banks
+ * Refresh count: 8K
+ * Row address: A[12:0] (8K)
+ * Column address A[9:0] (1K)
+ * Bank address BA[2:0] a(24,25) (8)
+ *
+ * This logic was taken from Atmel sample code for the SAMA5D3x-EK.
+ *
+ * Input Parameters:
+ * devtype - Either DDRAM_MT47H128M16RT or DDRAM_MT47H64M16HR
+ *
+ * Assumptions:
+ * The DDR memory regions is configured as strongly ordered memory. When
+ * we complete initialization of SDRAM and it is ready for use, we will
+ * make DRAM into normal memory.
+ *
+ ************************************************************************************/
+
+void board_sdram_config(uint8_t sdramtype)
+{
+ volatile uint8_t *ddr = (uint8_t *)SAM_DDRCS_VSECTION;
+ uint32_t regval;
+
+ /* Enable x2 clocking to the MPDDRC */
+
+ sam_mpddrc_enableclk();
+
+ /* Enable DDR clocking */
+
+ regval = getreg32(SAM_PMC_SCER);
+ regval |= SAM_PMC_SCER;
+ putreg32(regval, SAM_PMC_SCER);
+
+ /* Clear the low power register */
+
+ putreg32(0, SAM_MPDDRC_LPR);
+
+ /* Enabled autofresh during calibration (undocumented) */
+
+ regval = getreg32(SAM_MPDDRC_HS);
+ regval |= MPDDRC_HS_AUTOREFRESH_CAL;
+ putreg32(regval, SAM_MPDDRC_HS);
+
+ /* Force DDR_DQ and DDR_DQS input buffer always on (undocumented) */
+
+ regval = getreg32(SAM_SFR_DDRCFG);
+ regval |= SFR_DDRCFG_DRQON;
+ putreg32(regval, SAM_SFR_DDRCFG);
+
+ /* Configure the slave offset register */
+
+ regval = MPDDRC_DLL_SOR_S0OFF(1) | /* DLL Slave 0 Delay Line Offset */
+ MPDDRC_DLL_SOR_S1OFF(0) | /* DLL Slave 1 Delay Line Offset */
+ MPDDRC_DLL_SOR_S2OFF(1) | /* DLL Slave 2 Delay Line Offset */
+ MPDDRC_DLL_SOR_S3OFF(1); /* DLL Slave 3 Delay Line Offset */
+ putreg32(regval, SAM_MPDDRC_DLL_SOR);
+
+ /* Configure the master offset register (including upper mystery bits) */
+
+ regval = MPDDRC_DLL_MOR_MOFF(7) | /* DLL Master Delay Line Offset */
+ MPDDRC_DLL_MOR_CLK90OFF(31) | /* DLL CLK90 Delay Line Offset */
+ MPDDRC_DLL_MOR_SELOFF | /* DLL Offset Selection */
+ MPDDRC_DLL_MOR_KEY | /* Undocumented key */
+ putreg32(regval, SAM_MPDDRC_DLL_MOR);
+
+ /* Configure the I/O calibration register */
+
+ regval = getreg32(SAM_MPDDRC_IO_CALIBR);
+ regval &= ~(MPDDRC_IO_CALIBR_RDIV_MASK | MPDDRC_IO_CALIBR_TZQIO_MASK);
+ regval |= (MPDDRC_IO_CALIBR_RZQ48_40 | MPDDRC_IO_CALIBR_TZQIO(3));
+ putreg(regval, SAM_MPDDRC_IO_CALIBR);
+
+ /* Force DDR_DQ and DDR_DQS input buffer always on, clearing other bits
+ * (undocumented)
+ */
+
+ putreg32(SFR_DDRCFG_DRQON, SAM_SFR_DDRCFG);
+
+ /* Step 1: Program the memory device type
+ *
+ * DBW = 0 (32-bit bus wide)
+ * Memory Device = DDR2-SDRAM
+ */
+
+ putreg32(MPDDRC_MD_DDR2_SDRAM, SAM_MPDDRC_MD);
+
+ /* Step 2: Program the features of DDR2-SDRAM device into the Timing
+ * Register
+ *
+ * For DDRAM_MT47H128M16RT
+ *
+ * NC = 10 DDR column bits
+ * NR = 14 DDR row bits
+ * CAS = DDR2/LPDDR2 CAS Latency 4
+ * DLL = Disable reset (0)
+ * DIC_DS = 0
+ * DIS_DLL = Enable PLL (0)
+ * ZQ = Calibration command after initialization (0)
+ * OCD = OCD calibration mode exit, maintain setting (0)
+ * DQMS = Not shared (0)
+ * ENDRM = Disable read measure (0)
+ * NB = 8 banks
+ * NDQS = Not DQS disabled
+ * DECODE = Sequential decoding (0)
+ * UNAL = Unaliged access supported
+ */
+
+ if (sdramtype == DDRAM_MT47H128M16RT)
+ {
+ regval = MPDDRC_CR_NC_10 | /* Number of Column Bits */
+ MPDDRC_CR_NR_14 | /* Number of Row Bits */
+ MPDDRC_CR_CAS_4 | /* CAS Latency */
+ MPDDRC_CR_OCD_EXIT | /* Off-chip Driver */
+ MPDDRC_CR_8BANKS | /* Number of Banks */
+ MPDDRC_CR_NDQS | /* Not DQS */
+ MPDDRC_CR_UNAL; /* upport Unaligned Access */
+ putreg32(regval, SAM_MPDDRC_CR);
+ }
+
+ /* For DDRAM_MT47H128M16RT
+ *
+ * NC = 10 DDR column bits
+ * NR = 13 DDR row bits
+ * CAS = DDR2/LPDDR2 CAS Latency 3
+ * DLL = Disable reset (0)
+ * DIC_DS = 0
+ * DIS_DLL = Enable PLL (0)
+ * ZQ = Calibration command after initialization (0)
+ * OCD = OCD calibration mode exit, maintain setting (0)
+ * DQMS = Not shared (0)
+ * ENDRM = Disable read measure (0)
+ * NB = 8 banks
+ * NDQS = Not DQS disabled
+ * DECODE = Sequential decoding (0)
+ * UNAL = Unaliged access supported
+ */
+
+ else if (sdramtype == DDRAM_MT47H64M16HR)
+ {
+ regval = MPDDRC_CR_NC_10 | /* Number of Column Bits */
+ MPDDRC_CR_NR_13 | /* Number of Row Bits */
+ MPDDRC_CR_CAS_3 | /* CAS Latency */
+ MPDDRC_CR_OCD_EXIT | /* Off-chip Driver */
+ MPDDRC_CR_8BANKS | /* Number of Banks */
+ MPDDRC_CR_NDQS | /* Not DQS */
+ MPDDRC_CR_UNAL; /* upport Unaligned Access */
+ putreg32(regval, SAM_MPDDRC_CR);
+ }
+
+ /* Configure the Timing Parameter 0 Register */
+
+ regval = MPDDRC_TPR0_TRAS(6) | /* Active to Precharge Delay: 6 * 7.5 = 45 ns */
+ MPDDRC_TPR0_TRCD(2) | /* Row to Column Delay: 2 * 7.5 = 15 ns */
+ MPDDRC_TPR0_TWR(2) | /* Write Recovery Delay: 3 * 7.5 = 22.5 ns */
+ MPDDRC_TPR0_TRC(8) | /* Row Cycle Delay: 8 * 7.5 = 60 ns */
+ MPDDRC_TPR0_TRP(2) | /* Row Precharge Delay: 2 * 7.5 = 15 ns */
+ MPDDRC_TPR0_TRRD(1) | /* Active BankA to Active BankB: 2 * 7.5 = 15 ns */
+ MPDDRC_TPR0_TWTR(2) | /* Internal Write to Read Delay: 2 clock cycle */
+ MPDDRC_TPR0_TMRD(2); /* Load Mode Register Command to
+ * Activate or Refresh Command: 2 clock cycles */
+ putreg32(regval, SAM_MPDDRC_TPR0);
+
+ /* Configure the Timing Parameter 1 Register */
+
+ regval = MPDDRC_TPR1_TRFC(14) | /* Row Cycle Delay:
+ * 18 * 7.5 = 135 ns (min 127.5 ns for 1Gb DDR) */
+ MPDDRC_TPR1_TXSNR(16) | /* Exit Self Refresh Delay to Non Read Command:
+ * 20 * 7.5 > 142.5ns TXSNR: Exit self refresh
+ * delay to non read command */
+ MPDDRC_TPR1_TXSRD(208) | /* Exit Self Refresh Delay to Read Command:
+ * min 200 clock cycles, TXSRD: Exit self refresh
+ * delay to Read command */
+ MPDDRC_TPR1_TXP(2); /* Exit Power-down Delay to First Command:
+ * 2 * 7.5 = 15 ns */
+ putreg32(regval, SAM_MPDDRC_TPR1);
+
+ /* Configure the Timing Parameter 2 Register */
+
+ regval = MPDDRC_TPR2_TXARD(7) | /* Exit Active Power Down Delay to Read Command in Mode 'Fast Exit':
+ * min 2 clock cycles */
+ MPDDRC_TPR2_TXARDS(7) | /* Exit Active Power Down Delay to Read Command in Mode 'Slow Exit':
+ * min 7 clock cycles */
+ MPDDRC_TPR2_TRPA(2) | /* Row Precharge All Delay:
+ * min 18ns */
+ MPDDRC_TPR2_TRTP(2) | /* Four Active Windows:
+ * 2 * 7.5 = 15 ns (min 7.5ns) */
+ MPDDRC_TPR2_TFAW(10) ;
+ putreg32(regval, SAM_MPDDRC_TPR2);
+
+ /* DDRSDRC Low-power Register */
+
+ board_sdram_delay(13200);
+
+ regval = MPDDRC_LPR_LPCB_DISABLED | /* Low-power Feature is inhibited */
+ MPDDRC_LPR_TIMEOUT_0CLKS | /* Activates low-power mode after the end of transfer */
+ MPDDRC_LPR_APDE_FAST; /* Active Power Down Exit Time */
+ putreg32(regval, SAM_MPDDRC_LPR);
+
+ /* Step 3: An NOP command is issued to the DDR2-SDRAM. Program the NOP
+ * command into the Mode Register, the application must set MODE to 1 in
+ * the Mode Register.
+ */
+
+ putreg32(MPDDRC_MR_MODE_NOP, SAM_MPDDRC_MR);
+
+ /* Perform a write access to any DDR2-SDRAM address to acknowledge this
+ * command.
+ */
+
+ *ddr = 0;
+
+ /* Now clocks which drive DDR2-SDRAM device are enabled.*/
+ /* Step 4: An NOP command is issued to the DDR2-SDRAM */
+
+ putreg32(MPDDRC_MR_MODE_NOP, SAM_MPDDRC_MR);
+
+ /* Perform a write access to any DDR2-SDRAM address to acknowledge this command.*/
+
+ *ddr = 0;
+
+ /* Now CKE is driven high.*/
+ /* Wait 400 ns min */
+
+ board_sdram_delay(100);
+
+ /* Step 5: An all banks precharge command is issued to the DDR2-SDRAM. */
+
+ putreg32(MPDDRC_MR_MODE_PRCGALL, SAM_MPDDRC_MR);
+
+ /* Perform a write access to any DDR2-SDRAM address to acknowledge this command.*/
+
+ *ddr = 0;
+
+ /* Wait 400 ns min */
+
+ board_sdram_delay(100);
+
+ /* Step 6: An Extended Mode Register set (EMRS2) cycle is issued to chose
+ * between commercialor high temperature operations.
+ *
+ * The write address must be chosen so that BA[1] is set to 1 and BA[0] is
+ * set to 0.
+ */
+
+ putreg32(MPDDRC_MR_MODE_EXTLMR, SAM_MPDDRC_MR);
+ *((uint8_t *)(ddr + DDR2_BA1(sdramtype))) = 0;
+
+ /* Wait 2 cycles min */
+
+ board_sdram_delay(100);
+
+ /* Step 7: An Extended Mode Register set (EMRS3) cycle is issued to set
+ * all registers to 0.
+ *
+ * The write address must be chosen so that BA[1] is set to 1 and BA[0] is
+ * set to 1.
+ */
+
+ putreg32(MPDDRC_MR_MODE_EXTLMR, SAM_MPDDRC_MR);
+ *((uint8_t *)(ddr + DDR2_BA1(sdramtype) + DDR2_BA0(sdramtype))) = 0;
+
+ /* Wait 2 cycles min */
+
+ board_sdram_delay(100);
+
+ /* Step 8: An Extended Mode Register set (EMRS1) cycle is issued to enable DLL.
+ *
+ * The write address must be chosen so that BA[1] is set to 0 and BA[0] is set to 1.
+ */
+
+ putreg32(MPDDRC_MR_MODE_EXTLMR, SAM_MPDDRC_MR);
+ *((uint8_t *)(ddr + DDR2_BA0(sdramtype))) = 0;
+
+ /* An additional 200 cycles of clock are required for locking DLL */
+
+ board_sdram_delay(10000);
+
+ /* Step 9: Program DLL field into the Configuration Register.*/
+
+ regval = getreg32(SAM_MPDDRC_CR);
+ regval |= MPDDRC_CR_DLL;
+ putreg32(regval, SAM_MPDDRC_CR);
+
+ /* Step 10: A Mode Register set (MRS) cycle is issued to reset DLL.
+ *
+ * The write address must be chosen so that BA[1:0] bits are set to 0.
+ */
+
+ putreg32(MPDDRC_MR_MODE_LMR, SAM_MPDDRC_MR);
+ *ddr = 0;
+
+ /* Wait 2 cycles min */
+
+ board_sdram_delay(100);
+
+ /* Step 11: An all banks precharge command is issued to the DDR2-SDRAM.
+ *
+ * Perform a write access to any DDR2-SDRAM address to acknowledge this command */
+ */
+
+ putreg32(MPDDRC_MR_MODE_PRCGALL, SAM_MPDDRC_MR);
+ *ddr = 0;
+
+ /* Wait 2 cycles min */
+
+ board_sdram_delay(100);
+
+ /* Step 12: Two auto-refresh (CBR) cycles are provided. Program the auto
+ * refresh command (CBR) into the Mode Register.
+ *
+ * Perform a write access to any DDR2-SDRAM address to acknowledge this
+ * command.
+ */
+
+ putreg32(MPDDRC_MR_MODE_RFSH, SAM_MPDDRC_MR);
+ *ddr = 0;
+
+ /* Wait 2 cycles min */
+
+ board_sdram_delay(100);
+
+ /* Configure 2nd CBR.
+ *
+ * Perform a write access to any DDR2-SDRAM address to acknowledge this command.
+ */
+
+ putreg32(MPDDRC_MR_MODE_RFSH, SAM_MPDDRC_MR);
+ *ddr = 0;
+
+ /* Wait 2 cycles min */
+
+ board_sdram_delay(100);
+
+ /* Step 13: Program DLL field into the Configuration Register to low
+ * (Disable DLL reset).
+ */
+
+ regval = getreg32(SAM_MPDDRC_CR);
+ regval &= ~MPDDRC_CR_DLL;
+ putreg32(regval, SAM_MPDDRC_CR);
+
+ /* Step 14: A Mode Register set (MRS) cycle is issued to program the
+ * parameters of the DDR2-SDRAM devices.
+ *
+ * The write address must be chosen so that BA[1:0] are set to 0.
+ */
+
+ putreg32(MPDDRC_MR_MODE_LMR, SAM_MPDDRC_MR);
+ *ddr = 0;
+
+ /* Wait 2 cycles min */
+
+ board_sdram_delay(100);
+
+ /* Step 15: Program OCD field into the Configuration Register to high (OCD
+ * calibration default).
+ */
+
+ regval = getreg32(SAM_MPDDRC_CR);
+ retval |= MPDDRC_CR_OCD_DEFAULT;
+ putreg32(regval, SAM_MPDDRC_CR);
+
+ /* Step 16: An Extended Mode Register set (EMRS1) cycle is issued to OCD
+ * default value.
+ *
+ * The write address must be chosen so that BA[1] is set to 0 and BA[0] is
+ * set to 1.
+ */
+
+ putreg32(MPDDRC_MR_MODE_EXTLMR, SAM_MPDDRC_MR);
+ *((uint8_t *)(ddr + DDR2_BA0(sdramtype))) = 0;
+
+ /* Wait 2 cycles min */
+
+ board_sdram_delay(100);
+
+ /* Step 17: Program OCD field into the Configuration Register to low (OCD
+ * calibration mode exit).
+ */
+
+#if 0
+ regval = getreg32(SAM_MPDDRC_CR);
+ regval &= ~MPDDRC_CR_OCD_MASK;
+ putreg32(regval, SAM_MPDDRC_CR);
+#endif
+
+ /* Step 18: An Extended Mode Register set (EMRS1) cycle is issued to
+ * enable OCD exit.
+ *
+ * The write address must be chosen so that BA[1] is set to 0 and BA[0] is
+ * set to 1.
+ */
+
+ putreg32(MPDDRC_MR_MODE_EXTLMR, SAM_MPDDRC_MR);
+ *((uint8_t *)(ddr + DDR2_BA0(sdramtype))) = 0;
+
+ /* Wait 2 cycles min */
+
+ board_sdram_delay(100);
+
+ /* Step 19,20: A mode Normal command is provided. Program the Normal mode
+ * into Mode Register.
+ */
+
+ putreg32(MPDDRC_MR_MODE_NORMAL, SAM_MPDDRC_MR);
+ *ddr = 0;
+
+ /* Step 21: Write the refresh rate into the count field in the Refresh
+ * Timer register. The DDR2-SDRAM device requires a refresh every 15.625
+ * usec or 7.81 usec.
+ *
+ * With a 100MHz frequency, the refresh timer count register must to be
+ * set with (15.625 /100 MHz) = 1562 i.e. 0x061A or (7.81 /100MHz) = 781
+ * i.e. 0x030d.
+ */
+
+ /* For MT47H64M16HR, The refresh period is 64ms (commercial), This equates
+ * to an average refresh rate of 7.8125usec (commercial), To ensure all
+ * rows of all banks are properly refreshed, 8192 REFRESH commands must be
+ * issued every 64ms (commercial)
+ */
+
+ /* ((64 x 10(^-3))/8192) x133 x (10^6) */
+ /* Set Refresh timer 7.8125 us */
+
+ putreg32( MPDDRC_RTR_COUNT(300), SAM_MPDDRC_RTR);
+
+ /* OK now we are ready to work on the DDRSDR */
+ /* Wait for end of calibration */
+
+ board_sdram_delay(500);
+#warning Make SDRAM cacheable
+}
+
+#endif /* CONFIG_SAMA5_DDRCS && !CONFIG_SAMA5_BOOT_SDRAM && !CONFIG_BOOT_RUNFROMSDRAM */
+#endif /* CONFIG_SAMA5_BOOT_CS0FLASH */
diff --git a/nuttx/configs/sama5d3x-ek/src/sama5d3x-ek.h b/nuttx/configs/sama5d3x-ek/src/sama5d3x-ek.h
index 7c9c45f06..2b2a0d7fb 100644
--- a/nuttx/configs/sama5d3x-ek/src/sama5d3x-ek.h
+++ b/nuttx/configs/sama5d3x-ek/src/sama5d3x-ek.h
@@ -109,6 +109,37 @@
************************************************************************************/
/************************************************************************************
+ * Name: board_sdram_config
+ *
+ * Description:
+ * Configures DDR2 (MT47H128M16RT 128MB/ MT47H64M16HR)
+ *
+ * MT47H64M16HR : 8 Meg x 16 x 8 banks
+ * Refresh count: 8K
+ * Row address: A[12:0] (8K)
+ * Column address A[9:0] (1K)
+ * Bank address BA[2:0] a(24,25) (8)
+ *
+ * This logic was taken from Atmel sample code for the SAMA5D3x-EK.
+ *
+ * Input Parameters:
+ * devtype - Either DDRAM_MT47H128M16RT or DDRAM_MT47H64M16HR
+ *
+ * Assumptions:
+ * The DDR memory regions is configured as strongly ordered memory. When we
+ * complete initialization of SDRAM and it is ready for use, we will make DRAM
+ * into normal memory.
+ *
+ ************************************************************************************/
+
+#if defined(CONFIG_SAMA5_DDRCS) && !defined(CONFIG_SAMA5_BOOT_SDRAM) && \
+ !defined(CONFIG_BOOT_RUNFROMSDRAM)
+void board_sdram_config(uint8_t sdramtype);
+#else
+# define board_sdram_config(t)
+#endif
+
+/************************************************************************************
* Name: up_ledinit
************************************************************************************/