imxrt: Adds the ability to run from OCRAM (#407)
* imxrt: GPIO make tables const * imxrt: Call out to board to set up FlexRAM * imxrt: Add Knob for adding the ROM bootloaders 40Kib of RAM to heap * imxrt: imxrt1060-evk:Add the ability to run from OCRAM
This commit is contained in:
parent
4a4b2853c2
commit
fd3148dba6
@ -1096,6 +1096,13 @@ config IMXRT_DTCM_HEAP
|
||||
---help---
|
||||
Select to add the entire DTCM to the heap
|
||||
|
||||
config IMXRT_BOOTLOADER_HEAP
|
||||
bool "Add ROM bootloader 40Kib RAM to heap"
|
||||
default false
|
||||
depends on BOOT_RUNFROMISRAM
|
||||
---help---
|
||||
Select to add the memory used by the ROM bootloader to heap
|
||||
|
||||
config IMXRT_SDRAM_HEAP
|
||||
bool "Add SDRAM to heap"
|
||||
depends on IMXRT_SEMC_SDRAM && !IMXRT_SDRAM_PRIMARY
|
||||
|
@ -228,6 +228,10 @@
|
||||
# define REGION2_RAM_START IMXRT_OCRAM_START
|
||||
# define REGION2_RAM_SIZE IMXRT_OCRAM_SIZE
|
||||
# define IMXRT_OCRAM_ASSIGNED 1
|
||||
#elif defined(CONFIG_IMXRT_BOOTLOADER_HEAP)
|
||||
# define REGION2_RAM_START IMXRT_OCRAM2_BASE
|
||||
# define REGION2_RAM_SIZE (40 * 1024)
|
||||
# define IMXRT_SDRAM_ASSIGNED 1
|
||||
#elif defined(CONFIG_IMXRT_SDRAM_HEAP) && !defined(IMXRT_SDRAM_ASSIGNED)
|
||||
# define REGION2_RAM_START (CONFIG_IMXRT_SDRAM_START + CONFIG_IMXRT_SDRAM_HEAPOFFSET)
|
||||
# define REGION2_RAM_SIZE (CONFIG_IMXRT_SDRAM_SIZE - CONFIG_IMXRT_SDRAM_HEAPOFFSET)
|
||||
|
@ -348,7 +348,7 @@ static const uint8_t g_gpio5_padmux[IMXRT_GPIO_NPINS] =
|
||||
IMXRT_PADMUX_INVALID /* GPIO5 Pin 31 */
|
||||
};
|
||||
|
||||
static FAR const uint8_t *g_gpio_padmux[IMXRT_GPIO_NPORTS + 1] =
|
||||
static const uint8_t * const g_gpio_padmux[IMXRT_GPIO_NPORTS + 1] =
|
||||
{
|
||||
g_gpio1_padmux, /* GPIO1 */
|
||||
g_gpio2_padmux, /* GPIO2 */
|
||||
@ -375,7 +375,7 @@ static FAR const uint8_t *g_gpio_padmux[IMXRT_GPIO_NPORTS + 1] =
|
||||
|
||||
/* Look-up table that maps GPIO1..GPIOn indexes into GPIO register base addresses */
|
||||
|
||||
uintptr_t g_gpio_base[IMXRT_GPIO_NPORTS] =
|
||||
const uintptr_t g_gpio_base[IMXRT_GPIO_NPORTS] =
|
||||
{
|
||||
IMXRT_GPIO1_BASE
|
||||
#if IMXRT_GPIO_NPORTS > 1
|
||||
|
@ -258,7 +258,7 @@ extern "C"
|
||||
|
||||
/* Look-up table that maps GPIO1..GPIOn indexes into GPIO register base addresses */
|
||||
|
||||
EXTERN uintptr_t g_gpio_base[IMXRT_GPIO_NPORTS];
|
||||
EXTERN const uintptr_t g_gpio_base[IMXRT_GPIO_NPORTS];
|
||||
|
||||
/************************************************************************************
|
||||
* Public Function Prototypes
|
||||
|
@ -64,6 +64,7 @@
|
||||
****************************************************************************/
|
||||
|
||||
/* Memory Map ***************************************************************/
|
||||
|
||||
/* 0x2020:0000 - Start of on-chip RAM (OCRAM) and start of .data (_sdata)
|
||||
* - End of .data (_edata) and start of .bss (_sbss)
|
||||
* - End of .bss (_ebss) and bottom of idle stack
|
||||
@ -157,7 +158,7 @@ static inline void imxrt_fpuconfig(void)
|
||||
/* Enable full access to CP10 and CP11 */
|
||||
|
||||
regval = getreg32(NVIC_CPACR);
|
||||
regval |= ((3 << (2*10)) | (3 << (2*11)));
|
||||
regval |= ((3 << (2 * 10)) | (3 << (2 * 11)));
|
||||
putreg32(regval, NVIC_CPACR);
|
||||
}
|
||||
|
||||
@ -187,7 +188,7 @@ static inline void imxrt_fpuconfig(void)
|
||||
/* Enable full access to CP10 and CP11 */
|
||||
|
||||
regval = getreg32(NVIC_CPACR);
|
||||
regval |= ((3 << (2*10)) | (3 << (2*11)));
|
||||
regval |= ((3 << (2 * 10)) | (3 << (2 * 11)));
|
||||
putreg32(regval, NVIC_CPACR);
|
||||
}
|
||||
|
||||
@ -307,6 +308,10 @@ void __start(void)
|
||||
__asm__ volatile ("sub r10, sp, %0" : : "r" (CONFIG_IDLETHREAD_STACKSIZE - 64) : );
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_BOOT_RUNFROMISRAM
|
||||
imxrt_ocram_initialize();
|
||||
#endif
|
||||
|
||||
/* Clear .bss. We'll do this inline (vs. calling memset) just to be
|
||||
* certain that there are no issues with the state of global variables.
|
||||
*/
|
||||
|
@ -117,6 +117,19 @@ void imxrt_lowsetup(void);
|
||||
|
||||
void imxrt_boardinitialize(void);
|
||||
|
||||
/************************************************************************************
|
||||
* Name: imxrt_ocram_initialize
|
||||
*
|
||||
* Description:
|
||||
* Called off reset vector to reconfigure the flexRAM
|
||||
* and finish the FLASH to RAM Copy.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
#ifdef CONFIG_BOOT_RUNFROMISRAM
|
||||
void imxrt_ocram_initialize(void);
|
||||
#endif
|
||||
|
||||
#undef EXTERN
|
||||
#if defined(__cplusplus)
|
||||
}
|
||||
|
48
boards/arm/imxrt/imxrt1060-evk/configs/nshocram/defconfig
Normal file
48
boards/arm/imxrt/imxrt1060-evk/configs/nshocram/defconfig
Normal file
@ -0,0 +1,48 @@
|
||||
#
|
||||
# This file is autogenerated: PLEASE DO NOT EDIT IT.
|
||||
#
|
||||
# You can use "make menuconfig" to make any modifications to the installed .config file.
|
||||
# You can then do "make savedefconfig" to generate a new defconfig file that includes your
|
||||
# modifications.
|
||||
#
|
||||
CONFIG_ARCH="arm"
|
||||
CONFIG_ARCH_BOARD="imxrt1060-evk"
|
||||
CONFIG_ARCH_BOARD_IMXRT1060_EVK=y
|
||||
CONFIG_ARCH_CHIP="imxrt"
|
||||
CONFIG_ARCH_CHIP_IMXRT=y
|
||||
CONFIG_ARCH_CHIP_MIMXRT1062DVL6A=y
|
||||
CONFIG_ARCH_STACKDUMP=y
|
||||
CONFIG_ARMV7M_DCACHE=y
|
||||
CONFIG_ARMV7M_DCACHE_WRITETHROUGH=y
|
||||
CONFIG_ARMV7M_DTCM=y
|
||||
CONFIG_ARMV7M_ICACHE=y
|
||||
CONFIG_ARMV7M_USEBASEPRI=y
|
||||
CONFIG_BOARD_LOOPSPERMSEC=104926
|
||||
CONFIG_BOOT_RUNFROMISRAM=y
|
||||
CONFIG_BUILTIN=y
|
||||
CONFIG_FS_PROCFS=y
|
||||
CONFIG_IDLETHREAD_STACKSIZE=2048
|
||||
CONFIG_IMXRT_LPUART1=y
|
||||
CONFIG_IMXRT_BOOTLOADER_HEAP=y
|
||||
CONFIG_IMXRT_DTCM_HEAP=y
|
||||
CONFIG_INTELHEX_BINARY=y
|
||||
CONFIG_LPUART1_SERIAL_CONSOLE=y
|
||||
CONFIG_MAX_TASKS=16
|
||||
CONFIG_MAX_WDOGPARMS=2
|
||||
CONFIG_MM_REGIONS=3
|
||||
CONFIG_NFILE_DESCRIPTORS=8
|
||||
CONFIG_NFILE_STREAMS=8
|
||||
CONFIG_NSH_ARCHINIT=y
|
||||
CONFIG_NSH_BUILTIN_APPS=y
|
||||
CONFIG_NSH_DISABLE_IFUPDOWN=y
|
||||
CONFIG_NSH_FILEIOSIZE=512
|
||||
CONFIG_NSH_LINELEN=64
|
||||
CONFIG_NSH_READLINE=y
|
||||
CONFIG_PREALLOC_MQ_MSGS=4
|
||||
CONFIG_PREALLOC_WDOGS=16
|
||||
CONFIG_RAM_SIZE=786432
|
||||
CONFIG_RAM_START=0x20200000
|
||||
CONFIG_START_DAY=14
|
||||
CONFIG_START_MONTH=3
|
||||
CONFIG_SYSTEM_NSH=y
|
||||
CONFIG_USER_ENTRYPOINT="nsh_main"
|
@ -37,9 +37,9 @@ include ${TOPDIR}/.config
|
||||
include ${TOPDIR}/tools/Config.mk
|
||||
include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs
|
||||
|
||||
ifeq ($(CONFIG_ARMV7M_DTCM),y)
|
||||
LDSCRIPT = flash-dtcm.ld
|
||||
else
|
||||
ifeq ($(CONFIG_BOOT_RUNFROMFLASH),y)
|
||||
LDSCRIPT = flash.ld
|
||||
else ifeq ($(CONFIG_BOOT_RUNFROMISRAM),y)
|
||||
LDSCRIPT = flash-ocram.ld
|
||||
endif
|
||||
|
||||
@ -115,7 +115,7 @@ LIBEXT = .a
|
||||
EXEEXT =
|
||||
|
||||
ifneq ($(CROSSDEV),arm-nuttx-elf-)
|
||||
LDFLAGS += -nostartfiles -nodefaultlibs
|
||||
LDFLAGS += -nostartfiles -nodefaultlibs -Map nuttx.map
|
||||
endif
|
||||
ifeq ($(CONFIG_DEBUG_SYMBOLS),y)
|
||||
LDFLAGS += -g
|
||||
|
@ -1,9 +1,9 @@
|
||||
/****************************************************************************
|
||||
* boards/arm/imxrt/imxrt1060-evk/scripts/flash-ocram.ld
|
||||
*
|
||||
* Copyright (C) 2018 Gregory Nutt. All rights reserved.
|
||||
* Copyright (C) 2018, 2020 Gregory Nutt. All rights reserved.
|
||||
* Authors: Ivan Ucherdzhiev <ivanucherdjiev@gmail.com>
|
||||
* David Sidrane <david_s5@nscdg.com>
|
||||
* David Sidrane <david.sidrane@nscdg.com>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
@ -36,12 +36,42 @@
|
||||
|
||||
/* Specify the memory areas */
|
||||
|
||||
/* The imxrt162-evk has 8MiB of QSPI FLASH beginning at address,
|
||||
* 0x0060:0000, Upto 512Kb of DTCM RAM beginning at 0x2000:0000, and 1MiB OCRAM
|
||||
* beginning at 0x2020:0000. Neither DTCM or SDRAM are used in this
|
||||
* configuration.
|
||||
*
|
||||
* The default flexram setting on the iMXRT 1062 is
|
||||
* 256Kib to OCRRAM, 128Kib ITCM and 128Kib DTCM.
|
||||
* This can be changed by using a dcd by minipulating
|
||||
* IOMUX GPR16 and GPR17.
|
||||
* The configuartion we will use is 384Kib to OCRRAM, 0Kib ITCM and
|
||||
* 128Kib DTCM.
|
||||
*
|
||||
* This is the OCRAM inker script.
|
||||
* The NXP ROM bootloader will move the FLASH image to OCRAM.
|
||||
* We must reserve 32K for the bootloader' OCRAM usage from the OCRAM Size
|
||||
* and an additinal 8K for the ivt_s which is IVT_SIZE(8K) This 40K can be
|
||||
* reused once the application is running.
|
||||
*
|
||||
* 0x2020:A000 to 0x202d:ffff - The application Image's vector table
|
||||
* 0x2020:8000 to 0x2020:A000 - IVT
|
||||
* 0x2020:0000 to 0x2020:7fff - NXP ROM bootloader.
|
||||
*
|
||||
* We artificially split the FLASH to allow locating sections that we do not
|
||||
* want loaded inoto OCRAM. This is to save on OCRAM where the speen of the
|
||||
* code does not matter.
|
||||
*
|
||||
*/
|
||||
|
||||
MEMORY
|
||||
{
|
||||
flash (rx) : ORIGIN = 0x60000000, LENGTH = 8M
|
||||
sram (rwx) : ORIGIN = 0x20200000, LENGTH = 512M
|
||||
itcm (rwx) : ORIGIN = 0x00000000, LENGTH = 128K
|
||||
dtcm (rwx) : ORIGIN = 0x20000000, LENGTH = 128K
|
||||
flash (rx) : ORIGIN = 0x60000000, LENGTH = 7M
|
||||
flashxip (rx) : ORIGIN = 0x60700000, LENGTH = 1M
|
||||
/* Vectors @ boot+ivt OCRAM2 Flex RAM Boot IVT */
|
||||
sram (rwx) : ORIGIN = 0x2020A000, LENGTH = 512K + 256K + 128K - (32K + 8K)
|
||||
itcm (rwx) : ORIGIN = 0x00000000, LENGTH = 0K
|
||||
dtcm (rwx) : ORIGIN = 0x20000000, LENGTH = 128K
|
||||
}
|
||||
|
||||
OUTPUT_ARCH(arm)
|
||||
@ -49,6 +79,7 @@ EXTERN(_vectors)
|
||||
EXTERN(g_flash_config)
|
||||
EXTERN(g_image_vector_table)
|
||||
EXTERN(g_boot_data)
|
||||
EXTERN(g_dcd_data)
|
||||
|
||||
ENTRY(_stext)
|
||||
|
||||
@ -69,24 +100,40 @@ SECTIONS
|
||||
KEEP(*(.boot_hdr.dcd_data))
|
||||
__boot_hdr_end__ = ABSOLUTE(.) ;
|
||||
. = 0x2000 ;
|
||||
} >flash
|
||||
} > flash
|
||||
|
||||
/* Catch all the section we want not in OCRAM so that the *(.text .text.*) in flash does not */
|
||||
|
||||
.flashxip : ALIGN(4)
|
||||
{
|
||||
FILL(0xff)
|
||||
|
||||
/* Order matters */
|
||||
|
||||
imxrt_start.o(.text)
|
||||
imxrt_boot.o(.text)
|
||||
|
||||
*(.slow_memory)
|
||||
*(.rodata .rodata.*)
|
||||
KEEP(*(__param*))
|
||||
*(.fixup)
|
||||
*(.gnu.warning)
|
||||
*(.gnu.linkonce.t.*)
|
||||
*(.glue_7)
|
||||
*(.glue_7t)
|
||||
*(.got)
|
||||
*(.gcc_except_table)
|
||||
*(.gnu.linkonce.r.*)
|
||||
|
||||
} > flashxip
|
||||
|
||||
.text :
|
||||
{
|
||||
_stext = ABSOLUTE(.);
|
||||
*(.vectors)
|
||||
*(.text .text.*)
|
||||
*(.fixup)
|
||||
*(.gnu.warning)
|
||||
*(.rodata .rodata.*)
|
||||
*(.gnu.linkonce.t.*)
|
||||
*(.glue_7)
|
||||
*(.glue_7t)
|
||||
*(.got)
|
||||
*(.gcc_except_table)
|
||||
*(.gnu.linkonce.r.*)
|
||||
_etext = ABSOLUTE(.);
|
||||
} > flash
|
||||
} > sram AT > flash
|
||||
|
||||
.init_section :
|
||||
{
|
||||
|
139
boards/arm/imxrt/imxrt1060-evk/scripts/flash.ld
Normal file
139
boards/arm/imxrt/imxrt1060-evk/scripts/flash.ld
Normal file
@ -0,0 +1,139 @@
|
||||
/****************************************************************************
|
||||
* boards/arm/imxrt/imxrt1060-evk/scripts/flash-ocram.ld
|
||||
*
|
||||
* Licensed to the Apache Software Foundation (ASF) under one or more
|
||||
* contributor license agreements. See the NOTICE file distributed with
|
||||
* this work for additional information regarding copyright ownership. The
|
||||
* ASF licenses this file to you under the Apache License, Version 2.0 (the
|
||||
* "License"); you may not use this file except in compliance with the
|
||||
* License. You may obtain a copy of the License at
|
||||
*
|
||||
* http://www.apache.org/licenses/LICENSE-2.0
|
||||
*
|
||||
* Unless required by applicable law or agreed to in writing, software
|
||||
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
|
||||
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
|
||||
* License for the specific language governing permissions and limitations
|
||||
* under the License.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/* Specify the memory areas */
|
||||
|
||||
MEMORY
|
||||
{
|
||||
flash (rx) : ORIGIN = 0x60000000, LENGTH = 8M
|
||||
sram (rwx) : ORIGIN = 0x20200000, LENGTH = 512M
|
||||
itcm (rwx) : ORIGIN = 0x00000000, LENGTH = 128K
|
||||
dtcm (rwx) : ORIGIN = 0x20000000, LENGTH = 128K
|
||||
}
|
||||
|
||||
OUTPUT_ARCH(arm)
|
||||
EXTERN(_vectors)
|
||||
EXTERN(g_flash_config)
|
||||
EXTERN(g_image_vector_table)
|
||||
EXTERN(g_boot_data)
|
||||
|
||||
ENTRY(_stext)
|
||||
|
||||
SECTIONS
|
||||
{
|
||||
/* Image Vector Table and Boot Data for booting from external flash */
|
||||
|
||||
.boot_hdr : ALIGN(4)
|
||||
{
|
||||
FILL(0xff)
|
||||
__boot_hdr_start__ = ABSOLUTE(.) ;
|
||||
KEEP(*(.boot_hdr.conf))
|
||||
. = 0x1000 ;
|
||||
KEEP(*(.boot_hdr.ivt))
|
||||
. = 0x1020 ;
|
||||
KEEP(*(.boot_hdr.boot_data))
|
||||
. = 0x1030 ;
|
||||
KEEP(*(.boot_hdr.dcd_data))
|
||||
__boot_hdr_end__ = ABSOLUTE(.) ;
|
||||
. = 0x2000 ;
|
||||
} >flash
|
||||
|
||||
.text :
|
||||
{
|
||||
_stext = ABSOLUTE(.);
|
||||
*(.vectors)
|
||||
*(.text .text.*)
|
||||
*(.fixup)
|
||||
*(.gnu.warning)
|
||||
*(.rodata .rodata.*)
|
||||
*(.gnu.linkonce.t.*)
|
||||
*(.glue_7)
|
||||
*(.glue_7t)
|
||||
*(.got)
|
||||
*(.gcc_except_table)
|
||||
*(.gnu.linkonce.r.*)
|
||||
_etext = ABSOLUTE(.);
|
||||
} > flash
|
||||
|
||||
.init_section :
|
||||
{
|
||||
_sinit = ABSOLUTE(.);
|
||||
*(.init_array .init_array.*)
|
||||
_einit = ABSOLUTE(.);
|
||||
} > flash
|
||||
|
||||
.ARM.extab :
|
||||
{
|
||||
*(.ARM.extab*)
|
||||
} > flash
|
||||
|
||||
.ARM.exidx :
|
||||
{
|
||||
__exidx_start = ABSOLUTE(.);
|
||||
*(.ARM.exidx*)
|
||||
__exidx_end = ABSOLUTE(.);
|
||||
} > flash
|
||||
|
||||
_eronly = ABSOLUTE(.);
|
||||
|
||||
.data :
|
||||
{
|
||||
_sdata = ABSOLUTE(.);
|
||||
*(.data .data.*)
|
||||
*(.gnu.linkonce.d.*)
|
||||
CONSTRUCTORS
|
||||
. = ALIGN(4);
|
||||
_edata = ABSOLUTE(.);
|
||||
} > sram AT > flash
|
||||
|
||||
.ramfunc ALIGN(4):
|
||||
{
|
||||
_sramfuncs = ABSOLUTE(.);
|
||||
*(.ramfunc .ramfunc.*)
|
||||
_eramfuncs = ABSOLUTE(.);
|
||||
} > sram AT > flash
|
||||
|
||||
_framfuncs = LOADADDR(.ramfunc);
|
||||
|
||||
.bss :
|
||||
{
|
||||
_sbss = ABSOLUTE(.);
|
||||
*(.bss .bss.*)
|
||||
*(.gnu.linkonce.b.*)
|
||||
*(COMMON)
|
||||
. = ALIGN(4);
|
||||
_ebss = ABSOLUTE(.);
|
||||
} > sram
|
||||
|
||||
/* Stabs debugging sections. */
|
||||
|
||||
.stab 0 : { *(.stab) }
|
||||
.stabstr 0 : { *(.stabstr) }
|
||||
.stab.excl 0 : { *(.stab.excl) }
|
||||
.stab.exclstr 0 : { *(.stab.exclstr) }
|
||||
.stab.index 0 : { *(.stab.index) }
|
||||
.stab.indexstr 0 : { *(.stab.indexstr) }
|
||||
.comment 0 : { *(.comment) }
|
||||
.debug_abbrev 0 : { *(.debug_abbrev) }
|
||||
.debug_info 0 : { *(.debug_info) }
|
||||
.debug_line 0 : { *(.debug_line) }
|
||||
.debug_pubnames 0 : { *(.debug_pubnames) }
|
||||
.debug_aranges 0 : { *(.debug_aranges) }
|
||||
}
|
@ -45,11 +45,49 @@
|
||||
|
||||
#include "imxrt_start.h"
|
||||
#include "imxrt1060-evk.h"
|
||||
#include "up_arch.h"
|
||||
#include "imxrt_flexspi_nor_boot.h"
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: imxrt_ocram_initialize
|
||||
*
|
||||
* Description:
|
||||
* Called off reset vector to reconfigure the flexRAM
|
||||
* and finish the FLASH to RAM Copy.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
void imxrt_ocram_initialize(void)
|
||||
{
|
||||
const uint32_t *src;
|
||||
uint32_t *dest;
|
||||
uint32_t regval;
|
||||
|
||||
/* Reallocate 128K of Flex RAM from ITCM to OCRAM
|
||||
* Final Configuration is
|
||||
* 128 DTCM
|
||||
*
|
||||
* 128 FlexRAM OCRAM (202C:0000-202D:ffff)
|
||||
* 256 FlexRAM OCRAM (2028:0000-202B:ffff)
|
||||
* 512 System OCRAM2 (2020:0000-2027:ffff)
|
||||
* */
|
||||
|
||||
putreg32(0xaa555555, IMXRT_IOMUXC_GPR_GPR17);
|
||||
regval = getreg32(IMXRT_IOMUXC_GPR_GPR16);
|
||||
putreg32(regval | GPR_GPR16_FLEXRAM_BANK_CFG_SELF, IMXRT_IOMUXC_GPR_GPR16);
|
||||
|
||||
for (src = (uint32_t *)(LOCATE_IN_SRC(g_boot_data.start) + g_boot_data.size),
|
||||
dest = (uint32_t *)(g_boot_data.start + g_boot_data.size);
|
||||
dest < (uint32_t *) &_etext;)
|
||||
{
|
||||
*dest++ = *src++;
|
||||
}
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: imxrt_boardinitialize
|
||||
*
|
||||
|
@ -47,11 +47,11 @@ __attribute__((section(".boot_hdr.ivt")))
|
||||
const struct ivt_s g_image_vector_table =
|
||||
{
|
||||
IVT_HEADER, /* IVT Header */
|
||||
0x60002000, /* Image Entry Function */
|
||||
IMAGE_ENTRY_ADDRESS, /* Image Entry Function */
|
||||
IVT_RSVD, /* Reserved = 0 */
|
||||
(uint32_t)DCD_ADDRESS, /* Address where DCD information is stored */
|
||||
(uint32_t)BOOT_DATA_ADDRESS, /* Address where BOOT Data Structure is stored */
|
||||
(uint32_t)&g_image_vector_table, /* Pointer to IVT Self (absolute address */
|
||||
(uint32_t)IMAG_VECTOR_TABLE, /* Pointer to IVT Self (absolute address */
|
||||
(uint32_t)CSF_ADDRESS, /* Address where CSF file is stored */
|
||||
IVT_RSVD /* Reserved = 0 */
|
||||
};
|
||||
@ -59,8 +59,8 @@ const struct ivt_s g_image_vector_table =
|
||||
__attribute__((section(".boot_hdr.boot_data")))
|
||||
const struct boot_data_s g_boot_data =
|
||||
{
|
||||
FLASH_BASE, /* boot start location */
|
||||
(FLASH_END - FLASH_BASE), /* size */
|
||||
IMAGE_DEST, /* boot start location */
|
||||
(IMAGE_DEST_END - IMAGE_DEST), /* size */
|
||||
PLUGIN_FLAG, /* Plugin flag */
|
||||
0xffffffff /* empty - extra data word */
|
||||
};
|
||||
|
@ -76,13 +76,38 @@
|
||||
|
||||
#define FLASH_BASE 0x60000000
|
||||
#define FLASH_END 0x7f7fffff
|
||||
|
||||
/* This needs to take into account the memory configuration at boot bootloader */
|
||||
|
||||
#define ROM_BOOTLOADER_OCRAM_RES 0x8000
|
||||
#define OCRAM_BASE (0x20200000 + ROM_BOOTLOADER_OCRAM_RES)
|
||||
#define OCRAM_END (OCRAM_BASE + (512 * 1024) + (256 * 1024) \
|
||||
- ROM_BOOTLOADER_OCRAM_RES)
|
||||
|
||||
#define SCLK 1
|
||||
#if defined(CONFIG_BOOT_RUNFROMFLASH)
|
||||
# define IMAGE_DEST FLASH_BASE
|
||||
# define IMAGE_DEST_END FLASH_END
|
||||
# define IMAGE_DEST_OFFSET 0
|
||||
#else
|
||||
# define IMAGE_DEST OCRAM_BASE
|
||||
# define IMAGE_DEST_END OCRAM_END
|
||||
# define IMAGE_DEST_OFFSET IVT_SIZE
|
||||
#endif
|
||||
|
||||
#define LOCATE_IN_DEST(x) (((uint32_t)(x)) - FLASH_BASE + IMAGE_DEST)
|
||||
#define LOCATE_IN_SRC(x) (((uint32_t)(x)) - IMAGE_DEST + FLASH_BASE)
|
||||
|
||||
#define DCD_ADDRESS 0
|
||||
#define BOOT_DATA_ADDRESS &g_boot_data
|
||||
#define BOOT_DATA_ADDRESS LOCATE_IN_DEST(&g_boot_data)
|
||||
#define CSF_ADDRESS 0
|
||||
#define PLUGIN_FLAG (uint32_t)0
|
||||
|
||||
/* Located in Destination Memory */
|
||||
|
||||
#define IMAGE_ENTRY_ADDRESS ((uint32_t)&_vectors)
|
||||
#define IMAG_VECTOR_TABLE LOCATE_IN_DEST(&g_image_vector_table)
|
||||
|
||||
/****************************************************************************
|
||||
* Public Types
|
||||
****************************************************************************/
|
||||
@ -145,5 +170,7 @@ struct boot_data_s
|
||||
****************************************************************************/
|
||||
|
||||
extern const struct boot_data_s g_boot_data;
|
||||
extern const uint8_t g_dcd_data[];
|
||||
extern const uint32_t _vectors[];
|
||||
|
||||
#endif /* __BOARDS_ARM_IMXRT_IMXRT1060_EVK_SRC_IMXRT_FLEXSPI_NOR_BOOT_H */
|
||||
|
Loading…
Reference in New Issue
Block a user