summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorHaojian Zhuang <haojian.zhuang@linaro.org>2017-05-24 08:49:26 +0800
committerDan Handley <dan.handley@arm.com>2017-05-24 17:34:41 +0100
commit127793daba1831044fd0269931c4ea23bc378ab0 (patch)
treeaa18ed89cc4309c027cdcd3246da78b2205f1bf4
parentcfac68af163a4e95360bb681d35bba53081c6781 (diff)
hikey: support BL31
Support BL31 and PSCI. Enable multiple cores in PSCI. Change-Id: I66c39e1e9c4c45ac41a0142ed2070d79a3ac5ba3 Signed-off-by: Haojian Zhuang <haojian.zhuang@linaro.org> Signed-off-by: Dan Handley <dan.handley@arm.com>
-rw-r--r--plat/hisilicon/hikey/hikey_bl31_setup.c124
-rw-r--r--plat/hisilicon/hikey/hikey_pm.c202
-rw-r--r--plat/hisilicon/hikey/hikey_topology.c62
-rw-r--r--plat/hisilicon/hikey/hisi_ipc.c203
-rw-r--r--plat/hisilicon/hikey/hisi_pwrc.c81
-rw-r--r--plat/hisilicon/hikey/hisi_pwrc_sram.S70
-rw-r--r--plat/hisilicon/hikey/include/hisi_ipc.h46
-rw-r--r--plat/hisilicon/hikey/include/hisi_pwrc.h20
-rw-r--r--plat/hisilicon/hikey/platform.mk17
9 files changed, 825 insertions, 0 deletions
diff --git a/plat/hisilicon/hikey/hikey_bl31_setup.c b/plat/hisilicon/hikey/hikey_bl31_setup.c
new file mode 100644
index 00000000..9a1114a7
--- /dev/null
+++ b/plat/hisilicon/hikey/hikey_bl31_setup.c
@@ -0,0 +1,124 @@
+/*
+ * Copyright (c) 2017, ARM Limited and Contributors. All rights reserved.
+ *
+ * SPDX-License-Identifier: BSD-3-Clause
+ */
+
+#include <arm_gic.h>
+#include <assert.h>
+#include <bl_common.h>
+#include <cci.h>
+#include <console.h>
+#include <debug.h>
+#include <errno.h>
+#include <gicv2.h>
+#include <hi6220.h>
+#include <hisi_ipc.h>
+#include <hisi_pwrc.h>
+#include <platform_def.h>
+
+#include "hikey_def.h"
+#include "hikey_private.h"
+
+/*
+ * 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 BL31_RO_BASE (unsigned long)(&__RO_START__)
+#define BL31_RO_LIMIT (unsigned long)(&__RO_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 BL31_COHERENT_RAM_BASE (unsigned long)(&__COHERENT_RAM_START__)
+#define BL31_COHERENT_RAM_LIMIT (unsigned long)(&__COHERENT_RAM_END__)
+
+static entry_point_info_t bl32_ep_info;
+static entry_point_info_t bl33_ep_info;
+
+/******************************************************************************
+ * On a GICv2 system, the Group 1 secure interrupts are treated as Group 0
+ * interrupts.
+ *****************************************************************************/
+const unsigned int g0_interrupt_array[] = {
+ IRQ_SEC_PHY_TIMER,
+ IRQ_SEC_SGI_0
+};
+
+/*
+ * Ideally `arm_gic_data` structure definition should be a `const` but it is
+ * kept as modifiable for overwriting with different GICD and GICC base when
+ * running on FVP with VE memory map.
+ */
+gicv2_driver_data_t hikey_gic_data = {
+ .gicd_base = PLAT_ARM_GICD_BASE,
+ .gicc_base = PLAT_ARM_GICC_BASE,
+ .g0_interrupt_num = ARRAY_SIZE(g0_interrupt_array),
+ .g0_interrupt_array = g0_interrupt_array,
+};
+
+static const int cci_map[] = {
+ CCI400_SL_IFACE3_CLUSTER_IX,
+ CCI400_SL_IFACE4_CLUSTER_IX
+};
+
+entry_point_info_t *bl31_plat_get_next_image_ep_info(unsigned int 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;
+ return NULL;
+}
+
+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(CONSOLE_BASE, PL011_UART_CLK_IN_HZ, PL011_BAUDRATE);
+
+ /* Initialize CCI driver */
+ cci_init(CCI400_BASE, cci_map, ARRAY_SIZE(cci_map));
+
+ /*
+ * 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;
+}
+
+void bl31_plat_arch_setup(void)
+{
+ hikey_init_mmu_el3(BL31_BASE,
+ BL31_LIMIT - BL31_BASE,
+ BL31_RO_BASE,
+ BL31_RO_LIMIT,
+ BL31_COHERENT_RAM_BASE,
+ BL31_COHERENT_RAM_LIMIT);
+}
+
+void bl31_platform_setup(void)
+{
+ /* Initialize the GIC driver, cpu and distributor interfaces */
+ gicv2_driver_init(&hikey_gic_data);
+ gicv2_distif_init();
+ gicv2_pcpu_distif_init();
+ gicv2_cpuif_enable();
+
+ hisi_ipc_init();
+ hisi_pwrc_setup();
+}
+
+void bl31_plat_runtime_setup(void)
+{
+}
diff --git a/plat/hisilicon/hikey/hikey_pm.c b/plat/hisilicon/hikey/hikey_pm.c
new file mode 100644
index 00000000..9b4ef5bf
--- /dev/null
+++ b/plat/hisilicon/hikey/hikey_pm.c
@@ -0,0 +1,202 @@
+/*
+ * Copyright (c) 2017, ARM Limited and Contributors. All rights reserved.
+ *
+ * SPDX-License-Identifier: BSD-3-Clause
+ */
+
+#include <arch_helpers.h>
+#include <assert.h>
+#include <cci.h>
+#include <debug.h>
+#include <gicv2.h>
+#include <hi6220.h>
+#include <hisi_ipc.h>
+#include <hisi_pwrc.h>
+#include <hisi_sram_map.h>
+#include <mmio.h>
+#include <psci.h>
+
+#include "hikey_def.h"
+
+#define HIKEY_CLUSTER_STATE_ON 0
+#define HIKEY_CLUSTER_STATE_OFF 1
+
+static uintptr_t hikey_sec_entrypoint;
+/* There're two clusters in HiKey. */
+static int hikey_cluster_state[] = {HIKEY_CLUSTER_STATE_OFF,
+ HIKEY_CLUSTER_STATE_OFF};
+
+/*******************************************************************************
+ * Handler called when a power domain is about to be turned on. The
+ * level and mpidr determine the affinity instance.
+ ******************************************************************************/
+static int hikey_pwr_domain_on(u_register_t mpidr)
+{
+ int cpu, cluster;
+ int curr_cluster;
+
+ cluster = MPIDR_AFFLVL1_VAL(mpidr);
+ cpu = MPIDR_AFFLVL0_VAL(mpidr);
+ curr_cluster = MPIDR_AFFLVL1_VAL(read_mpidr());
+ if (cluster != curr_cluster)
+ hisi_ipc_cluster_on(cpu, cluster);
+
+ hisi_pwrc_set_core_bx_addr(cpu, cluster, hikey_sec_entrypoint);
+ hisi_ipc_cpu_on(cpu, cluster);
+ return 0;
+}
+
+static void hikey_pwr_domain_on_finish(const psci_power_state_t *target_state)
+{
+ unsigned long mpidr;
+ int cpu, cluster;
+
+ mpidr = read_mpidr();
+ cluster = MPIDR_AFFLVL1_VAL(mpidr);
+ cpu = MPIDR_AFFLVL0_VAL(mpidr);
+ if (hikey_cluster_state[cluster] == HIKEY_CLUSTER_STATE_OFF) {
+ /*
+ * Enable CCI coherency for this cluster.
+ * No need for locks as no other cpu is active at the moment.
+ */
+ cci_enable_snoop_dvm_reqs(MPIDR_AFFLVL1_VAL(mpidr));
+ hikey_cluster_state[cluster] = HIKEY_CLUSTER_STATE_ON;
+ }
+
+ /* Zero the jump address in the mailbox for this cpu */
+ hisi_pwrc_set_core_bx_addr(cpu, cluster, 0);
+
+ /* Program the GIC per-cpu distributor or re-distributor interface */
+ gicv2_pcpu_distif_init();
+ /* Enable the GIC cpu interface */
+ gicv2_cpuif_enable();
+}
+
+/*******************************************************************************
+ * Handler called when a power domain is about to be turned off. The
+ * target_state encodes the power state that each level should transition to.
+ ******************************************************************************/
+void hikey_pwr_domain_off(const psci_power_state_t *target_state)
+{
+ unsigned long mpidr;
+ int cpu, cluster;
+
+ gicv2_cpuif_disable();
+
+ mpidr = read_mpidr();
+ cluster = MPIDR_AFFLVL1_VAL(mpidr);
+ cpu = MPIDR_AFFLVL0_VAL(mpidr);
+ if (target_state->pwr_domain_state[MPIDR_AFFLVL1] ==
+ PLAT_MAX_OFF_STATE) {
+ hisi_ipc_spin_lock(HISI_IPC_SEM_CPUIDLE);
+ cci_disable_snoop_dvm_reqs(MPIDR_AFFLVL1_VAL(mpidr));
+ hisi_ipc_spin_unlock(HISI_IPC_SEM_CPUIDLE);
+
+ hisi_ipc_cluster_off(cpu, cluster);
+ hikey_cluster_state[cluster] = HIKEY_CLUSTER_STATE_OFF;
+ }
+ hisi_ipc_cpu_off(cpu, cluster);
+}
+
+/*******************************************************************************
+ * Handler to reboot the system.
+ ******************************************************************************/
+static void __dead2 hikey_system_reset(void)
+{
+ /* Send the system reset request */
+ mmio_write_32(AO_SC_SYS_STAT0, 0x48698284);
+ isb();
+ dsb();
+
+ wfi();
+ panic();
+}
+
+/*******************************************************************************
+ * Handler called to check the validity of the power state parameter.
+ ******************************************************************************/
+int hikey_validate_power_state(unsigned int power_state,
+ psci_power_state_t *req_state)
+{
+ int pstate = psci_get_pstate_type(power_state);
+ int pwr_lvl = psci_get_pstate_pwrlvl(power_state);
+ int i;
+
+ assert(req_state);
+
+ if (pwr_lvl > PLAT_MAX_PWR_LVL)
+ return PSCI_E_INVALID_PARAMS;
+
+ /* Sanity check the requested state */
+ if (pstate == PSTATE_TYPE_STANDBY) {
+ /*
+ * It's possible to enter standby only on power level 0
+ * Ignore any other power level.
+ */
+ if (pwr_lvl != MPIDR_AFFLVL0)
+ return PSCI_E_INVALID_PARAMS;
+
+ req_state->pwr_domain_state[MPIDR_AFFLVL0] =
+ PLAT_MAX_RET_STATE;
+ } else {
+ for (i = MPIDR_AFFLVL0; i <= pwr_lvl; i++)
+ req_state->pwr_domain_state[i] =
+ PLAT_MAX_OFF_STATE;
+ }
+
+ /*
+ * We expect the 'state id' to be zero.
+ */
+ if (psci_get_pstate_id(power_state))
+ return PSCI_E_INVALID_PARAMS;
+
+ return PSCI_E_SUCCESS;
+}
+
+/*******************************************************************************
+ * Handler called to check the validity of the non secure entrypoint.
+ ******************************************************************************/
+static int hikey_validate_ns_entrypoint(uintptr_t entrypoint)
+{
+ /*
+ * Check if the non secure entrypoint lies within the non
+ * secure DRAM.
+ */
+ if ((entrypoint > DDR_BASE) && (entrypoint < (DDR_BASE + DDR_SIZE)))
+ return PSCI_E_SUCCESS;
+
+ return PSCI_E_INVALID_ADDRESS;
+}
+
+/*******************************************************************************
+ * Export the platform handlers to enable psci to invoke them
+ ******************************************************************************/
+static const plat_psci_ops_t hikey_psci_ops = {
+ .cpu_standby = NULL,
+ .pwr_domain_on = hikey_pwr_domain_on,
+ .pwr_domain_on_finish = hikey_pwr_domain_on_finish,
+ .pwr_domain_off = hikey_pwr_domain_off,
+ .pwr_domain_suspend = NULL,
+ .pwr_domain_suspend_finish = NULL,
+ .system_off = NULL,
+ .system_reset = hikey_system_reset,
+ .validate_power_state = hikey_validate_power_state,
+ .validate_ns_entrypoint = hikey_validate_ns_entrypoint,
+ .get_sys_suspend_power_state = NULL,
+};
+
+/*******************************************************************************
+ * Export the platform specific power ops and initialize Power Controller
+ ******************************************************************************/
+int plat_setup_psci_ops(uintptr_t sec_entrypoint,
+ const plat_psci_ops_t **psci_ops)
+{
+ hikey_sec_entrypoint = sec_entrypoint;
+
+ /*
+ * Initialize PSCI ops struct
+ */
+ *psci_ops = &hikey_psci_ops;
+
+ return 0;
+}
diff --git a/plat/hisilicon/hikey/hikey_topology.c b/plat/hisilicon/hikey/hikey_topology.c
new file mode 100644
index 00000000..37ea20ad
--- /dev/null
+++ b/plat/hisilicon/hikey/hikey_topology.c
@@ -0,0 +1,62 @@
+/*
+ * Copyright (c) 2017, ARM Limited and Contributors. All rights reserved.
+ *
+ * SPDX-License-Identifier: BSD-3-Clause
+ */
+#include <arch.h>
+#include <platform_def.h>
+#include <psci.h>
+
+/*
+ * The HiKey power domain tree descriptor. The cluster power domains
+ * are arranged so that when the PSCI generic code creates the power
+ * domain tree, the indices of the CPU power domain nodes it allocates
+ * match the linear indices returned by plat_core_pos_by_mpidr().
+ */
+const unsigned char hikey_power_domain_tree_desc[] = {
+ /* Number of root nodes */
+ 1,
+ /* Number of clusters */
+ PLATFORM_CLUSTER_COUNT,
+ /* Number of CPU cores */
+ PLATFORM_CORE_COUNT
+};
+
+/*******************************************************************************
+ * This function returns the HiKey topology tree information.
+ ******************************************************************************/
+const unsigned char *plat_get_power_domain_tree_desc(void)
+{
+ return hikey_power_domain_tree_desc;
+}
+
+/*******************************************************************************
+ * This function implements a part of the critical interface between the psci
+ * generic layer and the platform that allows the former to query the platform
+ * to convert an MPIDR to a unique linear index. An error code (-1) is returned
+ * in case the MPIDR is invalid.
+ ******************************************************************************/
+int plat_core_pos_by_mpidr(u_register_t mpidr)
+{
+ unsigned int cluster_id, cpu_id;
+
+ mpidr &= MPIDR_AFFINITY_MASK;
+
+ if (mpidr & ~(MPIDR_CLUSTER_MASK | MPIDR_CPU_MASK))
+ return -1;
+
+ cluster_id = (mpidr >> MPIDR_AFF1_SHIFT) & MPIDR_AFFLVL_MASK;
+ cpu_id = (mpidr >> MPIDR_AFF0_SHIFT) & MPIDR_AFFLVL_MASK;
+
+ if (cluster_id >= PLATFORM_CLUSTER_COUNT)
+ return -1;
+
+ /*
+ * Validate cpu_id by checking whether it represents a CPU in
+ * one of the two clusters present on the platform.
+ */
+ if (cpu_id >= PLATFORM_CORE_COUNT_PER_CLUSTER)
+ return -1;
+
+ return (cpu_id + (cluster_id * 4));
+}
diff --git a/plat/hisilicon/hikey/hisi_ipc.c b/plat/hisilicon/hikey/hisi_ipc.c
new file mode 100644
index 00000000..0469a08b
--- /dev/null
+++ b/plat/hisilicon/hikey/hisi_ipc.c
@@ -0,0 +1,203 @@
+/*
+ * Copyright (c) 2017, ARM Limited and Contributors. All rights reserved.
+ *
+ * SPDX-License-Identifier: BSD-3-Clause
+ */
+
+#include <arch_helpers.h>
+#include <hisi_ipc.h>
+#include <hisi_sram_map.h>
+#include <mmio.h>
+#include <platform_def.h>
+#include <stdarg.h>
+#include <stdio.h>
+#include <string.h>
+
+static int ipc_init;
+
+static unsigned int cpu_ipc_num[PLATFORM_CLUSTER_COUNT][PLATFORM_CORE_COUNT_PER_CLUSTER] = {
+ {
+ HISI_IPC_MCU_INT_SRC_ACPU0_PD,
+ HISI_IPC_MCU_INT_SRC_ACPU1_PD,
+ HISI_IPC_MCU_INT_SRC_ACPU2_PD,
+ HISI_IPC_MCU_INT_SRC_ACPU3_PD,
+ },
+ {
+ HISI_IPC_MCU_INT_SRC_ACPU4_PD,
+ HISI_IPC_MCU_INT_SRC_ACPU5_PD,
+ HISI_IPC_MCU_INT_SRC_ACPU6_PD,
+ HISI_IPC_MCU_INT_SRC_ACPU7_PD,
+ }
+};
+
+int hisi_cpus_pd_in_cluster_besides_curr(unsigned int cpu,
+ unsigned int cluster)
+{
+ unsigned int val = 0, cpu_val = 0;
+ int i;
+
+ val = mmio_read_32(ACPU_CORE_POWERDOWN_FLAGS_ADDR);
+ val = val >> (cluster * 16);
+
+ for (i = 0; i < PLATFORM_CORE_COUNT_PER_CLUSTER; i++) {
+
+ if (cpu == i)
+ continue;
+
+ cpu_val = (val >> (i * 4)) & 0xF;
+ if (cpu_val == 0x8)
+ return 0;
+ }
+
+ return 1;
+}
+
+int hisi_cpus_powered_off_besides_curr(unsigned int cpu)
+{
+ unsigned int val;
+
+ val = mmio_read_32(ACPU_CORE_POWERDOWN_FLAGS_ADDR);
+ return (val == (0x8 << (cpu * 4)));
+}
+
+static void hisi_ipc_send(unsigned int ipc_num)
+{
+ if (!ipc_init) {
+ printf("error ipc base is null!!!\n");
+ return;
+ }
+
+ mmio_write_32(HISI_IPC_CPU_RAW_INT_ADDR, 1 << ipc_num);
+}
+
+void hisi_ipc_spin_lock(unsigned int signal)
+{
+ unsigned int hs_ctrl;
+
+ if (signal >= HISI_IPC_INT_SRC_NUM)
+ return;
+
+ do {
+ hs_ctrl = mmio_read_32(HISI_IPC_ACPU_CTRL(signal));
+ } while (hs_ctrl);
+}
+
+void hisi_ipc_spin_unlock(unsigned int signal)
+{
+ if (signal >= HISI_IPC_INT_SRC_NUM)
+ return;
+
+ mmio_write_32(HISI_IPC_ACPU_CTRL(signal), 0);
+}
+
+void hisi_ipc_cpu_on_off(unsigned int cpu, unsigned int cluster,
+ unsigned int mode)
+{
+ unsigned int val = 0;
+ unsigned int offset;
+
+ if (mode == HISI_IPC_PM_ON)
+ offset = cluster * 16 + cpu * 4;
+ else
+ offset = cluster * 16 + cpu * 4 + 1;
+
+ hisi_ipc_spin_lock(HISI_IPC_SEM_CPUIDLE);
+ val = mmio_read_32(ACPU_CORE_POWERDOWN_FLAGS_ADDR);
+ val |= (0x01 << offset);
+ mmio_write_32(ACPU_CORE_POWERDOWN_FLAGS_ADDR, val);
+ isb();
+ dsb();
+ hisi_ipc_spin_unlock(HISI_IPC_SEM_CPUIDLE);
+
+ hisi_ipc_send(cpu_ipc_num[cluster][cpu]);
+}
+
+void hisi_ipc_cpu_on(unsigned int cpu, unsigned int cluster)
+{
+ hisi_ipc_cpu_on_off(cpu, cluster, HISI_IPC_PM_ON);
+}
+
+void hisi_ipc_cpu_off(unsigned int cpu, unsigned int cluster)
+{
+ hisi_ipc_cpu_on_off(cpu, cluster, HISI_IPC_PM_OFF);
+}
+
+void hisi_ipc_cluster_on_off(unsigned int cpu, unsigned int cluster,
+ unsigned int mode)
+{
+ unsigned int val = 0;
+ unsigned int offset;
+
+ if (mode == HISI_IPC_PM_ON)
+ offset = cluster * 4;
+ else
+ offset = cluster * 4 + 1;
+
+ hisi_ipc_spin_lock(HISI_IPC_SEM_CPUIDLE);
+ val = mmio_read_32(ACPU_CLUSTER_POWERDOWN_FLAGS_ADDR);
+ val |= (0x01 << offset);
+ mmio_write_32(ACPU_CLUSTER_POWERDOWN_FLAGS_ADDR, val);
+ isb();
+ dsb();
+ hisi_ipc_spin_unlock(HISI_IPC_SEM_CPUIDLE);
+
+ hisi_ipc_send(cpu_ipc_num[cluster][cpu]);
+}
+
+void hisi_ipc_cluster_on(unsigned int cpu, unsigned int cluster)
+{
+ hisi_ipc_cluster_on_off(cpu, cluster, HISI_IPC_PM_ON);
+}
+
+void hisi_ipc_cluster_off(unsigned int cpu, unsigned int cluster)
+{
+ hisi_ipc_cluster_on_off(cpu, cluster, HISI_IPC_PM_OFF);
+}
+
+void hisi_ipc_cpu_suspend(unsigned int cpu, unsigned int cluster)
+{
+ unsigned int val = 0;
+ unsigned int offset;
+
+ offset = cluster * 16 + cpu * 4 + 2;
+
+ hisi_ipc_spin_lock(HISI_IPC_SEM_CPUIDLE);
+ val = mmio_read_32(ACPU_CORE_POWERDOWN_FLAGS_ADDR);
+ val |= (0x01 << offset);
+ mmio_write_32(ACPU_CORE_POWERDOWN_FLAGS_ADDR, val);
+ hisi_ipc_spin_unlock(HISI_IPC_SEM_CPUIDLE);
+
+ hisi_ipc_send(cpu_ipc_num[cluster][cpu]);
+}
+
+void hisi_ipc_cluster_suspend(unsigned int cpu, unsigned int cluster)
+{
+ unsigned int val;
+ unsigned int offset;
+
+ offset = cluster * 4 + 1;
+
+ hisi_ipc_spin_lock(HISI_IPC_SEM_CPUIDLE);
+ if (hisi_cpus_pd_in_cluster_besides_curr(cpu, cluster)) {
+ val = mmio_read_32(ACPU_CLUSTER_POWERDOWN_FLAGS_ADDR);
+ val |= (0x01 << offset);
+ mmio_write_32(ACPU_CLUSTER_POWERDOWN_FLAGS_ADDR, val);
+ }
+ hisi_ipc_spin_unlock(HISI_IPC_SEM_CPUIDLE);
+
+ hisi_ipc_send(cpu_ipc_num[cluster][cpu]);
+}
+
+void hisi_ipc_psci_system_off(void)
+{
+ hisi_ipc_send(HISI_IPC_MCU_INT_SRC_ACPU_PD);
+}
+
+int hisi_ipc_init(void)
+{
+ ipc_init = 1;
+
+ mmio_write_32(ACPU_CORE_POWERDOWN_FLAGS_ADDR, 0x8);
+ mmio_write_32(ACPU_CLUSTER_POWERDOWN_FLAGS_ADDR, 0x8);
+ return 0;
+}
diff --git a/plat/hisilicon/hikey/hisi_pwrc.c b/plat/hisilicon/hikey/hisi_pwrc.c
new file mode 100644
index 00000000..fcc9bd89
--- /dev/null
+++ b/plat/hisilicon/hikey/hisi_pwrc.c
@@ -0,0 +1,81 @@
+/*
+ * Copyright (c) 2017, ARM Limited and Contributors. All rights reserved.
+ *
+ * SPDX-License-Identifier: BSD-3-Clause
+ */
+
+#include <debug.h>
+#include <mmio.h>
+#include <hisi_ipc.h>
+#include <hisi_pwrc.h>
+#include <hisi_sram_map.h>
+#include <hi6220_regs_acpu.h>
+#include <hi6220_regs_ao.h>
+#include <stdarg.h>
+#include <stdio.h>
+#include <string.h>
+#include <platform_def.h>
+
+#define CLUSTER_CORE_COUNT (4)
+#define CLUSTER_CORE_MASK ((1 << CLUSTER_CORE_COUNT) - 1)
+
+void hisi_pwrc_set_core_bx_addr(unsigned int core, unsigned int cluster,
+ uintptr_t entry_point)
+{
+ uintptr_t *core_entry = (uintptr_t *)PWRCTRL_ACPU_ASM_D_ARM_PARA_AD;
+ unsigned int i;
+
+ if (!core_entry) {
+ INFO("%s: core entry point is null!\n", __func__);
+ return;
+ }
+
+ i = cluster * CLUSTER_CORE_COUNT + core;
+ mmio_write_64((uintptr_t)(core_entry + i), entry_point);
+}
+
+void hisi_pwrc_set_cluster_wfi(unsigned int cluster)
+{
+ unsigned int reg = 0;
+
+ if (cluster == 0) {
+ reg = mmio_read_32(ACPU_SC_SNOOP_PWD);
+ reg |= PD_DETECT_START0;
+ mmio_write_32(ACPU_SC_SNOOP_PWD, reg);
+ } else if (cluster == 1) {
+ reg = mmio_read_32(ACPU_SC_SNOOP_PWD);
+ reg |= PD_DETECT_START1;
+ mmio_write_32(ACPU_SC_SNOOP_PWD, reg);
+ }
+}
+
+int hisi_pwrc_setup(void)
+{
+ unsigned int reg, sec_entrypoint;
+ extern char pm_asm_code[], pm_asm_code_end[];
+ extern char v7_asm[], v7_asm_end[];
+
+ sec_entrypoint = PWRCTRL_ACPU_ASM_CODE_BASE;
+ mmio_write_32(ACPU_SC_CPUx_RVBARADDR(0), sec_entrypoint >> 2);
+ mmio_write_32(ACPU_SC_CPUx_RVBARADDR(1), sec_entrypoint >> 2);
+ mmio_write_32(ACPU_SC_CPUx_RVBARADDR(2), sec_entrypoint >> 2);
+ mmio_write_32(ACPU_SC_CPUx_RVBARADDR(3), sec_entrypoint >> 2);
+ mmio_write_32(ACPU_SC_CPUx_RVBARADDR(4), sec_entrypoint >> 2);
+ mmio_write_32(ACPU_SC_CPUx_RVBARADDR(5), sec_entrypoint >> 2);
+ mmio_write_32(ACPU_SC_CPUx_RVBARADDR(6), sec_entrypoint >> 2);
+ mmio_write_32(ACPU_SC_CPUx_RVBARADDR(7), sec_entrypoint >> 2);
+
+ memset((void *)PWRCTRL_ACPU_ASM_SPACE_ADDR, 0, 0x400);
+ memcpy((void *)PWRCTRL_ACPU_ASM_SPACE_ADDR, (void *)v7_asm,
+ v7_asm_end - v7_asm);
+
+ memcpy((void *)PWRCTRL_ACPU_ASM_CODE_BASE, (void *)pm_asm_code,
+ pm_asm_code_end - pm_asm_code);
+
+ reg = mmio_read_32(AO_SC_SYS_CTRL1);
+ reg |= AO_SC_SYS_CTRL1_REMAP_SRAM_AARM |
+ AO_SC_SYS_CTRL1_REMAP_SRAM_AARM_MSK;
+ mmio_write_32(AO_SC_SYS_CTRL1, reg);
+
+ return 0;
+}
diff --git a/plat/hisilicon/hikey/hisi_pwrc_sram.S b/plat/hisilicon/hikey/hisi_pwrc_sram.S
new file mode 100644
index 00000000..054763bb
--- /dev/null
+++ b/plat/hisilicon/hikey/hisi_pwrc_sram.S
@@ -0,0 +1,70 @@
+/*
+ * Copyright (c) 2017, ARM Limited and Contributors. All rights reserved.
+ *
+ * SPDX-License-Identifier: BSD-3-Clause
+ */
+
+#include <arch.h>
+#include <asm_macros.S>
+#include <cortex_a53.h>
+#include <hi6220.h>
+#include <hisi_sram_map.h>
+
+ .global pm_asm_code
+ .global pm_asm_code_end
+ .global v7_asm
+ .global v7_asm_end
+
+ .align 3
+func pm_asm_code
+ mov x0, 0
+ msr oslar_el1, x0
+
+ mrs x0, CPUACTLR_EL1
+ bic x0, x0, #(CPUACTLR_RADIS | CPUACTLR_L1RADIS)
+ orr x0, x0, #0x180000
+ orr x0, x0, #0xe000
+ msr CPUACTLR_EL1, x0
+
+ mrs x3, actlr_el3
+ orr x3, x3, #ACTLR_EL3_L2ECTLR_BIT
+ msr actlr_el3, x3
+
+ mrs x3, actlr_el2
+ orr x3, x3, #ACTLR_EL2_L2ECTLR_BIT
+ msr actlr_el2, x3
+
+ ldr x3, =PWRCTRL_ACPU_ASM_D_ARM_PARA_AD
+ mrs x0, mpidr_el1
+ and x1, x0, #MPIDR_CPU_MASK
+ and x0, x0, #MPIDR_CLUSTER_MASK
+ add x0, x1, x0, LSR #6
+pen: ldr x4, [x3, x0, LSL #3]
+ cbz x4, pen
+
+ mov x0, #0x0
+ mov x1, #0x0
+ mov x2, #0x0
+ mov x3, #0x0
+ br x4
+
+ .ltorg
+
+pm_asm_code_end:
+endfunc pm_asm_code
+
+ /*
+ * By default, all cores in Hi6220 reset with aarch32 mode.
+ * Now hardcode ARMv7 instructions to execute warm reset for
+ * switching aarch64 mode.
+ */
+ .align 3
+ .section .rodata.v7_asm, "aS"
+v7_asm:
+ .word 0xE1A00000 // nop
+ .word 0xE3A02003 // mov r2, #3
+ .word 0xEE0C2F50 // mcr 15, 0, r2, cr12, cr0, {2}
+ .word 0xE320F003 // wfi
+
+ .ltorg
+v7_asm_end:
diff --git a/plat/hisilicon/hikey/include/hisi_ipc.h b/plat/hisilicon/hikey/include/hisi_ipc.h
new file mode 100644
index 00000000..b20742fe
--- /dev/null
+++ b/plat/hisilicon/hikey/include/hisi_ipc.h
@@ -0,0 +1,46 @@
+/*
+ * Copyright (c) 2017, ARM Limited and Contributors. All rights reserved.
+ *
+ * SPDX-License-Identifier: BSD-3-Clause
+ */
+
+#ifndef __HISI_IPC_H__
+#define __HISI_IPC_H__
+
+#define HISI_IPC_CORE_ACPU 0x0
+
+#define HISI_IPC_MCU_INT_SRC_ACPU0_PD 10
+#define HISI_IPC_MCU_INT_SRC_ACPU1_PD 11
+#define HISI_IPC_MCU_INT_SRC_ACPU2_PD 12
+#define HISI_IPC_MCU_INT_SRC_ACPU3_PD 13
+#define HISI_IPC_MCU_INT_SRC_ACPU_PD 16
+#define HISI_IPC_MCU_INT_SRC_ACPU4_PD 26
+#define HISI_IPC_MCU_INT_SRC_ACPU5_PD 27
+#define HISI_IPC_MCU_INT_SRC_ACPU6_PD 28
+#define HISI_IPC_MCU_INT_SRC_ACPU7_PD 29
+
+#define HISI_IPC_SEM_CPUIDLE 27
+#define HISI_IPC_INT_SRC_NUM 32
+
+#define HISI_IPC_PM_ON 0
+#define HISI_IPC_PM_OFF 1
+
+#define HISI_IPC_OK (0)
+#define HISI_IPC_ERROR (-1)
+
+#define HISI_IPC_BASE_ADDR (0xF7510000)
+#define HISI_IPC_CPU_RAW_INT_ADDR (0xF7510420)
+#define HISI_IPC_ACPU_CTRL(i) (0xF7510800 + (i << 3))
+
+void hisi_ipc_spin_lock(unsigned int signal);
+void hisi_ipc_spin_unlock(unsigned int signal);
+void hisi_ipc_cpu_on(unsigned int cpu, unsigned int cluster);
+void hisi_ipc_cpu_off(unsigned int cpu, unsigned int cluster);
+void hisi_ipc_cpu_suspend(unsigned int cpu, unsigned int cluster);
+void hisi_ipc_cluster_on(unsigned int cpu, unsigned int cluster);
+void hisi_ipc_cluster_off(unsigned int cpu, unsigned int cluster);
+void hisi_ipc_cluster_suspend(unsigned int cpu, unsigned int cluster);
+void hisi_ipc_psci_system_off(void);
+int hisi_ipc_init(void);
+
+#endif /* __HISI_IPC_H__ */
diff --git a/plat/hisilicon/hikey/include/hisi_pwrc.h b/plat/hisilicon/hikey/include/hisi_pwrc.h
new file mode 100644
index 00000000..3a87e72b
--- /dev/null
+++ b/plat/hisilicon/hikey/include/hisi_pwrc.h
@@ -0,0 +1,20 @@
+/*
+ * Copyright (c) 2017, ARM Limited and Contributors. All rights reserved.
+ *
+ * SPDX-License-Identifier: BSD-3-Clause
+ */
+
+#ifndef __HISI_PWRC_H__
+#define __HISI_PWRC_H__
+
+#ifndef __ASSEMBLY__
+
+void hisi_pwrc_set_cluster_wfi(unsigned int id);
+void hisi_pwrc_set_core_bx_addr(unsigned int core,
+ unsigned int cluster,
+ uintptr_t entry_point);
+int hisi_pwrc_setup(void);
+
+#endif /*__ASSEMBLY__*/
+
+#endif /* __HISI_PWRC_H__ */
diff --git a/plat/hisilicon/hikey/platform.mk b/plat/hisilicon/hikey/platform.mk
index 9d8f94a7..ec4bb5ca 100644
--- a/plat/hisilicon/hikey/platform.mk
+++ b/plat/hisilicon/hikey/platform.mk
@@ -58,3 +58,20 @@ BL2_SOURCES += drivers/arm/sp804/sp804_delay_timer.c \
plat/hisilicon/hikey/hikey_io_storage.c \
plat/hisilicon/hikey/hisi_dvfs.c \
plat/hisilicon/hikey/hisi_mcu.c
+
+HIKEY_GIC_SOURCES := drivers/arm/gic/common/gic_common.c \
+ drivers/arm/gic/v2/gicv2_main.c \
+ drivers/arm/gic/v2/gicv2_helpers.c \
+ plat/common/plat_gicv2.c
+
+BL31_SOURCES += drivers/arm/cci/cci.c \
+ lib/cpus/aarch64/cortex_a53.S \
+ plat/common/aarch64/plat_psci_common.c \
+ plat/hisilicon/hikey/aarch64/hikey_helpers.S \
+ plat/hisilicon/hikey/hikey_bl31_setup.c \
+ plat/hisilicon/hikey/hikey_pm.c \
+ plat/hisilicon/hikey/hikey_topology.c \
+ plat/hisilicon/hikey/hisi_ipc.c \
+ plat/hisilicon/hikey/hisi_pwrc.c \
+ plat/hisilicon/hikey/hisi_pwrc_sram.S \
+ ${HIKEY_GIC_SOURCES}