Support for NVIDIA's Tegra T210 SoCs

T210 is the latest chip in the Tegra family of SoCs from NVIDIA. It is an
ARM v8 dual-cluster (A57/A53) SoC, with any one of the clusters being active
at a given point in time.

This patch adds support to boot the Trusted Firmware on T210 SoCs. The patch
also adds support to boot secondary CPUs, enter/exit core power states for
all CPUs in the slow/fast clusters. The support to switch between clusters
is still not available in this patch and would be available later.

Signed-off-by: Varun Wadekar <vwadekar@nvidia.com>
diff --git a/plat/nvidia/tegra/include/drivers/flowctrl.h b/plat/nvidia/tegra/include/drivers/flowctrl.h
new file mode 100644
index 0000000..8bc821d
--- /dev/null
+++ b/plat/nvidia/tegra/include/drivers/flowctrl.h
@@ -0,0 +1,85 @@
+/*
+ * Copyright (c) 2015, 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 __FLOWCTRL_H__
+#define __FLOWCTRL_H__
+
+#include <mmio.h>
+#include <tegra_def.h>
+
+#define FLOWCTRL_HALT_CPU0_EVENTS	0x0
+#define  FLOWCTRL_WAITEVENT		(2 << 29)
+#define  FLOWCTRL_WAIT_FOR_INTERRUPT	(4 << 29)
+#define  FLOWCTRL_JTAG_RESUME		(1 << 28)
+#define  FLOWCTRL_HALT_SCLK		(1 << 27)
+#define  FLOWCTRL_HALT_LIC_IRQ		(1 << 11)
+#define  FLOWCTRL_HALT_LIC_FIQ		(1 << 10)
+#define  FLOWCTRL_HALT_GIC_IRQ		(1 << 9)
+#define  FLOWCTRL_HALT_GIC_FIQ		(1 << 8)
+#define FLOWCTRL_HALT_BPMP_EVENTS	0x4
+#define FLOWCTRL_CPU0_CSR		0x8
+#define  FLOW_CTRL_CSR_PWR_OFF_STS	(1 << 16)
+#define  FLOWCTRL_CSR_INTR_FLAG		(1 << 15)
+#define  FLOWCTRL_CSR_EVENT_FLAG	(1 << 14)
+#define  FLOWCTRL_CSR_IMMEDIATE_WAKE	(1 << 3)
+#define  FLOWCTRL_CSR_ENABLE		(1 << 0)
+#define FLOWCTRL_HALT_CPU1_EVENTS	0x14
+#define FLOWCTRL_CPU1_CSR		0x18
+#define FLOWCTRL_CC4_CORE0_CTRL		0x6c
+#define FLOWCTRL_WAIT_WFI_BITMAP	0x100
+#define FLOWCTRL_L2_FLUSH_CONTROL	0x94
+#define FLOWCTRL_BPMP_CLUSTER_CONTROL	0x98
+#define  FLOWCTRL_BPMP_CLUSTER_PWRON_LOCK	(1 << 2)
+
+#define FLOWCTRL_ENABLE_EXT		12
+#define FLOWCTRL_ENABLE_EXT_MASK	3
+#define FLOWCTRL_PG_CPU_NONCPU		0x1
+#define FLOWCTRL_TURNOFF_CPURAIL	0x2
+
+static inline uint32_t tegra_fc_read_32(uint32_t off)
+{
+	return mmio_read_32(TEGRA_FLOWCTRL_BASE + off);
+}
+
+static inline void tegra_fc_write_32(uint32_t off, uint32_t val)
+{
+	mmio_write_32(TEGRA_FLOWCTRL_BASE + off, val);
+}
+
+void tegra_fc_cpu_idle(uint32_t mpidr);
+void tegra_fc_cluster_idle(uint32_t midr);
+void tegra_fc_cluster_powerdn(uint32_t midr);
+void tegra_fc_soc_powerdn(uint32_t midr);
+void tegra_fc_cpu_on(int cpu);
+void tegra_fc_cpu_off(int cpu);
+void tegra_fc_lock_active_cluster(void);
+void tegra_fc_reset_bpmp(void);
+
+#endif /* __FLOWCTRL_H__ */
diff --git a/plat/nvidia/tegra/include/drivers/memctrl.h b/plat/nvidia/tegra/include/drivers/memctrl.h
new file mode 100644
index 0000000..867f09e
--- /dev/null
+++ b/plat/nvidia/tegra/include/drivers/memctrl.h
@@ -0,0 +1,80 @@
+/*
+ * Copyright (c) 2015, 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 __MEMCTRL_H__
+#define __MEMCTRL_H__
+
+#include <mmio.h>
+#include <tegra_def.h>
+
+/* SMMU registers */
+#define MC_SMMU_CONFIG_0			0x10
+#define  MC_SMMU_CONFIG_0_SMMU_ENABLE_DISABLE	0
+#define  MC_SMMU_CONFIG_0_SMMU_ENABLE_ENABLE	1
+#define MC_SMMU_TLB_CONFIG_0			0x14
+#define  MC_SMMU_TLB_CONFIG_0_RESET_VAL		0x20000010
+#define MC_SMMU_PTC_CONFIG_0			0x18
+#define  MC_SMMU_PTC_CONFIG_0_RESET_VAL		0x2000003f
+#define MC_SMMU_TLB_FLUSH_0			0x30
+#define  TLB_FLUSH_VA_MATCH_ALL			0
+#define  TLB_FLUSH_ASID_MATCH_DISABLE		0
+#define  TLB_FLUSH_ASID_MATCH_SHIFT		31
+#define  MC_SMMU_TLB_FLUSH_ALL		\
+	 (TLB_FLUSH_VA_MATCH_ALL | 	\
+	 (TLB_FLUSH_ASID_MATCH_DISABLE << TLB_FLUSH_ASID_MATCH_SHIFT))
+#define MC_SMMU_PTC_FLUSH_0			0x34
+#define  MC_SMMU_PTC_FLUSH_ALL			0
+#define MC_SMMU_ASID_SECURITY_0			0x38
+#define  MC_SMMU_ASID_SECURITY			0
+#define MC_SMMU_TRANSLATION_ENABLE_0_0		0x228
+#define MC_SMMU_TRANSLATION_ENABLE_1_0		0x22c
+#define MC_SMMU_TRANSLATION_ENABLE_2_0		0x230
+#define MC_SMMU_TRANSLATION_ENABLE_3_0		0x234
+#define MC_SMMU_TRANSLATION_ENABLE_4_0		0xb98
+#define  MC_SMMU_TRANSLATION_ENABLE		(~0)
+
+/* TZDRAM carveout configuration registers */
+#define MC_SECURITY_CFG0_0			0x70
+#define MC_SECURITY_CFG1_0			0x74
+
+static inline uint32_t tegra_mc_read_32(uint32_t off)
+{
+	return mmio_read_32(TEGRA_MC_BASE + off);
+}
+
+static inline void tegra_mc_write_32(uint32_t off, uint32_t val)
+{
+	mmio_write_32(TEGRA_MC_BASE + off, val);
+}
+
+void tegra_memctrl_setup(void);
+void tegra_memctrl_tzdram_setup(uint64_t phys_base, uint32_t size_in_bytes);
+
+#endif /* __MEMCTRL_H__ */
diff --git a/plat/nvidia/tegra/include/drivers/pmc.h b/plat/nvidia/tegra/include/drivers/pmc.h
new file mode 100644
index 0000000..c0616d0
--- /dev/null
+++ b/plat/nvidia/tegra/include/drivers/pmc.h
@@ -0,0 +1,66 @@
+/*
+ * Copyright (c) 2015, 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 __PMC_H__
+#define __PMC_H__
+
+#include <mmio.h>
+#include <tegra_def.h>
+
+#define PMC_CONFIG				0x0
+#define PMC_PWRGATE_STATUS			0x38
+#define PMC_PWRGATE_TOGGLE			0x30
+#define  PMC_TOGGLE_START			0x100
+#define PMC_SCRATCH39				0x138
+#define PMC_SECURE_DISABLE2			0x2c4
+#define  PMC_SECURE_DISABLE2_WRITE22_ON		(1 << 28)
+#define PMC_SECURE_SCRATCH22			0x338
+#define PMC_SECURE_DISABLE3			0x2d8
+#define  PMC_SECURE_DISABLE3_WRITE34_ON		(1 << 20)
+#define  PMC_SECURE_DISABLE3_WRITE35_ON		(1 << 22)
+#define PMC_SECURE_SCRATCH34			0x368
+#define PMC_SECURE_SCRATCH35			0x36c
+
+static inline uint32_t tegra_pmc_read_32(uint32_t off)
+{
+	return mmio_read_32(TEGRA_PMC_BASE + off);
+}
+
+static inline void tegra_pmc_write_32(uint32_t off, uint32_t val)
+{
+	mmio_write_32(TEGRA_PMC_BASE + off, val);
+}
+
+void tegra_pmc_cpu_setup(uint64_t reset_addr);
+void tegra_pmc_lock_cpu_vectors(void);
+void tegra_pmc_cpu_on(int cpu);
+__dead2 void tegra_pmc_system_reset(void);
+
+#endif /* __PMC_H__ */
diff --git a/plat/nvidia/tegra/include/plat_macros.S b/plat/nvidia/tegra/include/plat_macros.S
new file mode 100644
index 0000000..0868b41
--- /dev/null
+++ b/plat/nvidia/tegra/include/plat_macros.S
@@ -0,0 +1,94 @@
+/*
+ * Copyright (c) 2015, 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 __PLAT_MACROS_S__
+#define __PLAT_MACROS_S__
+
+#include <gic_v2.h>
+#include <tegra_def.h>
+
+.section .rodata.gic_reg_name, "aS"
+gicc_regs:
+	.asciz "gicc_hppir", "gicc_ahppir", "gicc_ctlr", ""
+gicd_pend_reg:
+	.asciz "gicd_ispendr regs (Offsets 0x200 - 0x278)\n Offset:\t\t\tvalue\n"
+newline:
+	.asciz "\n"
+spacer:
+	.asciz ":\t\t0x"
+
+/* ---------------------------------------------
+ * The below macro prints out relevant GIC
+ * registers whenever an unhandled exception is
+ * taken in BL31.
+ * ---------------------------------------------
+ */
+.macro plat_print_gic_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 */
+	ldr	w8, [x16, #GICC_HPPIR]
+	ldr	w9, [x16, #GICC_AHPPIR]
+	ldr	w10, [x16, #GICC_CTLR]
+	/* Store to the crash buf and print to cosole */
+	bl	str_in_crash_buf_print
+
+	/* Print the GICD_ISPENDR regs */
+	add	x7, x16, #GICD_ISPENDR
+	adr	x4, gicd_pend_reg
+	bl	asm_print_str
+2:
+	sub	x4, x7, x16
+	cmp	x4, #0x280
+	b.eq	1f
+	bl	asm_print_hex
+	adr	x4, spacer
+	bl	asm_print_str
+	ldr	x4, [x7], #8
+	bl	asm_print_hex
+	adr	x4, newline
+	bl	asm_print_str
+	b	2b
+1:
+.endm
+
+/* ------------------------------------------------
+ * The below required platform porting macro prints
+ * out relevant interconnect registers whenever an
+ * unhandled exception is taken in BL3-1.
+  * ------------------------------------------------
+ */
+.macro plat_print_interconnect_regs
+	nop
+.endm
+
+#endif /* __PLAT_MACROS_S__ */
diff --git a/plat/nvidia/tegra/include/platform_def.h b/plat/nvidia/tegra/include/platform_def.h
new file mode 100644
index 0000000..6be777e
--- /dev/null
+++ b/plat/nvidia/tegra/include/platform_def.h
@@ -0,0 +1,90 @@
+/*
+ * Copyright (c) 2015, 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 __PLATFORM_DEF_H__
+#define __PLATFORM_DEF_H__
+
+#include <arch.h>
+#include <common_def.h>
+
+/*******************************************************************************
+ * Generic platform constants
+ ******************************************************************************/
+
+/* Size of cacheable stacks */
+#if DEBUG_XLAT_TABLE
+#define PLATFORM_STACK_SIZE 0x800
+#elif IMAGE_BL31
+#define PLATFORM_STACK_SIZE 0x400
+#endif
+
+#define TEGRA_PRIMARY_CPU		0x0
+
+#define PLATFORM_MAX_AFFLVL		MPIDR_AFFLVL2
+#define PLATFORM_CORE_COUNT		PLATFORM_MAX_CPUS_PER_CLUSTER
+#define PLATFORM_NUM_AFFS		((PLATFORM_CLUSTER_COUNT * \
+					  PLATFORM_CORE_COUNT) + \
+					  PLATFORM_CLUSTER_COUNT + 1)
+
+/*******************************************************************************
+ * Platform console related constants
+ ******************************************************************************/
+#define TEGRA_CONSOLE_BAUDRATE		115200
+#define TEGRA_BOOT_UART_CLK_IN_HZ	408000000
+
+/*******************************************************************************
+ * Platform memory map related constants
+ ******************************************************************************/
+/* Size of trusted dram */
+#define TZDRAM_SIZE			0x00400000
+#define TZDRAM_END			(TZDRAM_BASE + TZDRAM_SIZE)
+
+/*******************************************************************************
+ * BL31 specific defines.
+ ******************************************************************************/
+#define BL31_BASE			TZDRAM_BASE
+#define BL31_LIMIT			(TZDRAM_BASE + 0x11FFF)
+
+/*******************************************************************************
+ * Platform specific page table and MMU setup constants
+ ******************************************************************************/
+#define ADDR_SPACE_SIZE			(1ull << 32)
+#define MAX_XLAT_TABLES			3
+#define MAX_MMAP_REGIONS		8
+
+/*******************************************************************************
+ * Some data must be aligned on the biggest cache line size in the platform.
+ * This is known only to the platform as it might have a combination of
+ * integrated and external caches.
+ ******************************************************************************/
+#define CACHE_WRITEBACK_SHIFT		6
+#define CACHE_WRITEBACK_GRANULE		(1 << CACHE_WRITEBACK_SHIFT)
+
+#endif /* __PLATFORM_DEF_H__ */
diff --git a/plat/nvidia/tegra/include/t210/tegra_def.h b/plat/nvidia/tegra/include/t210/tegra_def.h
new file mode 100644
index 0000000..c72d081
--- /dev/null
+++ b/plat/nvidia/tegra/include/t210/tegra_def.h
@@ -0,0 +1,91 @@
+/*
+ * Copyright (c) 2015, 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_DEF_H__
+#define __TEGRA_DEF_H__
+
+#include <platform_def.h>
+
+/*******************************************************************************
+ * Implementation defined ACTLR_EL3 bit definitions
+ ******************************************************************************/
+#define ACTLR_EL3_L2ACTLR_BIT		(1 << 6)
+#define ACTLR_EL3_L2ECTLR_BIT		(1 << 5)
+#define ACTLR_EL3_L2CTLR_BIT		(1 << 4)
+#define ACTLR_EL3_CPUECTLR_BIT		(1 << 1)
+#define ACTLR_EL3_CPUACTLR_BIT		(1 << 0)
+#define ACTLR_EL3_ENABLE_ALL_ACCESS	(ACTLR_EL3_L2ACTLR_BIT | \
+					 ACTLR_EL3_L2ECTLR_BIT | \
+					 ACTLR_EL3_L2CTLR_BIT | \
+					 ACTLR_EL3_CPUECTLR_BIT | \
+					 ACTLR_EL3_CPUACTLR_BIT)
+
+/*******************************************************************************
+ * GIC memory map
+ ******************************************************************************/
+#define TEGRA_GICD_BASE			0x50041000
+#define TEGRA_GICC_BASE			0x50042000
+
+/*******************************************************************************
+ * Tegra micro-seconds timer constants
+ ******************************************************************************/
+#define TEGRA_TMRUS_BASE		0x60005010
+
+/*******************************************************************************
+ * Tegra Clock and Reset Controller constants
+ ******************************************************************************/
+#define TEGRA_CAR_RESET_BASE		0x60006000
+
+/*******************************************************************************
+ * Tegra Flow Controller constants
+ ******************************************************************************/
+#define TEGRA_FLOWCTRL_BASE		0x60007000
+
+/*******************************************************************************
+ * Tegra Secure Boot Controller constants
+ ******************************************************************************/
+#define TEGRA_SB_BASE			0x6000C200
+
+/*******************************************************************************
+ * Tegra Exception Vectors constants
+ ******************************************************************************/
+#define TEGRA_EVP_BASE			0x6000F000
+
+/*******************************************************************************
+ * Tegra Power Mgmt Controller constants
+ ******************************************************************************/
+#define TEGRA_PMC_BASE			0x7000E400
+
+/*******************************************************************************
+ * Tegra Memory Controller constants
+ ******************************************************************************/
+#define TEGRA_MC_BASE			0x70019000
+
+#endif /* __TEGRA_DEF_H__ */
diff --git a/plat/nvidia/tegra/include/tegra_private.h b/plat/nvidia/tegra/include/tegra_private.h
new file mode 100644
index 0000000..484879e
--- /dev/null
+++ b/plat/nvidia/tegra/include/tegra_private.h
@@ -0,0 +1,70 @@
+/*
+ * Copyright (c) 2015, 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_PRIVATE_H__
+#define __TEGRA_PRIVATE_H__
+
+#include <xlat_tables.h>
+#include <platform_def.h>
+
+typedef struct plat_params_from_bl2 {
+	uint64_t tzdram_size;
+	uintptr_t bl32_params;
+} plat_params_from_bl2_t;
+
+/* Declarations for plat_setup.c */
+const mmap_region_t *plat_get_mmio_map(void);
+uint64_t plat_get_syscnt_freq(void);
+
+/* Declarations for plat_secondary.c */
+void plat_secondary_setup(void);
+int plat_lock_cpu_vectors(void);
+
+/* Declarations for tegra_gic.c */
+void tegra_gic_setup(void);
+void tegra_gic_cpuif_deactivate(void);
+
+/* Declarations for tegra_security.c */
+void tegra_security_setup(void);
+void tegra_security_setup_videomem(uintptr_t base, uint64_t size);
+
+/* Declarations for tegra_pm.c */
+void tegra_pm_system_suspend_entry(void);
+void tegra_pm_system_suspend_exit(void);
+int tegra_system_suspended(void);
+
+/* Declarations for tegraXXX_pm.c */
+int tegra_prepare_cpu_suspend(unsigned int id, unsigned int afflvl);
+int tegra_prepare_cpu_on_finish(unsigned long mpidr);
+
+/* Declarations for tegra_bl31_setup.c */
+plat_params_from_bl2_t *bl31_get_plat_params(void);
+
+#endif /* __TEGRA_PRIVATE_H__ */