Merge pull request #310 from sandrine-bailleux/sb/tf-issue-304-phase1

Enhance BL3-1 entrypoint handling to support non-TF boot firmware - Phase 1
diff --git a/Makefile b/Makefile
index 9fabdca..c33670b 100644
--- a/Makefile
+++ b/Makefile
@@ -215,6 +215,7 @@
 				-Iinclude/drivers		\
 				-Iinclude/drivers/arm		\
 				-Iinclude/drivers/io		\
+				-Iinclude/drivers/ti/uart	\
 				-Iinclude/lib			\
 				-Iinclude/lib/aarch64		\
 				-Iinclude/lib/cpus/aarch64	\
diff --git a/bl1/bl1_main.c b/bl1/bl1_main.c
index a5db085..a7a872c 100644
--- a/bl1/bl1_main.c
+++ b/bl1/bl1_main.c
@@ -126,9 +126,9 @@
 	 * Ensure that MMU/Caches and coherency are turned on
 	 */
 	val = read_sctlr_el3();
-	assert(val | SCTLR_M_BIT);
-	assert(val | SCTLR_C_BIT);
-	assert(val | SCTLR_I_BIT);
+	assert(val & SCTLR_M_BIT);
+	assert(val & SCTLR_C_BIT);
+	assert(val & SCTLR_I_BIT);
 	/*
 	 * Check that Cache Writeback Granule (CWG) in CTR_EL0 matches the
 	 * provided platform value
diff --git a/bl31/aarch64/runtime_exceptions.S b/bl31/aarch64/runtime_exceptions.S
index accb11b..bbc7f1b 100644
--- a/bl31/aarch64/runtime_exceptions.S
+++ b/bl31/aarch64/runtime_exceptions.S
@@ -79,6 +79,14 @@
 	str	x30, [sp, #CTX_GPREGS_OFFSET + CTX_GPREG_LR]
 	bl	save_gp_registers
 
+	/*
+	 * Save the EL3 system registers needed to return from
+	 * this exception.
+	 */
+	mrs	x0, spsr_el3
+	mrs	x1, elr_el3
+	stp	x0, x1, [sp, #CTX_EL3STATE_OFFSET + CTX_SPSR_EL3]
+
 	/* Switch to the runtime stack i.e. SP_EL0 */
 	ldr	x2, [sp, #CTX_EL3STATE_OFFSET + CTX_RUNTIME_SP]
 	mov	x20, sp
@@ -96,13 +104,29 @@
 
 	/*
 	 * Get the registered handler for this interrupt type. A
-	 * NULL return value implies that an interrupt was generated
-	 * for which there is no handler registered or the interrupt
-	 * was routed incorrectly. This is a problem of the framework
-	 * so report it as an error.
+	 * NULL return value could be 'cause of the following
+	 * conditions:
+	 *
+	 * a. An interrupt of a type was routed correctly but a
+	 *    handler for its type was not registered.
+	 *
+	 * b. An interrupt of a type was not routed correctly so
+	 *    a handler for its type was not registered.
+	 *
+	 * c. An interrupt of a type was routed correctly to EL3,
+	 *    but was deasserted before its pending state could
+	 *    be read. Another interrupt of a different type pended
+	 *    at the same time and its type was reported as pending
+	 *    instead. However, a handler for this type was not
+	 *    registered.
+	 *
+	 * a. and b. can only happen due to a programming error.
+	 * The occurrence of c. could be beyond the control of
+	 * Trusted Firmware. It makes sense to return from this
+	 * exception instead of reporting an error.
 	 */
 	bl	get_interrupt_type_handler
-	cbz	x0, interrupt_error_\label
+	cbz	x0, interrupt_exit_\label
 	mov	x21, x0
 
 	mov	x0, #INTR_ID_UNAVAILABLE
@@ -117,14 +141,6 @@
 	b.eq	interrupt_exit_\label
 #endif
 
-	/*
-	 * Save the EL3 system registers needed to return from
-	 * this exception.
-	 */
-	mrs	x3, spsr_el3
-	mrs	x4, elr_el3
-	stp	x3, x4, [x20, #CTX_EL3STATE_OFFSET + CTX_SPSR_EL3]
-
 	/* Set the current security state in the 'flags' parameter */
 	mrs	x2, scr_el3
 	ubfx	x1, x2, #0, #1
@@ -142,13 +158,6 @@
 	/* Return from exception, possibly in a different security state */
 	b	el3_exit
 
-	/*
-	 * This label signifies a problem with the interrupt management
-	 * framework where it is not safe to go back to the instruction
-	 * where the interrupt was generated.
-	 */
-interrupt_error_\label:
-	bl	report_unhandled_interrupt
 	.endm
 
 
diff --git a/docs/plat/nvidia-tegra.md b/docs/plat/nvidia-tegra.md
new file mode 100644
index 0000000..e4f9a05
--- /dev/null
+++ b/docs/plat/nvidia-tegra.md
@@ -0,0 +1,30 @@
+Tegra-T210 Overview
+====================
+
+T210 has Quad ARM® Cortex®-A57 cores in a switched configuration with a
+companion set of quad ARM Cortex-A53 cores. The Cortex-A57 and A53 cores
+support ARMv8, executing both 64-bit Aarch64 code, and 32-bit Aarch32 code
+including legacy ARMv7 applications. The Cortex-A57 processors each have
+48 KB Instruction and 32 KB Data Level 1 caches; and have a 2 MB shared
+Level 2 unified cache. The Cortex-A53 processors each have 32 KB Instruction
+and 32 KB Data Level 1 caches; and have a 512 KB shared Level 2 unified cache.
+
+Directory structure
+====================
+
+* plat/nvidia/tegra/common - Common code for all Tegra SoCs
+* plat/nvidia/tegra/soc/txxx - Chip specific code
+
+Trusted OS dispatcher
+=====================
+Tegra supports multiple Trusted OS', Trusted Little Kernel (TLK) being one of
+them. In order to include the 'tlkd' dispatcher in the image, pass 'SPD=tlkd'
+on the command line while preparing a bl31 image. This allows other Trusted OS
+vendors to use the upstream code and include their dispatchers in the image
+without changing any makefiles.
+
+Preparing the BL31 image to run on Tegra SoCs
+===================================================
+CROSS_COMPILE=<path-to-aarch64-gcc>/bin/aarch64-none-elf- make PLAT=tegra \
+TARGET_SOC=<target-soc e.g. t210> BL32=<path-to-trusted-os-binary> \
+SPD=<dispatcher e.g. tlkd> all
diff --git a/docs/optee-dispatcher.md b/docs/spd/optee-dispatcher.md
similarity index 100%
rename from docs/optee-dispatcher.md
rename to docs/spd/optee-dispatcher.md
diff --git a/docs/tlk-dispatcher.md b/docs/spd/tlk-dispatcher.md
similarity index 93%
rename from docs/tlk-dispatcher.md
rename to docs/spd/tlk-dispatcher.md
index a2212b5..890b35e 100644
--- a/docs/tlk-dispatcher.md
+++ b/docs/spd/tlk-dispatcher.md
@@ -10,10 +10,11 @@
 just needs to compile, any BL32 image would do. To use TLK as the BL32, please
 refer to the "Build TLK" section.
 
-Once a BL32 is ready, TLKD can be compiled using the following command:
+Once a BL32 is ready, TLKD can be included in the image using the following
+command:
 
 CROSS_COMPILE=<path_to_linaro_chain>/bin/aarch64-none-elf- make NEED_BL1=0
-NEED_BL2=0 BL32=<path_to_BL32_image> PLAT=<platform> all
+NEED_BL2=0 BL32=<path_to_BL32_image> PLAT=<platform> SPD=tlkd all
 _
 Trusted Little Kernel (TLK)
 ===========================
diff --git a/docs/user-guide.md b/docs/user-guide.md
index 908665c..ef26f11 100644
--- a/docs/user-guide.md
+++ b/docs/user-guide.md
@@ -326,7 +326,7 @@
 
 #### ARM development platform specific build options
 
-*   `ARM_TSP_RAM_LOCATION_ID`: location of the TSP binary. Options:
+*   `ARM_TSP_RAM_LOCATION`: location of the TSP binary. Options:
     -   `tsram` : Trusted SRAM (default option)
     -   `tdram` : Trusted DRAM (if available)
     -   `dram`  : Secure region in DRAM (configured by the TrustZone controller)
diff --git a/drivers/arm/gic/arm_gic.c b/drivers/arm/gic/arm_gic.c
index 2888e71..5217471 100644
--- a/drivers/arm/gic/arm_gic.c
+++ b/drivers/arm/gic/arm_gic.c
@@ -401,7 +401,7 @@
 	uint32_t id;
 
 	assert(g_gicc_base);
-	id = gicc_read_hppir(g_gicc_base);
+	id = gicc_read_hppir(g_gicc_base) & INT_ID_MASK;
 
 	/* Assume that all secure interrupts are S-EL1 interrupts */
 	if (id < 1022)
@@ -423,7 +423,7 @@
 	uint32_t id;
 
 	assert(g_gicc_base);
-	id = gicc_read_hppir(g_gicc_base);
+	id = gicc_read_hppir(g_gicc_base) & INT_ID_MASK;
 
 	if (id < 1022)
 		return id;
@@ -435,7 +435,7 @@
 	 * Find out which non-secure interrupt it is under the assumption that
 	 * the GICC_CTLR.AckCtl bit is 0.
 	 */
-	return gicc_read_ahppir(g_gicc_base);
+	return gicc_read_ahppir(g_gicc_base) & INT_ID_MASK;
 }
 
 /*******************************************************************************
diff --git a/drivers/arm/sp804/sp804_delay_timer.c b/drivers/arm/sp804/sp804_delay_timer.c
new file mode 100644
index 0000000..78940bf
--- /dev/null
+++ b/drivers/arm/sp804/sp804_delay_timer.c
@@ -0,0 +1,79 @@
+/*
+ * 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.
+ */
+
+#include <assert.h>
+#include <delay_timer.h>
+#include <mmio.h>
+
+uintptr_t sp804_base_addr;
+
+#define SP804_TIMER1_LOAD	(sp804_base_addr + 0x000)
+#define SP804_TIMER1_VALUE	(sp804_base_addr + 0x004)
+#define SP804_TIMER1_CONTROL	(sp804_base_addr + 0x008)
+#define SP804_TIMER1_BGLOAD	(sp804_base_addr + 0x018)
+
+#define TIMER_CTRL_ONESHOT	(1 << 0)
+#define TIMER_CTRL_32BIT	(1 << 1)
+#define TIMER_CTRL_DIV1		(0 << 2)
+#define TIMER_CTRL_DIV16	(1 << 2)
+#define TIMER_CTRL_DIV256	(2 << 2)
+#define TIMER_CTRL_IE		(1 << 5)
+#define TIMER_CTRL_PERIODIC	(1 << 6)
+#define TIMER_CTRL_ENABLE	(1 << 7)
+
+/********************************************************************
+ * The SP804 timer delay function
+ ********************************************************************/
+uint32_t sp804_get_timer_value(void)
+{
+	return mmio_read_32(SP804_TIMER1_VALUE);
+}
+
+/********************************************************************
+ * Initialize the 1st timer in the SP804 dual timer with a base
+ * address and a timer ops
+ ********************************************************************/
+void sp804_timer_ops_init(uintptr_t base_addr, const timer_ops_t *ops)
+{
+	assert(base_addr != 0);
+	assert(ops != 0 && ops->get_timer_value == sp804_get_timer_value);
+
+	sp804_base_addr = base_addr;
+	timer_init(ops);
+
+	/* disable timer1 */
+	mmio_write_32(SP804_TIMER1_CONTROL, 0);
+	mmio_write_32(SP804_TIMER1_LOAD, UINT32_MAX);
+	mmio_write_32(SP804_TIMER1_VALUE, UINT32_MAX);
+
+	/* enable as a free running 32-bit counter */
+	mmio_write_32(SP804_TIMER1_CONTROL,
+			TIMER_CTRL_32BIT | TIMER_CTRL_ENABLE);
+}
diff --git a/drivers/delay_timer/delay_timer.c b/drivers/delay_timer/delay_timer.c
new file mode 100644
index 0000000..0bee876
--- /dev/null
+++ b/drivers/delay_timer/delay_timer.c
@@ -0,0 +1,87 @@
+/*
+ * 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.
+ */
+
+#include <assert.h>
+#include <delay_timer.h>
+#include <platform_def.h>
+
+/***********************************************************
+ * The delay timer implementation
+ ***********************************************************/
+static const timer_ops_t *ops;
+
+/***********************************************************
+ * Delay for the given number of microseconds. The driver must
+ * be initialized before calling this function.
+ ***********************************************************/
+void udelay(uint32_t usec)
+{
+	assert(ops != 0 &&
+		(ops->clk_mult != 0) &&
+		(ops->clk_div != 0) &&
+		(ops->get_timer_value != 0));
+
+	uint32_t start, cnt, delta, delta_us;
+
+	/* counter is decreasing */
+	start = ops->get_timer_value();
+	do {
+		cnt = ops->get_timer_value();
+		if (cnt > start) {
+			delta = UINT32_MAX - cnt;
+			delta += start;
+		} else
+			delta = start - cnt;
+		delta_us = (delta * ops->clk_mult) / ops->clk_div;
+	} while (delta_us < usec);
+}
+
+/***********************************************************
+ * Delay for the given number of milliseconds. The driver must
+ * be initialized before calling this function.
+ ***********************************************************/
+void mdelay(uint32_t msec)
+{
+	udelay(msec*1000);
+}
+
+/***********************************************************
+ * Initialize the timer. The fields in the provided timer
+ * ops pointer must be valid.
+ ***********************************************************/
+void timer_init(const timer_ops_t *ops_ptr)
+{
+	assert(ops_ptr != 0  &&
+		(ops_ptr->clk_mult != 0) &&
+		(ops_ptr->clk_div != 0) &&
+		(ops_ptr->get_timer_value != 0));
+
+	ops = ops_ptr;
+}
diff --git a/drivers/ti/uart/16550_console.S b/drivers/ti/uart/16550_console.S
new file mode 100644
index 0000000..ebb4615
--- /dev/null
+++ b/drivers/ti/uart/16550_console.S
@@ -0,0 +1,155 @@
+/*
+ * 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.
+ */
+
+#include <arch.h>
+#include <asm_macros.S>
+#include <uart_16550.h>
+
+	.globl	console_core_init
+	.globl	console_core_putc
+	.globl	console_core_getc
+
+	/* -----------------------------------------------
+	 * int console_core_init(unsigned long base_addr,
+	 * unsigned int uart_clk, unsigned int baud_rate)
+	 * Function to initialize the console without a
+	 * C Runtime to print debug information. This
+	 * function will be accessed by console_init and
+	 * crash reporting.
+	 * In: x0 - console base address
+	 *     w1 - Uart clock in Hz
+	 *     w2 - Baud rate
+	 * Out: return 1 on success
+	 * Clobber list : x1, x2, x3
+	 * -----------------------------------------------
+	 */
+func console_core_init
+	/* Check the input base address */
+	cbz	x0, init_fail
+	/* Check baud rate and uart clock for sanity */
+	cbz	w1, init_fail
+	cbz	w2, init_fail
+
+	/* Program the baudrate */
+	/* Divisor =  Uart clock / (16 * baudrate) */
+	lsl	w2, w2, #4
+	udiv	w2, w1, w2
+	and	w1, w2, #0xff		/* w1 = DLL */
+	lsr	w2, w2, #8
+	and	w2, w2, #0xff		/* w2 = DLLM */
+	ldr	w3, [x0, #UARTLCR]
+	orr	w3, w3, #UARTLCR_DLAB
+	str	w3, [x0, #UARTLCR]	/* enable DLL, DLLM programming */
+	str	w1, [x0, #UARTDLL]	/* program DLL */
+	str	w2, [x0, #UARTDLLM]	/* program DLLM */
+	mov	w2, #~UARTLCR_DLAB
+	and	w3, w3, w2
+	str	w3, [x0, #UARTLCR]	/* disable DLL, DLLM programming */
+
+	/* 8n1 */
+	mov	w3, #3
+	str	w3, [x0, #UARTLCR]
+	/* no interrupt */
+	mov	w3, #0
+	str	w3, [x0, #UARTIER]
+	/* enable fifo, DMA */
+	mov	w3, #(UARTFCR_FIFOEN | UARTFCR_DMAEN)
+	str	w3, [x0, #UARTFCR]
+	/* DTR + RTS */
+	mov	w3, #3
+	str	w3, [x0, #UARTMCR]
+	mov	w0, #1
+init_fail:
+	ret
+endfunc console_core_init
+
+	/* --------------------------------------------------------
+	 * int console_core_putc(int c, unsigned int base_addr)
+	 * Function to output a character over the console. It
+	 * returns the character printed on success or -1 on error.
+	 * In : w0 - character to be printed
+	 *      x1 - console base address
+	 * Out : return -1 on error else return character.
+	 * Clobber list : x2
+	 * --------------------------------------------------------
+	 */
+func console_core_putc
+	/* Check the input parameter */
+	cbz	x1, putc_error
+
+	/* Prepend '\r' to '\n' */
+	cmp	w0, #0xA
+	b.ne	2f
+	/* Check if the transmit FIFO is full */
+1:	ldr	w2, [x1, #UARTLSR]
+	and	w2, w2, #(UARTLSR_TEMT | UARTLSR_THRE)
+	cmp	w2, #(UARTLSR_TEMT | UARTLSR_THRE)
+	b.ne	1b
+	mov	w2, #0xD		/* '\r' */
+	str	w2, [x1, #UARTTX]
+	ldr	w2, [x1, #UARTFCR]
+	orr	w2, w2, #UARTFCR_TXCLR
+	str	w2, [x1, #UARTFCR]
+
+	/* Check if the transmit FIFO is full */
+2:	ldr	w2, [x1, #UARTLSR]
+	and	w2, w2, #(UARTLSR_TEMT | UARTLSR_THRE)
+	cmp	w2, #(UARTLSR_TEMT | UARTLSR_THRE)
+	b.ne	2b
+	str	w0, [x1, #UARTTX]
+	ldr	w2, [x1, #UARTFCR]
+	orr	w2, w2, #UARTFCR_TXCLR
+	str	w2, [x1, #UARTFCR]
+	ret
+putc_error:
+	mov	w0, #-1
+	ret
+endfunc console_core_putc
+
+	/* ---------------------------------------------
+	 * int console_core_getc(void)
+	 * Function to get a character from the console.
+	 * It returns the character grabbed on success
+	 * or -1 on error.
+	 * In : w0 - console base address
+	 * Out : return -1 on error else return character.
+	 * Clobber list : x0, x1
+	 * ---------------------------------------------
+	 */
+func console_core_getc
+	/* Check if the receive FIFO is empty */
+1:	ldr	w1, [x0, #UARTLSR]
+	tbz	w1, #UARTLSR_RDR, 1b
+	ldr	w0, [x0, #UARTRX]
+	ret
+getc_error:
+	mov	w0, #-1
+	ret
+endfunc console_core_getc
diff --git a/include/drivers/arm/gic_v2.h b/include/drivers/arm/gic_v2.h
index a2d3eee..54276b8 100644
--- a/include/drivers/arm/gic_v2.h
+++ b/include/drivers/arm/gic_v2.h
@@ -99,6 +99,9 @@
 #define GICC_DIR		0x1000
 #define GICC_PRIODROP           GICC_EOIR
 
+/* Common CPU Interface definitions */
+#define INT_ID_MASK		0x3ff
+
 /* GICC_CTLR bit definitions */
 #define EOI_MODE_NS		(1 << 10)
 #define EOI_MODE_S		(1 << 9)
diff --git a/include/drivers/arm/sp804_delay_timer.h b/include/drivers/arm/sp804_delay_timer.h
new file mode 100644
index 0000000..5a33571
--- /dev/null
+++ b/include/drivers/arm/sp804_delay_timer.h
@@ -0,0 +1,47 @@
+/*
+ * 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 __SP804_DELAY_TIMER_H__
+#define __SP804_DELAY_TIMER_H__
+
+#include <delay_timer.h>
+#include <stdint.h>
+
+
+uint32_t sp804_get_timer_value(void);
+
+void sp804_timer_ops_init(uintptr_t base_addr, const timer_ops_t *ops);
+
+#define sp804_timer_init(base_addr, clk_mult, clk_div)			\
+	sp804_timer_ops_init((base_addr), &(const timer_ops_t)		\
+			{ sp804_get_timer_value, (clk_mult), (clk_div) })
+
+
+#endif /* __SP804_DELAY_TIMER_H__ */
diff --git a/include/drivers/delay_timer.h b/include/drivers/delay_timer.h
new file mode 100644
index 0000000..4f3bdc8
--- /dev/null
+++ b/include/drivers/delay_timer.h
@@ -0,0 +1,55 @@
+/*
+ * 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 __DELAY_TIMER_H__
+#define __DELAY_TIMER_H__
+
+#include <stdint.h>
+
+/********************************************************************
+ * A simple timer driver providing synchronous delay functionality.
+ * The driver must be initialized with a structure that provides a
+ * function pointer to return the timer value and a clock
+ * multiplier/divider. The ratio of the multiplier and the divider is
+ * the clock frequency in MHz.
+ ********************************************************************/
+
+typedef struct timer_ops {
+	uint32_t (*get_timer_value)(void);
+	uint32_t clk_mult;
+	uint32_t clk_div;
+} timer_ops_t;
+
+void mdelay(uint32_t msec);
+void udelay(uint32_t usec);
+void timer_init(const timer_ops_t *ops);
+
+
+#endif /* __DELAY_TIMER_H__ */
diff --git a/include/drivers/ti/uart/uart_16550.h b/include/drivers/ti/uart/uart_16550.h
new file mode 100644
index 0000000..2c814ef
--- /dev/null
+++ b/include/drivers/ti/uart/uart_16550.h
@@ -0,0 +1,93 @@
+/*
+ * 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 __UART_16550_H__
+#define __UART_16550_H__
+
+/* UART16550 Registers */
+#define UARTTX			0x0
+#define UARTRX			0x0
+#define UARTDLL			0x0
+#define UARTIER			0x4
+#define UARTDLLM		0x4
+#define UARTIIR			0x8
+#define UARTFCR			0x8
+#define UARTLCR			0xc
+#define UARTMCR			0x10
+#define UARTLSR			0x14
+#define UARTMSR			0x18
+#define UARTSPR			0x1c
+#define UARTCSR			0x20
+#define UARTRXFIFOCFG		0x24
+#define UARTMIE			0x28
+#define UARTVNDR		0x2c
+#define UARTASR			0x3c
+
+/* FIFO Control Register bits */
+#define UARTFCR_FIFOMD_16450	(0 << 6)
+#define UARTFCR_FIFOMD_16550	(1 << 6)
+#define UARTFCR_RXTRIG_1	(0 << 6)
+#define UARTFCR_RXTRIG_4	(1 << 6)
+#define UARTFCR_RXTRIG_8	(2 << 6)
+#define UARTFCR_RXTRIG_16	(3 << 6)
+#define UARTFCR_TXTRIG_1	(0 << 4)
+#define UARTFCR_TXTRIG_4	(1 << 4)
+#define UARTFCR_TXTRIG_8	(2 << 4)
+#define UARTFCR_TXTRIG_16	(3 << 4)
+#define UARTFCR_DMAEN		(1 << 3)	/* Enable DMA mode */
+#define UARTFCR_TXCLR		(1 << 2)	/* Clear contents of Tx FIFO */
+#define UARTFCR_RXCLR		(1 << 1)	/* Clear contents of Rx FIFO */
+#define UARTFCR_FIFOEN		(1 << 0)	/* Enable the Tx/Rx FIFO */
+
+/* Line Control Register bits */
+#define UARTLCR_DLAB		(1 << 7)	/* Divisor Latch Access */
+#define UARTLCR_SETB		(1 << 6)	/* Set BREAK Condition */
+#define UARTLCR_SETP		(1 << 5)	/* Set Parity to LCR[4] */
+#define UARTLCR_EVEN		(1 << 4)	/* Even Parity Format */
+#define UARTLCR_PAR		(1 << 3)	/* Parity */
+#define UARTLCR_STOP		(1 << 2)	/* Stop Bit */
+#define UARTLCR_WORDSZ_5	0		/* Word Length of 5 */
+#define UARTLCR_WORDSZ_6	1		/* Word Length of 6 */
+#define UARTLCR_WORDSZ_7	2		/* Word Length of 7 */
+#define UARTLCR_WORDSZ_8	3		/* Word Length of 8 */
+
+/* Line Status Register bits */
+#define UARTLSR_RXFIFOEMT	(1 << 9)	/* Rx Fifo Empty */
+#define UARTLSR_TXFIFOFULL	(1 << 8)	/* Tx Fifo Full */
+#define UARTLSR_RXFIFOERR	(1 << 7)	/* Rx Fifo Error */
+#define UARTLSR_TEMT		(1 << 6)	/* Tx Shift Register Empty */
+#define UARTLSR_THRE		(1 << 5)	/* Tx Holding Register Empty */
+#define UARTLSR_BRK		(1 << 4)	/* Break Condition Detected */
+#define UARTLSR_FERR		(1 << 3)	/* Framing Error */
+#define UARTLSR_PERR		(1 << 3)	/* Parity Error */
+#define UARTLSR_OVRF		(1 << 2)	/* Rx Overrun Error */
+#define UARTLSR_RDR		(1 << 2)	/* Rx Data Ready */
+
+#endif	/* __UART_16550_H__ */
diff --git a/include/plat/arm/board/common/v2m_def.h b/include/plat/arm/board/common/v2m_def.h
index c16e9bc..7a4ef5a 100644
--- a/include/plat/arm/board/common/v2m_def.h
+++ b/include/plat/arm/board/common/v2m_def.h
@@ -105,6 +105,9 @@
 #define V2M_IOFPGA_UART2_CLK_IN_HZ	24000000
 #define V2M_IOFPGA_UART3_CLK_IN_HZ	24000000
 
+/* SP804 timer related constants */
+#define V2M_SP804_TIMER0_BASE		0x1C110000
+#define V2M_SP804_TIMER1_BASE		0x1C120000
 
 #define V2M_MAP_FLASH0			MAP_REGION_FLAT(V2M_FLASH0_BASE,\
 						V2M_FLASH0_SIZE,	\
diff --git a/include/plat/arm/css/common/css_def.h b/include/plat/arm/css/common/css_def.h
index 12a0550..268438f 100644
--- a/include/plat/arm/css/common/css_def.h
+++ b/include/plat/arm/css/common/css_def.h
@@ -37,11 +37,9 @@
 /*************************************************************************
  * Definitions common to all ARM Compute SubSystems (CSS)
  *************************************************************************/
-#define MHU_SECURE_BASE			ARM_SHARED_RAM_BASE
-#define MHU_SECURE_SIZE			ARM_SHARED_RAM_SIZE
 #define MHU_PAYLOAD_CACHED		0
 
-#define TRUSTED_MAILBOXES_BASE		MHU_SECURE_BASE
+#define TRUSTED_MAILBOXES_BASE		ARM_TRUSTED_SRAM_BASE
 #define TRUSTED_MAILBOX_SHIFT		4
 
 #define NSROM_BASE			0x1f000000
@@ -66,11 +64,29 @@
 #define CSS_IRQ_TZC			80
 #define CSS_IRQ_TZ_WDOG			86
 
-/* SCP <=> AP boot configuration */
-#define SCP_BOOT_CFG_ADDR		0x04000080
+/*
+ * SCP <=> AP boot configuration
+ *
+ * The SCP/AP boot configuration is a 32-bit word located at a known offset from
+ * the start of the Trusted SRAM. Part of this configuration is which CPU is the
+ * primary, according to the shift and mask definitions below.
+ *
+ * Note that the value stored at this address is only valid at boot time, before
+ * the BL3-0 image is transferred to SCP.
+ */
+#define SCP_BOOT_CFG_ADDR		(ARM_TRUSTED_SRAM_BASE + 0x80)
 #define PRIMARY_CPU_SHIFT		8
-#define PRIMARY_CPU_MASK		0xf
+#define PRIMARY_CPU_BIT_WIDTH		4
 
+/*
+ * Base address of the first memory region used for communication between AP
+ * and SCP. Used by the BOM and SCPI protocols.
+ *
+ * Note that this is located at the same address as SCP_BOOT_CFG_ADDR, which
+ * means the SCP/AP configuration data gets overwritten when the AP initiates
+ * communication with the SCP.
+ */
+#define SCP_COM_SHARED_MEM_BASE		(ARM_TRUSTED_SRAM_BASE + 0x80)
 
 #define CSS_MAP_DEVICE			MAP_REGION_FLAT(		\
 						CSS_DEVICE_BASE,	\
diff --git a/plat/arm/board/fvp/aarch64/fvp_helpers.S b/plat/arm/board/fvp/aarch64/fvp_helpers.S
index dd56687..d176fac 100644
--- a/plat/arm/board/fvp/aarch64/fvp_helpers.S
+++ b/plat/arm/board/fvp/aarch64/fvp_helpers.S
@@ -123,7 +123,7 @@
 	ldr	x1, =PWRC_BASE
 	str	w2, [x1, #PSYSR_OFF]
 	ldr	w2, [x1, #PSYSR_OFF]
-	ubfx	w2, w2, #PSYSR_WK_SHIFT, #PSYSR_WK_MASK
+	ubfx	w2, w2, #PSYSR_WK_SHIFT, #PSYSR_WK_WIDTH
 	cmp	w2, #WKUP_PPONR
 	beq	warm_reset
 	cmp	w2, #WKUP_GICREQ
diff --git a/plat/arm/board/fvp/drivers/pwrc/fvp_pwrc.h b/plat/arm/board/fvp/drivers/pwrc/fvp_pwrc.h
index 5b755af..3dc9aad 100644
--- a/plat/arm/board/fvp/drivers/pwrc/fvp_pwrc.h
+++ b/plat/arm/board/fvp/drivers/pwrc/fvp_pwrc.h
@@ -48,7 +48,8 @@
 #define PSYSR_PP		(1 << 26)
 
 #define PSYSR_WK_SHIFT		24
-#define PSYSR_WK_MASK		0x3
+#define PSYSR_WK_WIDTH		0x2
+#define PSYSR_WK_MASK		((1 << PSYSR_WK_WIDTH) - 1)
 #define PSYSR_WK(x)		(x >> PSYSR_WK_SHIFT) & PSYSR_WK_MASK
 
 #define WKUP_COLD		0x0
diff --git a/plat/arm/board/fvp/fvp_bl2_setup.c b/plat/arm/board/fvp/fvp_bl2_setup.c
index a08f42c..b1cdef4 100644
--- a/plat/arm/board/fvp/fvp_bl2_setup.c
+++ b/plat/arm/board/fvp/fvp_bl2_setup.c
@@ -29,6 +29,9 @@
  */
 
 #include <plat_arm.h>
+#include <sp804_delay_timer.h>
+#include <v2m_def.h>
+#include "fvp_def.h"
 #include "fvp_private.h"
 
 
@@ -39,3 +42,12 @@
 	/* Initialize the platform config for future decision making */
 	fvp_config_setup();
 }
+
+void bl2_platform_setup(void)
+{
+	arm_bl2_platform_setup();
+
+	/* Initialize delay timer driver using SP804 dual timer 0 */
+	sp804_timer_init(V2M_SP804_TIMER0_BASE,
+			SP804_TIMER_CLKMULT, SP804_TIMER_CLKDIV);
+}
diff --git a/plat/arm/board/fvp/fvp_def.h b/plat/arm/board/fvp/fvp_def.h
index 47723c7..68ef297 100644
--- a/plat/arm/board/fvp/fvp_def.h
+++ b/plat/arm/board/fvp/fvp_def.h
@@ -83,6 +83,9 @@
 /* FVP Power controller base address*/
 #define PWRC_BASE			0x1c100000
 
+/* FVP SP804 timer frequency is 35 MHz*/
+#define SP804_TIMER_CLKMULT		35
+#define SP804_TIMER_CLKDIV		1
 
 /*******************************************************************************
  * GIC-400 & interrupt handling related constants
diff --git a/plat/arm/board/fvp/platform.mk b/plat/arm/board/fvp/platform.mk
index cba18c7..949e6ad 100644
--- a/plat/arm/board/fvp/platform.mk
+++ b/plat/arm/board/fvp/platform.mk
@@ -46,7 +46,9 @@
 				plat/arm/board/fvp/fvp_bl1_setup.c		\
 				plat/arm/board/fvp/fvp_io_storage.c
 
-BL2_SOURCES		+=	drivers/io/io_semihosting.c			\
+BL2_SOURCES		+=	drivers/arm/sp804/sp804_delay_timer.c		\
+				drivers/io/io_semihosting.c			\
+				drivers/delay_timer/delay_timer.c		\
 				lib/semihosting/semihosting.c			\
 				lib/semihosting/aarch64/semihosting_call.S	\
 				plat/arm/board/fvp/fvp_bl2_setup.c		\
diff --git a/plat/arm/css/common/aarch64/css_helpers.S b/plat/arm/css/common/aarch64/css_helpers.S
index 1eee762..3903278 100644
--- a/plat/arm/css/common/aarch64/css_helpers.S
+++ b/plat/arm/css/common/aarch64/css_helpers.S
@@ -115,7 +115,7 @@
 	bl	platform_get_core_pos
 	ldr	x1, =SCP_BOOT_CFG_ADDR
 	ldr	x1, [x1]
-	ubfx	x1, x1, #PRIMARY_CPU_SHIFT, #PRIMARY_CPU_MASK
+	ubfx	x1, x1, #PRIMARY_CPU_SHIFT, #PRIMARY_CPU_BIT_WIDTH
 	cmp	x0, x1
 	cset	x0, eq
 	ret	x9
diff --git a/plat/arm/css/common/css_scp_bootloader.c b/plat/arm/css/common/css_scp_bootloader.c
index 6cf1667..acc7351 100644
--- a/plat/arm/css/common/css_scp_bootloader.c
+++ b/plat/arm/css/common/css_scp_bootloader.c
@@ -60,7 +60,7 @@
  * Unlike the SCPI protocol, the boot protocol uses the same memory region
  * for both AP -> SCP and SCP -> AP transfers; define the address of this...
  */
-#define BOM_SHARED_MEM		(MHU_SECURE_BASE + 0x0080)
+#define BOM_SHARED_MEM		SCP_COM_SHARED_MEM_BASE
 #define BOM_CMD_HEADER		((bom_cmd_t *) BOM_SHARED_MEM)
 #define BOM_CMD_PAYLOAD		((void *) (BOM_SHARED_MEM + sizeof(bom_cmd_t)))
 
@@ -181,7 +181,7 @@
 
 	BOM_CMD_HEADER->id = BOOT_CMD_DATA;
 	cmd_data_payload = BOM_CMD_PAYLOAD;
-	cmd_data_payload->offset = (uintptr_t) image - MHU_SECURE_BASE;
+	cmd_data_payload->offset = (uintptr_t) image - ARM_TRUSTED_SRAM_BASE;
 	cmd_data_payload->block_size = image_size;
 
 	scp_boot_message_send(sizeof(*cmd_data_payload));
diff --git a/plat/arm/css/common/css_scpi.c b/plat/arm/css/common/css_scpi.c
index 9127259..0a4eafe 100644
--- a/plat/arm/css/common/css_scpi.c
+++ b/plat/arm/css/common/css_scpi.c
@@ -37,8 +37,8 @@
 #include "css_mhu.h"
 #include "css_scpi.h"
 
-#define SCPI_SHARED_MEM_SCP_TO_AP	(MHU_SECURE_BASE + 0x0080)
-#define SCPI_SHARED_MEM_AP_TO_SCP	(MHU_SECURE_BASE + 0x0180)
+#define SCPI_SHARED_MEM_SCP_TO_AP	SCP_COM_SHARED_MEM_BASE
+#define SCPI_SHARED_MEM_AP_TO_SCP	(SCP_COM_SHARED_MEM_BASE + 0x100)
 
 #define SCPI_CMD_HEADER_AP_TO_SCP		\
 	((scpi_cmd_t *) SCPI_SHARED_MEM_AP_TO_SCP)
diff --git a/plat/nvidia/tegra/common/aarch64/tegra_helpers.S b/plat/nvidia/tegra/common/aarch64/tegra_helpers.S
new file mode 100644
index 0000000..264749b
--- /dev/null
+++ b/plat/nvidia/tegra/common/aarch64/tegra_helpers.S
@@ -0,0 +1,344 @@
+/*
+ * 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.
+ */
+#include <arch.h>
+#include <asm_macros.S>
+#include <assert_macros.S>
+#include <cpu_macros.S>
+#include <cortex_a57.h>
+#include <cortex_a53.h>
+#include <tegra_def.h>
+
+	/* Global functions */
+	.globl	platform_is_primary_cpu
+	.globl	platform_get_core_pos
+	.globl	platform_get_entrypoint
+	.globl	plat_secondary_cold_boot_setup
+	.globl	platform_mem_init
+	.globl	plat_crash_console_init
+	.globl	plat_crash_console_putc
+	.globl	tegra_secure_entrypoint
+	.globl	plat_reset_handler
+
+	/* Global variables */
+	.globl	sec_entry_point
+	.globl	ns_image_entrypoint
+	.globl	tegra_bl31_phys_base
+
+	/* ---------------------
+	 * Common CPU init code
+	 * ---------------------
+	 */
+.macro	cpu_init_common
+
+	/* -------------------------------------------------------
+	 * Enable L2 and CPU ECTLR RW access from non-secure world
+	 * -------------------------------------------------------
+	*/
+	mov	x0, #ACTLR_EL3_ENABLE_ALL_ACCESS
+	msr	actlr_el3, x0
+	msr	actlr_el2, x0
+	isb
+
+	/* --------------------------------
+	 * Enable the cycle count register
+	 * --------------------------------
+	 */
+	mrs	x0, pmcr_el0
+	ubfx	x0, x0, #11, #5		// read PMCR.N field
+	mov	x1, #1
+	lsl	x0, x1, x0
+	sub	x0, x0, #1		// mask of event counters
+	orr	x0, x0, #0x80000000	// disable overflow intrs
+	msr	pmintenclr_el1, x0
+	msr	pmuserenr_el0, x1	// enable user mode access
+
+	/* ----------------------------------------------------------------
+	 * Allow non-privileged access to CNTVCT: Set CNTKCTL (Kernel Count
+	 * register), bit 1 (EL0VCTEN) to enable access to CNTVCT/CNTFRQ
+	 * registers from EL0.
+	 * ----------------------------------------------------------------
+	 */
+	mrs	x0, cntkctl_el1
+	orr	x0, x0, #EL0VCTEN_BIT
+	msr	cntkctl_el1, x0
+.endm
+
+	/* -----------------------------------------------------
+	 * int platform_is_primary_cpu(int mpidr);
+	 *
+	 * This function checks if this is the Primary CPU
+	 * -----------------------------------------------------
+	 */
+func platform_is_primary_cpu
+	and	x0, x0, #(MPIDR_CLUSTER_MASK | MPIDR_CPU_MASK)
+	cmp	x0, #TEGRA_PRIMARY_CPU
+	cset	x0, eq
+	ret
+endfunc platform_is_primary_cpu
+
+	/* -----------------------------------------------------
+	 * int platform_get_core_pos(int mpidr);
+	 *
+	 * With this function: CorePos = CoreId
+	 * -----------------------------------------------------
+	 */
+func platform_get_core_pos
+	and	x0, x0, #MPIDR_CPU_MASK
+	ret
+endfunc platform_get_core_pos
+
+	/* -----------------------------------------------------
+	 * void plat_secondary_cold_boot_setup (void);
+	 *
+	 * This function performs any platform specific actions
+	 * needed for a secondary cpu after a cold reset. Right
+	 * now this is a stub function.
+	 * -----------------------------------------------------
+	 */
+func plat_secondary_cold_boot_setup
+	mov	x0, #0
+	ret
+endfunc plat_secondary_cold_boot_setup
+
+	/* -----------------------------------------------------
+	 * void platform_get_entrypoint (unsigned int mpidr);
+	 *
+	 * Main job of this routine is to distinguish between
+	 * a cold and warm boot. If the sec_entry_point for
+	 * this CPU is present, then it's a warm boot.
+	 *
+	 * -----------------------------------------------------
+	 */
+func platform_get_entrypoint
+	and	x0, x0, #MPIDR_CPU_MASK
+	adr	x1, sec_entry_point
+	ldr	x0, [x1, x0, lsl #3]
+	ret
+endfunc platform_get_entrypoint
+
+	/* --------------------------------------------------------
+	 * void platform_mem_init (void);
+	 *
+	 * Any memory init, relocation to be done before the
+	 * platform boots. Called very early in the boot process.
+	 * --------------------------------------------------------
+	 */
+func platform_mem_init
+	mov	x0, #0
+	ret
+endfunc platform_mem_init
+
+	/* ---------------------------------------------
+	 * int plat_crash_console_init(void)
+	 * Function to initialize the crash console
+	 * without a C Runtime to print crash report.
+	 * Clobber list : x0, x1, x2
+	 * ---------------------------------------------
+	 */
+func plat_crash_console_init
+	mov_imm	x0, TEGRA_BOOT_UART_BASE
+	mov_imm	x1, TEGRA_BOOT_UART_CLK_IN_HZ
+	mov_imm	x2, TEGRA_CONSOLE_BAUDRATE
+	b	console_core_init
+endfunc plat_crash_console_init
+
+	/* ---------------------------------------------
+	 * int plat_crash_console_putc(void)
+	 * Function to print a character on the crash
+	 * console without a C Runtime.
+	 * Clobber list : x1, x2
+	 * ---------------------------------------------
+	 */
+func plat_crash_console_putc
+	mov_imm	x1, TEGRA_BOOT_UART_BASE
+	b	console_core_putc
+endfunc plat_crash_console_putc
+
+	/* ---------------------------------------------------
+	 * Function to handle a platform reset and store
+	 * input parameters passed by BL2.
+	 * ---------------------------------------------------
+	 */
+func plat_reset_handler
+
+	/* -----------------------------------
+	 * derive and save the phys_base addr
+	 * -----------------------------------
+	 */
+	adr	x17, tegra_bl31_phys_base
+	ldr	x18, [x17]
+	cbnz	x18, 1f
+	adr	x18, bl31_entrypoint
+	str	x18, [x17]
+
+1:	cpu_init_common
+
+	ret
+endfunc plat_reset_handler
+
+	/* ----------------------------------------
+	 * Secure entrypoint function for CPU boot
+	 * ----------------------------------------
+	 */
+	.align 6
+func tegra_secure_entrypoint
+
+#if ERRATA_TEGRA_INVALIDATE_BTB_AT_BOOT
+
+	/* -------------------------------------------------------
+	 * Invalidate BTB along with I$ to remove any stale
+	 * entries from the branch predictor array.
+	 * -------------------------------------------------------
+	 */
+	mrs	x0, CPUACTLR_EL1
+	orr	x0, x0, #1
+	msr	CPUACTLR_EL1, x0	/* invalidate BTB and I$ together */
+	dsb	sy
+	isb
+	ic	iallu			/* actual invalidate */
+	dsb	sy
+	isb
+
+	mrs	x0, CPUACTLR_EL1
+	bic	x0, x0, #1
+	msr	CPUACTLR_EL1, X0	/* restore original CPUACTLR_EL1 */
+	dsb	sy
+	isb
+
+	.rept	7
+	nop				/* wait */
+	.endr
+
+	/* -----------------------------------------------
+	 * Extract OSLK bit and check if it is '1'. This
+	 * bit remains '0' for A53 on warm-resets. If '1',
+	 * turn off regional clock gating and request warm
+	 * reset.
+	 * -----------------------------------------------
+	 */
+	mrs	x0, oslsr_el1
+	and	x0, x0, #2
+	mrs	x1, mpidr_el1
+	bics	xzr, x0, x1, lsr #7	/* 0 = slow cluster or warm reset */
+	b.eq	restore_oslock
+	mov	x0, xzr
+	msr	oslar_el1, x0		/* os lock stays 0 across warm reset */
+	mov	x3, #3
+	movz	x4, #0x8000, lsl #48
+	msr	CPUACTLR_EL1, x4	/* turn off RCG */
+	isb
+	msr	rmr_el3, x3		/* request warm reset */
+	isb
+	dsb	sy
+1:	wfi
+	b	1b
+
+	/* --------------------------------------------------
+	 * These nops are here so that speculative execution
+	 * won't harm us before we are done with warm reset.
+	 * --------------------------------------------------
+	 */
+	.rept	65
+	nop
+	.endr
+
+	/* --------------------------------------------------
+	 * Do not insert instructions here
+	 * --------------------------------------------------
+	 */
+#endif
+
+	/* --------------------------------------------------
+	 * Restore OS Lock bit
+	 * --------------------------------------------------
+	 */
+restore_oslock:
+	mov	x0, #1
+	msr	oslar_el1, x0
+
+	cpu_init_common
+
+	/* ---------------------------------------------------------------------
+	 * The initial state of the Architectural feature trap register
+	 * (CPTR_EL3) is unknown and it must be set to a known state. All
+	 * feature traps are disabled. Some bits in this register are marked as
+	 * Reserved and should not be modified.
+	 *
+	 * CPTR_EL3.TCPAC: This causes a direct access to the CPACR_EL1 from EL1
+	 *  or the CPTR_EL2 from EL2 to trap to EL3 unless it is trapped at EL2.
+	 * CPTR_EL3.TTA: This causes access to the Trace functionality to trap
+	 *  to EL3 when executed from EL0, EL1, EL2, or EL3. If system register
+	 *  access to trace functionality is not supported, this bit is RES0.
+	 * CPTR_EL3.TFP: This causes instructions that access the registers
+	 *  associated with Floating Point and Advanced SIMD execution to trap
+	 *  to EL3 when executed from any exception level, unless trapped to EL1
+	 *  or EL2.
+	 * ---------------------------------------------------------------------
+	 */
+	mrs	x1, cptr_el3
+	bic	w1, w1, #TCPAC_BIT
+	bic	w1, w1, #TTA_BIT
+	bic	w1, w1, #TFP_BIT
+	msr	cptr_el3, x1
+
+	/* --------------------------------------------------
+	 * Get secure world's entry point and jump to it
+	 * --------------------------------------------------
+	 */
+	mrs	x0, mpidr_el1
+	bl	platform_get_entrypoint
+	br	x0
+endfunc tegra_secure_entrypoint
+
+	.data
+	.align 3
+
+	/* --------------------------------------------------
+	 * Per-CPU Secure entry point - resume from suspend
+	 * --------------------------------------------------
+	 */
+sec_entry_point:
+	.rept	PLATFORM_CORE_COUNT
+	.quad	0
+	.endr
+
+	/* --------------------------------------------------
+	 * NS world's cold boot entry point
+	 * --------------------------------------------------
+	 */
+ns_image_entrypoint:
+	.quad	0
+
+	/* --------------------------------------------------
+	 * BL31's physical base address
+	 * --------------------------------------------------
+	 */
+tegra_bl31_phys_base:
+	.quad	0
diff --git a/plat/nvidia/tegra/common/drivers/flowctrl/flowctrl.c b/plat/nvidia/tegra/common/drivers/flowctrl/flowctrl.c
new file mode 100644
index 0000000..a36cf2d
--- /dev/null
+++ b/plat/nvidia/tegra/common/drivers/flowctrl/flowctrl.c
@@ -0,0 +1,243 @@
+/*
+ * 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.
+ */
+
+#include <arch_helpers.h>
+#include <assert.h>
+#include <debug.h>
+#include <mmio.h>
+#include <pmc.h>
+#include <cortex_a53.h>
+#include <flowctrl.h>
+#include <tegra_def.h>
+
+#define CLK_RST_DEV_L_SET		0x300
+#define CLK_RST_DEV_L_CLR		0x304
+#define  CLK_BPMP_RST			(1 << 1)
+
+#define EVP_BPMP_RESET_VECTOR		0x200
+
+static const uint64_t flowctrl_offset_cpu_csr[4] = {
+	(TEGRA_FLOWCTRL_BASE + FLOWCTRL_CPU0_CSR),
+	(TEGRA_FLOWCTRL_BASE + FLOWCTRL_CPU1_CSR),
+	(TEGRA_FLOWCTRL_BASE + FLOWCTRL_CPU1_CSR + 8),
+	(TEGRA_FLOWCTRL_BASE + FLOWCTRL_CPU1_CSR + 16)
+};
+
+static const uint64_t flowctrl_offset_halt_cpu[4] = {
+	(TEGRA_FLOWCTRL_BASE + FLOWCTRL_HALT_CPU0_EVENTS),
+	(TEGRA_FLOWCTRL_BASE + FLOWCTRL_HALT_CPU1_EVENTS),
+	(TEGRA_FLOWCTRL_BASE + FLOWCTRL_HALT_CPU1_EVENTS + 8),
+	(TEGRA_FLOWCTRL_BASE + FLOWCTRL_HALT_CPU1_EVENTS + 16)
+};
+
+static const uint64_t flowctrl_offset_cc4_ctrl[4] = {
+	(TEGRA_FLOWCTRL_BASE + FLOWCTRL_CC4_CORE0_CTRL),
+	(TEGRA_FLOWCTRL_BASE + FLOWCTRL_CC4_CORE0_CTRL + 4),
+	(TEGRA_FLOWCTRL_BASE + FLOWCTRL_CC4_CORE0_CTRL + 8),
+	(TEGRA_FLOWCTRL_BASE + FLOWCTRL_CC4_CORE0_CTRL + 12)
+};
+
+static inline void tegra_fc_cc4_ctrl(int cpu_id, uint32_t val)
+{
+	mmio_write_32(flowctrl_offset_cc4_ctrl[cpu_id], val);
+	val = mmio_read_32(flowctrl_offset_cc4_ctrl[cpu_id]);
+}
+
+static inline void tegra_fc_cpu_csr(int cpu_id, uint32_t val)
+{
+	mmio_write_32(flowctrl_offset_cpu_csr[cpu_id], val);
+	val = mmio_read_32(flowctrl_offset_cpu_csr[cpu_id]);
+}
+
+static inline void tegra_fc_halt_cpu(int cpu_id, uint32_t val)
+{
+	mmio_write_32(flowctrl_offset_halt_cpu[cpu_id], val);
+	val = mmio_read_32(flowctrl_offset_halt_cpu[cpu_id]);
+}
+
+static void tegra_fc_prepare_suspend(int cpu_id, uint32_t csr)
+{
+	uint32_t val;
+
+	val = FLOWCTRL_HALT_GIC_IRQ | FLOWCTRL_HALT_GIC_FIQ |
+	      FLOWCTRL_HALT_LIC_IRQ | FLOWCTRL_HALT_LIC_FIQ |
+	      FLOWCTRL_WAITEVENT;
+	tegra_fc_halt_cpu(cpu_id, val);
+
+	val = FLOWCTRL_CSR_INTR_FLAG | FLOWCTRL_CSR_EVENT_FLAG |
+	      FLOWCTRL_CSR_ENABLE | (FLOWCTRL_WAIT_WFI_BITMAP << cpu_id);
+	tegra_fc_cpu_csr(cpu_id, val | csr);
+}
+
+/*******************************************************************************
+ * Suspend the current CPU
+ ******************************************************************************/
+void tegra_fc_cpu_idle(uint32_t mpidr)
+{
+	int cpu = mpidr & MPIDR_CPU_MASK;
+
+	VERBOSE("CPU%d powering down...\n", cpu);
+	tegra_fc_prepare_suspend(cpu, 0);
+}
+
+/*******************************************************************************
+ * Suspend the current CPU cluster
+ ******************************************************************************/
+void tegra_fc_cluster_idle(uint32_t mpidr)
+{
+	int cpu = mpidr & MPIDR_CPU_MASK;
+	uint32_t val;
+
+	VERBOSE("Entering cluster idle state...\n");
+
+	tegra_fc_cc4_ctrl(cpu, 0);
+
+	/* hardware L2 flush is faster for A53 only */
+	tegra_fc_write_32(FLOWCTRL_L2_FLUSH_CONTROL,
+		!!MPIDR_AFFLVL1_VAL(mpidr));
+
+	/* suspend the CPU cluster */
+	val = FLOWCTRL_PG_CPU_NONCPU << FLOWCTRL_ENABLE_EXT;
+	tegra_fc_prepare_suspend(cpu, val);
+}
+
+/*******************************************************************************
+ * Power down the current CPU cluster
+ ******************************************************************************/
+void tegra_fc_cluster_powerdn(uint32_t mpidr)
+{
+	int cpu = mpidr & MPIDR_CPU_MASK;
+	uint32_t val;
+
+	VERBOSE("Entering cluster powerdn state...\n");
+
+	tegra_fc_cc4_ctrl(cpu, 0);
+
+	/* hardware L2 flush is faster for A53 only */
+	tegra_fc_write_32(FLOWCTRL_L2_FLUSH_CONTROL,
+		read_midr() == CORTEX_A53_MIDR);
+
+	/* power down the CPU cluster */
+	val = FLOWCTRL_TURNOFF_CPURAIL << FLOWCTRL_ENABLE_EXT;
+	tegra_fc_prepare_suspend(cpu, val);
+}
+
+/*******************************************************************************
+ * Suspend the entire SoC
+ ******************************************************************************/
+void tegra_fc_soc_powerdn(uint32_t mpidr)
+{
+	int cpu = mpidr & MPIDR_CPU_MASK;
+	uint32_t val;
+
+	VERBOSE("Entering SoC powerdn state...\n");
+
+	tegra_fc_cc4_ctrl(cpu, 0);
+
+	tegra_fc_write_32(FLOWCTRL_L2_FLUSH_CONTROL, 1);
+
+	val = FLOWCTRL_TURNOFF_CPURAIL << FLOWCTRL_ENABLE_EXT;
+	tegra_fc_prepare_suspend(cpu, val);
+
+	/* overwrite HALT register */
+	tegra_fc_halt_cpu(cpu, FLOWCTRL_WAITEVENT);
+}
+
+/*******************************************************************************
+ * Power up the CPU
+ ******************************************************************************/
+void tegra_fc_cpu_on(int cpu)
+{
+	tegra_fc_cpu_csr(cpu, FLOWCTRL_CSR_ENABLE);
+	tegra_fc_halt_cpu(cpu, FLOWCTRL_WAITEVENT | FLOWCTRL_HALT_SCLK);
+}
+
+/*******************************************************************************
+ * Power down the CPU
+ ******************************************************************************/
+void tegra_fc_cpu_off(int cpu)
+{
+	uint32_t val;
+
+	/*
+	 * Flow controller powers down the CPU during wfi. The CPU would be
+	 * powered on when it receives any interrupt.
+	 */
+	val = FLOWCTRL_CSR_INTR_FLAG | FLOWCTRL_CSR_EVENT_FLAG |
+		FLOWCTRL_CSR_ENABLE | (FLOWCTRL_WAIT_WFI_BITMAP << cpu);
+	tegra_fc_cpu_csr(cpu, val);
+	tegra_fc_halt_cpu(cpu, FLOWCTRL_WAITEVENT);
+	tegra_fc_cc4_ctrl(cpu, 0);
+}
+
+/*******************************************************************************
+ * Inform the BPMP that we have completed the cluster power up
+ ******************************************************************************/
+void tegra_fc_lock_active_cluster(void)
+{
+	uint32_t val;
+
+	val = tegra_fc_read_32(FLOWCTRL_BPMP_CLUSTER_CONTROL);
+	val |= FLOWCTRL_BPMP_CLUSTER_PWRON_LOCK;
+	tegra_fc_write_32(FLOWCTRL_BPMP_CLUSTER_CONTROL, val);
+	val = tegra_fc_read_32(FLOWCTRL_BPMP_CLUSTER_CONTROL);
+}
+
+/*******************************************************************************
+ * Reset BPMP processor
+ ******************************************************************************/
+void tegra_fc_reset_bpmp(void)
+{
+	uint32_t val;
+
+	/* halt BPMP */
+	tegra_fc_write_32(FLOWCTRL_HALT_BPMP_EVENTS, FLOWCTRL_WAITEVENT);
+
+	/* Assert BPMP reset */
+	mmio_write_32(TEGRA_CAR_RESET_BASE + CLK_RST_DEV_L_SET, CLK_BPMP_RST);
+
+	/* Restore reset address (stored in PMC_SCRATCH39) */
+	val = tegra_pmc_read_32(PMC_SCRATCH39);
+	mmio_write_32(TEGRA_EVP_BASE + EVP_BPMP_RESET_VECTOR, val);
+	while (val != mmio_read_32(TEGRA_EVP_BASE + EVP_BPMP_RESET_VECTOR))
+		; /* wait till value reaches EVP_BPMP_RESET_VECTOR */
+
+	/* Wait for 2us before de-asserting the reset signal. */
+	val = mmio_read_32(TEGRA_TMRUS_BASE);
+	val += 2;
+	while (val > mmio_read_32(TEGRA_TMRUS_BASE))
+		; /* wait for 2us */
+
+	/* De-assert BPMP reset */
+	mmio_write_32(TEGRA_CAR_RESET_BASE + CLK_RST_DEV_L_CLR, CLK_BPMP_RST);
+
+	/* Un-halt BPMP */
+	tegra_fc_write_32(FLOWCTRL_HALT_BPMP_EVENTS, 0);
+}
diff --git a/plat/nvidia/tegra/common/drivers/memctrl/memctrl.c b/plat/nvidia/tegra/common/drivers/memctrl/memctrl.c
new file mode 100644
index 0000000..fff8951
--- /dev/null
+++ b/plat/nvidia/tegra/common/drivers/memctrl/memctrl.c
@@ -0,0 +1,171 @@
+/*
+ * 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.
+ */
+
+#include <arch_helpers.h>
+#include <assert.h>
+#include <debug.h>
+#include <mmio.h>
+#include <memctrl.h>
+#include <string.h>
+#include <tegra_def.h>
+#include <xlat_tables.h>
+
+extern void zeromem16(void *mem, unsigned int length);
+
+#define TEGRA_GPU_RESET_REG_OFFSET	0x28c
+#define  GPU_RESET_BIT			(1 << 24)
+
+/* Video Memory base and size (live values) */
+static uintptr_t video_mem_base;
+static uint64_t video_mem_size;
+
+/*
+ * Init SMMU.
+ */
+void tegra_memctrl_setup(void)
+{
+	/*
+	 * Setup the Memory controller to allow only secure accesses to
+	 * the TZDRAM carveout
+	 */
+	INFO("Configuring SMMU\n");
+
+	/* allow translations for all MC engines */
+	tegra_mc_write_32(MC_SMMU_TRANSLATION_ENABLE_0_0,
+			(unsigned int)MC_SMMU_TRANSLATION_ENABLE);
+	tegra_mc_write_32(MC_SMMU_TRANSLATION_ENABLE_1_0,
+			(unsigned int)MC_SMMU_TRANSLATION_ENABLE);
+	tegra_mc_write_32(MC_SMMU_TRANSLATION_ENABLE_2_0,
+			(unsigned int)MC_SMMU_TRANSLATION_ENABLE);
+	tegra_mc_write_32(MC_SMMU_TRANSLATION_ENABLE_3_0,
+			(unsigned int)MC_SMMU_TRANSLATION_ENABLE);
+	tegra_mc_write_32(MC_SMMU_TRANSLATION_ENABLE_4_0,
+			(unsigned int)MC_SMMU_TRANSLATION_ENABLE);
+
+	tegra_mc_write_32(MC_SMMU_ASID_SECURITY_0, MC_SMMU_ASID_SECURITY);
+
+	tegra_mc_write_32(MC_SMMU_TLB_CONFIG_0, MC_SMMU_TLB_CONFIG_0_RESET_VAL);
+	tegra_mc_write_32(MC_SMMU_PTC_CONFIG_0, MC_SMMU_PTC_CONFIG_0_RESET_VAL);
+
+	/* flush PTC and TLB */
+	tegra_mc_write_32(MC_SMMU_PTC_FLUSH_0, MC_SMMU_PTC_FLUSH_ALL);
+	(void)tegra_mc_read_32(MC_SMMU_CONFIG_0); /* read to flush writes */
+	tegra_mc_write_32(MC_SMMU_TLB_FLUSH_0, MC_SMMU_TLB_FLUSH_ALL);
+
+	/* enable SMMU */
+	tegra_mc_write_32(MC_SMMU_CONFIG_0,
+			  MC_SMMU_CONFIG_0_SMMU_ENABLE_ENABLE);
+	(void)tegra_mc_read_32(MC_SMMU_CONFIG_0); /* read to flush writes */
+
+	/* video memory carveout */
+	tegra_mc_write_32(MC_VIDEO_PROTECT_BASE, video_mem_base);
+	tegra_mc_write_32(MC_VIDEO_PROTECT_SIZE_MB, video_mem_size);
+}
+
+/*
+ * Secure the BL31 DRAM aperture.
+ *
+ * phys_base = physical base of TZDRAM aperture
+ * size_in_bytes = size of aperture in bytes
+ */
+void tegra_memctrl_tzdram_setup(uint64_t phys_base, uint32_t size_in_bytes)
+{
+	/*
+	 * Setup the Memory controller to allow only secure accesses to
+	 * the TZDRAM carveout
+	 */
+	INFO("Configuring TrustZone DRAM Memory Carveout\n");
+
+	tegra_mc_write_32(MC_SECURITY_CFG0_0, phys_base);
+	tegra_mc_write_32(MC_SECURITY_CFG1_0, size_in_bytes >> 20);
+}
+
+/*
+ * Program the Video Memory carveout region
+ *
+ * phys_base = physical base of aperture
+ * size_in_bytes = size of aperture in bytes
+ */
+void tegra_memctrl_videomem_setup(uint64_t phys_base, uint32_t size_in_bytes)
+{
+	uintptr_t vmem_end_old = video_mem_base + (video_mem_size << 20);
+	uintptr_t vmem_end_new = phys_base + size_in_bytes;
+	uint32_t regval;
+
+	/*
+	 * The GPU is the user of the Video Memory region. In order to
+	 * transition to the new memory region smoothly, we program the
+	 * new base/size ONLY if the GPU is in reset mode.
+	 */
+	regval = mmio_read_32(TEGRA_CAR_RESET_BASE + TEGRA_GPU_RESET_REG_OFFSET);
+	if ((regval & GPU_RESET_BIT) == 0) {
+		ERROR("GPU not in reset! Video Memory setup failed\n");
+		return;
+	}
+
+	/*
+	 * Setup the Memory controller to restrict CPU accesses to the Video
+	 * Memory region
+	 */
+	INFO("Configuring Video Memory Carveout\n");
+
+	/*
+	 * Configure Memory Controller directly for the first time.
+	 */
+	if (video_mem_base == 0)
+		goto done;
+
+	/*
+	 * Clear the old regions now being exposed. The following cases
+	 * can occur -
+	 *
+	 * 1. clear whole old region (no overlap with new region)
+	 * 2. clear old sub-region below new base
+	 * 3. clear old sub-region above new end
+	 */
+	INFO("Cleaning previous Video Memory Carveout\n");
+
+	disable_mmu_el3();
+	if (phys_base > vmem_end_old || video_mem_base > vmem_end_new)
+		zeromem16((void *)video_mem_base, video_mem_size << 20);
+	else if (video_mem_base < phys_base)
+		zeromem16((void *)video_mem_base, phys_base - video_mem_base);
+	else if (vmem_end_old > vmem_end_new)
+		zeromem16((void *)vmem_end_new, vmem_end_old - vmem_end_new);
+	enable_mmu_el3(0);
+
+done:
+	tegra_mc_write_32(MC_VIDEO_PROTECT_BASE, phys_base);
+	tegra_mc_write_32(MC_VIDEO_PROTECT_SIZE_MB, size_in_bytes >> 20);
+
+	/* store new values */
+	video_mem_base = phys_base;
+	video_mem_size = size_in_bytes >> 20;
+}
diff --git a/plat/nvidia/tegra/common/drivers/pmc/pmc.c b/plat/nvidia/tegra/common/drivers/pmc/pmc.c
new file mode 100644
index 0000000..5796ac7
--- /dev/null
+++ b/plat/nvidia/tegra/common/drivers/pmc/pmc.c
@@ -0,0 +1,122 @@
+/*
+ * 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.
+ */
+
+#include <arch_helpers.h>
+#include <assert.h>
+#include <debug.h>
+#include <mmio.h>
+#include <pmc.h>
+#include <tegra_def.h>
+
+/* Module IDs used during power ungate procedure */
+static const int pmc_cpu_powergate_id[4] = {
+	0, /* CPU 0 */
+	9, /* CPU 1 */
+	10, /* CPU 2 */
+	11 /* CPU 3 */
+};
+
+/*******************************************************************************
+ * Power ungate CPU to start the boot process. CPU reset vectors must be
+ * populated before calling this function.
+ ******************************************************************************/
+void tegra_pmc_cpu_on(int cpu)
+{
+	uint32_t val;
+
+	/*
+	 * The PMC deasserts the START bit when it starts the power
+	 * ungate process. Loop till no power toggle is in progress.
+	 */
+	do {
+		val = tegra_pmc_read_32(PMC_PWRGATE_TOGGLE);
+	} while (val & PMC_TOGGLE_START);
+
+	/*
+	 * Start the power ungate procedure
+	 */
+	val = pmc_cpu_powergate_id[cpu] | PMC_TOGGLE_START;
+	tegra_pmc_write_32(PMC_PWRGATE_TOGGLE, val);
+
+	/*
+	 * The PMC deasserts the START bit when it starts the power
+	 * ungate process. Loop till powergate START bit is asserted.
+	 */
+	do {
+		val = tegra_pmc_read_32(PMC_PWRGATE_TOGGLE);
+	} while (val & (1 << 8));
+
+	/* loop till the CPU is power ungated */
+	do {
+		val = tegra_pmc_read_32(PMC_PWRGATE_STATUS);
+	} while ((val & (1 << pmc_cpu_powergate_id[cpu])) == 0);
+}
+
+/*******************************************************************************
+ * Setup CPU vectors for resume from deep sleep
+ ******************************************************************************/
+void tegra_pmc_cpu_setup(uint64_t reset_addr)
+{
+	uint32_t val;
+
+	tegra_pmc_write_32(PMC_SECURE_SCRATCH34, (reset_addr & 0xFFFFFFFF) | 1);
+	val = reset_addr >> 32;
+	tegra_pmc_write_32(PMC_SECURE_SCRATCH35, val & 0x7FF);
+}
+
+/*******************************************************************************
+ * Lock CPU vectors to restrict further writes
+ ******************************************************************************/
+void tegra_pmc_lock_cpu_vectors(void)
+{
+	uint32_t val;
+
+	/* lock PMC_SECURE_SCRATCH34/35 */
+	val = tegra_pmc_read_32(PMC_SECURE_DISABLE3);
+	val |= (PMC_SECURE_DISABLE3_WRITE34_ON |
+		PMC_SECURE_DISABLE3_WRITE35_ON);
+	tegra_pmc_write_32(PMC_SECURE_DISABLE3, val);
+}
+
+/*******************************************************************************
+ * Restart the system
+ ******************************************************************************/
+__dead2 void tegra_pmc_system_reset(void)
+{
+	uint32_t reg;
+
+	reg = tegra_pmc_read_32(PMC_CONFIG);
+	reg |= 0x10;		/* restart */
+	tegra_pmc_write_32(PMC_CONFIG, reg);
+	wfi();
+
+	ERROR("Tegra System Reset: operation not handled.\n");
+	panic();
+}
diff --git a/plat/nvidia/tegra/common/tegra_bl31_setup.c b/plat/nvidia/tegra/common/tegra_bl31_setup.c
new file mode 100644
index 0000000..dea8457
--- /dev/null
+++ b/plat/nvidia/tegra/common/tegra_bl31_setup.c
@@ -0,0 +1,262 @@
+/*
+ * 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.
+ */
+
+#include <arch.h>
+#include <arch_helpers.h>
+#include <assert.h>
+#include <bl31.h>
+#include <bl_common.h>
+#include <console.h>
+#include <cortex_a57.h>
+#include <cortex_a53.h>
+#include <debug.h>
+#include <errno.h>
+#include <memctrl.h>
+#include <mmio.h>
+#include <platform.h>
+#include <platform_def.h>
+#include <stddef.h>
+#include <tegra_private.h>
+
+/*******************************************************************************
+ * 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 __BL31_END__;
+
+#if USE_COHERENT_MEM
+extern unsigned long __COHERENT_RAM_START__;
+extern unsigned long __COHERENT_RAM_END__;
+#endif
+
+extern uint64_t tegra_bl31_phys_base;
+
+/*
+ * The next 3 constants identify the extents of the code, RO data region and the
+ * limit of the BL3-1 image.  These addresses are used by the MMU setup code and
+ * therefore they must be page-aligned.  It is the responsibility of the linker
+ * 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_END (unsigned long)(&__BL31_END__)
+
+#if USE_COHERENT_MEM
+/*
+ * The next 2 constants identify the extents of the coherent memory region.
+ * These addresses are used by the MMU setup code and therefore they must be
+ * page-aligned.  It is the responsibility of the linker script to ensure that
+ * __COHERENT_RAM_START__ and __COHERENT_RAM_END__ linker symbols
+ * refer to page-aligned addresses.
+ */
+#define BL31_COHERENT_RAM_BASE (unsigned long)(&__COHERENT_RAM_START__)
+#define BL31_COHERENT_RAM_LIMIT (unsigned long)(&__COHERENT_RAM_END__)
+#endif
+
+static entry_point_info_t bl33_image_ep_info, bl32_image_ep_info;
+static plat_params_from_bl2_t plat_bl31_params_from_bl2 = {
+	(uint64_t)TZDRAM_SIZE, (uintptr_t)NULL
+};
+
+/*******************************************************************************
+ * This variable holds the non-secure image entry address
+ ******************************************************************************/
+extern uint64_t ns_image_entrypoint;
+
+/*******************************************************************************
+ * Return a pointer to the 'entry_point_info' structure of the next image for
+ * security state specified. BL33 corresponds to the non-secure image type
+ * while BL32 corresponds to the secure image type.
+ ******************************************************************************/
+entry_point_info_t *bl31_plat_get_next_image_ep_info(uint32_t type)
+{
+	if (type == NON_SECURE)
+		return &bl33_image_ep_info;
+
+	if (type == SECURE)
+		return &bl32_image_ep_info;
+
+	return NULL;
+}
+
+/*******************************************************************************
+ * Return a pointer to the 'plat_params_from_bl2_t' structure. The BL2 image
+ * passes this platform specific information.
+ ******************************************************************************/
+plat_params_from_bl2_t *bl31_get_plat_params(void)
+{
+	return &plat_bl31_params_from_bl2;
+}
+
+/*******************************************************************************
+ * Perform any BL31 specific platform actions. Populate the BL33 and BL32 image
+ * info.
+ ******************************************************************************/
+void bl31_early_platform_setup(bl31_params_t *from_bl2,
+				void *plat_params_from_bl2)
+{
+	plat_params_from_bl2_t *plat_params =
+		(plat_params_from_bl2_t *)plat_params_from_bl2;
+
+	/*
+	 * Configure the UART port to be used as the console
+	 */
+	console_init(TEGRA_BOOT_UART_BASE, TEGRA_BOOT_UART_CLK_IN_HZ,
+			TEGRA_CONSOLE_BAUDRATE);
+
+	/* Initialise crash console */
+	plat_crash_console_init();
+
+	/*
+	 * Copy BL3-3, BL3-2 entry point information.
+	 * They are stored in Secure RAM, in BL2's address space.
+	 */
+	bl33_image_ep_info = *from_bl2->bl33_ep_info;
+	bl32_image_ep_info = *from_bl2->bl32_ep_info;
+
+	/*
+	 * Parse platform specific parameters - TZDRAM aperture size and
+	 * pointer to BL32 params.
+	 */
+	if (plat_params) {
+		plat_bl31_params_from_bl2.tzdram_size = plat_params->tzdram_size;
+		plat_bl31_params_from_bl2.bl32_params = plat_params->bl32_params;
+	}
+}
+
+/*******************************************************************************
+ * Initialize the gic, configure the SCR.
+ ******************************************************************************/
+void bl31_platform_setup(void)
+{
+	uint32_t tmp_reg;
+
+	/*
+	 * Setup secondary CPU POR infrastructure.
+	 */
+	plat_secondary_setup();
+
+	/*
+	 * Initial Memory Controller configuration.
+	 */
+	tegra_memctrl_setup();
+
+	/*
+	 * Do initial security configuration to allow DRAM/device access.
+	 */
+	tegra_memctrl_tzdram_setup(tegra_bl31_phys_base,
+			plat_bl31_params_from_bl2.tzdram_size);
+
+	/* Set the next EL to be AArch64 */
+	tmp_reg = SCR_RES1_BITS | SCR_RW_BIT;
+	write_scr(tmp_reg);
+
+	/* Initialize the gic cpu and distributor interfaces */
+	tegra_gic_setup();
+}
+
+/*******************************************************************************
+ * Perform the very early platform specific architectural setup here. At the
+ * moment this only intializes the mmu in a quick and dirty way.
+ ******************************************************************************/
+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 = TZDRAM_END - BL31_RO_BASE;
+	unsigned long ro_start = bl31_base_pa;
+	unsigned long ro_size = BL31_RO_LIMIT - BL31_RO_BASE;
+	unsigned long coh_start = 0;
+	unsigned long coh_size = 0;
+	const mmap_region_t *plat_mmio_map = NULL;
+
+#if USE_COHERENT_MEM
+	coh_start = total_base + (BL31_COHERENT_RAM_BASE - BL31_RO_BASE);
+	coh_size = BL31_COHERENT_RAM_LIMIT - BL31_COHERENT_RAM_BASE;
+#endif
+
+	/* add memory regions */
+	mmap_add_region(total_base, total_base,
+			total_size,
+			MT_MEMORY | MT_RW | MT_SECURE);
+	mmap_add_region(ro_start, ro_start,
+			ro_size,
+			MT_MEMORY | MT_RO | MT_SECURE);
+#if USE_COHERENT_MEM
+	mmap_add_region(coh_start, coh_start,
+			coh_size,
+			MT_DEVICE | MT_RW | MT_SECURE);
+#endif
+
+	/* add MMIO space */
+	plat_mmio_map = plat_get_mmio_map();
+	if (plat_mmio_map)
+		mmap_add(plat_mmio_map);
+	else
+		WARN("MMIO map not available\n");
+
+	/* set up translation tables */
+	init_xlat_tables();
+
+	/* enable the MMU */
+	enable_mmu_el3(0);
+}
+
+/*******************************************************************************
+ * Check if the given NS DRAM range is valid
+ ******************************************************************************/
+int bl31_check_ns_address(uint64_t base, uint64_t size_in_bytes)
+{
+	uint64_t end = base + size_in_bytes - 1;
+
+	/*
+	 * Check if the NS DRAM address is valid
+	 */
+	if ((base < TEGRA_DRAM_BASE) || (end > TEGRA_DRAM_END) ||
+	    (base >= end)) {
+		ERROR("NS address is out-of-bounds!\n");
+		return -EFAULT;
+	}
+
+	/*
+	 * TZDRAM aperture contains the BL31 and BL32 images, so we need
+	 * to check if the NS DRAM range overlaps the TZDRAM aperture.
+	 */
+	if ((base < TZDRAM_END) && (end > tegra_bl31_phys_base)) {
+		ERROR("NS address overlaps TZDRAM!\n");
+		return -ENOTSUP;
+	}
+
+	/* valid NS address */
+	return 0;
+}
diff --git a/plat/nvidia/tegra/common/tegra_common.mk b/plat/nvidia/tegra/common/tegra_common.mk
new file mode 100644
index 0000000..12d684f
--- /dev/null
+++ b/plat/nvidia/tegra/common/tegra_common.mk
@@ -0,0 +1,63 @@
+#
+# 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.
+#
+
+CRASH_REPORTING		:=	1
+$(eval $(call add_define,CRASH_REPORTING))
+
+ASM_ASSERTION		:=	1
+$(eval $(call add_define,ASM_ASSERTION))
+
+PLAT_INCLUDES		:=	-Iplat/nvidia/tegra/include/drivers \
+				-Iplat/nvidia/tegra/include \
+				-Iplat/nvidia/tegra/include/${TARGET_SOC}
+
+PLAT_BL_COMMON_SOURCES	:=	lib/aarch64/xlat_tables.c			\
+				plat/common/aarch64/plat_common.c
+
+COMMON_DIR		:=	plat/nvidia/tegra/common
+
+BL31_SOURCES		+=	drivers/arm/gic/arm_gic.c			\
+				drivers/arm/gic/gic_v2.c			\
+				drivers/arm/gic/gic_v3.c			\
+				drivers/console/console.S			\
+				drivers/ti/uart/16550_console.S			\
+				lib/cpus/aarch64/cortex_a53.S			\
+				lib/cpus/aarch64/cortex_a57.S			\
+				plat/common/plat_gic.c				\
+				plat/common/aarch64/platform_mp_stack.S		\
+				${COMMON_DIR}/aarch64/tegra_helpers.S		\
+				${COMMON_DIR}/drivers/memctrl/memctrl.c		\
+				${COMMON_DIR}/drivers/pmc/pmc.c			\
+				${COMMON_DIR}/drivers/flowctrl/flowctrl.c	\
+				${COMMON_DIR}/tegra_bl31_setup.c		\
+				${COMMON_DIR}/tegra_gic.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_gic.c b/plat/nvidia/tegra/common/tegra_gic.c
new file mode 100644
index 0000000..2dafae7
--- /dev/null
+++ b/plat/nvidia/tegra/common/tegra_gic.c
@@ -0,0 +1,95 @@
+/*
+ * 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.
+ */
+
+#include <arch_helpers.h>
+#include <assert.h>
+#include <bl_common.h>
+#include <debug.h>
+#include <gic_v2.h>
+#include <interrupt_mgmt.h>
+#include <platform.h>
+#include <stdint.h>
+#include <tegra_private.h>
+#include <tegra_def.h>
+
+/*******************************************************************************
+ * Place the cpu interface in a state where it can never make a cpu exit wfi as
+ * as result of an asserted interrupt. This is critical for powering down a cpu
+ ******************************************************************************/
+void tegra_gic_cpuif_deactivate(void)
+{
+	unsigned int val;
+
+	/* Disable secure, non-secure interrupts and disable their bypass */
+	val = gicc_read_ctlr(TEGRA_GICC_BASE);
+	val &= ~(ENABLE_GRP0 | ENABLE_GRP1);
+	val |= FIQ_BYP_DIS_GRP1 | FIQ_BYP_DIS_GRP0;
+	val |= IRQ_BYP_DIS_GRP0 | IRQ_BYP_DIS_GRP1;
+	gicc_write_ctlr(TEGRA_GICC_BASE, val);
+}
+
+/*******************************************************************************
+ * Enable secure interrupts and set the priority mask register to allow all
+ * interrupts to trickle in.
+ ******************************************************************************/
+static void tegra_gic_cpuif_setup(unsigned int gicc_base)
+{
+	gicc_write_ctlr(gicc_base, ENABLE_GRP0 | ENABLE_GRP1);
+	gicc_write_pmr(gicc_base, GIC_PRI_MASK);
+}
+
+/*******************************************************************************
+ * Global gic distributor setup which will be done by the primary cpu after a
+ * cold boot. It marks out the non secure SPIs, PPIs & SGIs and enables them.
+ * It then enables the secure GIC distributor interface.
+ ******************************************************************************/
+static void tegra_gic_distif_setup(unsigned int gicd_base)
+{
+	unsigned int ctr, num_ints;
+
+	/*
+	 * Mark out non-secure interrupts. Calculate number of
+	 * IGROUPR registers to consider. Will be equal to the
+	 * number of IT_LINES
+	 */
+	num_ints = gicd_read_typer(gicd_base) & IT_LINES_NO_MASK;
+	num_ints++;
+	for (ctr = 0; ctr < num_ints; ctr++)
+		gicd_write_igroupr(gicd_base, ctr << IGROUPR_SHIFT, ~0);
+
+	/* enable distributor */
+	gicd_write_ctlr(gicd_base, ENABLE_GRP0 | ENABLE_GRP1);
+}
+
+void tegra_gic_setup(void)
+{
+	tegra_gic_cpuif_setup(TEGRA_GICC_BASE);
+	tegra_gic_distif_setup(TEGRA_GICD_BASE);
+}
diff --git a/plat/nvidia/tegra/common/tegra_pm.c b/plat/nvidia/tegra/common/tegra_pm.c
new file mode 100644
index 0000000..243407d
--- /dev/null
+++ b/plat/nvidia/tegra/common/tegra_pm.c
@@ -0,0 +1,332 @@
+/*
+ * 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.
+ */
+
+#include <arch_helpers.h>
+#include <assert.h>
+#include <bl_common.h>
+#include <context.h>
+#include <context_mgmt.h>
+#include <debug.h>
+#include <memctrl.h>
+#include <mmio.h>
+#include <platform.h>
+#include <platform_def.h>
+#include <pmc.h>
+#include <psci.h>
+#include <tegra_def.h>
+#include <tegra_private.h>
+
+extern uint64_t tegra_bl31_phys_base;
+extern uint64_t sec_entry_point[PLATFORM_CORE_COUNT];
+static int system_suspended;
+
+/*
+ * The following platform setup functions are weakly defined. They
+ * provide typical implementations that will be overridden by a SoC.
+ */
+#pragma weak tegra_prepare_cpu_suspend
+#pragma weak tegra_prepare_cpu_on
+#pragma weak tegra_prepare_cpu_off
+#pragma weak tegra_prepare_cpu_on_finish
+
+int tegra_prepare_cpu_suspend(unsigned int id, unsigned int afflvl)
+{
+	return PSCI_E_NOT_SUPPORTED;
+}
+
+int tegra_prepare_cpu_on(unsigned long mpidr)
+{
+	return PSCI_E_SUCCESS;
+}
+
+int tegra_prepare_cpu_off(unsigned long mpidr)
+{
+	return PSCI_E_SUCCESS;
+}
+
+int tegra_prepare_cpu_on_finish(unsigned long mpidr)
+{
+	return PSCI_E_SUCCESS;
+}
+
+/*******************************************************************************
+ * Track system suspend entry.
+ ******************************************************************************/
+void tegra_pm_system_suspend_entry(void)
+{
+	system_suspended = 1;
+}
+
+/*******************************************************************************
+ * Track system suspend exit.
+ ******************************************************************************/
+void tegra_pm_system_suspend_exit(void)
+{
+	system_suspended = 0;
+}
+
+/*******************************************************************************
+ * Get the system suspend state.
+ ******************************************************************************/
+int tegra_system_suspended(void)
+{
+	return system_suspended;
+}
+
+/*******************************************************************************
+ * Handler called when an affinity instance is about to enter standby.
+ ******************************************************************************/
+void tegra_affinst_standby(unsigned int power_state)
+{
+	/*
+	 * Enter standby state
+	 * dsb is good practice before using wfi to enter low power states
+	 */
+	dsb();
+	wfi();
+}
+
+/*******************************************************************************
+ * Handler called to check the validity of the power state parameter.
+ ******************************************************************************/
+int32_t tegra_validate_power_state(unsigned int power_state)
+{
+	/* Sanity check the requested state */
+	if (psci_get_pstate_type(power_state) == PSTATE_TYPE_STANDBY) {
+		/*
+		 * It's possible to enter standby only on affinity level 0 i.e.
+		 * a cpu on Tegra. Ignore any other affinity level.
+		 */
+		if (psci_get_pstate_afflvl(power_state) != MPIDR_AFFLVL0)
+			return PSCI_E_INVALID_PARAMS;
+	}
+
+	return PSCI_E_SUCCESS;
+}
+
+/*******************************************************************************
+ * Handler called when an affinity instance is about to be turned on. The
+ * level and mpidr determine the affinity instance.
+ ******************************************************************************/
+int tegra_affinst_on(unsigned long mpidr,
+		   unsigned long sec_entrypoint,
+		   unsigned int afflvl,
+		   unsigned int state)
+{
+	int cpu = mpidr & MPIDR_CPU_MASK;
+
+	/*
+	 * Support individual CPU power on only.
+	 */
+	if (afflvl > MPIDR_AFFLVL0)
+		return PSCI_E_SUCCESS;
+
+	/*
+	 * Flush entrypoint variable to PoC since it will be
+	 * accessed after a reset with the caches turned off.
+	 */
+	sec_entry_point[cpu] = sec_entrypoint;
+	flush_dcache_range((uint64_t)&sec_entry_point[cpu], sizeof(uint64_t));
+
+	return tegra_prepare_cpu_on(mpidr);
+}
+
+/*******************************************************************************
+ * Handler called when an affinity instance is about to be turned off. The
+ * level determines the affinity instance. The 'state' arg. allows the
+ * platform to decide whether the cluster is being turned off and take apt
+ * actions.
+ *
+ * CAUTION: This function is called with coherent stacks so that caches can be
+ * turned off, flushed and coherency disabled. There is no guarantee that caches
+ * will remain turned on across calls to this function as each affinity level is
+ * dealt with. So do not write & read global variables across calls. It will be
+ * wise to do flush a write to the global to prevent unpredictable results.
+ ******************************************************************************/
+void tegra_affinst_off(unsigned int afflvl, unsigned int state)
+{
+	/*
+	 * Support individual CPU power off only.
+	 */
+	if (afflvl > MPIDR_AFFLVL0)
+		return;
+
+	tegra_prepare_cpu_off(read_mpidr());
+}
+
+/*******************************************************************************
+ * Handler called when an affinity instance is about to be suspended. The
+ * level and mpidr determine the affinity instance. The 'state' arg. allows the
+ * platform to decide whether the cluster is being turned off and take apt
+ * actions.
+ *
+ * CAUTION: This function is called with coherent stacks so that caches can be
+ * turned off, flushed and coherency disabled. There is no guarantee that caches
+ * will remain turned on across calls to this function as each affinity level is
+ * dealt with. So do not write & read global variables across calls. It will be
+ * wise to flush a write to the global variable, to prevent unpredictable
+ * results.
+ ******************************************************************************/
+void tegra_affinst_suspend(unsigned long sec_entrypoint,
+			unsigned int afflvl,
+			unsigned int state)
+{
+	int id = psci_get_suspend_stateid();
+	int cpu = read_mpidr() & MPIDR_CPU_MASK;
+
+	if (afflvl > PLATFORM_MAX_AFFLVL)
+		return;
+
+	/*
+	 * Flush entrypoint variable to PoC since it will be
+	 * accessed after a reset with the caches turned off.
+	 */
+	sec_entry_point[cpu] = sec_entrypoint;
+	flush_dcache_range((uint64_t)&sec_entry_point[cpu], sizeof(uint64_t));
+
+	tegra_prepare_cpu_suspend(id, afflvl);
+
+	/* disable GICC */
+	tegra_gic_cpuif_deactivate();
+}
+
+/*******************************************************************************
+ * Handler called when an affinity instance has just been powered on after
+ * being turned off earlier. The level determines the affinity instance.
+ * The 'state' arg. allows the platform to decide whether the cluster was
+ * turned off prior to wakeup and do what's necessary to set it up.
+ ******************************************************************************/
+void tegra_affinst_on_finish(unsigned int afflvl, unsigned int state)
+{
+	plat_params_from_bl2_t *plat_params;
+
+	/*
+	 * Support individual CPU power on only.
+	 */
+	if (afflvl > MPIDR_AFFLVL0)
+		return;
+
+	/*
+	 * Initialize the GIC cpu and distributor interfaces
+	 */
+	tegra_gic_setup();
+
+	/*
+	 * Check if we are exiting from deep sleep.
+	 */
+	if (tegra_system_suspended()) {
+
+		/*
+		 * Lock scratch registers which hold the CPU vectors.
+		 */
+		tegra_pmc_lock_cpu_vectors();
+
+		/*
+		 * SMMU configuration.
+		 */
+		tegra_memctrl_setup();
+
+		/*
+		 * Security configuration to allow DRAM/device access.
+		 */
+		plat_params = bl31_get_plat_params();
+		tegra_memctrl_tzdram_setup(tegra_bl31_phys_base,
+			plat_params->tzdram_size);
+	}
+
+	/*
+	 * Reset hardware settings.
+	 */
+	tegra_prepare_cpu_on_finish(read_mpidr());
+}
+
+/*******************************************************************************
+ * Handler called when an affinity instance has just been powered on after
+ * having been suspended earlier. The level and mpidr determine the affinity
+ * instance.
+ ******************************************************************************/
+void tegra_affinst_suspend_finish(unsigned int afflvl, unsigned int state)
+{
+	if (afflvl == MPIDR_AFFLVL0)
+		tegra_affinst_on_finish(afflvl, state);
+}
+
+/*******************************************************************************
+ * Handler called when the system wants to be powered off
+ ******************************************************************************/
+__dead2 void tegra_system_off(void)
+{
+	ERROR("Tegra System Off: operation not handled.\n");
+	panic();
+}
+
+/*******************************************************************************
+ * Handler called when the system wants to be restarted.
+ ******************************************************************************/
+__dead2 void tegra_system_reset(void)
+{
+	/*
+	 * Program the PMC in order to restart the system.
+	 */
+	tegra_pmc_system_reset();
+}
+
+/*******************************************************************************
+ * Export the platform handlers to enable psci to invoke them
+ ******************************************************************************/
+static const plat_pm_ops_t tegra_plat_pm_ops = {
+	.affinst_standby	= tegra_affinst_standby,
+	.affinst_on		= tegra_affinst_on,
+	.affinst_off		= tegra_affinst_off,
+	.affinst_suspend	= tegra_affinst_suspend,
+	.affinst_on_finish	= tegra_affinst_on_finish,
+	.affinst_suspend_finish	= tegra_affinst_suspend_finish,
+	.system_off		= tegra_system_off,
+	.system_reset		= tegra_system_reset,
+	.validate_power_state	= tegra_validate_power_state
+};
+
+/*******************************************************************************
+ * Export the platform specific power ops & initialize the fvp power controller
+ ******************************************************************************/
+int platform_setup_pm(const plat_pm_ops_t **plat_ops)
+{
+	/*
+	 * Reset hardware settings.
+	 */
+	tegra_prepare_cpu_on_finish(read_mpidr());
+
+	/*
+	 * Initialize PM ops struct
+	 */
+	*plat_ops = &tegra_plat_pm_ops;
+
+	return 0;
+}
diff --git a/plat/nvidia/tegra/common/tegra_sip_calls.c b/plat/nvidia/tegra/common/tegra_sip_calls.c
new file mode 100644
index 0000000..1d79c80
--- /dev/null
+++ b/plat/nvidia/tegra/common/tegra_sip_calls.c
@@ -0,0 +1,105 @@
+/*
+ * 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.
+ */
+
+#include <arch_helpers.h>
+#include <assert.h>
+#include <bl_common.h>
+#include <context_mgmt.h>
+#include <debug.h>
+#include <errno.h>
+#include <memctrl.h>
+#include <runtime_svc.h>
+#include <tegra_private.h>
+
+#define TEGRA_SIP_NEW_VIDEOMEM_REGION		0x82000003
+
+/*******************************************************************************
+ * This function is responsible for handling all SiP calls from the NS world
+ ******************************************************************************/
+uint64_t tegra_sip_handler(uint32_t smc_fid,
+			   uint64_t x1,
+			   uint64_t x2,
+			   uint64_t x3,
+			   uint64_t x4,
+			   void *cookie,
+			   void *handle,
+			   uint64_t flags)
+{
+	uint32_t ns;
+	int err;
+
+	/* Determine which security state this SMC originated from */
+	ns = is_caller_non_secure(flags);
+	if (!ns)
+		SMC_RET1(handle, SMC_UNK);
+
+	switch (smc_fid) {
+
+	case TEGRA_SIP_NEW_VIDEOMEM_REGION:
+
+		/*
+		 * Check if Video Memory overlaps TZDRAM (contains bl31/bl32)
+		 * or falls outside of the valid DRAM range
+		 */
+		err = bl31_check_ns_address(x1, x2);
+		if (err)
+			SMC_RET1(handle, err);
+
+		/*
+		 * Check if Video Memory is aligned to 1MB.
+		 */
+		if ((x1 & 0xFFFFF) || (x2 & 0xFFFFF)) {
+			ERROR("Unaligned Video Memory base address!\n");
+			SMC_RET1(handle, -ENOTSUP);
+		}
+
+		/* new video memory carveout settings */
+		tegra_memctrl_videomem_setup(x1, x2);
+
+		SMC_RET1(handle, 0);
+
+	default:
+		ERROR("%s: unhandled SMC (0x%x)\n", __func__, smc_fid);
+		break;
+	}
+
+	SMC_RET1(handle, SMC_UNK);
+}
+
+/* Define a runtime service descriptor for fast SMC calls */
+DECLARE_RT_SVC(
+	tegra_sip_fast,
+
+	OEN_SIP_START,
+	OEN_SIP_END,
+	SMC_TYPE_FAST,
+	NULL,
+	tegra_sip_handler
+);
diff --git a/plat/nvidia/tegra/common/tegra_topology.c b/plat/nvidia/tegra/common/tegra_topology.c
new file mode 100644
index 0000000..220e697
--- /dev/null
+++ b/plat/nvidia/tegra/common/tegra_topology.c
@@ -0,0 +1,72 @@
+/*
+ * 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.
+ */
+
+#include <arch_helpers.h>
+#include <platform_def.h>
+#include <psci.h>
+
+/*******************************************************************************
+ * This function implements a part of the critical interface between the psci
+ * generic layer and the platform to allow the former to detect the platform
+ * topology. psci queries the platform to determine how many affinity instances
+ * are present at a particular level for a given mpidr.
+ ******************************************************************************/
+unsigned int plat_get_aff_count(unsigned int aff_lvl,
+				unsigned long mpidr)
+{
+	switch (aff_lvl) {
+	case MPIDR_AFFLVL2:
+		/* Last supported affinity level */
+		return 1;
+
+	case MPIDR_AFFLVL1:
+		/* Return # of clusters */
+		return PLATFORM_CLUSTER_COUNT;
+
+	case MPIDR_AFFLVL0:
+		/* # of cpus per cluster */
+		return PLATFORM_MAX_CPUS_PER_CLUSTER;
+
+	default:
+		return PSCI_AFF_ABSENT;
+	}
+}
+
+/*******************************************************************************
+ * This function implements a part of the critical interface between the psci
+ * generic layer and the platform to allow the former to detect the state of a
+ * affinity instance in the platform topology. psci queries the platform to
+ * determine whether an affinity instance is present or absent.
+ ******************************************************************************/
+unsigned int plat_get_aff_state(unsigned int aff_lvl,
+				unsigned long mpidr)
+{
+	return (aff_lvl <= MPIDR_AFFLVL2) ? PSCI_AFF_PRESENT : PSCI_AFF_ABSENT;
+}
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..26c8057
--- /dev/null
+++ b/plat/nvidia/tegra/include/drivers/memctrl.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 __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
+
+/* Video Memory carveout configuration registers */
+#define MC_VIDEO_PROTECT_BASE			0x648
+#define MC_VIDEO_PROTECT_SIZE_MB		0x64c
+
+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);
+void tegra_memctrl_videomem_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..d4b0ce2
--- /dev/null
+++ b/plat/nvidia/tegra/include/platform_def.h
@@ -0,0 +1,93 @@
+/*
+ * 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_SIZE			0x20000
+#define BL31_BASE			TZDRAM_BASE
+#define BL31_LIMIT			(TZDRAM_BASE + BL31_SIZE - 1)
+#define BL32_BASE			(TZDRAM_BASE + BL31_SIZE)
+#define BL32_LIMIT			TZDRAM_END
+
+/*******************************************************************************
+ * 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..fa29fbb
--- /dev/null
+++ b/plat/nvidia/tegra/include/tegra_private.h
@@ -0,0 +1,77 @@
+/*
+ * 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>
+
+/*******************************************************************************
+ * Tegra DRAM memory base address
+ ******************************************************************************/
+#define TEGRA_DRAM_BASE		0x80000000
+#define TEGRA_DRAM_END		0x27FFFFFFF
+
+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);
+int bl31_check_ns_address(uint64_t base, uint64_t size_in_bytes);
+
+#endif /* __TEGRA_PRIVATE_H__ */
diff --git a/plat/nvidia/tegra/platform.mk b/plat/nvidia/tegra/platform.mk
new file mode 100644
index 0000000..0d6e525
--- /dev/null
+++ b/plat/nvidia/tegra/platform.mk
@@ -0,0 +1,34 @@
+#
+# 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.
+#
+
+SOC_DIR		:=	plat/nvidia/tegra/soc/${TARGET_SOC}
+
+include plat/nvidia/tegra/common/tegra_common.mk
+include ${SOC_DIR}/platform_${TARGET_SOC}.mk
diff --git a/plat/nvidia/tegra/soc/t210/plat_psci_handlers.c b/plat/nvidia/tegra/soc/t210/plat_psci_handlers.c
new file mode 100644
index 0000000..7ac784b
--- /dev/null
+++ b/plat/nvidia/tegra/soc/t210/plat_psci_handlers.c
@@ -0,0 +1,141 @@
+/*
+ * 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.
+ */
+
+#include <arch_helpers.h>
+#include <assert.h>
+#include <debug.h>
+#include <mmio.h>
+#include <platform.h>
+#include <platform_def.h>
+#include <psci.h>
+#include <pmc.h>
+#include <flowctrl.h>
+#include <tegra_def.h>
+#include <tegra_private.h>
+
+/* Power down state IDs */
+#define PSTATE_ID_CORE_POWERDN		7
+#define PSTATE_ID_CLUSTER_IDLE		16
+#define PSTATE_ID_CLUSTER_POWERDN	17
+#define PSTATE_ID_SOC_POWERDN		27
+
+static int cpu_powergate_mask[PLATFORM_MAX_CPUS_PER_CLUSTER];
+
+int tegra_prepare_cpu_suspend(unsigned int id, unsigned int afflvl)
+{
+	/* There's nothing to be done for affinity level 1 */
+	if (afflvl == MPIDR_AFFLVL1)
+		return PSCI_E_SUCCESS;
+
+	switch (id) {
+	/* Prepare for cpu idle */
+	case PSTATE_ID_CORE_POWERDN:
+		tegra_fc_cpu_idle(read_mpidr());
+		return PSCI_E_SUCCESS;
+
+	/* Prepare for cluster idle */
+	case PSTATE_ID_CLUSTER_IDLE:
+		tegra_fc_cluster_idle(read_mpidr());
+		return PSCI_E_SUCCESS;
+
+	/* Prepare for cluster powerdn */
+	case PSTATE_ID_CLUSTER_POWERDN:
+		tegra_fc_cluster_powerdn(read_mpidr());
+		return PSCI_E_SUCCESS;
+
+	/* Prepare for system idle */
+	case PSTATE_ID_SOC_POWERDN:
+
+		/* Enter system suspend state */
+		tegra_pm_system_suspend_entry();
+
+		/* suspend the entire soc */
+		tegra_fc_soc_powerdn(read_mpidr());
+
+		return PSCI_E_SUCCESS;
+
+	default:
+		ERROR("Unknown state id (%d)\n", id);
+		break;
+	}
+
+	return PSCI_E_NOT_SUPPORTED;
+}
+
+int tegra_prepare_cpu_on_finish(unsigned long mpidr)
+{
+	/*
+	 * Check if we are exiting from SOC_POWERDN.
+	 */
+	if (tegra_system_suspended()) {
+
+		/*
+		 * Restore Boot and Power Management Processor (BPMP) reset
+		 * address and reset it.
+		 */
+		tegra_fc_reset_bpmp();
+
+		/*
+		 * System resume complete.
+		 */
+		tegra_pm_system_suspend_exit();
+	}
+
+	/*
+	 * T210 has a dedicated ARMv7 boot and power mgmt processor, BPMP. It's
+	 * used for power management and boot purposes. Inform the BPMP that
+	 * we have completed the cluster power up.
+	 */
+	if (psci_get_max_phys_off_afflvl() == MPIDR_AFFLVL1)
+		tegra_fc_lock_active_cluster();
+
+	return PSCI_E_SUCCESS;
+}
+
+int tegra_prepare_cpu_on(unsigned long mpidr)
+{
+	int cpu = mpidr & MPIDR_CPU_MASK;
+
+	/* Turn on CPU using flow controller or PMC */
+	if (cpu_powergate_mask[cpu] == 0) {
+		tegra_pmc_cpu_on(cpu);
+		cpu_powergate_mask[cpu] = 1;
+	} else {
+		tegra_fc_cpu_on(cpu);
+	}
+
+	return PSCI_E_SUCCESS;
+}
+
+int tegra_prepare_cpu_off(unsigned long mpidr)
+{
+	tegra_fc_cpu_off(mpidr & MPIDR_CPU_MASK);
+	return PSCI_E_SUCCESS;
+}
diff --git a/plat/nvidia/tegra/soc/t210/plat_secondary.c b/plat/nvidia/tegra/soc/t210/plat_secondary.c
new file mode 100644
index 0000000..fb3cf71
--- /dev/null
+++ b/plat/nvidia/tegra/soc/t210/plat_secondary.c
@@ -0,0 +1,63 @@
+/*
+ * 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.
+ */
+
+#include <debug.h>
+#include <mmio.h>
+#include <pmc.h>
+#include <tegra_def.h>
+
+#define SB_CSR				0x0
+#define  SB_CSR_NS_RST_VEC_WR_DIS	(1 << 1)
+
+/* CPU reset vector */
+#define SB_AA64_RESET_LOW		0x30	/* width = 31:0 */
+#define SB_AA64_RESET_HI		0x34	/* width = 11:0 */
+
+extern void tegra_secure_entrypoint(void);
+
+/*******************************************************************************
+ * Setup secondary CPU vectors
+ ******************************************************************************/
+void plat_secondary_setup(void)
+{
+	uint32_t val;
+	uint64_t reset_addr = (uint64_t)tegra_secure_entrypoint;
+
+	INFO("Setting up secondary CPU boot\n");
+
+	/* setup secondary CPU vector */
+	mmio_write_32(TEGRA_SB_BASE + SB_AA64_RESET_LOW,
+			(reset_addr & 0xFFFFFFFF) | 1);
+	val = reset_addr >> 32;
+	mmio_write_32(TEGRA_SB_BASE + SB_AA64_RESET_HI, val & 0x7FF);
+
+	/* configure PMC */
+	tegra_pmc_cpu_setup(reset_addr);
+}
diff --git a/plat/nvidia/tegra/soc/t210/plat_setup.c b/plat/nvidia/tegra/soc/t210/plat_setup.c
new file mode 100644
index 0000000..cbe7a04
--- /dev/null
+++ b/plat/nvidia/tegra/soc/t210/plat_setup.c
@@ -0,0 +1,69 @@
+/*
+ * 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.
+ */
+
+#include <console.h>
+#include <tegra_def.h>
+#include <xlat_tables.h>
+
+/* sets of MMIO ranges setup */
+#define MMIO_RANGE_0_ADDR	0x50000000
+#define MMIO_RANGE_1_ADDR	0x60000000
+#define MMIO_RANGE_2_ADDR	0x70000000
+#define MMIO_RANGE_SIZE		0x200000
+
+/*
+ * Table of regions to map using the MMU.
+ */
+static const mmap_region_t tegra_mmap[] = {
+	MAP_REGION_FLAT(MMIO_RANGE_0_ADDR, MMIO_RANGE_SIZE,
+			MT_DEVICE | MT_RW | MT_SECURE),
+	MAP_REGION_FLAT(MMIO_RANGE_1_ADDR, MMIO_RANGE_SIZE,
+			MT_DEVICE | MT_RW | MT_SECURE),
+	MAP_REGION_FLAT(MMIO_RANGE_2_ADDR, MMIO_RANGE_SIZE,
+			MT_DEVICE | MT_RW | MT_SECURE),
+	{0}
+};
+
+/*******************************************************************************
+ * Set up the pagetables as per the platform memory map & initialize the MMU
+ ******************************************************************************/
+const mmap_region_t *plat_get_mmio_map(void)
+{
+	/* MMIO space */
+	return tegra_mmap;
+}
+
+/*******************************************************************************
+ * Handler to get the System Counter Frequency
+ ******************************************************************************/
+uint64_t plat_get_syscnt_freq(void)
+{
+	return 19200000;
+}
diff --git a/plat/nvidia/tegra/soc/t210/platform_t210.mk b/plat/nvidia/tegra/soc/t210/platform_t210.mk
new file mode 100644
index 0000000..41651d3
--- /dev/null
+++ b/plat/nvidia/tegra/soc/t210/platform_t210.mk
@@ -0,0 +1,51 @@
+#
+# 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.
+#
+
+TEGRA_BOOT_UART_BASE 		:= 0x70006000
+$(eval $(call add_define,TEGRA_BOOT_UART_BASE))
+
+TZDRAM_BASE			:= 0xFDC00000
+$(eval $(call add_define,TZDRAM_BASE))
+
+ERRATA_TEGRA_INVALIDATE_BTB_AT_BOOT	:= 1
+$(eval $(call add_define,ERRATA_TEGRA_INVALIDATE_BTB_AT_BOOT))
+
+PLATFORM_CLUSTER_COUNT		:= 2
+$(eval $(call add_define,PLATFORM_CLUSTER_COUNT))
+
+PLATFORM_MAX_CPUS_PER_CLUSTER	:= 4
+$(eval $(call add_define,PLATFORM_MAX_CPUS_PER_CLUSTER))
+
+BL31_SOURCES		+=	${SOC_DIR}/plat_psci_handlers.c \
+				${SOC_DIR}/plat_setup.c \
+				${SOC_DIR}/plat_secondary.c
+
+# Enable workarounds for selected Cortex-A53 erratas.
+ERRATA_A53_826319	:=	1
diff --git a/services/std_svc/psci/psci_common.c b/services/std_svc/psci/psci_common.c
index 237cf1e..63d8476 100644
--- a/services/std_svc/psci/psci_common.c
+++ b/services/std_svc/psci/psci_common.c
@@ -185,8 +185,8 @@
 	aff_shift = get_afflvl_shift(aff_lvl);
 
 	/* Clear the existing affinity instance & set the new one*/
-	mpidr &= ~(MPIDR_AFFLVL_MASK << aff_shift);
-	mpidr |= aff_inst << aff_shift;
+	mpidr &= ~(((unsigned long)MPIDR_AFFLVL_MASK) << aff_shift);
+	mpidr |= ((unsigned long)aff_inst) << aff_shift;
 
 	return mpidr;
 }