Support for NVIDIA's Tegra T210 SoCs
T210 is the latest chip in the Tegra family of SoCs from NVIDIA. It is an
ARM v8 dual-cluster (A57/A53) SoC, with any one of the clusters being active
at a given point in time.
This patch adds support to boot the Trusted Firmware on T210 SoCs. The patch
also adds support to boot secondary CPUs, enter/exit core power states for
all CPUs in the slow/fast clusters. The support to switch between clusters
is still not available in this patch and would be available later.
Signed-off-by: Varun Wadekar <vwadekar@nvidia.com>
diff --git a/plat/nvidia/tegra/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..9a8ba66
--- /dev/null
+++ b/plat/nvidia/tegra/common/drivers/memctrl/memctrl.c
@@ -0,0 +1,92 @@
+/*
+ * 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 <debug.h>
+#include <mmio.h>
+#include <memctrl.h>
+#include <tegra_def.h>
+
+/*
+ * 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 */
+}
+
+/*
+ * 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);
+}
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..628dc2a
--- /dev/null
+++ b/plat/nvidia/tegra/common/tegra_bl31_setup.c
@@ -0,0 +1,228 @@
+/*
+ * 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 <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;
+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;
+
+ 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 entry point information.
+ * They are stored in Secure RAM, in BL2's address space.
+ */
+ bl33_image_ep_info = *from_bl2->bl33_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);
+}
diff --git a/plat/nvidia/tegra/common/tegra_common.mk b/plat/nvidia/tegra/common/tegra_common.mk
new file mode 100644
index 0000000..b1ce51f
--- /dev/null
+++ b/plat/nvidia/tegra/common/tegra_common.mk
@@ -0,0 +1,62 @@
+#
+# 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_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_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;
+}