Support for NVIDIA's Tegra T210 SoCs
authorVarun Wadekar <vwadekar@nvidia.com>
Tue, 19 May 2015 11:18:04 +0000 (16:48 +0530)
committerVarun Wadekar <vwadekar@nvidia.com>
Fri, 29 May 2015 11:13:25 +0000 (16:43 +0530)
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>
22 files changed:
docs/plat/nvidia-tegra.md [new file with mode: 0644]
plat/nvidia/tegra/common/aarch64/tegra_helpers.S [new file with mode: 0644]
plat/nvidia/tegra/common/drivers/flowctrl/flowctrl.c [new file with mode: 0644]
plat/nvidia/tegra/common/drivers/memctrl/memctrl.c [new file with mode: 0644]
plat/nvidia/tegra/common/drivers/pmc/pmc.c [new file with mode: 0644]
plat/nvidia/tegra/common/tegra_bl31_setup.c [new file with mode: 0644]
plat/nvidia/tegra/common/tegra_common.mk [new file with mode: 0644]
plat/nvidia/tegra/common/tegra_gic.c [new file with mode: 0644]
plat/nvidia/tegra/common/tegra_pm.c [new file with mode: 0644]
plat/nvidia/tegra/common/tegra_topology.c [new file with mode: 0644]
plat/nvidia/tegra/include/drivers/flowctrl.h [new file with mode: 0644]
plat/nvidia/tegra/include/drivers/memctrl.h [new file with mode: 0644]
plat/nvidia/tegra/include/drivers/pmc.h [new file with mode: 0644]
plat/nvidia/tegra/include/plat_macros.S [new file with mode: 0644]
plat/nvidia/tegra/include/platform_def.h [new file with mode: 0644]
plat/nvidia/tegra/include/t210/tegra_def.h [new file with mode: 0644]
plat/nvidia/tegra/include/tegra_private.h [new file with mode: 0644]
plat/nvidia/tegra/platform.mk [new file with mode: 0644]
plat/nvidia/tegra/soc/t210/plat_psci_handlers.c [new file with mode: 0644]
plat/nvidia/tegra/soc/t210/plat_secondary.c [new file with mode: 0644]
plat/nvidia/tegra/soc/t210/plat_setup.c [new file with mode: 0644]
plat/nvidia/tegra/soc/t210/platform_t210.mk [new file with mode: 0644]

diff --git a/docs/plat/nvidia-tegra.md b/docs/plat/nvidia-tegra.md
new file mode 100644 (file)
index 0000000..242e8db
--- /dev/null
@@ -0,0 +1,21 @@
+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
+
+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> all
diff --git a/plat/nvidia/tegra/common/aarch64/tegra_helpers.S b/plat/nvidia/tegra/common/aarch64/tegra_helpers.S
new file mode 100644 (file)
index 0000000..264749b
--- /dev/null
@@ -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 (file)
index 0000000..a36cf2d
--- /dev/null
@@ -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 (file)
index 0000000..9a8ba66
--- /dev/null
@@ -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 (file)
index 0000000..5796ac7
--- /dev/null
@@ -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 (file)
index 0000000..628dc2a
--- /dev/null
@@ -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 (file)
index 0000000..b1ce51f
--- /dev/null
@@ -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 (file)
index 0000000..2dafae7
--- /dev/null
@@ -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 (file)
index 0000000..243407d
--- /dev/null
@@ -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 (file)
index 0000000..220e697
--- /dev/null
@@ -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 (file)
index 0000000..8bc821d
--- /dev/null
@@ -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 (file)
index 0000000..867f09e
--- /dev/null
@@ -0,0 +1,80 @@
+/*
+ * Copyright (c) 2015, ARM Limited and Contributors. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *
+ * Redistributions of source code must retain the above copyright notice, this
+ * list of conditions and the following disclaimer.
+ *
+ * Redistributions in binary form must reproduce the above copyright notice,
+ * this list of conditions and the following disclaimer in the documentation
+ * and/or other materials provided with the distribution.
+ *
+ * Neither the name of ARM nor the names of its contributors may be used
+ * to endorse or promote products derived from this software without specific
+ * prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
+ * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
+ * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
+ * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
+ * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ */
+
+#ifndef __MEMCTRL_H__
+#define __MEMCTRL_H__
+
+#include <mmio.h>
+#include <tegra_def.h>
+
+/* SMMU registers */
+#define MC_SMMU_CONFIG_0                       0x10
+#define  MC_SMMU_CONFIG_0_SMMU_ENABLE_DISABLE  0
+#define  MC_SMMU_CONFIG_0_SMMU_ENABLE_ENABLE   1
+#define MC_SMMU_TLB_CONFIG_0                   0x14
+#define  MC_SMMU_TLB_CONFIG_0_RESET_VAL                0x20000010
+#define MC_SMMU_PTC_CONFIG_0                   0x18
+#define  MC_SMMU_PTC_CONFIG_0_RESET_VAL                0x2000003f
+#define MC_SMMU_TLB_FLUSH_0                    0x30
+#define  TLB_FLUSH_VA_MATCH_ALL                        0
+#define  TLB_FLUSH_ASID_MATCH_DISABLE          0
+#define  TLB_FLUSH_ASID_MATCH_SHIFT            31
+#define  MC_SMMU_TLB_FLUSH_ALL         \
+        (TLB_FLUSH_VA_MATCH_ALL |      \
+        (TLB_FLUSH_ASID_MATCH_DISABLE << TLB_FLUSH_ASID_MATCH_SHIFT))
+#define MC_SMMU_PTC_FLUSH_0                    0x34
+#define  MC_SMMU_PTC_FLUSH_ALL                 0
+#define MC_SMMU_ASID_SECURITY_0                        0x38
+#define  MC_SMMU_ASID_SECURITY                 0
+#define MC_SMMU_TRANSLATION_ENABLE_0_0         0x228
+#define MC_SMMU_TRANSLATION_ENABLE_1_0         0x22c
+#define MC_SMMU_TRANSLATION_ENABLE_2_0         0x230
+#define MC_SMMU_TRANSLATION_ENABLE_3_0         0x234
+#define MC_SMMU_TRANSLATION_ENABLE_4_0         0xb98
+#define  MC_SMMU_TRANSLATION_ENABLE            (~0)
+
+/* TZDRAM carveout configuration registers */
+#define MC_SECURITY_CFG0_0                     0x70
+#define MC_SECURITY_CFG1_0                     0x74
+
+static inline uint32_t tegra_mc_read_32(uint32_t off)
+{
+       return mmio_read_32(TEGRA_MC_BASE + off);
+}
+
+static inline void tegra_mc_write_32(uint32_t off, uint32_t val)
+{
+       mmio_write_32(TEGRA_MC_BASE + off, val);
+}
+
+void tegra_memctrl_setup(void);
+void tegra_memctrl_tzdram_setup(uint64_t phys_base, uint32_t size_in_bytes);
+
+#endif /* __MEMCTRL_H__ */
diff --git a/plat/nvidia/tegra/include/drivers/pmc.h b/plat/nvidia/tegra/include/drivers/pmc.h
new file mode 100644 (file)
index 0000000..c0616d0
--- /dev/null
@@ -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 (file)
index 0000000..0868b41
--- /dev/null
@@ -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 (file)
index 0000000..6be777e
--- /dev/null
@@ -0,0 +1,90 @@
+/*
+ * Copyright (c) 2015, ARM Limited and Contributors. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *
+ * Redistributions of source code must retain the above copyright notice, this
+ * list of conditions and the following disclaimer.
+ *
+ * Redistributions in binary form must reproduce the above copyright notice,
+ * this list of conditions and the following disclaimer in the documentation
+ * and/or other materials provided with the distribution.
+ *
+ * Neither the name of ARM nor the names of its contributors may be used
+ * to endorse or promote products derived from this software without specific
+ * prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
+ * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
+ * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
+ * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
+ * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ */
+
+#ifndef __PLATFORM_DEF_H__
+#define __PLATFORM_DEF_H__
+
+#include <arch.h>
+#include <common_def.h>
+
+/*******************************************************************************
+ * Generic platform constants
+ ******************************************************************************/
+
+/* Size of cacheable stacks */
+#if DEBUG_XLAT_TABLE
+#define PLATFORM_STACK_SIZE 0x800
+#elif IMAGE_BL31
+#define PLATFORM_STACK_SIZE 0x400
+#endif
+
+#define TEGRA_PRIMARY_CPU              0x0
+
+#define PLATFORM_MAX_AFFLVL            MPIDR_AFFLVL2
+#define PLATFORM_CORE_COUNT            PLATFORM_MAX_CPUS_PER_CLUSTER
+#define PLATFORM_NUM_AFFS              ((PLATFORM_CLUSTER_COUNT * \
+                                         PLATFORM_CORE_COUNT) + \
+                                         PLATFORM_CLUSTER_COUNT + 1)
+
+/*******************************************************************************
+ * Platform console related constants
+ ******************************************************************************/
+#define TEGRA_CONSOLE_BAUDRATE         115200
+#define TEGRA_BOOT_UART_CLK_IN_HZ      408000000
+
+/*******************************************************************************
+ * Platform memory map related constants
+ ******************************************************************************/
+/* Size of trusted dram */
+#define TZDRAM_SIZE                    0x00400000
+#define TZDRAM_END                     (TZDRAM_BASE + TZDRAM_SIZE)
+
+/*******************************************************************************
+ * BL31 specific defines.
+ ******************************************************************************/
+#define BL31_BASE                      TZDRAM_BASE
+#define BL31_LIMIT                     (TZDRAM_BASE + 0x11FFF)
+
+/*******************************************************************************
+ * Platform specific page table and MMU setup constants
+ ******************************************************************************/
+#define ADDR_SPACE_SIZE                        (1ull << 32)
+#define MAX_XLAT_TABLES                        3
+#define MAX_MMAP_REGIONS               8
+
+/*******************************************************************************
+ * Some data must be aligned on the biggest cache line size in the platform.
+ * This is known only to the platform as it might have a combination of
+ * integrated and external caches.
+ ******************************************************************************/
+#define CACHE_WRITEBACK_SHIFT          6
+#define CACHE_WRITEBACK_GRANULE                (1 << CACHE_WRITEBACK_SHIFT)
+
+#endif /* __PLATFORM_DEF_H__ */
diff --git a/plat/nvidia/tegra/include/t210/tegra_def.h b/plat/nvidia/tegra/include/t210/tegra_def.h
new file mode 100644 (file)
index 0000000..c72d081
--- /dev/null
@@ -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 (file)
index 0000000..484879e
--- /dev/null
@@ -0,0 +1,70 @@
+/*
+ * Copyright (c) 2015, ARM Limited and Contributors. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *
+ * Redistributions of source code must retain the above copyright notice, this
+ * list of conditions and the following disclaimer.
+ *
+ * Redistributions in binary form must reproduce the above copyright notice,
+ * this list of conditions and the following disclaimer in the documentation
+ * and/or other materials provided with the distribution.
+ *
+ * Neither the name of ARM nor the names of its contributors may be used
+ * to endorse or promote products derived from this software without specific
+ * prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
+ * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
+ * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
+ * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
+ * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ */
+
+#ifndef __TEGRA_PRIVATE_H__
+#define __TEGRA_PRIVATE_H__
+
+#include <xlat_tables.h>
+#include <platform_def.h>
+
+typedef struct plat_params_from_bl2 {
+       uint64_t tzdram_size;
+       uintptr_t bl32_params;
+} plat_params_from_bl2_t;
+
+/* Declarations for plat_setup.c */
+const mmap_region_t *plat_get_mmio_map(void);
+uint64_t plat_get_syscnt_freq(void);
+
+/* Declarations for plat_secondary.c */
+void plat_secondary_setup(void);
+int plat_lock_cpu_vectors(void);
+
+/* Declarations for tegra_gic.c */
+void tegra_gic_setup(void);
+void tegra_gic_cpuif_deactivate(void);
+
+/* Declarations for tegra_security.c */
+void tegra_security_setup(void);
+void tegra_security_setup_videomem(uintptr_t base, uint64_t size);
+
+/* Declarations for tegra_pm.c */
+void tegra_pm_system_suspend_entry(void);
+void tegra_pm_system_suspend_exit(void);
+int tegra_system_suspended(void);
+
+/* Declarations for tegraXXX_pm.c */
+int tegra_prepare_cpu_suspend(unsigned int id, unsigned int afflvl);
+int tegra_prepare_cpu_on_finish(unsigned long mpidr);
+
+/* Declarations for tegra_bl31_setup.c */
+plat_params_from_bl2_t *bl31_get_plat_params(void);
+
+#endif /* __TEGRA_PRIVATE_H__ */
diff --git a/plat/nvidia/tegra/platform.mk b/plat/nvidia/tegra/platform.mk
new file mode 100644 (file)
index 0000000..0d6e525
--- /dev/null
@@ -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 (file)
index 0000000..7ac784b
--- /dev/null
@@ -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 (file)
index 0000000..fb3cf71
--- /dev/null
@@ -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 (file)
index 0000000..cbe7a04
--- /dev/null
@@ -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 (file)
index 0000000..41651d3
--- /dev/null
@@ -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