Merge pull request #863 from vwadekar/tegra-changes-from-downstream-v4

Tegra changes from downstream v4
diff --git a/plat/nvidia/tegra/common/tegra_bl31_setup.c b/plat/nvidia/tegra/common/tegra_bl31_setup.c
index 246a03e..9e7e576 100644
--- a/plat/nvidia/tegra/common/tegra_bl31_setup.c
+++ b/plat/nvidia/tegra/common/tegra_bl31_setup.c
@@ -1,5 +1,5 @@
 /*
- * Copyright (c) 2015-2016, ARM Limited and Contributors. All rights reserved.
+ * Copyright (c) 2015-2017, ARM Limited and Contributors. All rights reserved.
  *
  * Redistribution and use in source and binary forms, with or without
  * modification, are permitted provided that the following conditions are met:
@@ -54,8 +54,12 @@
  * Declarations of linker defined symbols which will help us find the layout
  * of trusted SRAM
  ******************************************************************************/
-extern unsigned long __RO_START__;
-extern unsigned long __RO_END__;
+extern unsigned long __TEXT_START__;
+extern unsigned long __TEXT_END__;
+extern unsigned long __RW_START__;
+extern unsigned long __RW_END__;
+extern unsigned long __RODATA_START__;
+extern unsigned long __RODATA_END__;
 extern unsigned long __BL31_END__;
 
 extern uint64_t tegra_bl31_phys_base;
@@ -68,8 +72,10 @@
  * script to ensure that __RO_START__, __RO_END__ & __BL31_END__ linker symbols
  * refer to page-aligned addresses.
  */
-#define BL31_RO_BASE (unsigned long)(&__RO_START__)
-#define BL31_RO_LIMIT (unsigned long)(&__RO_END__)
+#define BL31_RW_START (unsigned long)(&__RW_START__)
+#define BL31_RW_END (unsigned long)(&__RW_END__)
+#define BL31_RODATA_BASE (unsigned long)(&__RODATA_START__)
+#define BL31_RODATA_END (unsigned long)(&__RODATA_END__)
 #define BL31_END (unsigned long)(&__BL31_END__)
 
 static entry_point_info_t bl33_image_ep_info, bl32_image_ep_info;
@@ -188,18 +194,18 @@
 	 * Get the base address of the UART controller to be used for the
 	 * console
 	 */
-	assert(plat_params->uart_id);
 	tegra_console_base = plat_get_console_from_id(plat_params->uart_id);
 
-	/*
-	 * Configure the UART port to be used as the console
-	 */
-	assert(tegra_console_base);
-	console_init(tegra_console_base, TEGRA_BOOT_UART_CLK_IN_HZ,
-		TEGRA_CONSOLE_BAUDRATE);
+	if (tegra_console_base != (uint64_t)0) {
+		/*
+		 * Configure the UART port to be used as the console
+		 */
+		console_init(tegra_console_base, TEGRA_BOOT_UART_CLK_IN_HZ,
+			TEGRA_CONSOLE_BAUDRATE);
 
-	/* Initialise crash console */
-	plat_crash_console_init();
+		/* Initialise crash console */
+		plat_crash_console_init();
+	}
 
 	/*
 	 * Do initial security configuration to allow DRAM/device access.
@@ -293,9 +299,7 @@
  ******************************************************************************/
 void bl31_plat_runtime_setup(void)
 {
-	/* Initialize the runtime console */
-	console_init(tegra_console_base, TEGRA_BOOT_UART_CLK_IN_HZ,
-		TEGRA_CONSOLE_BAUDRATE);
+	; /* do nothing */
 }
 
 /*******************************************************************************
@@ -304,11 +308,12 @@
  ******************************************************************************/
 void bl31_plat_arch_setup(void)
 {
-	unsigned long bl31_base_pa = tegra_bl31_phys_base;
-	unsigned long total_base = bl31_base_pa;
-	unsigned long total_size = BL32_BASE - BL31_RO_BASE;
-	unsigned long ro_start = bl31_base_pa;
-	unsigned long ro_size = BL31_RO_LIMIT - BL31_RO_BASE;
+	unsigned long rw_start = BL31_RW_START;
+	unsigned long rw_size = BL31_RW_END - BL31_RW_START;
+	unsigned long rodata_start = BL31_RODATA_BASE;
+	unsigned long rodata_size = BL31_RODATA_END - BL31_RODATA_BASE;
+	unsigned long code_base = (unsigned long)(&__TEXT_START__);
+	unsigned long code_size = (unsigned long)(&__TEXT_END__) - code_base;
 	const mmap_region_t *plat_mmio_map = NULL;
 #if USE_COHERENT_MEM
 	unsigned long coh_start, coh_size;
@@ -316,12 +321,15 @@
 	plat_params_from_bl2_t *params_from_bl2 = bl31_get_plat_params();
 
 	/* add memory regions */
-	mmap_add_region(total_base, total_base,
-			total_size,
+	mmap_add_region(rw_start, rw_start,
+			rw_size,
 			MT_MEMORY | MT_RW | MT_SECURE);
-	mmap_add_region(ro_start, ro_start,
-			ro_size,
-			MT_MEMORY | MT_RO | MT_SECURE);
+	mmap_add_region(rodata_start, rodata_start,
+			rodata_size,
+			MT_RO_DATA | MT_SECURE);
+	mmap_add_region(code_base, code_base,
+			code_size,
+			MT_CODE | MT_SECURE);
 
 	/* map TZDRAM used by BL31 as coherent memory */
 	if (TEGRA_TZRAM_BASE == tegra_bl31_phys_base) {
diff --git a/plat/nvidia/tegra/common/tegra_common.mk b/plat/nvidia/tegra/common/tegra_common.mk
index 7f789c5..3617396 100644
--- a/plat/nvidia/tegra/common/tegra_common.mk
+++ b/plat/nvidia/tegra/common/tegra_common.mk
@@ -1,5 +1,5 @@
 #
-# Copyright (c) 2015-2016, ARM Limited and Contributors. All rights reserved.
+# Copyright (c) 2015-2017, ARM Limited and Contributors. All rights reserved.
 #
 # Redistribution and use in source and binary forms, with or without
 # modification, are permitted provided that the following conditions are met:
@@ -36,6 +36,8 @@
 
 USE_COHERENT_MEM	:=	0
 
+SEPARATE_CODE_AND_RODATA :=	1
+
 PLAT_INCLUDES		:=	-Iplat/nvidia/tegra/include/drivers \
 				-Iplat/nvidia/tegra/include \
 				-Iplat/nvidia/tegra/include/${TARGET_SOC}
@@ -57,6 +59,7 @@
 				${COMMON_DIR}/tegra_delay_timer.c		\
 				${COMMON_DIR}/tegra_fiq_glue.c			\
 				${COMMON_DIR}/tegra_gic.c			\
+				${COMMON_DIR}/tegra_platform.c			\
 				${COMMON_DIR}/tegra_pm.c			\
 				${COMMON_DIR}/tegra_sip_calls.c			\
 				${COMMON_DIR}/tegra_topology.c
diff --git a/plat/nvidia/tegra/common/tegra_platform.c b/plat/nvidia/tegra/common/tegra_platform.c
new file mode 100644
index 0000000..5b96459
--- /dev/null
+++ b/plat/nvidia/tegra/common/tegra_platform.c
@@ -0,0 +1,167 @@
+/*
+ * Copyright (c) 2017, ARM Limited and Contributors. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *
+ * Redistributions of source code must retain the above copyright notice, this
+ * list of conditions and the following disclaimer.
+ *
+ * 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.
+ *
+ * Neither the name of ARM 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 HOLDER 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.
+ */
+
+#include <arch_helpers.h>
+#include <mmio.h>
+#include <tegra_def.h>
+#include <tegra_platform.h>
+#include <tegra_private.h>
+
+/*******************************************************************************
+ * Tegra platforms
+ ******************************************************************************/
+typedef enum tegra_platform {
+	TEGRA_PLATFORM_SILICON = 0,
+	TEGRA_PLATFORM_QT,
+	TEGRA_PLATFORM_FPGA,
+	TEGRA_PLATFORM_EMULATION,
+	TEGRA_PLATFORM_MAX,
+} tegra_platform_t;
+
+/*******************************************************************************
+ * Tegra macros defining all the SoC minor versions
+ ******************************************************************************/
+#define TEGRA_MINOR_QT			0
+#define TEGRA_MINOR_FPGA		1
+#define TEGRA_MINOR_EMULATION_MIN	2
+#define TEGRA_MINOR_EMULATION_MAX	10
+
+/*******************************************************************************
+ * Tegra major, minor version helper macros
+ ******************************************************************************/
+#define MAJOR_VERSION_SHIFT		0x4
+#define MAJOR_VERSION_MASK		0xF
+#define MINOR_VERSION_SHIFT		0x10
+#define MINOR_VERSION_MASK		0xF
+#define CHIP_ID_SHIFT			8
+#define CHIP_ID_MASK			0xFF
+
+/*******************************************************************************
+ * Tegra chip ID values
+ ******************************************************************************/
+typedef enum tegra_chipid {
+	TEGRA_CHIPID_TEGRA13 = 0x13,
+	TEGRA_CHIPID_TEGRA21 = 0x21,
+} tegra_chipid_t;
+
+/*
+ * Read the chip ID value
+ */
+static uint32_t tegra_get_chipid(void)
+{
+	return mmio_read_32(TEGRA_MISC_BASE + HARDWARE_REVISION_OFFSET);
+}
+
+/*
+ * Read the chip's major version from chip ID value
+ */
+static uint32_t tegra_get_chipid_major(void)
+{
+	return (tegra_get_chipid() >> MAJOR_VERSION_SHIFT) & MAJOR_VERSION_MASK;
+}
+
+/*
+ * Read the chip's minor version from the chip ID value
+ */
+static uint32_t tegra_get_chipid_minor(void)
+{
+	return (tegra_get_chipid() >> MINOR_VERSION_SHIFT) & MINOR_VERSION_MASK;
+}
+
+uint8_t tegra_chipid_is_t132(void)
+{
+	uint32_t chip_id = (tegra_get_chipid() >> CHIP_ID_SHIFT) & CHIP_ID_MASK;
+
+	return (chip_id == TEGRA_CHIPID_TEGRA13);
+}
+
+uint8_t tegra_chipid_is_t210(void)
+{
+	uint32_t chip_id = (tegra_get_chipid() >> CHIP_ID_SHIFT) & CHIP_ID_MASK;
+
+	return (chip_id == TEGRA_CHIPID_TEGRA21);
+}
+
+/*
+ * Read the chip ID value and derive the platform
+ */
+static tegra_platform_t tegra_get_platform(void)
+{
+	uint32_t major = tegra_get_chipid_major();
+	uint32_t minor = tegra_get_chipid_minor();
+
+	/* Actual silicon platforms have a non-zero major version */
+	if (major > 0)
+		return TEGRA_PLATFORM_SILICON;
+
+	/*
+	 * The minor version number is used by simulation platforms
+	 */
+
+	/*
+	 * Cadence's QuickTurn emulation system is a Solaris-based
+	 * chip emulation system
+	 */
+	if (minor == TEGRA_MINOR_QT)
+		return TEGRA_PLATFORM_QT;
+
+	/*
+	 * FPGAs are used during early software/hardware development
+	 */
+	if (minor == TEGRA_MINOR_FPGA)
+		return TEGRA_PLATFORM_FPGA;
+
+	/* Minor version reserved for other emulation platforms */
+	if ((minor > TEGRA_MINOR_FPGA) && (minor <= TEGRA_MINOR_EMULATION_MAX))
+		return TEGRA_PLATFORM_EMULATION;
+
+	/* unsupported platform */
+	return TEGRA_PLATFORM_MAX;
+}
+
+uint8_t tegra_platform_is_silicon(void)
+{
+	return (tegra_get_platform() == TEGRA_PLATFORM_SILICON);
+}
+
+uint8_t tegra_platform_is_qt(void)
+{
+	return (tegra_get_platform() == TEGRA_PLATFORM_QT);
+}
+
+uint8_t tegra_platform_is_fpga(void)
+{
+	return (tegra_get_platform() == TEGRA_PLATFORM_FPGA);
+}
+
+uint8_t tegra_platform_is_emulation(void)
+{
+	return (tegra_get_platform() == TEGRA_PLATFORM_EMULATION);
+}
diff --git a/plat/nvidia/tegra/common/tegra_pm.c b/plat/nvidia/tegra/common/tegra_pm.c
index b2703dd..5376d52 100644
--- a/plat/nvidia/tegra/common/tegra_pm.c
+++ b/plat/nvidia/tegra/common/tegra_pm.c
@@ -33,6 +33,7 @@
 #include <bl_common.h>
 #include <context.h>
 #include <context_mgmt.h>
+#include <console.h>
 #include <debug.h>
 #include <memctrl.h>
 #include <mmio.h>
@@ -45,6 +46,7 @@
 
 extern uint64_t tegra_bl31_phys_base;
 extern uint64_t tegra_sec_entry_point;
+extern uint64_t tegra_console_base;
 
 /*
  * The following platform setup functions are weakly defined. They
@@ -99,13 +101,13 @@
 					     const plat_local_state_t *states,
 					     unsigned int ncpu)
 {
-	plat_local_state_t target = PLAT_MAX_RET_STATE, temp;
+	plat_local_state_t target = PLAT_MAX_OFF_STATE, temp;
 
 	assert(ncpu);
 
 	do {
 		temp = *states++;
-		if ((temp > target) && (temp != PLAT_MAX_OFF_STATE))
+		if ((temp < target))
 			target = temp;
 	} while (--ncpu);
 
@@ -164,6 +166,11 @@
 {
 	tegra_soc_pwr_domain_suspend(target_state);
 
+	/* Disable console if we are entering deep sleep. */
+	if (target_state->pwr_domain_state[PLAT_MAX_PWR_LVL] ==
+			PSTATE_ID_SOC_POWERDN)
+		console_uninit();
+
 	/* disable GICC */
 	tegra_gic_cpuif_deactivate();
 }
@@ -206,6 +213,12 @@
 	if (target_state->pwr_domain_state[PLAT_MAX_PWR_LVL] ==
 			PSTATE_ID_SOC_POWERDN) {
 
+		/* Initialize the runtime console */
+		if (tegra_console_base != (uint64_t)0) {
+			console_init(tegra_console_base, TEGRA_BOOT_UART_CLK_IN_HZ,
+				TEGRA_CONSOLE_BAUDRATE);
+		}
+
 		/*
 		 * Restore Memory Controller settings as it loses state
 		 * during system suspend.
diff --git a/plat/nvidia/tegra/common/tegra_sip_calls.c b/plat/nvidia/tegra/common/tegra_sip_calls.c
index ba0e1ef..4dd4353 100644
--- a/plat/nvidia/tegra/common/tegra_sip_calls.c
+++ b/plat/nvidia/tegra/common/tegra_sip_calls.c
@@ -85,7 +85,6 @@
 	case TEGRA_SIP_NEW_VIDEOMEM_REGION:
 
 		/* clean up the high bits */
-		x1 = (uint32_t)x1;
 		x2 = (uint32_t)x2;
 
 		/*
diff --git a/plat/nvidia/tegra/include/plat_macros.S b/plat/nvidia/tegra/include/plat_macros.S
index 1afe454..7db6930 100644
--- a/plat/nvidia/tegra/include/plat_macros.S
+++ b/plat/nvidia/tegra/include/plat_macros.S
@@ -52,7 +52,7 @@
  */
 .macro plat_crash_print_regs
 	mov_imm	x16, TEGRA_GICC_BASE
-	cbz	x16, 1f
+
 	/* gicc base address is now in x16 */
 	adr	x6, gicc_regs	/* Load the gicc reg list to x6 */
 	/* Load the gicc regs to gp regs used by str_in_crash_buf_print */
@@ -63,6 +63,7 @@
 	bl	str_in_crash_buf_print
 
 	/* Print the GICD_ISPENDR regs */
+	mov_imm	x16, TEGRA_GICD_BASE
 	add	x7, x16, #GICD_ISPENDR
 	adr	x4, gicd_pend_reg
 	bl	asm_print_str
diff --git a/plat/nvidia/tegra/include/platform_def.h b/plat/nvidia/tegra/include/platform_def.h
index ad245e2..4df309d 100644
--- a/plat/nvidia/tegra/include/platform_def.h
+++ b/plat/nvidia/tegra/include/platform_def.h
@@ -77,7 +77,7 @@
 /*******************************************************************************
  * Platform specific page table and MMU setup constants
  ******************************************************************************/
-#define ADDR_SPACE_SIZE			(1ull << 32)
+#define ADDR_SPACE_SIZE			(1ull << 35)
 
 /*******************************************************************************
  * Some data must be aligned on the biggest cache line size in the platform.
diff --git a/plat/nvidia/tegra/include/t132/tegra_def.h b/plat/nvidia/tegra/include/t132/tegra_def.h
index 318f4de..314b700 100644
--- a/plat/nvidia/tegra/include/t132/tegra_def.h
+++ b/plat/nvidia/tegra/include/t132/tegra_def.h
@@ -80,6 +80,12 @@
 #define TEGRA_EVP_BASE			0x6000F000
 
 /*******************************************************************************
+ * Tegra Miscellaneous register constants
+ ******************************************************************************/
+#define TEGRA_MISC_BASE			0x70000000
+#define  HARDWARE_REVISION_OFFSET	0x804
+
+/*******************************************************************************
  * Tegra UART controller base addresses
  ******************************************************************************/
 #define TEGRA_UARTA_BASE		0x70006000
diff --git a/plat/nvidia/tegra/include/t210/tegra_def.h b/plat/nvidia/tegra/include/t210/tegra_def.h
index ce85427..d24377d 100644
--- a/plat/nvidia/tegra/include/t210/tegra_def.h
+++ b/plat/nvidia/tegra/include/t210/tegra_def.h
@@ -105,6 +105,12 @@
 #define TEGRA_EVP_BASE			0x6000F000
 
 /*******************************************************************************
+ * Tegra Miscellaneous register constants
+ ******************************************************************************/
+#define TEGRA_MISC_BASE			0x70000000
+#define  HARDWARE_REVISION_OFFSET	0x804
+
+/*******************************************************************************
  * Tegra UART controller base addresses
  ******************************************************************************/
 #define TEGRA_UARTA_BASE		0x70006000
diff --git a/plat/nvidia/tegra/include/tegra_platform.h b/plat/nvidia/tegra/include/tegra_platform.h
new file mode 100644
index 0000000..f9d7b60
--- /dev/null
+++ b/plat/nvidia/tegra/include/tegra_platform.h
@@ -0,0 +1,50 @@
+/*
+ * Copyright (c) 2017, ARM Limited and Contributors. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *
+ * Redistributions of source code must retain the above copyright notice, this
+ * list of conditions and the following disclaimer.
+ *
+ * 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.
+ *
+ * Neither the name of ARM 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 HOLDER 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.
+ */
+
+#ifndef __TEGRA_PLATFORM_H__
+#define __TEGRA_PLATFORM_H__
+
+#include <sys/cdefs.h>
+
+/*
+ * Tegra chip identifiers
+ */
+uint8_t tegra_is_t132(void);
+uint8_t tegra_is_t210(void);
+
+/*
+ * Tegra platform identifiers
+ */
+uint8_t tegra_platform_is_silicon(void);
+uint8_t tegra_platform_is_qt(void);
+uint8_t tegra_platform_is_emulation(void);
+uint8_t tegra_platform_is_fpga(void);
+
+#endif /* __TEGRA_PLATFORM_H__ */
diff --git a/plat/nvidia/tegra/soc/t210/plat_psci_handlers.c b/plat/nvidia/tegra/soc/t210/plat_psci_handlers.c
index 95fb93f..05028a1 100644
--- a/plat/nvidia/tegra/soc/t210/plat_psci_handlers.c
+++ b/plat/nvidia/tegra/soc/t210/plat_psci_handlers.c
@@ -76,7 +76,7 @@
 		 * Cluster powerdown/idle request only for afflvl 1
 		 */
 		req_state->pwr_domain_state[MPIDR_AFFLVL1] = state_id;
-		req_state->pwr_domain_state[MPIDR_AFFLVL0] = PLAT_MAX_OFF_STATE;
+		req_state->pwr_domain_state[MPIDR_AFFLVL0] = state_id;
 
 		break;
 
@@ -111,8 +111,10 @@
 
 	if (stateid_afflvl2 == PSTATE_ID_SOC_POWERDN) {
 
-		assert(stateid_afflvl0 == PLAT_MAX_OFF_STATE);
-		assert(stateid_afflvl1 == PLAT_MAX_OFF_STATE);
+		assert((stateid_afflvl0 == PLAT_MAX_OFF_STATE) ||
+		       (stateid_afflvl0 == PSTATE_ID_SOC_POWERDN));
+		assert((stateid_afflvl1 == PLAT_MAX_OFF_STATE) ||
+		       (stateid_afflvl1 == PSTATE_ID_SOC_POWERDN));
 
 		/* suspend the entire soc */
 		tegra_fc_soc_powerdn(mpidr);
diff --git a/plat/nvidia/tegra/soc/t210/platform_t210.mk b/plat/nvidia/tegra/soc/t210/platform_t210.mk
index 2c908f9..d0fe18f 100644
--- a/plat/nvidia/tegra/soc/t210/platform_t210.mk
+++ b/plat/nvidia/tegra/soc/t210/platform_t210.mk
@@ -28,7 +28,7 @@
 # POSSIBILITY OF SUCH DAMAGE.
 #
 
-TZDRAM_BASE				:= 0xFDC00000
+TZDRAM_BASE				:= 0xFF800000
 $(eval $(call add_define,TZDRAM_BASE))
 
 ERRATA_TEGRA_INVALIDATE_BTB_AT_BOOT	:= 1