Commit 4731e8f0 authored by danh-arm's avatar danh-arm
Browse files

Merge pull request #295 from danh-arm/dh/plat-port-reorg

ARM platform port reorganization
parents 6403a306 4a75b84a
/*
* Copyright (c) 2014, ARM Limited and Contributors. All rights reserved.
* Copyright (c) 2014-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:
......@@ -30,10 +30,10 @@
#include <arch_helpers.h>
#include <bakery_lock.h>
#include <css_def.h>
#include <mmio.h>
#include "juno_def.h"
#include "juno_private.h"
#include "mhu.h"
#include <plat_arm.h>
#include "css_mhu.h"
/* SCP MHU secure channel registers */
#define SCP_INTR_S_STAT 0x200
......@@ -45,20 +45,15 @@
#define CPU_INTR_S_SET 0x308
#define CPU_INTR_S_CLEAR 0x310
#if IMAGE_BL31
#if USE_COHERENT_MEM
static bakery_lock_t mhu_secure_lock __attribute__ ((section("tzfw_coherent_mem")));
#define LOCK_ARG &mhu_secure_lock
#else
#define LOCK_ARG JUNO_MHU_BAKERY_ID
#endif /*__USE_COHERENT_MEM__ */
#else
#define LOCK_ARG /* Locks required only for BL3-1 images */
#endif /* __IMAGE_BL31__ */
ARM_INSTANTIATE_LOCK
/* Weak definition may be overridden in specific CSS based platform */
#pragma weak plat_arm_pwrc_setup
void mhu_secure_message_start(void)
{
juno_lock_get(LOCK_ARG);
arm_lock_get();
/* Make sure any previous command has finished */
while (mmio_read_32(MHU_BASE + CPU_INTR_S_STAT) != 0)
......@@ -85,15 +80,18 @@ uint32_t mhu_secure_message_wait(void)
void mhu_secure_message_end(void)
{
/* Clear any response we got by writing all ones to the CLEAR register */
/*
* Clear any response we got by writing all ones to the CLEAR
* register
*/
mmio_write_32(MHU_BASE + SCP_INTR_S_CLEAR, 0xffffffffu);
juno_lock_release(LOCK_ARG);
arm_lock_release();
}
void mhu_secure_init(void)
{
juno_lock_init(LOCK_ARG);
arm_lock_init();
/*
* Clear the CPU's INTR register to make sure we don't see a stale
......@@ -101,3 +99,8 @@ void mhu_secure_init(void)
*/
mmio_write_32(MHU_BASE + CPU_INTR_S_CLEAR, 0xffffffffu);
}
void plat_arm_pwrc_setup(void)
{
mhu_secure_init();
}
......@@ -28,8 +28,8 @@
* POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef __MHU_H__
#define __MHU_H__
#ifndef __CSS_MHU_H__
#define __CSS_MHU_H__
#include <stdint.h>
......@@ -40,4 +40,4 @@ extern void mhu_secure_message_end(void);
extern void mhu_secure_init(void);
#endif /* __MHU_H__ */
#endif /* __CSS_MHU_H__ */
/*
* Copyright (c) 2013, ARM Limited and Contributors. All rights reserved.
* 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:
......@@ -32,20 +32,20 @@
#include <arch_helpers.h>
#include <arm_gic.h>
#include <cci.h>
#include <css_def.h>
#include <debug.h>
#include <errno.h>
#include <plat_arm.h>
#include <platform.h>
#include <platform_def.h>
#include <psci.h>
#include "juno_def.h"
#include "juno_private.h"
#include "scpi.h"
#include "css_scpi.h"
/*******************************************************************************
* Private Juno function to program the mailbox for a cpu before it is released
* Private function to program the mailbox for a cpu before it is released
* from reset.
******************************************************************************/
static void juno_program_mailbox(uint64_t mpidr, uint64_t address)
static void css_program_mailbox(uint64_t mpidr, uint64_t address)
{
uint64_t linear_id;
uint64_t mbox;
......@@ -57,63 +57,10 @@ static void juno_program_mailbox(uint64_t mpidr, uint64_t address)
}
/*******************************************************************************
* Private Juno function which is used to determine if any platform actions
* should be performed for the specified affinity instance given its
* state. Nothing needs to be done if the 'state' is not off or if this is not
* the highest affinity level which will enter the 'state'.
******************************************************************************/
static int32_t juno_do_plat_actions(uint32_t afflvl, uint32_t state)
{
uint32_t max_phys_off_afflvl;
assert(afflvl <= MPIDR_AFFLVL1);
if (state != PSCI_STATE_OFF)
return -EAGAIN;
/*
* Find the highest affinity level which will be suspended and postpone
* all the platform specific actions until that level is hit.
*/
max_phys_off_afflvl = psci_get_max_phys_off_afflvl();
assert(max_phys_off_afflvl != PSCI_INVALID_DATA);
assert(psci_get_suspend_afflvl() >= max_phys_off_afflvl);
if (afflvl != max_phys_off_afflvl)
return -EAGAIN;
return 0;
}
/*******************************************************************************
* Juno handler called to check the validity of the power state parameter.
******************************************************************************/
int32_t juno_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 the Juno. Ignore any other affinity level.
*/
if (psci_get_pstate_afflvl(power_state) != MPIDR_AFFLVL0)
return PSCI_E_INVALID_PARAMS;
}
/*
* We expect the 'state id' to be zero.
*/
if (psci_get_pstate_id(power_state))
return PSCI_E_INVALID_PARAMS;
return PSCI_E_SUCCESS;
}
/*******************************************************************************
* Juno handler called when an affinity instance is about to be turned on. The
* Handler called when an affinity instance is about to be turned on. The
* level and mpidr determine the affinity instance.
******************************************************************************/
int32_t juno_affinst_on(uint64_t mpidr,
int32_t css_affinst_on(uint64_t mpidr,
uint64_t sec_entrypoint,
uint32_t afflvl,
uint32_t state)
......@@ -128,7 +75,7 @@ int32_t juno_affinst_on(uint64_t mpidr,
/*
* Setup mailbox with address for CPU entrypoint when it next powers up
*/
juno_program_mailbox(mpidr, sec_entrypoint);
css_program_mailbox(mpidr, sec_entrypoint);
scpi_set_css_power_state(mpidr, scpi_power_on, scpi_power_on,
scpi_power_on);
......@@ -137,18 +84,18 @@ int32_t juno_affinst_on(uint64_t mpidr,
}
/*******************************************************************************
* Juno handler called when an affinity instance has just been powered on after
* Handler called when an affinity instance has just been powered on after
* being turned off earlier. The level and mpidr determine 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 setup it up
* correctly.
******************************************************************************/
void juno_affinst_on_finish(uint32_t afflvl, uint32_t state)
void css_affinst_on_finish(uint32_t afflvl, uint32_t state)
{
unsigned long mpidr;
/* Determine if any platform actions need to be executed. */
if (juno_do_plat_actions(afflvl, state) == -EAGAIN)
if (arm_do_affinst_actions(afflvl, state) == -EAGAIN)
return;
/* Get the mpidr for this cpu */
......@@ -164,20 +111,20 @@ void juno_affinst_on_finish(uint32_t afflvl, uint32_t state)
/* Enable the gic cpu interface */
arm_gic_cpuif_setup();
/* Juno todo: Is this setup only needed after a cold boot? */
/* todo: Is this setup only needed after a cold boot? */
arm_gic_pcpu_distif_setup();
/* Clear the mailbox for this cpu. */
juno_program_mailbox(mpidr, 0);
css_program_mailbox(mpidr, 0);
}
/*******************************************************************************
* Common function called while turning a cpu off or suspending it. It is called
* from juno_off() or juno_suspend() when these functions in turn are called for
* from css_off() or css_suspend() when these functions in turn are called for
* the highest affinity level which will be powered down. It performs the
* actions common to the OFF and SUSPEND calls.
******************************************************************************/
static void juno_power_down_common(uint32_t afflvl)
static void css_power_down_common(uint32_t afflvl)
{
uint32_t cluster_state = scpi_power_on;
......@@ -211,13 +158,13 @@ static void juno_power_down_common(uint32_t afflvl)
* global variables across calls. It will be wise to do flush a write to the
* global to prevent unpredictable results.
******************************************************************************/
static void juno_affinst_off(uint32_t afflvl, uint32_t state)
static void css_affinst_off(uint32_t afflvl, uint32_t state)
{
/* Determine if any platform actions need to be executed */
if (juno_do_plat_actions(afflvl, state) == -EAGAIN)
if (arm_do_affinst_actions(afflvl, state) == -EAGAIN)
return;
juno_power_down_common(afflvl);
css_power_down_common(afflvl);
}
/*******************************************************************************
......@@ -232,39 +179,39 @@ static void juno_affinst_off(uint32_t afflvl, uint32_t state)
* global variables across calls. It will be wise to do flush a write to the
* global to prevent unpredictable results.
******************************************************************************/
static void juno_affinst_suspend(uint64_t sec_entrypoint,
static void css_affinst_suspend(uint64_t sec_entrypoint,
uint32_t afflvl,
uint32_t state)
{
/* Determine if any platform actions need to be executed */
if (juno_do_plat_actions(afflvl, state) == -EAGAIN)
if (arm_do_affinst_actions(afflvl, state) == -EAGAIN)
return;
/*
* Setup mailbox with address for CPU entrypoint when it next powers up.
*/
juno_program_mailbox(read_mpidr_el1(), sec_entrypoint);
css_program_mailbox(read_mpidr_el1(), sec_entrypoint);
juno_power_down_common(afflvl);
css_power_down_common(afflvl);
}
/*******************************************************************************
* Juno handler called when an affinity instance has just been powered on after
* Handler called when an affinity instance has just been powered on after
* having been suspended earlier. The level and mpidr determine the affinity
* instance.
* TODO: At the moment we reuse the on finisher and reinitialize the secure
* context. Need to implement a separate suspend finisher.
******************************************************************************/
static void juno_affinst_suspend_finish(uint32_t afflvl,
static void css_affinst_suspend_finish(uint32_t afflvl,
uint32_t state)
{
juno_affinst_on_finish(afflvl, state);
css_affinst_on_finish(afflvl, state);
}
/*******************************************************************************
* Juno handlers to shutdown/reboot the system
* Handlers to shutdown/reboot the system
******************************************************************************/
static void __dead2 juno_system_off(void)
static void __dead2 css_system_off(void)
{
uint32_t response;
......@@ -272,15 +219,15 @@ static void __dead2 juno_system_off(void)
response = scpi_sys_power_state(scpi_system_shutdown);
if (response != SCP_OK) {
ERROR("Juno System Off: SCP error %u.\n", response);
ERROR("CSS System Off: SCP error %u.\n", response);
panic();
}
wfi();
ERROR("Juno System Off: operation not handled.\n");
ERROR("CSS System Off: operation not handled.\n");
panic();
}
static void __dead2 juno_system_reset(void)
static void __dead2 css_system_reset(void)
{
uint32_t response;
......@@ -288,18 +235,18 @@ static void __dead2 juno_system_reset(void)
response = scpi_sys_power_state(scpi_system_reboot);
if (response != SCP_OK) {
ERROR("Juno System Reset: SCP error %u.\n", response);
ERROR("CSS System Reset: SCP error %u.\n", response);
panic();
}
wfi();
ERROR("Juno System Reset: operation not handled.\n");
ERROR("CSS System Reset: operation not handled.\n");
panic();
}
/*******************************************************************************
* Handler called when an affinity instance is about to enter standby.
******************************************************************************/
void juno_affinst_standby(unsigned int power_state)
void css_affinst_standby(unsigned int power_state)
{
unsigned int scr;
......@@ -320,16 +267,16 @@ void juno_affinst_standby(unsigned int power_state)
/*******************************************************************************
* Export the platform handlers to enable psci to invoke them
******************************************************************************/
static const plat_pm_ops_t juno_ops = {
.affinst_on = juno_affinst_on,
.affinst_on_finish = juno_affinst_on_finish,
.affinst_off = juno_affinst_off,
.affinst_standby = juno_affinst_standby,
.affinst_suspend = juno_affinst_suspend,
.affinst_suspend_finish = juno_affinst_suspend_finish,
.system_off = juno_system_off,
.system_reset = juno_system_reset,
.validate_power_state = juno_validate_power_state
static const plat_pm_ops_t css_ops = {
.affinst_on = css_affinst_on,
.affinst_on_finish = css_affinst_on_finish,
.affinst_off = css_affinst_off,
.affinst_standby = css_affinst_standby,
.affinst_suspend = css_affinst_suspend,
.affinst_suspend_finish = css_affinst_suspend_finish,
.system_off = css_system_off,
.system_reset = css_system_reset,
.validate_power_state = arm_validate_power_state
};
/*******************************************************************************
......@@ -337,6 +284,6 @@ static const plat_pm_ops_t juno_ops = {
******************************************************************************/
int32_t platform_setup_pm(const plat_pm_ops_t **plat_ops)
{
*plat_ops = &juno_ops;
*plat_ops = &css_ops;
return 0;
}
......@@ -29,11 +29,11 @@
*/
#include <arch_helpers.h>
#include <css_def.h>
#include <platform.h>
#include "juno_def.h"
#include "mhu.h"
#include "scp_bootloader.h"
#include "scpi.h"
#include "css_mhu.h"
#include "css_scp_bootloader.h"
#include "css_scpi.h"
/* Boot commands sent from AP -> SCP */
#define BOOT_CMD_START 0x01
......
......@@ -28,9 +28,9 @@
* POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef __SCP_BOOTLOADER_H__
#define __SCP_BOOTLOADER_H__
#ifndef __CSS_SCP_BOOTLOADER_H__
#define __CSS_SCP_BOOTLOADER_H__
int scp_bootloader_transfer(void *image, unsigned int image_size);
#endif
#endif /* __CSS_SCP_BOOTLOADER_H__ */
......@@ -29,10 +29,10 @@
*/
#include <arch_helpers.h>
#include <css_def.h>
#include <platform.h>
#include "juno_def.h"
#include "mhu.h"
#include "scpi.h"
#include "css_mhu.h"
#include "css_scpi.h"
#define MHU_SECURE_SCP_TO_AP_PAYLOAD (MHU_SECURE_BASE+0x0080)
#define MHU_SECURE_AP_TO_SCP_PAYLOAD (MHU_SECURE_BASE+0x0280)
......
......@@ -28,15 +28,16 @@
* POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef __SCPI_H__
#define __SCPI_H__
#ifndef __CSS_SCPI_H__
#define __CSS_SCPI_H__
#include <stddef.h>
#include <stdint.h>
extern void *scpi_secure_message_start(void);
extern void scpi_secure_message_send(unsigned command, size_t size);
extern unsigned scpi_secure_message_receive(void **message_out, size_t *size_out);
extern unsigned scpi_secure_message_receive(void **message_out,
size_t *size_out);
extern void scpi_secure_message_end(void);
......@@ -75,8 +76,11 @@ typedef enum {
} scpi_system_state_t;
extern int scpi_wait_ready(void);
extern void scpi_set_css_power_state(unsigned mpidr, scpi_power_state_t cpu_state,
scpi_power_state_t cluster_state, scpi_power_state_t css_state);
extern void scpi_set_css_power_state(unsigned mpidr,
scpi_power_state_t cpu_state,
scpi_power_state_t cluster_state,
scpi_power_state_t css_state);
uint32_t scpi_sys_power_state(scpi_system_state_t system_state);
#endif /* __SCPI_H__ */
#endif /* __CSS_SCPI_H__ */
#
# 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.
#
PLAT_INCLUDES += -Iinclude/plat/arm/soc/common/
#PLAT_BL_COMMON_SOURCES +=
#BL1_SOURCES +=
BL2_SOURCES += plat/arm/soc/common/soc_css_security.c
#BL31_SOURCES +=
/*
* 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 <board_css_def.h>
#include <mmio.h>
#include <platform_def.h>
#include <soc_css_def.h>
/*
* Address of slave 'n' security setting in the NIC-400 address region
* control
* TODO: Ideally this macro should be moved in a "nic-400.h" header file but
* it would be the only thing in there so it's not worth it at the moment.
*/
#define NIC400_ADDR_CTRL_SECURITY_REG(n) (0x8 + (n) * 4)
void soc_css_init_nic400(void)
{
/*
* NIC-400 Access Control Initialization
*
* Define access privileges by setting each corresponding bit to:
* 0 = Secure access only
* 1 = Non-secure access allowed
*/
/*
* Allow non-secure access to some SOC regions, excluding UART1, which
* remains secure.
* Note: This is the NIC-400 device on the SOC
*/
mmio_write_32(SOC_CSS_NIC400_BASE +
NIC400_ADDR_CTRL_SECURITY_REG(SOC_CSS_NIC400_USB_EHCI), ~0);
mmio_write_32(SOC_CSS_NIC400_BASE +
NIC400_ADDR_CTRL_SECURITY_REG(SOC_CSS_NIC400_TLX_MASTER), ~0);
mmio_write_32(SOC_CSS_NIC400_BASE +
NIC400_ADDR_CTRL_SECURITY_REG(SOC_CSS_NIC400_USB_OHCI), ~0);
mmio_write_32(SOC_CSS_NIC400_BASE +
NIC400_ADDR_CTRL_SECURITY_REG(SOC_CSS_NIC400_PL354_SMC), ~0);
mmio_write_32(SOC_CSS_NIC400_BASE +
NIC400_ADDR_CTRL_SECURITY_REG(SOC_CSS_NIC400_APB4_BRIDGE), ~0);
mmio_write_32(SOC_CSS_NIC400_BASE +
NIC400_ADDR_CTRL_SECURITY_REG(SOC_CSS_NIC400_BOOTSEC_BRIDGE),
~SOC_CSS_NIC400_BOOTSEC_BRIDGE_UART1);
/*
* Allow non-secure access to some CSS regions.
* Note: This is the NIC-400 device on the CSS
*/
mmio_write_32(PLAT_SOC_CSS_NIC400_BASE +
NIC400_ADDR_CTRL_SECURITY_REG(CSS_NIC400_SLAVE_BOOTSECURE),
~0);
}
#define PCIE_SECURE_REG 0x3000
/* Mask uses REG and MEM access bits */
#define PCIE_SEC_ACCESS_MASK ((1 << 0) | (1 << 1))
void soc_css_init_pcie(void)
{
#if !PLAT_juno
/*
* Do not initialize PCIe in emulator environment.
* Platform ID register not supported on Juno
*/
if (BOARD_CSS_GET_PLAT_TYPE(BOARD_CSS_PLAT_ID_REG_ADDR) ==
BOARD_CSS_PLAT_TYPE_EMULATOR)
return;
#endif /* PLAT_juno */
/*
* PCIE Root Complex Security settings to enable non-secure
* access to config registers.
*/
mmio_write_32(SOC_CSS_PCIE_CONTROL_BASE + PCIE_SECURE_REG,
PCIE_SEC_ACCESS_MASK);
}
/*
* Copyright (c) 2013-2014, 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 <console.h>
#include <platform.h>
#include <platform_def.h>
#include <string.h>
#include "fvp_def.h"
#include "fvp_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__;
#if USE_COHERENT_MEM
extern unsigned long __COHERENT_RAM_START__;
extern unsigned long __COHERENT_RAM_END__;
#endif
/*
* The next 2 constants identify the extents of the code & RO data 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
* __RO_START__ and __RO_END__ linker symbols refer to page-aligned addresses.
*/
#define BL2_RO_BASE (unsigned long)(&__RO_START__)
#define BL2_RO_LIMIT (unsigned long)(&__RO_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 BL2_COHERENT_RAM_BASE (unsigned long)(&__COHERENT_RAM_START__)
#define BL2_COHERENT_RAM_LIMIT (unsigned long)(&__COHERENT_RAM_END__)
#endif
/* Data structure which holds the extents of the trusted SRAM for BL2 */
static meminfo_t bl2_tzram_layout
__attribute__ ((aligned(PLATFORM_CACHE_LINE_SIZE)));
/* Assert that BL3-1 parameters fit in shared memory */
CASSERT((PARAMS_BASE + sizeof(bl2_to_bl31_params_mem_t)) <
(FVP_SHARED_MEM_BASE + FVP_SHARED_MEM_SIZE),
assert_bl31_params_do_not_fit_in_shared_memory);
/*******************************************************************************
* Reference to structures which holds the arguments which need to be passed
* to BL31
******************************************************************************/
static bl31_params_t *bl2_to_bl31_params;
static entry_point_info_t *bl31_ep_info;
meminfo_t *bl2_plat_sec_mem_layout(void)
{
return &bl2_tzram_layout;
}
/*******************************************************************************
* This function assigns a pointer to the memory that the platform has kept
* aside to pass platform specific and trusted firmware related information
* to BL31. This memory is allocated by allocating memory to
* bl2_to_bl31_params_mem_t structure which is a superset of all the
* structure whose information is passed to BL31
* NOTE: This function should be called only once and should be done
* before generating params to BL31
******************************************************************************/
bl31_params_t *bl2_plat_get_bl31_params(void)
{
bl2_to_bl31_params_mem_t *bl31_params_mem;
/*
* Allocate the memory for all the arguments that needs to
* be passed to BL31
*/
bl31_params_mem = (bl2_to_bl31_params_mem_t *)PARAMS_BASE;
memset((void *)PARAMS_BASE, 0, sizeof(bl2_to_bl31_params_mem_t));
/* Assign memory for TF related information */
bl2_to_bl31_params = &bl31_params_mem->bl31_params;
SET_PARAM_HEAD(bl2_to_bl31_params, PARAM_BL31, VERSION_1, 0);
/* Fill BL31 related information */
bl31_ep_info = &bl31_params_mem->bl31_ep_info;
bl2_to_bl31_params->bl31_image_info = &bl31_params_mem->bl31_image_info;
SET_PARAM_HEAD(bl2_to_bl31_params->bl31_image_info, PARAM_IMAGE_BINARY,
VERSION_1, 0);
/* Fill BL32 related information if it exists */
if (BL32_BASE) {
bl2_to_bl31_params->bl32_ep_info =
&bl31_params_mem->bl32_ep_info;
SET_PARAM_HEAD(bl2_to_bl31_params->bl32_ep_info,
PARAM_EP, VERSION_1, 0);
bl2_to_bl31_params->bl32_image_info =
&bl31_params_mem->bl32_image_info;
SET_PARAM_HEAD(bl2_to_bl31_params->bl32_image_info,
PARAM_IMAGE_BINARY,
VERSION_1, 0);
}
/* Fill BL33 related information */
bl2_to_bl31_params->bl33_ep_info = &bl31_params_mem->bl33_ep_info;
SET_PARAM_HEAD(bl2_to_bl31_params->bl33_ep_info,
PARAM_EP, VERSION_1, 0);
bl2_to_bl31_params->bl33_image_info = &bl31_params_mem->bl33_image_info;
SET_PARAM_HEAD(bl2_to_bl31_params->bl33_image_info, PARAM_IMAGE_BINARY,
VERSION_1, 0);
return bl2_to_bl31_params;
}
/*******************************************************************************
* This function returns a pointer to the shared memory that the platform
* has kept to point to entry point information of BL31 to BL2
******************************************************************************/
struct entry_point_info *bl2_plat_get_bl31_ep_info(void)
{
#if DEBUG
bl31_ep_info->args.arg1 = FVP_BL31_PLAT_PARAM_VAL;
#endif
return bl31_ep_info;
}
/*******************************************************************************
* BL1 has passed the extents of the trusted SRAM that should be visible to BL2
* in x0. This memory layout is sitting at the base of the free trusted SRAM.
* Copy it to a safe loaction before its reclaimed by later BL2 functionality.
******************************************************************************/
void bl2_early_platform_setup(meminfo_t *mem_layout)
{
/* Initialize the console to provide early debug support */
console_init(PL011_UART0_BASE, PL011_UART0_CLK_IN_HZ, PL011_BAUDRATE);
/* Setup the BL2 memory layout */
bl2_tzram_layout = *mem_layout;
/* Initialize the platform config for future decision making */
fvp_config_setup();
/* Initialise the IO layer and register platform IO devices */
fvp_io_setup();
}
/*******************************************************************************
* Perform platform specific setup. For now just initialize the memory location
* to use for passing arguments to BL31.
******************************************************************************/
void bl2_platform_setup(void)
{
/*
* Do initial security configuration to allow DRAM/device access. On
* Base FVP only DRAM security is programmable (via TrustZone), but
* other platforms might have more programmable security devices
* present.
*/
fvp_security_setup();
}
/* Flush the TF params and the TF plat params */
void bl2_plat_flush_bl31_params(void)
{
flush_dcache_range((unsigned long)PARAMS_BASE, \
sizeof(bl2_to_bl31_params_mem_t));
}
/*******************************************************************************
* Perform the very early platform specific architectural setup here. At the
* moment this is only intializes the mmu in a quick and dirty way.
******************************************************************************/
void bl2_plat_arch_setup(void)
{
fvp_configure_mmu_el1(bl2_tzram_layout.total_base,
bl2_tzram_layout.total_size,
BL2_RO_BASE,
BL2_RO_LIMIT
#if USE_COHERENT_MEM
, BL2_COHERENT_RAM_BASE,
BL2_COHERENT_RAM_LIMIT
#endif
);
}
/*******************************************************************************
* Before calling this function BL31 is loaded in memory and its entrypoint
* is set by load_image. This is a placeholder for the platform to change
* the entrypoint of BL31 and set SPSR and security state.
* On FVP we are only setting the security state, entrypoint
******************************************************************************/
void bl2_plat_set_bl31_ep_info(image_info_t *bl31_image_info,
entry_point_info_t *bl31_ep_info)
{
SET_SECURITY_STATE(bl31_ep_info->h.attr, SECURE);
bl31_ep_info->spsr = SPSR_64(MODE_EL3, MODE_SP_ELX,
DISABLE_ALL_EXCEPTIONS);
}
/*******************************************************************************
* Before calling this function BL32 is loaded in memory and its entrypoint
* is set by load_image. This is a placeholder for the platform to change
* the entrypoint of BL32 and set SPSR and security state.
* On FVP we are only setting the security state, entrypoint
******************************************************************************/
void bl2_plat_set_bl32_ep_info(image_info_t *bl32_image_info,
entry_point_info_t *bl32_ep_info)
{
SET_SECURITY_STATE(bl32_ep_info->h.attr, SECURE);
bl32_ep_info->spsr = fvp_get_spsr_for_bl32_entry();
}
/*******************************************************************************
* Before calling this function BL33 is loaded in memory and its entrypoint
* is set by load_image. This is a placeholder for the platform to change
* the entrypoint of BL33 and set SPSR and security state.
* On FVP we are only setting the security state, entrypoint
******************************************************************************/
void bl2_plat_set_bl33_ep_info(image_info_t *image,
entry_point_info_t *bl33_ep_info)
{
SET_SECURITY_STATE(bl33_ep_info->h.attr, NON_SECURE);
bl33_ep_info->spsr = fvp_get_spsr_for_bl33_entry();
}
/*******************************************************************************
* Populate the extents of memory available for loading BL32
******************************************************************************/
void bl2_plat_get_bl32_meminfo(meminfo_t *bl32_meminfo)
{
/*
* Populate the extents of memory available for loading BL32.
*/
bl32_meminfo->total_base = BL32_BASE;
bl32_meminfo->free_base = BL32_BASE;
bl32_meminfo->total_size =
(TSP_SEC_MEM_BASE + TSP_SEC_MEM_SIZE) - BL32_BASE;
bl32_meminfo->free_size =
(TSP_SEC_MEM_BASE + TSP_SEC_MEM_SIZE) - BL32_BASE;
}
/*******************************************************************************
* Populate the extents of memory available for loading BL33
******************************************************************************/
void bl2_plat_get_bl33_meminfo(meminfo_t *bl33_meminfo)
{
bl33_meminfo->total_base = DRAM1_NS_BASE;
bl33_meminfo->total_size = DRAM1_NS_SIZE;
bl33_meminfo->free_base = DRAM1_NS_BASE;
bl33_meminfo->free_size = DRAM1_NS_SIZE;
}
/*
* Copyright (c) 2014, 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 __FVP_DEF_H__
#define __FVP_DEF_H__
/* Firmware Image Package */
#define FIP_IMAGE_NAME "fip.bin"
#define FVP_PRIMARY_CPU 0x0
/* Memory location options for TSP */
#define FVP_TRUSTED_SRAM_ID 0
#define FVP_TRUSTED_DRAM_ID 1
#define FVP_DRAM_ID 2
/*
* Some of the definitions in this file use the 'ull' suffix in order to avoid
* subtle integer overflow errors due to implicit integer type promotion when
* working with 32-bit values.
*
* The TSP linker script includes some of these definitions to define the BL3-2
* memory map, but the GNU LD does not support the 'ull' suffix, causing the
* build process to fail. To solve this problem, the auxiliary macro MAKE_ULL(x)
* will add the 'ull' suffix only when the macro __LINKER__ is not defined
* (__LINKER__ is defined in the command line to preprocess the linker script).
* Constants in the linker script will not have the 'ull' suffix, but this is
* not a problem since the linker evaluates all constant expressions to 64 bit
* (assuming the target architecture is 64 bit).
*/
#ifndef __LINKER__
#define MAKE_ULL(x) x##ull
#else
#define MAKE_ULL(x) x
#endif
/*******************************************************************************
* FVP memory map related constants
******************************************************************************/
#define FVP_TRUSTED_ROM_BASE 0x00000000
#define FVP_TRUSTED_ROM_SIZE 0x04000000 /* 64 MB */
/* The first 4KB of Trusted SRAM are used as shared memory */
#define FVP_SHARED_MEM_BASE 0x04000000
#define FVP_SHARED_MEM_SIZE 0x00001000 /* 4 KB */
/* The remaining Trusted SRAM is used to load the BL images */
#define FVP_TRUSTED_SRAM_BASE 0x04001000
#define FVP_TRUSTED_SRAM_SIZE 0x0003F000 /* 252 KB */
#define FVP_TRUSTED_DRAM_BASE 0x06000000
#define FVP_TRUSTED_DRAM_SIZE 0x02000000 /* 32 MB */
#define FLASH0_BASE 0x08000000
#define FLASH0_SIZE 0x04000000
#define FLASH1_BASE 0x0c000000
#define FLASH1_SIZE 0x04000000
#define PSRAM_BASE 0x14000000
#define PSRAM_SIZE 0x04000000
#define VRAM_BASE 0x18000000
#define VRAM_SIZE 0x02000000
/* Aggregate of all devices in the first GB */
#define DEVICE0_BASE 0x1a000000
#define DEVICE0_SIZE 0x12200000
#define DEVICE1_BASE 0x2f000000
#define DEVICE1_SIZE 0x200000
#define NSRAM_BASE 0x2e000000
#define NSRAM_SIZE 0x10000
#define DRAM1_BASE MAKE_ULL(0x80000000)
#define DRAM1_SIZE MAKE_ULL(0x80000000)
#define DRAM1_END (DRAM1_BASE + DRAM1_SIZE - 1)
/* Define the top 16 MB of DRAM1 as secure */
#define DRAM1_SEC_SIZE MAKE_ULL(0x01000000)
#define DRAM1_SEC_BASE (DRAM1_BASE + DRAM1_SIZE - DRAM1_SEC_SIZE)
#define DRAM1_SEC_END (DRAM1_SEC_BASE + DRAM1_SEC_SIZE - 1)
#define DRAM1_NS_BASE DRAM1_BASE
#define DRAM1_NS_SIZE (DRAM1_SIZE - DRAM1_SEC_SIZE)
#define DRAM1_NS_END (DRAM1_NS_BASE + DRAM1_NS_SIZE - 1)
#define DRAM_BASE DRAM1_BASE
#define DRAM_SIZE DRAM1_SIZE
#define DRAM2_BASE MAKE_ULL(0x880000000)
#define DRAM2_SIZE MAKE_ULL(0x780000000)
#define DRAM2_END (DRAM2_BASE + DRAM2_SIZE - 1)
#define PCIE_EXP_BASE 0x40000000
#define TZRNG_BASE 0x7fe60000
#define TZNVCTR_BASE 0x7fe70000
#define TZROOTKEY_BASE 0x7fe80000
/* Memory mapped Generic timer interfaces */
#define SYS_CNTCTL_BASE 0x2a430000
#define SYS_CNTREAD_BASE 0x2a800000
#define SYS_TIMCTL_BASE 0x2a810000
/* V2M motherboard system registers & offsets */
#define VE_SYSREGS_BASE 0x1c010000
#define V2M_SYS_ID 0x0
#define V2M_SYS_SWITCH 0x4
#define V2M_SYS_LED 0x8
#define V2M_SYS_CFGDATA 0xa0
#define V2M_SYS_CFGCTRL 0xa4
#define V2M_SYS_CFGSTATUS 0xa8
#define CFGCTRL_START (1 << 31)
#define CFGCTRL_RW (1 << 30)
#define CFGCTRL_FUNC_SHIFT 20
#define CFGCTRL_FUNC(fn) (fn << CFGCTRL_FUNC_SHIFT)
#define FUNC_CLK_GEN 0x01
#define FUNC_TEMP 0x04
#define FUNC_DB_RESET 0x05
#define FUNC_SCC_CFG 0x06
#define FUNC_SHUTDOWN 0x08
#define FUNC_REBOOT 0x09
/*
* The number of regions like RO(code), coherent and data required by
* different BL stages which need to be mapped in the MMU.
*/
#if USE_COHERENT_MEM
#define FVP_BL_REGIONS 3
#else
#define FVP_BL_REGIONS 2
#endif
/*
* The FVP_MAX_MMAP_REGIONS depend on the number of entries in fvp_mmap[]
* defined for each BL stage in fvp_common.c.
*/
#if IMAGE_BL1
#define FVP_MMAP_ENTRIES 5
#endif
#if IMAGE_BL2
#define FVP_MMAP_ENTRIES 7
#endif
#if IMAGE_BL31
#define FVP_MMAP_ENTRIES 4
#endif
#if IMAGE_BL32
#define FVP_MMAP_ENTRIES 3
#endif
/* Load address of BL33 in the FVP port */
#define NS_IMAGE_OFFSET (DRAM1_BASE + 0x8000000) /* DRAM + 128MB */
/* Special value used to verify platform parameters from BL2 to BL3-1 */
#define FVP_BL31_PLAT_PARAM_VAL 0x0f1e2d3c4b5a6978ULL
/*
* V2M sysled bit definitions. The values written to this
* register are defined in arch.h & runtime_svc.h. Only
* used by the primary cpu to diagnose any cold boot issues.
*
* SYS_LED[0] - Security state (S=0/NS=1)
* SYS_LED[2:1] - Exception Level (EL3-EL0)
* SYS_LED[7:3] - Exception Class (Sync/Async & origin)
*
*/
#define SYS_LED_SS_SHIFT 0x0
#define SYS_LED_EL_SHIFT 0x1
#define SYS_LED_EC_SHIFT 0x3
#define SYS_LED_SS_MASK 0x1
#define SYS_LED_EL_MASK 0x3
#define SYS_LED_EC_MASK 0x1f
/* V2M sysid register bits */
#define SYS_ID_REV_SHIFT 28
#define SYS_ID_HBI_SHIFT 16
#define SYS_ID_BLD_SHIFT 12
#define SYS_ID_ARCH_SHIFT 8
#define SYS_ID_FPGA_SHIFT 0
#define SYS_ID_REV_MASK 0xf
#define SYS_ID_HBI_MASK 0xfff
#define SYS_ID_BLD_MASK 0xf
#define SYS_ID_ARCH_MASK 0xf
#define SYS_ID_FPGA_MASK 0xff
#define SYS_ID_BLD_LENGTH 4
#define HBI_FVP_BASE 0x020
#define REV_FVP_BASE_V0 0x0
#define HBI_FOUNDATION 0x010
#define REV_FOUNDATION_V2_0 0x0
#define REV_FOUNDATION_V2_1 0x1
#define BLD_GIC_VE_MMAP 0x0
#define BLD_GIC_A53A57_MMAP 0x1
#define ARCH_MODEL 0x1
/* FVP Power controller base address*/
#define PWRC_BASE 0x1c100000
/*******************************************************************************
* CCI-400 related constants
******************************************************************************/
#define CCI400_BASE 0x2c090000
#define CCI400_CLUSTER0_SL_IFACE_IX 3
#define CCI400_CLUSTER1_SL_IFACE_IX 4
/*******************************************************************************
* GIC-400 & interrupt handling related constants
******************************************************************************/
/* VE compatible GIC memory map */
#define VE_GICD_BASE 0x2c001000
#define VE_GICC_BASE 0x2c002000
#define VE_GICH_BASE 0x2c004000
#define VE_GICV_BASE 0x2c006000
/* Base FVP compatible GIC memory map */
#define BASE_GICD_BASE 0x2f000000
#define BASE_GICR_BASE 0x2f100000
#define BASE_GICC_BASE 0x2c000000
#define BASE_GICH_BASE 0x2c010000
#define BASE_GICV_BASE 0x2c02f000
#define IRQ_TZ_WDOG 56
#define IRQ_SEC_PHY_TIMER 29
#define IRQ_SEC_SGI_0 8
#define IRQ_SEC_SGI_1 9
#define IRQ_SEC_SGI_2 10
#define IRQ_SEC_SGI_3 11
#define IRQ_SEC_SGI_4 12
#define IRQ_SEC_SGI_5 13
#define IRQ_SEC_SGI_6 14
#define IRQ_SEC_SGI_7 15
/*******************************************************************************
* PL011 related constants
******************************************************************************/
#define PL011_UART0_BASE 0x1c090000
#define PL011_UART1_BASE 0x1c0a0000
#define PL011_UART2_BASE 0x1c0b0000
#define PL011_UART3_BASE 0x1c0c0000
#define PL011_BAUDRATE 115200
#define PL011_UART0_CLK_IN_HZ 24000000
#define PL011_UART1_CLK_IN_HZ 24000000
#define PL011_UART2_CLK_IN_HZ 24000000
#define PL011_UART3_CLK_IN_HZ 24000000
/*******************************************************************************
* TrustZone address space controller related constants
******************************************************************************/
#define TZC400_BASE 0x2a4a0000
/*
* The NSAIDs for this platform as used to program the TZC400.
*/
/* NSAIDs used by devices in TZC filter 0 on FVP */
#define FVP_NSAID_DEFAULT 0
#define FVP_NSAID_PCI 1
#define FVP_NSAID_VIRTIO 8 /* from FVP v5.6 onwards */
#define FVP_NSAID_AP 9 /* Application Processors */
#define FVP_NSAID_VIRTIO_OLD 15 /* until FVP v5.5 */
/* NSAIDs used by devices in TZC filter 2 on FVP */
#define FVP_NSAID_HDLCD0 2
#define FVP_NSAID_CLCD 7
/*******************************************************************************
* Shared Data
******************************************************************************/
/* Entrypoint mailboxes */
#define MBOX_BASE FVP_SHARED_MEM_BASE
#define MBOX_SIZE 0x200
/* Base address where parameters to BL31 are stored */
#define PARAMS_BASE (MBOX_BASE + MBOX_SIZE)
#endif /* __FVP_DEF_H__ */
/*
* Copyright (c) 2014, 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 <io_driver.h>
#include <io_fip.h>
#include <io_memmap.h>
#include <io_storage.h>
#include <io_semihosting.h>
#include <platform_def.h>
#include <semihosting.h> /* For FOPEN_MODE_... */
#include <string.h>
/* IO devices */
static const io_dev_connector_t *sh_dev_con;
static uintptr_t sh_dev_spec;
static uintptr_t sh_init_params;
static uintptr_t sh_dev_handle;
static const io_dev_connector_t *fip_dev_con;
static uintptr_t fip_dev_spec;
static uintptr_t fip_dev_handle;
static const io_dev_connector_t *memmap_dev_con;
static uintptr_t memmap_dev_spec;
static uintptr_t memmap_init_params;
static uintptr_t memmap_dev_handle;
static const io_block_spec_t fip_block_spec = {
.offset = FLASH0_BASE,
.length = FLASH0_SIZE
};
static const io_file_spec_t bl2_file_spec = {
.path = BL2_IMAGE_NAME,
.mode = FOPEN_MODE_RB
};
static const io_file_spec_t bl31_file_spec = {
.path = BL31_IMAGE_NAME,
.mode = FOPEN_MODE_RB
};
static const io_file_spec_t bl32_file_spec = {
.path = BL32_IMAGE_NAME,
.mode = FOPEN_MODE_RB
};
static const io_file_spec_t bl33_file_spec = {
.path = BL33_IMAGE_NAME,
.mode = FOPEN_MODE_RB
};
#if TRUSTED_BOARD_BOOT
static const io_file_spec_t bl2_cert_file_spec = {
.path = BL2_CERT_NAME,
.mode = FOPEN_MODE_RB
};
static const io_file_spec_t trusted_key_cert_file_spec = {
.path = TRUSTED_KEY_CERT_NAME,
.mode = FOPEN_MODE_RB
};
static const io_file_spec_t bl30_key_cert_file_spec = {
.path = BL30_KEY_CERT_NAME,
.mode = FOPEN_MODE_RB
};
static const io_file_spec_t bl31_key_cert_file_spec = {
.path = BL31_KEY_CERT_NAME,
.mode = FOPEN_MODE_RB
};
static const io_file_spec_t bl32_key_cert_file_spec = {
.path = BL32_KEY_CERT_NAME,
.mode = FOPEN_MODE_RB
};
static const io_file_spec_t bl33_key_cert_file_spec = {
.path = BL33_KEY_CERT_NAME,
.mode = FOPEN_MODE_RB
};
static const io_file_spec_t bl30_cert_file_spec = {
.path = BL30_CERT_NAME,
.mode = FOPEN_MODE_RB
};
static const io_file_spec_t bl31_cert_file_spec = {
.path = BL31_CERT_NAME,
.mode = FOPEN_MODE_RB
};
static const io_file_spec_t bl32_cert_file_spec = {
.path = BL32_CERT_NAME,
.mode = FOPEN_MODE_RB
};
static const io_file_spec_t bl33_cert_file_spec = {
.path = BL33_CERT_NAME,
.mode = FOPEN_MODE_RB
};
#endif /* TRUSTED_BOARD_BOOT */
static int open_fip(const uintptr_t spec);
static int open_memmap(const uintptr_t spec);
struct plat_io_policy {
char *image_name;
uintptr_t *dev_handle;
uintptr_t image_spec;
int (*check)(const uintptr_t spec);
};
static const struct plat_io_policy policies[] = {
{
FIP_IMAGE_NAME,
&memmap_dev_handle,
(uintptr_t)&fip_block_spec,
open_memmap
}, {
BL2_IMAGE_NAME,
&fip_dev_handle,
(uintptr_t)&bl2_file_spec,
open_fip
}, {
BL31_IMAGE_NAME,
&fip_dev_handle,
(uintptr_t)&bl31_file_spec,
open_fip
}, {
BL32_IMAGE_NAME,
&fip_dev_handle,
(uintptr_t)&bl32_file_spec,
open_fip
}, {
BL33_IMAGE_NAME,
&fip_dev_handle,
(uintptr_t)&bl33_file_spec,
open_fip
}, {
#if TRUSTED_BOARD_BOOT
BL2_CERT_NAME,
&fip_dev_handle,
(uintptr_t)&bl2_cert_file_spec,
open_fip
}, {
TRUSTED_KEY_CERT_NAME,
&fip_dev_handle,
(uintptr_t)&trusted_key_cert_file_spec,
open_fip
}, {
BL30_KEY_CERT_NAME,
&fip_dev_handle,
(uintptr_t)&bl30_key_cert_file_spec,
open_fip
}, {
BL31_KEY_CERT_NAME,
&fip_dev_handle,
(uintptr_t)&bl31_key_cert_file_spec,
open_fip
}, {
BL32_KEY_CERT_NAME,
&fip_dev_handle,
(uintptr_t)&bl32_key_cert_file_spec,
open_fip
}, {
BL33_KEY_CERT_NAME,
&fip_dev_handle,
(uintptr_t)&bl33_key_cert_file_spec,
open_fip
}, {
BL30_CERT_NAME,
&fip_dev_handle,
(uintptr_t)&bl30_cert_file_spec,
open_fip
}, {
BL31_CERT_NAME,
&fip_dev_handle,
(uintptr_t)&bl31_cert_file_spec,
open_fip
}, {
BL32_CERT_NAME,
&fip_dev_handle,
(uintptr_t)&bl32_cert_file_spec,
open_fip
}, {
BL33_CERT_NAME,
&fip_dev_handle,
(uintptr_t)&bl33_cert_file_spec,
open_fip
}, {
#endif /* TRUSTED_BOARD_BOOT */
0, 0, 0
}
};
static int open_fip(const uintptr_t spec)
{
int result = IO_FAIL;
/* See if a Firmware Image Package is available */
result = io_dev_init(fip_dev_handle, (uintptr_t)FIP_IMAGE_NAME);
if (result == IO_SUCCESS) {
VERBOSE("Using FIP\n");
/*TODO: Check image defined in spec is present in FIP. */
}
return result;
}
static int open_memmap(const uintptr_t spec)
{
int result = IO_FAIL;
uintptr_t local_image_handle;
result = io_dev_init(memmap_dev_handle, memmap_init_params);
if (result == IO_SUCCESS) {
result = io_open(memmap_dev_handle, spec, &local_image_handle);
if (result == IO_SUCCESS) {
VERBOSE("Using Memmap IO\n");
io_close(local_image_handle);
}
}
return result;
}
static int open_semihosting(const uintptr_t spec)
{
int result = IO_FAIL;
uintptr_t local_image_handle;
/* See if the file exists on semi-hosting.*/
result = io_dev_init(sh_dev_handle, sh_init_params);
if (result == IO_SUCCESS) {
result = io_open(sh_dev_handle, spec, &local_image_handle);
if (result == IO_SUCCESS) {
VERBOSE("Using Semi-hosting IO\n");
io_close(local_image_handle);
}
}
return result;
}
void fvp_io_setup (void)
{
int io_result = IO_FAIL;
/* Register the IO devices on this platform */
io_result = register_io_dev_sh(&sh_dev_con);
assert(io_result == IO_SUCCESS);
io_result = register_io_dev_fip(&fip_dev_con);
assert(io_result == IO_SUCCESS);
io_result = register_io_dev_memmap(&memmap_dev_con);
assert(io_result == IO_SUCCESS);
/* Open connections to devices and cache the handles */
io_result = io_dev_open(sh_dev_con, sh_dev_spec, &sh_dev_handle);
assert(io_result == IO_SUCCESS);
io_result = io_dev_open(fip_dev_con, fip_dev_spec, &fip_dev_handle);
assert(io_result == IO_SUCCESS);
io_result = io_dev_open(memmap_dev_con, memmap_dev_spec,
&memmap_dev_handle);
assert(io_result == IO_SUCCESS);
/* Ignore improbable errors in release builds */
(void)io_result;
}
/* Return an IO device handle and specification which can be used to access
* an image. Use this to enforce platform load policy */
int plat_get_image_source(const char *image_name, uintptr_t *dev_handle,
uintptr_t *image_spec)
{
int result = IO_FAIL;
const struct plat_io_policy *policy;
if ((image_name != NULL) && (dev_handle != NULL) &&
(image_spec != NULL)) {
policy = policies;
while (policy->image_name != NULL) {
if (strcmp(policy->image_name, image_name) == 0) {
result = policy->check(policy->image_spec);
if (result == IO_SUCCESS) {
*image_spec = policy->image_spec;
*dev_handle = *(policy->dev_handle);
break;
} else {
result = open_semihosting(
policy->image_spec);
if (result == IO_SUCCESS) {
*dev_handle = sh_dev_handle;
*image_spec =
policy->image_spec;
}
}
}
policy++;
}
} else {
result = IO_FAIL;
}
return result;
}
/*
* Copyright (c) 2014, 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 <plat_config.h>
#include <tzc400.h>
#include "fvp_def.h"
#include "fvp_private.h"
/* Used to improve readability for configuring regions. */
#define FILTER_SHIFT(filter) (1 << filter)
/*
* For the moment we assume that all security programming is done by the
* primary core.
* TODO:
* Might want to enable interrupt on violations when supported?
*/
void fvp_security_setup(void)
{
/*
* The Base FVP has a TrustZone address space controller, the Foundation
* FVP does not. Trying to program the device on the foundation FVP will
* cause an abort.
*
* If the platform had additional peripheral specific security
* configurations, those would be configured here.
*/
if (!(get_plat_config()->flags & CONFIG_HAS_TZC))
return;
/*
* The TrustZone controller controls access to main DRAM. Give
* full NS access for the moment to use with OS.
*/
INFO("Configuring TrustZone Controller\n");
/*
* The driver does some error checking and will assert.
* - Provide base address of device on platform.
* - Provide width of ACE-Lite IDs on platform.
*/
tzc_init(TZC400_BASE);
/*
* Currently only filters 0 and 2 are connected on Base FVP.
* Filter 0 : CPU clusters (no access to DRAM by default)
* Filter 1 : not connected
* Filter 2 : LCDs (access to VRAM allowed by default)
* Filter 3 : not connected
* Programming unconnected filters will have no effect at the
* moment. These filter could, however, be connected in future.
* So care should be taken not to configure the unused filters.
*/
/* Disable all filters before programming. */
tzc_disable_filters();
/*
* Allow only non-secure access to all DRAM to supported devices.
* Give access to the CPUs and Virtio. Some devices
* would normally use the default ID so allow that too. We use
* two regions to cover the blocks of physical memory in the FVPs
* plus one region to reserve some memory as secure.
*
* Software executing in the secure state, such as a secure
* boot-loader, can access the DRAM by using the NS attributes in
* the MMU translation tables and descriptors.
*/
/* Region 1 set to cover the Non-Secure DRAM */
tzc_configure_region(FILTER_SHIFT(0), 1,
DRAM1_NS_BASE, DRAM1_NS_END,
TZC_REGION_S_NONE,
TZC_REGION_ACCESS_RDWR(FVP_NSAID_DEFAULT) |
TZC_REGION_ACCESS_RDWR(FVP_NSAID_PCI) |
TZC_REGION_ACCESS_RDWR(FVP_NSAID_AP) |
TZC_REGION_ACCESS_RDWR(FVP_NSAID_VIRTIO) |
TZC_REGION_ACCESS_RDWR(FVP_NSAID_VIRTIO_OLD));
/* Region 2 set to cover the Secure DRAM */
tzc_configure_region(FILTER_SHIFT(0), 2,
DRAM1_SEC_BASE, DRAM1_SEC_END,
TZC_REGION_S_RDWR,
0x0);
/* Region 3 set to cover the second block of DRAM */
tzc_configure_region(FILTER_SHIFT(0), 3,
DRAM2_BASE, DRAM2_END, TZC_REGION_S_NONE,
TZC_REGION_ACCESS_RDWR(FVP_NSAID_DEFAULT) |
TZC_REGION_ACCESS_RDWR(FVP_NSAID_PCI) |
TZC_REGION_ACCESS_RDWR(FVP_NSAID_AP) |
TZC_REGION_ACCESS_RDWR(FVP_NSAID_VIRTIO) |
TZC_REGION_ACCESS_RDWR(FVP_NSAID_VIRTIO_OLD));
/*
* TODO: Interrupts are not currently supported. The only
* options we have are for access errors to occur quietly or to
* cause an exception. We choose to cause an exception.
*/
tzc_set_action(TZC_ACTION_ERR);
/* Enable filters. */
tzc_enable_filters();
}
/*
* Copyright (c) 2014, 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 <cci.h>
#include <gic_v2.h>
#include <plat_config.h>
#include "../fvp_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 BL3-1.
* Clobbers: x0 - x10, x16, x17, sp
* ---------------------------------------------
*/
.macro plat_print_gic_regs
mov_imm x0, (VE_SYSREGS_BASE + V2M_SYS_ID)
ldr w16, [x0]
/* Extract BLD (12th - 15th bits) from the SYS_ID */
ubfx x16, x16, #SYS_ID_BLD_SHIFT, #4
/* Check if VE mmap */
cmp w16, #BLD_GIC_VE_MMAP
b.eq use_ve_mmap
/* Check if Cortex-A53/A57 mmap */
cmp w16, #BLD_GIC_A53A57_MMAP
b.ne exit_print_gic_regs
mov_imm x17, BASE_GICC_BASE
mov_imm x16, BASE_GICD_BASE
b print_gicc_regs
use_ve_mmap:
mov_imm x17, VE_GICC_BASE
mov_imm x16, VE_GICD_BASE
print_gicc_regs:
/* gicc base address is now in x17 */
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, [x17, #GICC_HPPIR]
ldr w9, [x17, #GICC_AHPPIR]
ldr w10, [x17, #GICC_CTLR]
/* Store to the crash buf and print to console */
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
gicd_ispendr_loop:
sub x4, x7, x16
cmp x4, #0x280
b.eq exit_print_gic_regs
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 gicd_ispendr_loop
exit_print_gic_regs:
.endm
.section .rodata.cci_reg_name, "aS"
cci_iface_regs:
.asciz "cci_snoop_ctrl_cluster0", "cci_snoop_ctrl_cluster1" , ""
/* ------------------------------------------------
* The below macro prints out relevant interconnect
* registers whenever an unhandled exception is
* taken in BL3-1.
* Clobbers: x0 - x9, sp
* ------------------------------------------------
*/
.macro plat_print_interconnect_regs
adr x6, cci_iface_regs
/* Store in x7 the base address of the first interface */
mov_imm x7, (CCI400_BASE + SLAVE_IFACE3_OFFSET)
ldr w8, [x7, #SNOOP_CTRL_REG]
/* Store in x7 the base address of the second interface */
mov_imm x7, (CCI400_BASE + SLAVE_IFACE4_OFFSET)
ldr w9, [x7, #SNOOP_CTRL_REG]
/* Store to the crash buf and print to console */
bl str_in_crash_buf_print
.endm
/*
* Copyright (c) 2013-2014, 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 <arm_gic.h>
#include <assert.h>
#include <bl_common.h>
#include <cci.h>
#include <debug.h>
#include <mmio.h>
#include <platform.h>
#include <platform_def.h>
#include <xlat_tables.h>
#include "../juno_def.h"
#define MAP_MHU_SECURE MAP_REGION_FLAT(MHU_SECURE_BASE, \
MHU_SECURE_SIZE, \
(MHU_PAYLOAD_CACHED ? \
MT_MEMORY : MT_DEVICE) \
| MT_RW | MT_SECURE)
#define MAP_FLASH MAP_REGION_FLAT(FLASH_BASE, \
FLASH_SIZE, \
MT_MEMORY | MT_RO | MT_SECURE)
#define MAP_IOFPGA MAP_REGION_FLAT(IOFPGA_BASE, \
IOFPGA_SIZE, \
MT_DEVICE | MT_RW | MT_SECURE)
#define MAP_DEVICE0 MAP_REGION_FLAT(DEVICE0_BASE, \
DEVICE0_SIZE, \
MT_DEVICE | MT_RW | MT_SECURE)
#define MAP_DEVICE1 MAP_REGION_FLAT(DEVICE1_BASE, \
DEVICE1_SIZE, \
MT_DEVICE | MT_RW | MT_SECURE)
#define MAP_NS_DRAM MAP_REGION_FLAT(DRAM_NS_BASE, \
DRAM_NS_SIZE, \
MT_MEMORY | MT_RW | MT_NS)
#define MAP_TSP_MEM MAP_REGION_FLAT(TSP_SEC_MEM_BASE, \
TSP_SEC_MEM_SIZE, \
MT_MEMORY | MT_RW | MT_SECURE)
/*
* Table of regions for different BL stages to map using the MMU.
* This doesn't include Trusted RAM as the 'mem_layout' argument passed to
* configure_mmu_elx() will give the available subset of that,
*/
#if IMAGE_BL1
static const mmap_region_t juno_mmap[] = {
MAP_MHU_SECURE,
MAP_FLASH,
MAP_IOFPGA,
MAP_DEVICE0,
MAP_DEVICE1,
{0}
};
#endif
#if IMAGE_BL2
static const mmap_region_t juno_mmap[] = {
MAP_MHU_SECURE,
MAP_FLASH,
MAP_IOFPGA,
MAP_DEVICE0,
MAP_DEVICE1,
MAP_NS_DRAM,
MAP_TSP_MEM,
{0}
};
#endif
#if IMAGE_BL31
static const mmap_region_t juno_mmap[] = {
MAP_MHU_SECURE,
MAP_IOFPGA,
MAP_DEVICE0,
MAP_DEVICE1,
{0}
};
#endif
#if IMAGE_BL32
static const mmap_region_t juno_mmap[] = {
MAP_IOFPGA,
MAP_DEVICE0,
MAP_DEVICE1,
{0}
};
#endif
CASSERT(ARRAY_SIZE(juno_mmap) + JUNO_BL_REGIONS \
<= MAX_MMAP_REGIONS, assert_max_mmap_regions);
/* Array of secure interrupts to be configured by the gic driver */
const unsigned int irq_sec_array[] = {
IRQ_MHU,
IRQ_GPU_SMMU_0,
IRQ_GPU_SMMU_1,
IRQ_ETR_SMMU,
IRQ_TZC400,
IRQ_TZ_WDOG,
IRQ_SEC_PHY_TIMER,
IRQ_SEC_SGI_0,
IRQ_SEC_SGI_1,
IRQ_SEC_SGI_2,
IRQ_SEC_SGI_3,
IRQ_SEC_SGI_4,
IRQ_SEC_SGI_5,
IRQ_SEC_SGI_6,
IRQ_SEC_SGI_7
};
static const int cci_map[] = {
CCI400_CLUSTER0_SL_IFACE_IX,
CCI400_CLUSTER1_SL_IFACE_IX
};
void plat_cci_init(void)
{
cci_init(CCI400_BASE,
cci_map,
ARRAY_SIZE(cci_map));
}
/*******************************************************************************
* Macro generating the code for the function setting up the pagetables as per
* the platform memory map & initialize the mmu, for the given exception level
******************************************************************************/
#if USE_COHERENT_MEM
#define DEFINE_CONFIGURE_MMU_EL(_el) \
void configure_mmu_el##_el(unsigned long total_base, \
unsigned long total_size, \
unsigned long ro_start, \
unsigned long ro_limit, \
unsigned long coh_start, \
unsigned long coh_limit) \
{ \
mmap_add_region(total_base, total_base, \
total_size, \
MT_MEMORY | MT_RW | MT_SECURE); \
mmap_add_region(ro_start, ro_start, \
ro_limit - ro_start, \
MT_MEMORY | MT_RO | MT_SECURE); \
mmap_add_region(coh_start, coh_start, \
coh_limit - coh_start, \
MT_DEVICE | MT_RW | MT_SECURE); \
mmap_add(juno_mmap); \
init_xlat_tables(); \
\
enable_mmu_el##_el(0); \
}
#else
#define DEFINE_CONFIGURE_MMU_EL(_el) \
void configure_mmu_el##_el(unsigned long total_base, \
unsigned long total_size, \
unsigned long ro_start, \
unsigned long ro_limit) \
{ \
mmap_add_region(total_base, total_base, \
total_size, \
MT_MEMORY | MT_RW | MT_SECURE); \
mmap_add_region(ro_start, ro_start, \
ro_limit - ro_start, \
MT_MEMORY | MT_RO | MT_SECURE); \
mmap_add(juno_mmap); \
init_xlat_tables(); \
\
enable_mmu_el##_el(0); \
}
#endif
/* Define EL1 and EL3 variants of the function initialising the MMU */
DEFINE_CONFIGURE_MMU_EL(1)
DEFINE_CONFIGURE_MMU_EL(3)
unsigned long plat_get_ns_image_entrypoint(void)
{
return NS_IMAGE_OFFSET;
}
uint64_t plat_get_syscnt_freq(void)
{
uint64_t counter_base_frequency;
/* Read the frequency from Frequency modes table */
counter_base_frequency = mmio_read_32(SYS_CNTCTL_BASE + CNTFID_OFF);
/* The first entry of the frequency modes table must not be 0 */
if (counter_base_frequency == 0)
panic();
return counter_base_frequency;
}
void plat_gic_init(void)
{
arm_gic_init(GICC_BASE,
GICD_BASE,
0,
irq_sec_array,
ARRAY_SIZE(irq_sec_array));
}
/*
* Copyright (c) 2013-2014, 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 <cci.h>
#include <console.h>
#include <debug.h>
#include <mmio.h>
#include <platform.h>
#include <platform_def.h>
#include "../../bl1/bl1_private.h"
#include "juno_def.h"
#include "juno_private.h"
#if USE_COHERENT_MEM
/*******************************************************************************
* Declarations of linker defined symbols which will help us find the layout
* of trusted RAM
******************************************************************************/
extern unsigned long __COHERENT_RAM_START__;
extern unsigned long __COHERENT_RAM_END__;
/*
* 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 BL1_COHERENT_RAM_BASE (unsigned long)(&__COHERENT_RAM_START__)
#define BL1_COHERENT_RAM_LIMIT (unsigned long)(&__COHERENT_RAM_END__)
#endif
/* Data structure which holds the extents of the trusted RAM for BL1 */
static meminfo_t bl1_tzram_layout;
meminfo_t *bl1_plat_sec_mem_layout(void)
{
return &bl1_tzram_layout;
}
/*******************************************************************************
* Perform any BL1 specific platform actions.
******************************************************************************/
void bl1_early_platform_setup(void)
{
const size_t bl1_size = BL1_RAM_LIMIT - BL1_RAM_BASE;
/* Initialize the console to provide early debug support */
console_init(PL011_UART2_BASE, PL011_UART2_CLK_IN_HZ, PL011_BAUDRATE);
/*
* Enable CCI-400 for this cluster. No need for locks as no other cpu is
* active at the moment
*/
plat_cci_init();
cci_enable_snoop_dvm_reqs(MPIDR_AFFLVL1_VAL(read_mpidr()));
/* Allow BL1 to see the whole Trusted RAM */
bl1_tzram_layout.total_base = TZRAM_BASE;
bl1_tzram_layout.total_size = TZRAM_SIZE;
/* Calculate how much RAM BL1 is using and how much remains free */
bl1_tzram_layout.free_base = TZRAM_BASE;
bl1_tzram_layout.free_size = TZRAM_SIZE;
reserve_mem(&bl1_tzram_layout.free_base,
&bl1_tzram_layout.free_size,
BL1_RAM_BASE,
bl1_size);
INFO("BL1: 0x%lx - 0x%lx [size = %lu]\n", BL1_RAM_BASE, BL1_RAM_LIMIT,
bl1_size);
}
/*
* Address of slave 'n' security setting in the NIC-400 address region
* control
* TODO: Ideally this macro should be moved in a "nic-400.h" header file but
* it would be the only thing in there so it's not worth it at the moment.
*/
#define NIC400_ADDR_CTRL_SECURITY_REG(n) (0x8 + (n) * 4)
static void init_nic400(void)
{
/*
* NIC-400 Access Control Initialization
*
* Define access privileges by setting each corresponding bit to:
* 0 = Secure access only
* 1 = Non-secure access allowed
*/
/*
* Allow non-secure access to some SOC regions, excluding UART1, which
* remains secure.
* Note: This is the NIC-400 device on the SOC
*/
mmio_write_32(SOC_NIC400_BASE +
NIC400_ADDR_CTRL_SECURITY_REG(SOC_NIC400_USB_EHCI), ~0);
mmio_write_32(SOC_NIC400_BASE +
NIC400_ADDR_CTRL_SECURITY_REG(SOC_NIC400_TLX_MASTER), ~0);
mmio_write_32(SOC_NIC400_BASE +
NIC400_ADDR_CTRL_SECURITY_REG(SOC_NIC400_USB_OHCI), ~0);
mmio_write_32(SOC_NIC400_BASE +
NIC400_ADDR_CTRL_SECURITY_REG(SOC_NIC400_PL354_SMC), ~0);
mmio_write_32(SOC_NIC400_BASE +
NIC400_ADDR_CTRL_SECURITY_REG(SOC_NIC400_APB4_BRIDGE), ~0);
mmio_write_32(SOC_NIC400_BASE +
NIC400_ADDR_CTRL_SECURITY_REG(SOC_NIC400_BOOTSEC_BRIDGE),
~SOC_NIC400_BOOTSEC_BRIDGE_UART1);
/*
* Allow non-secure access to some CSS regions.
* Note: This is the NIC-400 device on the CSS
*/
mmio_write_32(CSS_NIC400_BASE +
NIC400_ADDR_CTRL_SECURITY_REG(CSS_NIC400_SLAVE_BOOTSECURE),
~0);
}
#define PCIE_SECURE_REG 0x3000
#define PCIE_SEC_ACCESS_MASK ((1 << 0) | (1 << 1)) /* REG and MEM access bits */
static void init_pcie(void)
{
/*
* PCIE Root Complex Security settings to enable non-secure
* access to config registers.
*/
mmio_write_32(PCIE_CONTROL_BASE + PCIE_SECURE_REG, PCIE_SEC_ACCESS_MASK);
}
/*******************************************************************************
* Function which will perform any remaining platform-specific setup that can
* occur after the MMU and data cache have been enabled.
******************************************************************************/
void bl1_platform_setup(void)
{
init_nic400();
init_pcie();
/* Initialise the IO layer and register platform IO devices */
io_setup();
/* Enable and initialize the System level generic timer */
mmio_write_32(SYS_CNTCTL_BASE + CNTCR_OFF, CNTCR_FCREQ(0) | CNTCR_EN);
}
/*******************************************************************************
* Perform the very early platform specific architecture setup here. At the
* moment this only does basic initialization. Later architectural setup
* (bl1_arch_setup()) does not do anything platform specific.
******************************************************************************/
void bl1_plat_arch_setup(void)
{
configure_mmu_el3(bl1_tzram_layout.total_base,
bl1_tzram_layout.total_size,
TZROM_BASE,
TZROM_BASE + TZROM_SIZE
#if USE_COHERENT_MEM
, BL1_COHERENT_RAM_BASE,
BL1_COHERENT_RAM_LIMIT
#endif
);
}
/*******************************************************************************
* Before calling this function BL2 is loaded in memory and its entrypoint
* is set by load_image. This is a placeholder for the platform to change
* the entrypoint of BL2 and set SPSR and security state.
* On Juno we are only setting the security state, entrypoint
******************************************************************************/
void bl1_plat_set_bl2_ep_info(image_info_t *bl2_image,
entry_point_info_t *bl2_ep)
{
SET_SECURITY_STATE(bl2_ep->h.attr, SECURE);
bl2_ep->spsr = SPSR_64(MODE_EL1, MODE_SP_ELX, DISABLE_ALL_EXCEPTIONS);
}
/*
* Copyright (c) 2013-2014, 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 <arm_gic.h>
#include <assert.h>
#include <bl31.h>
#include <bl_common.h>
#include <cci.h>
#include <console.h>
#include <mmio.h>
#include <platform.h>
#include <stddef.h>
#include "juno_def.h"
#include "juno_private.h"
#include "mhu.h"
/*******************************************************************************
* Declarations of linker defined symbols which will help us find the layout
* of trusted RAM
******************************************************************************/
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
/*
* 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
/******************************************************************************
* Placeholder variables for copying the arguments that have been passed to
* BL3-1 from BL2.
******************************************************************************/
static entry_point_info_t bl32_ep_info;
static entry_point_info_t bl33_ep_info;
/*******************************************************************************
* Return a pointer to the 'entry_point_info' structure of the next image for
* the security state specified. BL3-3 corresponds to the non-secure image type
* while BL3-2 corresponds to the secure image type. A NULL pointer is returned
* if the image does not exist.
******************************************************************************/
entry_point_info_t *bl31_plat_get_next_image_ep_info(uint32_t type)
{
entry_point_info_t *next_image_info;
next_image_info = (type == NON_SECURE) ? &bl33_ep_info : &bl32_ep_info;
/* None of the images on this platform can have 0x0 as the entrypoint */
if (next_image_info->pc)
return next_image_info;
else
return NULL;
}
/*******************************************************************************
* Perform any BL3-1 specific platform actions. Here is an opportunity to copy
* parameters passed by the calling EL (S-EL1 in BL2 & S-EL3 in BL1) before they
* are lost (potentially). This needs to be done before the MMU is initialized
* so that the memory layout can be used while creating page tables. Also, BL2
* has flushed this information to memory, so we are guaranteed to pick up good
* data
******************************************************************************/
void bl31_early_platform_setup(bl31_params_t *from_bl2,
void *plat_params_from_bl2)
{
/* Initialize the console to provide early debug support */
console_init(PL011_UART2_BASE, PL011_UART2_CLK_IN_HZ, PL011_BAUDRATE);
/*
* Initialise the CCI-400 driver for BL31 so that it is accessible after
* a warm boot. BL1 should have already enabled CCI coherency for this
* cluster during cold boot.
*/
plat_cci_init();
/*
* Check params passed from BL2 should not be NULL,
*/
assert(from_bl2 != NULL);
assert(from_bl2->h.type == PARAM_BL31);
assert(from_bl2->h.version >= VERSION_1);
/*
* In debug builds, we pass a special value in 'plat_params_from_bl2'
* to verify platform parameters from BL2 to BL3-1.
* In release builds, it's not used.
*/
assert(((unsigned long long)plat_params_from_bl2) ==
JUNO_BL31_PLAT_PARAM_VAL);
/*
* Copy BL3-2 and BL3-3 entry point information.
* They are stored in Secure RAM, in BL2's address space.
*/
bl32_ep_info = *from_bl2->bl32_ep_info;
bl33_ep_info = *from_bl2->bl33_ep_info;
}
/*******************************************************************************
* Initialize the MHU and the GIC.
******************************************************************************/
void bl31_platform_setup(void)
{
unsigned int reg_val;
mhu_secure_init();
/* Initialize the gic cpu and distributor interfaces */
plat_gic_init();
arm_gic_setup();
/* Enable and initialize the System level generic timer */
mmio_write_32(SYS_CNTCTL_BASE + CNTCR_OFF, CNTCR_FCREQ(0) | CNTCR_EN);
/* Allow access to the System counter timer module */
reg_val = (1 << CNTACR_RPCT_SHIFT) | (1 << CNTACR_RVCT_SHIFT);
reg_val |= (1 << CNTACR_RFRQ_SHIFT) | (1 << CNTACR_RVOFF_SHIFT);
reg_val |= (1 << CNTACR_RWVT_SHIFT) | (1 << CNTACR_RWPT_SHIFT);
mmio_write_32(SYS_TIMCTL_BASE + CNTACR_BASE(1), reg_val);
reg_val = (1 << CNTNSAR_NS_SHIFT(1));
mmio_write_32(SYS_TIMCTL_BASE + CNTNSAR, reg_val);
/* Topologies are best known to the platform. */
plat_setup_topology();
}
/*******************************************************************************
* Perform the very early platform specific architectural setup here. At the
* moment this is only intializes the mmu in a quick and dirty way.
******************************************************************************/
void bl31_plat_arch_setup(void)
{
configure_mmu_el3(BL31_RO_BASE,
(BL31_END - BL31_RO_BASE),
BL31_RO_BASE,
BL31_RO_LIMIT
#if USE_COHERENT_MEM
,
BL31_COHERENT_RAM_BASE,
BL31_COHERENT_RAM_LIMIT
#endif
);
}
/*
* Copyright (c) 2014, 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 "../juno_def.h"
/*******************************************************************************
* Platform binary types for linking
******************************************************************************/
#define PLATFORM_LINKER_FORMAT "elf64-littleaarch64"
#define PLATFORM_LINKER_ARCH aarch64
/*******************************************************************************
* Generic platform constants
******************************************************************************/
/* Size of cacheable stacks */
#if TRUSTED_BOARD_BOOT && (IMAGE_BL1 || IMAGE_BL2)
#define PLATFORM_STACK_SIZE 0x1000
#else
#define PLATFORM_STACK_SIZE 0x800
#endif
#define FIRMWARE_WELCOME_STR "Booting Trusted Firmware\n"
/* Trusted Boot Firmware BL2 */
#define BL2_IMAGE_NAME "bl2.bin"
/* EL3 Runtime Firmware BL3-1 */
#define BL31_IMAGE_NAME "bl31.bin"
/* SCP Firmware BL3-0 */
#define BL30_IMAGE_NAME "bl30.bin"
/* Secure Payload BL3-2 (Trusted OS) */
#define BL32_IMAGE_NAME "bl32.bin"
/* Non-Trusted Firmware BL3-3 */
#define BL33_IMAGE_NAME "bl33.bin" /* e.g. UEFI */
/* Firmware Image Package */
#define FIP_IMAGE_NAME "fip.bin"
#if TRUSTED_BOARD_BOOT
/* Certificates */
# define BL2_CERT_NAME "bl2.crt"
# define TRUSTED_KEY_CERT_NAME "trusted_key.crt"
# define BL30_KEY_CERT_NAME "bl30_key.crt"
# define BL31_KEY_CERT_NAME "bl31_key.crt"
# define BL32_KEY_CERT_NAME "bl32_key.crt"
# define BL33_KEY_CERT_NAME "bl33_key.crt"
# define BL30_CERT_NAME "bl30.crt"
# define BL31_CERT_NAME "bl31.crt"
# define BL32_CERT_NAME "bl32.crt"
# define BL33_CERT_NAME "bl33.crt"
#endif /* TRUSTED_BOARD_BOOT */
#define PLATFORM_CACHE_LINE_SIZE 64
#define PLATFORM_CLUSTER_COUNT 2
#define PLATFORM_CORE_COUNT 6
#define PLATFORM_NUM_AFFS (PLATFORM_CLUSTER_COUNT + \
PLATFORM_CORE_COUNT)
#define PLATFORM_MAX_AFFLVL MPIDR_AFFLVL1
#define MAX_IO_DEVICES 3
#define MAX_IO_HANDLES 4
/*******************************************************************************
* BL1 specific defines.
* BL1 RW data is relocated from ROM to RAM at runtime so we need 2 base
* addresses.
******************************************************************************/
#define BL1_RO_BASE TZROM_BASE
#define BL1_RO_LIMIT (TZROM_BASE + TZROM_SIZE)
/*
* Put BL1 RW at the top of the Trusted SRAM. BL1_RW_BASE is calculated using
* the current BL1 RW debug size plus a little space for growth.
*/
#if TRUSTED_BOARD_BOOT
#define BL1_RW_BASE (TZRAM_BASE + TZRAM_SIZE - 0x8000)
#else
#define BL1_RW_BASE (TZRAM_BASE + TZRAM_SIZE - 0x6000)
#endif
#define BL1_RW_LIMIT (TZRAM_BASE + TZRAM_SIZE)
/*******************************************************************************
* BL2 specific defines.
******************************************************************************/
/*
* Put BL2 just below BL3-1. BL2_BASE is calculated using the current BL2 debug
* size plus a little space for growth.
*/
#if TRUSTED_BOARD_BOOT
#define BL2_BASE (BL31_BASE - 0x1D000)
#else
#define BL2_BASE (BL31_BASE - 0xC000)
#endif
#define BL2_LIMIT BL31_BASE
/*******************************************************************************
* Load address of BL3-0 in the Juno port
* BL3-0 is loaded to the same place as BL3-1. Once BL3-0 is transferred to the
* SCP, it is discarded and BL3-1 is loaded over the top.
******************************************************************************/
#define BL30_BASE BL31_BASE
/*******************************************************************************
* BL3-1 specific defines.
******************************************************************************/
/*
* Put BL3-1 at the top of the Trusted SRAM. BL31_BASE is calculated using the
* current BL3-1 debug size plus a little space for growth.
*/
#define BL31_BASE (TZRAM_BASE + TZRAM_SIZE - 0x1D000)
#define BL31_PROGBITS_LIMIT BL1_RW_BASE
#define BL31_LIMIT (TZRAM_BASE + TZRAM_SIZE)
/*******************************************************************************
* BL3-2 specific defines.
******************************************************************************/
#if (PLAT_TSP_LOCATION_ID == PLAT_TRUSTED_SRAM_ID)
# define TSP_SEC_MEM_BASE TZRAM_BASE
# define TSP_SEC_MEM_SIZE TZRAM_SIZE
# define BL32_BASE TZRAM_BASE
# define BL32_LIMIT BL31_BASE
# define BL32_PROGBITS_LIMIT BL2_BASE
#elif (PLAT_TSP_LOCATION_ID == PLAT_DRAM_ID)
# define TSP_SEC_MEM_BASE DRAM_SEC_BASE
# define TSP_SEC_MEM_SIZE (DRAM_SEC_SIZE - DRAM_SCP_SIZE)
# define BL32_BASE DRAM_SEC_BASE
# define BL32_LIMIT (DRAM_SEC_BASE + DRAM_SEC_SIZE - \
DRAM_SCP_SIZE)
#else
# error "Unsupported PLAT_TSP_LOCATION_ID value"
#endif
/*******************************************************************************
* Load address of BL3-3 in the Juno port
******************************************************************************/
#define NS_IMAGE_OFFSET 0xE0000000
/*******************************************************************************
* Platform specific page table and MMU setup constants
******************************************************************************/
#define ADDR_SPACE_SIZE (1ull << 32)
#if IMAGE_BL1 || IMAGE_BL31
# define MAX_XLAT_TABLES 2
#endif
#if IMAGE_BL2 || IMAGE_BL32
# define MAX_XLAT_TABLES 3
#endif
#define MAX_MMAP_REGIONS (JUNO_MMAP_ENTRIES + JUNO_BL_REGIONS)
/*******************************************************************************
* ID of the secure physical generic timer interrupt used by the TSP
******************************************************************************/
#define TSP_IRQ_SEC_PHY_TIMER IRQ_SEC_PHY_TIMER
/*******************************************************************************
* Declarations and constants to access the mailboxes safely. Each mailbox is
* 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. Such alignment ensures that two maiboxes do not sit on the same cache
* line at any cache level. They could belong to different cpus/clusters &
* get written while being protected by different locks causing corruption of
* a valid mailbox address.
******************************************************************************/
#define CACHE_WRITEBACK_SHIFT 6
#define CACHE_WRITEBACK_GRANULE (1 << CACHE_WRITEBACK_SHIFT)
#if !USE_COHERENT_MEM
/*******************************************************************************
* Size of the per-cpu data in bytes that should be reserved in the generic
* per-cpu data structure for the Juno port.
******************************************************************************/
#define PLAT_PCPU_DATA_SIZE 2
#endif
#endif /* __PLATFORM_DEF_H__ */
/*
* Copyright (c) 2014, 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 __JUNO_DEF_H__
#define __JUNO_DEF_H__
/* Special value used to verify platform parameters from BL2 to BL3-1 */
#define JUNO_BL31_PLAT_PARAM_VAL 0x0f1e2d3c4b5a6978ULL
/*******************************************************************************
* Juno memory map related constants
******************************************************************************/
#define FLASH_BASE 0x08000000
#define FLASH_SIZE 0x04000000
/* Bypass offset from start of NOR flash */
#define BL1_ROM_BYPASS_OFFSET 0x03EC0000
#ifndef TZROM_BASE
/* Use the bypass address */
#define TZROM_BASE FLASH_BASE + BL1_ROM_BYPASS_OFFSET
#endif
/* Actual ROM size on Juno is 64 KB, but TBB requires at least 80 KB in debug
* mode. We can test TBB on Juno bypassing the ROM and using 128 KB of flash */
#if TRUSTED_BOARD_BOOT
#define TZROM_SIZE 0x00020000
#else
#define TZROM_SIZE 0x00010000
#endif
#define TZRAM_BASE 0x04001000
#define TZRAM_SIZE 0x0003F000
#define PLAT_TRUSTED_SRAM_ID 0
#define PLAT_DRAM_ID 1
#define MHU_SECURE_BASE 0x04000000
#define MHU_SECURE_SIZE 0x00001000
#define MHU_PAYLOAD_CACHED 0
#define TRUSTED_MAILBOXES_BASE MHU_SECURE_BASE
#define TRUSTED_MAILBOX_SHIFT 4
#define EMMC_BASE 0x0c000000
#define EMMC_SIZE 0x04000000
#define PSRAM_BASE 0x14000000
#define PSRAM_SIZE 0x02000000
#define IOFPGA_BASE 0x1c000000
#define IOFPGA_SIZE 0x03000000
#define NSROM_BASE 0x1f000000
#define NSROM_SIZE 0x00001000
/* Following covers Columbus Peripherals excluding NSROM and NSRAM */
#define DEVICE0_BASE 0x20000000
#define DEVICE0_SIZE 0x0e000000
#define MHU_BASE 0x2b1f0000
#define NSRAM_BASE 0x2e000000
#define NSRAM_SIZE 0x00008000
/* Following covers Juno Peripherals and PCIe expansion area */
#define DEVICE1_BASE 0x40000000
#define DEVICE1_SIZE 0x40000000
#define PCIE_CONTROL_BASE 0x7ff20000
#define DRAM_BASE 0x80000000
#define DRAM_SIZE 0x80000000
/*
* DRAM at 0x8000_0000 is divided in two regions:
* - Secure DRAM (default is the top 16MB except for the last 2MB, which are
* used by the SCP for DDR retraining)
* - Non-Secure DRAM (remaining DRAM starting at DRAM_BASE)
*/
#define DRAM_SCP_SIZE 0x00200000
#define DRAM_SCP_BASE (DRAM_BASE + DRAM_SIZE - DRAM_SCP_SIZE)
#define DRAM_SEC_SIZE 0x00E00000
#define DRAM_SEC_BASE (DRAM_SCP_BASE - DRAM_SEC_SIZE)
#define DRAM_NS_BASE DRAM_BASE
#define DRAM_NS_SIZE (DRAM_SIZE - DRAM_SCP_SIZE - DRAM_SEC_SIZE)
/* Second region of DRAM */
#define DRAM2_BASE 0x880000000
#define DRAM2_SIZE 0x180000000
/* Memory mapped Generic timer interfaces */
#define SYS_CNTCTL_BASE 0x2a430000
#define SYS_CNTREAD_BASE 0x2a800000
#define SYS_TIMCTL_BASE 0x2a810000
/*
* Base memory address of the V2M-Juno motherboard APB system registers in the
* IOFPGA
*/
#define VE_SYSREGS_BASE 0x1c010000
/* APB system registers in address offset order from the base memory address */
#define V2M_SYS_ID 0x0
#define V2M_SYS_LED 0x8
/* V2M SYS_ID register bits */
#define SYS_ID_REV_SHIFT 28
#define SYS_ID_REV_MASK 0xf
/* Board revisions */
#define REV_JUNO_R0 0x1 /* Rev B */
#define REV_JUNO_R1 0x2 /* Rev C */
/*
* V2M sysled bit definitions. The values written to this
* register are defined in arch.h & runtime_svc.h. Only
* used by the primary cpu to diagnose any cold boot issues.
*
* SYS_LED[0] - Security state (S=0/NS=1)
* SYS_LED[2:1] - Exception Level (EL3-EL0)
* SYS_LED[7:3] - Exception Class (Sync/Async & origin)
*
*/
#define SYS_LED_SS_SHIFT 0x0
#define SYS_LED_EL_SHIFT 0x1
#define SYS_LED_EC_SHIFT 0x3
/*
* The number of regions like RO(code), coherent and data required by
* different BL stages which need to be mapped in the MMU.
*/
#if USE_COHERENT_MEM
#define JUNO_BL_REGIONS 3
#else
#define JUNO_BL_REGIONS 2
#endif
/*
* The JUNO_MAX_MMAP_REGIONS depend on the number of entries in juno_mmap[]
* defined for each BL stage in juno_common.c.
*/
#if IMAGE_BL1
#define JUNO_MMAP_ENTRIES 6
#endif
#if IMAGE_BL2
#define JUNO_MMAP_ENTRIES 8
#endif
#if IMAGE_BL31
#define JUNO_MMAP_ENTRIES 5
#endif
#if IMAGE_BL32
#define JUNO_MMAP_ENTRIES 4
#endif
/*******************************************************************************
* GIC-400 & interrupt handling related constants
******************************************************************************/
#define GICD_BASE 0x2c010000
#define GICC_BASE 0x2c02f000
#define GICH_BASE 0x2c04f000
#define GICV_BASE 0x2c06f000
#define IRQ_MHU 69
#define IRQ_GPU_SMMU_0 71
#define IRQ_GPU_SMMU_1 73
#define IRQ_ETR_SMMU 75
#define IRQ_TZC400 80
#define IRQ_TZ_WDOG 86
#define IRQ_SEC_PHY_TIMER 29
#define IRQ_SEC_SGI_0 8
#define IRQ_SEC_SGI_1 9
#define IRQ_SEC_SGI_2 10
#define IRQ_SEC_SGI_3 11
#define IRQ_SEC_SGI_4 12
#define IRQ_SEC_SGI_5 13
#define IRQ_SEC_SGI_6 14
#define IRQ_SEC_SGI_7 15
/*******************************************************************************
* PL011 related constants
******************************************************************************/
/* FPGA UART0 */
#define PL011_UART0_BASE 0x1c090000
/* FPGA UART1 */
#define PL011_UART1_BASE 0x1c0a0000
/* SoC UART0 */
#define PL011_UART2_BASE 0x7ff80000
/* SoC UART1 */
#define PL011_UART3_BASE 0x7ff70000
#define PL011_BAUDRATE 115200
#define PL011_UART0_CLK_IN_HZ 24000000
#define PL011_UART1_CLK_IN_HZ 24000000
#define PL011_UART2_CLK_IN_HZ 7273800
#define PL011_UART3_CLK_IN_HZ 7273800
/*******************************************************************************
* NIC-400 related constants
******************************************************************************/
/* CSS NIC-400 Global Programmers View (GPV) */
#define CSS_NIC400_BASE 0x2a000000
/* The slave_bootsecure controls access to GPU, DMC and CS. */
#define CSS_NIC400_SLAVE_BOOTSECURE 8
/* SoC NIC-400 Global Programmers View (GPV) */
#define SOC_NIC400_BASE 0x7fd00000
#define SOC_NIC400_USB_EHCI 0
#define SOC_NIC400_TLX_MASTER 1
#define SOC_NIC400_USB_OHCI 2
#define SOC_NIC400_PL354_SMC 3
/*
* The apb4_bridge controls access to:
* - the PCIe configuration registers
* - the MMU units for USB, HDLCD and DMA
*/
#define SOC_NIC400_APB4_BRIDGE 4
/*
* The bootsec_bridge controls access to a bunch of peripherals, e.g. the UARTs.
*/
#define SOC_NIC400_BOOTSEC_BRIDGE 5
#define SOC_NIC400_BOOTSEC_BRIDGE_UART1 (1 << 12)
/*******************************************************************************
* TZC-400 related constants
******************************************************************************/
#define TZC400_BASE 0x2a4a0000
#define TZC400_NSAID_CCI400 0 /* Note: Same as default NSAID!! */
#define TZC400_NSAID_PCIE 1
#define TZC400_NSAID_HDLCD0 2
#define TZC400_NSAID_HDLCD1 3
#define TZC400_NSAID_USB 4
#define TZC400_NSAID_DMA330 5
#define TZC400_NSAID_THINLINKS 6
#define TZC400_NSAID_AP 9
#define TZC400_NSAID_GPU 10
#define TZC400_NSAID_SCP 11
#define TZC400_NSAID_CORESIGHT 12
/*******************************************************************************
* CCI-400 related constants
******************************************************************************/
#define CCI400_BASE 0x2c090000
#define CCI400_CLUSTER0_SL_IFACE_IX 4
#define CCI400_CLUSTER1_SL_IFACE_IX 3
/*******************************************************************************
* SCP <=> AP boot configuration
******************************************************************************/
#define SCP_BOOT_CFG_ADDR 0x04000080
#define PRIMARY_CPU_SHIFT 8
#define PRIMARY_CPU_MASK 0xf
/*******************************************************************************
* MMU-401 related constants
******************************************************************************/
#define MMU401_SSD_OFFSET 0x4000
#define MMU401_DMA330_BASE 0x7fb00000
#endif /* __JUNO_DEF_H__ */
/*
* Copyright (c) 2014, 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 __JUNO_PRIVATE_H__
#define __JUNO_PRIVATE_H__
#include <bakery_lock.h>
#include <bl_common.h>
#include <cpu_data.h>
#include <platform_def.h>
#include <stdint.h>
/*******************************************************************************
* Forward declarations
******************************************************************************/
struct plat_pm_ops;
struct meminfo;
struct bl31_params;
struct image_info;
struct entry_point_info;
/*******************************************************************************
* This structure represents the superset of information that is passed to
* BL3-1 e.g. while passing control to it from BL2 which is bl31_params
* and other platform specific params
******************************************************************************/
typedef struct bl2_to_bl31_params_mem {
struct bl31_params bl31_params;
struct image_info bl31_image_info;
struct image_info bl32_image_info;
struct image_info bl33_image_info;
struct entry_point_info bl33_ep_info;
struct entry_point_info bl32_ep_info;
struct entry_point_info bl31_ep_info;
} bl2_to_bl31_params_mem_t;
#if IMAGE_BL31
#if USE_COHERENT_MEM
/*
* These are wrapper macros to the Coherent Memory Bakery Lock API.
*/
#define juno_lock_init(_lock_arg) bakery_lock_init(_lock_arg)
#define juno_lock_get(_lock_arg) bakery_lock_get(_lock_arg)
#define juno_lock_release(_lock_arg) bakery_lock_release(_lock_arg)
#else
/*******************************************************************************
* Constants that specify how many bakeries this platform implements and bakery
* ids.
******************************************************************************/
#define JUNO_MAX_BAKERIES 1
#define JUNO_MHU_BAKERY_ID 0
/*******************************************************************************
* Definition of structure which holds platform specific per-cpu data. Currently
* it holds only the bakery lock information for each cpu. Constants to specify
* how many bakeries this platform implements and bakery ids are specified in
* juno_def.h
******************************************************************************/
typedef struct juno_cpu_data {
bakery_info_t pcpu_bakery_info[JUNO_MAX_BAKERIES];
} juno_cpu_data_t;
/* Macro to define the offset of bakery_info_t in juno_cpu_data_t */
#define JUNO_CPU_DATA_LOCK_OFFSET __builtin_offsetof\
(juno_cpu_data_t, pcpu_bakery_info)
/*******************************************************************************
* Helper macros for bakery lock api when using the above juno_cpu_data_t for
* bakery lock data structures. It assumes that the bakery_info is at the
* beginning of the platform specific per-cpu data.
******************************************************************************/
#define juno_lock_init(_lock_arg) /* No init required */
#define juno_lock_get(_lock_arg) bakery_lock_get(_lock_arg, \
CPU_DATA_PLAT_PCPU_OFFSET + \
JUNO_CPU_DATA_LOCK_OFFSET)
#define juno_lock_release(_lock_arg) bakery_lock_release(_lock_arg, \
CPU_DATA_PLAT_PCPU_OFFSET + \
JUNO_CPU_DATA_LOCK_OFFSET)
/*
* Ensure that the size of the Juno specific per-cpu data structure and the size
* of the memory allocated in generic per-cpu data for the platform are the same.
*/
CASSERT(PLAT_PCPU_DATA_SIZE == sizeof(juno_cpu_data_t), \
juno_pcpu_data_size_mismatch);
#endif /* __USE_COHERENT_MEM__ */
#else
/*
* Dummy wrapper macros for all other BL stages other than BL3-1
*/
#define juno_lock_init(_lock_arg)
#define juno_lock_get(_lock_arg)
#define juno_lock_release(_lock_arg)
#endif /* __IMAGE_BL31__ */
/*******************************************************************************
* Function and variable prototypes
******************************************************************************/
void bl1_plat_arch_setup(void);
void bl2_plat_arch_setup(void);
void bl31_plat_arch_setup(void);
int platform_setup_pm(const struct plat_pm_ops **plat_ops);
unsigned int platform_get_core_pos(unsigned long mpidr);
void configure_mmu_el1(unsigned long total_base,
unsigned long total_size,
unsigned long ro_start,
unsigned long ro_limit
#if USE_COHERENT_MEM
, unsigned long coh_start,
unsigned long coh_limit
#endif
);
void configure_mmu_el3(unsigned long total_base,
unsigned long total_size,
unsigned long ro_start,
unsigned long ro_limit
#if USE_COHERENT_MEM
, unsigned long coh_start,
unsigned long coh_limit
#endif
);
void plat_report_exception(unsigned long type);
unsigned long plat_get_ns_image_entrypoint(void);
unsigned long platform_get_stack(unsigned long mpidr);
uint64_t plat_get_syscnt_freq(void);
void plat_gic_init(void);
void plat_cci_init(void);
/* Declarations for plat_topology.c */
int plat_setup_topology(void);
unsigned int plat_get_aff_count(unsigned int aff_lvl, unsigned long mpidr);
unsigned int plat_get_aff_state(unsigned int aff_lvl, unsigned long mpidr);
/* Declarations for plat_io_storage.c */
void io_setup(void);
int plat_get_image_source(const char *image_name,
uintptr_t *dev_handle,
uintptr_t *image_spec);
/* Declarations for security.c */
void plat_security_setup(void);
/*
* Before calling this function BL2 is loaded in memory and its entrypoint
* is set by load_image. This is a placeholder for the platform to change
* the entrypoint of BL2 and set SPSR and security state.
* On Juno we are only setting the security state, entrypoint
*/
void bl1_plat_set_bl2_ep_info(struct image_info *image,
struct entry_point_info *ep);
/*
* Before calling this function BL3-1 is loaded in memory and its entrypoint
* is set by load_image. This is a placeholder for the platform to change
* the entrypoint of BL3-1 and set SPSR and security state.
* On Juno we are only setting the security state, entrypoint
*/
void bl2_plat_set_bl31_ep_info(struct image_info *image,
struct entry_point_info *ep);
/*
* Before calling this function BL3-2 is loaded in memory and its entrypoint
* is set by load_image. This is a placeholder for the platform to change
* the entrypoint of BL3-2 and set SPSR and security state.
* On Juno we are only setting the security state, entrypoint
*/
void bl2_plat_set_bl32_ep_info(struct image_info *image,
struct entry_point_info *ep);
/*
* Before calling this function BL3-3 is loaded in memory and its entrypoint
* is set by load_image. This is a placeholder for the platform to change
* the entrypoint of BL3-3 and set SPSR and security state.
* On Juno we are only setting the security state, entrypoint
*/
void bl2_plat_set_bl33_ep_info(struct image_info *image,
struct entry_point_info *ep);
/* Gets the memory layout for BL3-2 */
void bl2_plat_get_bl32_meminfo(struct meminfo *mem_info);
/* Gets the memory layout for BL3-3 */
void bl2_plat_get_bl33_meminfo(struct meminfo *mem_info);
#endif /* __JUNO_PRIVATE_H__ */
Markdown is supported
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment