Support for Rockchip's family SoCs

This patch adds to support the RK3368 and RK3399 SoCs.

RK3368/RK3399 is one of the Rockchip family SoCs, which is an
multi-cores ARM SoCs.

This patch adds support to boot the Trusted Firmware on RK3368/RK3399
SoCs, and adds support to boot secondary CPUs, enter/exit core
power states for all CPUs in the slow/fast clusters.

This is the initial version for rockchip SoCs.(RK3368/RK3399 and next SoCs)
* Support arm gicv2 & gicv3.
* Boot up multi-cores CPU.
* Add generic CPU helper functions.
* Support suspend/resume.
* Add system_off & system_reset implementation.
* Add delay timer platform implementation.
* Support the new porting interface for the PSCI implementation.

Change-Id: I704bb3532d65e8c70dbd99b512c5e6e440ea6f43
Signed-off-by: Tony Xie <tony.xie@rock-chips.com>
Signed-off-by: Caesar Wang <wxt@rock-chips.com>
Signed-off-by: Shengfei xu <xsf@rock-chips.com>
diff --git a/plat/rockchip/common/aarch64/plat_helpers.S b/plat/rockchip/common/aarch64/plat_helpers.S
new file mode 100644
index 0000000..a90dcd7
--- /dev/null
+++ b/plat/rockchip/common/aarch64/plat_helpers.S
@@ -0,0 +1,252 @@
+/*
+ * Copyright (c) 2013-2016, ARM Limited and Contributors. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *
+ * Redistributions of source code must retain the above copyright notice, this
+ * list of conditions and the following disclaimer.
+ *
+ * Redistributions in binary form must reproduce the above copyright notice,
+ * this list of conditions and the following disclaimer in the documentation
+ * and/or other materials provided with the distribution.
+ *
+ * Neither the name of ARM nor the names of its contributors may be used
+ * to endorse or promote products derived from this software without specific
+ * prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
+ * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
+ * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
+ * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
+ * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ */
+
+#include <arch.h>
+#include <asm_macros.S>
+#include <bl_common.h>
+#include <cortex_a53.h>
+#include <cortex_a72.h>
+#include <plat_private.h>
+#include <platform_def.h>
+
+	.globl	cpuson_entry_point
+	.globl	cpuson_flags
+	.globl	platform_cpu_warmboot
+	.globl	plat_secondary_cold_boot_setup
+	.globl	plat_report_exception
+	.globl	platform_is_primary_cpu
+	.globl	plat_crash_console_init
+	.globl	plat_crash_console_putc
+	.globl	plat_my_core_pos
+	.globl	plat_reset_handler
+
+
+#define RK_REVISION(rev) RK_PLAT_CFG##rev
+#define RK_HANDLER(rev) plat_reset_handler_juno_r##rev
+#define JUMP_TO_HANDLER_IF_RK_R(revision)	\
+	jump_to_handler RK_REVISION(revision), RK_HANDLER(revision)
+
+	/*
+	 * Helper macro to jump to the given handler if the board revision
+	 * matches.
+	 * Expects the Juno board revision in x0.
+	 *
+	 */
+	.macro jump_to_handler _revision, _handler
+	cmp	x0, #\_revision
+	b.eq	\_handler
+	.endm
+
+	/*
+	 * Helper macro that reads the part number of the current CPU and jumps
+	 * to the given label if it matches the CPU MIDR provided.
+	 */
+	.macro  jump_if_cpu_midr _cpu_midr, _label
+	mrs	x0, midr_el1
+	ubfx	x0, x0, MIDR_PN_SHIFT, #12
+	cmp     w0, #((\_cpu_midr >> MIDR_PN_SHIFT) & MIDR_PN_MASK)
+	b.eq	\_label
+	.endm
+
+	/*
+	 * Platform reset handler for rockchip.
+	 * only A53 cores
+	 */
+func RK_HANDLER(0)
+	ret
+endfunc RK_HANDLER(0)
+
+	/*
+	 * Platform reset handler for rockchip.
+	 * - Cortex-A53 processor cluster;
+	 * - Cortex-A72 processor cluster.
+	 *
+	 * This handler does the following:
+	 * - Set the L2 Data RAM latency to 2 (i.e. 3 cycles) for Cortex-A72
+	 * - Set the L2 Tag RAM latency to 1 (i.e. 2 cycles) for Cortex-A72
+	 */
+func RK_HANDLER(1)
+	/*
+	 * Nothing to do on Cortex-A53.
+	 *
+	 */
+	jump_if_cpu_midr CORTEX_A72_MIDR, A72
+	ret
+
+A72:
+	/* Cortex-A72 specific settings */
+	mov	x0, #((2 << L2CTLR_DATA_RAM_LATENCY_SHIFT) |	\
+		     (0x1 << 5))
+	msr     L2CTLR_EL1, x0
+	isb
+	ret
+endfunc RK_HANDLER(1)
+
+	/*
+	 * void plat_reset_handler(void);
+	 *
+	 * Determine the SOC type and call the appropriate reset
+	 * handler.
+	 *
+	 */
+func plat_reset_handler
+
+	mov	x0, RK_PLAT_AARCH_CFG
+
+	JUMP_TO_HANDLER_IF_RK_R(0)
+	JUMP_TO_HANDLER_IF_RK_R(1)
+
+	/* SOC type is not supported */
+not_supported:
+	b	not_supported
+endfunc plat_reset_handler
+
+func plat_my_core_pos
+	mrs	x0, mpidr_el1
+	and	x1, x0, #MPIDR_CPU_MASK
+	and	x0, x0, #MPIDR_CLUSTER_MASK
+	add	x0, x1, x0, LSR #6
+	ret
+endfunc plat_my_core_pos
+
+	/* --------------------------------------------------------------------
+	 * void plat_secondary_cold_boot_setup (void);
+	 *
+	 * This function performs any platform specific actions
+	 * needed for a secondary cpu after a cold reset e.g
+	 * mark the cpu's presence, mechanism to place it in a
+	 * holding pen etc.
+	 * --------------------------------------------------------------------
+	 */
+func plat_secondary_cold_boot_setup
+	/* rk3368 does not do cold boot for secondary CPU */
+cb_panic:
+	b	cb_panic
+endfunc plat_secondary_cold_boot_setup
+
+func platform_is_primary_cpu
+	and	x0, x0, #(MPIDR_CLUSTER_MASK | MPIDR_CPU_MASK)
+	cmp	x0, #PLAT_RK_PRIMARY_CPU
+	cset	x0, eq
+	ret
+endfunc platform_is_primary_cpu
+
+	/* --------------------------------------------------------------------
+	 * int plat_crash_console_init(void)
+	 * Function to initialize the crash console
+	 * without a C Runtime to print crash report.
+	 * Clobber list : x0, x1, x2
+	 * --------------------------------------------------------------------
+	 */
+func plat_crash_console_init
+	mov_imm	x0, PLAT_RK_UART_BASE
+	mov_imm	x1, PLAT_RK_UART_CLOCK
+	mov_imm	x2, PLAT_RK_UART_BAUDRATE
+	b	console_core_init
+endfunc plat_crash_console_init
+
+	/* --------------------------------------------------------------------
+	 * int plat_crash_console_putc(void)
+	 * Function to print a character on the crash
+	 * console without a C Runtime.
+	 * Clobber list : x1, x2
+	 * --------------------------------------------------------------------
+	 */
+func plat_crash_console_putc
+	mov_imm x1, PLAT_RK_UART_BASE
+	b	console_core_putc
+endfunc plat_crash_console_putc
+
+	/* --------------------------------------------------------------------
+	 * void platform_cpu_warmboot (void);
+	 * cpus online or resume enterpoint
+	 * --------------------------------------------------------------------
+	 */
+func platform_cpu_warmboot
+	mrs	x0, MPIDR_EL1
+	and	x1, x0, #MPIDR_CPU_MASK
+	and	x0, x0, #MPIDR_CLUSTER_MASK
+	/* --------------------------------------------------------------------
+	 * big cluster id is 1
+	 * big cores id is from 0-3, little cores id 4-7
+	 * --------------------------------------------------------------------
+	 */
+	add	x0, x1, x0, lsr #6
+	/* --------------------------------------------------------------------
+	 * get per cpuup flag
+         * --------------------------------------------------------------------
+	 */
+	adr	x4, cpuson_flags
+	add	x4, x4, x0, lsl #2
+	ldr	w1, [x4]
+	/* --------------------------------------------------------------------
+	 * get per cpuup boot addr
+         * --------------------------------------------------------------------
+	 */
+	adr	x5, cpuson_entry_point
+	ldr	x2, [x5, x0, lsl #3]
+	/* --------------------------------------------------------------------
+	 * check cpuon reason
+         * --------------------------------------------------------------------
+	 */
+	ldr	w3, =PMU_CPU_AUTO_PWRDN
+	cmp	w1, w3
+	b.eq	boot_entry
+	ldr	w3, =PMU_CPU_HOTPLUG
+	cmp	w1, w3
+	b.eq	boot_entry
+	/* --------------------------------------------------------------------
+	 * If the boot core cpuson_flags or cpuson_entry_point is not
+	 * expection. force the core into wfe.
+         * --------------------------------------------------------------------
+	 */
+wfe_loop:
+	wfe
+	b	wfe_loop
+boot_entry:
+	mov	w0, #0
+	str	w0, [x4]
+	br	x2
+endfunc platform_cpu_warmboot
+
+	/* --------------------------------------------------------------------
+	 * Per-CPU Secure entry point - resume or power up
+	 * --------------------------------------------------------------------
+	 */
+	.section tzfw_coherent_mem, "a"
+	.align  3
+cpuson_entry_point:
+	.rept	PLATFORM_CORE_COUNT
+	.quad	0
+	.endr
+cpuson_flags:
+	.rept	PLATFORM_CORE_COUNT
+	.quad	0
+	.endr
diff --git a/plat/rockchip/common/aarch64/platform_common.c b/plat/rockchip/common/aarch64/platform_common.c
new file mode 100644
index 0000000..3f912a4
--- /dev/null
+++ b/plat/rockchip/common/aarch64/platform_common.c
@@ -0,0 +1,107 @@
+/*
+ * Copyright (c) 2013-2016, 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 <bl_common.h>
+#include <cci.h>
+#include <debug.h>
+#include <string.h>
+#include <xlat_tables.h>
+#include <platform_def.h>
+#include <plat_private.h>
+
+#ifdef PLAT_RK_CCI_BASE
+static const int cci_map[] = {
+	PLAT_RK_CCI_CLUSTER0_SL_IFACE_IX,
+	PLAT_RK_CCI_CLUSTER1_SL_IFACE_IX
+};
+#endif
+
+/******************************************************************************
+ * 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
+ ******************************************************************************/
+#define DEFINE_CONFIGURE_MMU_EL(_el)					\
+	void plat_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(plat_rk_mmap);					\
+		init_xlat_tables();					\
+									\
+		enable_mmu_el ## _el(0);				\
+	}
+
+/* Define EL3 variants of the function initialising the MMU */
+DEFINE_CONFIGURE_MMU_EL(3)
+
+uint64_t plat_get_syscnt_freq(void)
+{
+	return SYS_COUNTER_FREQ_IN_TICKS;
+}
+
+void plat_cci_init(void)
+{
+#ifdef PLAT_RK_CCI_BASE
+	/* Initialize CCI driver */
+	cci_init(PLAT_RK_CCI_BASE, cci_map, ARRAY_SIZE(cci_map));
+#endif
+}
+
+void plat_cci_enable(void)
+{
+	/*
+	 * Enable CCI coherency for this cluster.
+	 * No need for locks as no other cpu is active at the moment.
+	 */
+#ifdef PLAT_RK_CCI_BASE
+	cci_enable_snoop_dvm_reqs(MPIDR_AFFLVL1_VAL(read_mpidr()));
+#endif
+}
+
+void plat_cci_disable(void)
+{
+#ifdef PLAT_RK_CCI_BASE
+	cci_disable_snoop_dvm_reqs(MPIDR_AFFLVL1_VAL(read_mpidr()));
+#endif
+}
diff --git a/plat/rockchip/common/bl31_plat_setup.c b/plat/rockchip/common/bl31_plat_setup.c
new file mode 100644
index 0000000..30fb5ac
--- /dev/null
+++ b/plat/rockchip/common/bl31_plat_setup.c
@@ -0,0 +1,152 @@
+/*
+ * Copyright (c) 2016, 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 <arm_gic.h>
+#include <assert.h>
+#include <bl_common.h>
+#include <console.h>
+#include <debug.h>
+#include <mmio.h>
+#include <platform.h>
+#include <plat_private.h>
+#include <platform_def.h>
+
+/*******************************************************************************
+ * Declarations of linker defined symbols which will help us find the layout
+ * of trusted SRAM
+ ******************************************************************************/
+unsigned long __RO_START__;
+unsigned long __RO_END__;
+
+unsigned long __COHERENT_RAM_START__;
+unsigned long __COHERENT_RAM_END__;
+
+/*
+ * 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;
+
+/*******************************************************************************
+ * Return a pointer to the 'entry_point_info' structure of the next image for
+ * the security state specified. BL33 corresponds to the non-secure image type
+ * while BL32 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 early platform setup. 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.
+ * 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)
+{
+	console_init(PLAT_RK_UART_BASE, PLAT_RK_UART_CLOCK,
+		     PLAT_RK_UART_BAUDRATE);
+
+	VERBOSE("bl31_setup\n");
+
+	/* Passing a NULL context is a critical programming error */
+	assert(from_bl2);
+
+	assert(from_bl2->h.type == PARAM_BL31);
+	assert(from_bl2->h.version >= VERSION_1);
+
+	bl32_ep_info = *from_bl2->bl32_ep_info;
+	bl33_ep_info = *from_bl2->bl33_ep_info;
+
+	/*
+	 * The code for resuming cpu from suspend must be excuted in pmusram.
+	 * Copy the code into pmusram.
+	 */
+	plat_rockchip_pmusram_prepare();
+}
+
+/*******************************************************************************
+ * Perform any BL3-1 platform setup code
+ ******************************************************************************/
+void bl31_platform_setup(void)
+{
+	plat_delay_timer_init();
+	plat_rockchip_soc_init();
+
+	/* Initialize the gic cpu and distributor interfaces */
+	plat_rockchip_gic_driver_init();
+	plat_rockchip_gic_init();
+	plat_rockchip_pmu_init();
+}
+
+/*******************************************************************************
+ * 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)
+{
+	plat_cci_init();
+	plat_cci_enable();
+	plat_configure_mmu_el3(BL31_RO_BASE,
+			       (BL31_COHERENT_RAM_LIMIT - BL31_RO_BASE),
+			       BL31_RO_BASE,
+			       BL31_RO_LIMIT,
+			       BL31_COHERENT_RAM_BASE,
+			       BL31_COHERENT_RAM_LIMIT);
+}
diff --git a/plat/rockchip/common/drivers/pmu/pmu_com.h b/plat/rockchip/common/drivers/pmu/pmu_com.h
new file mode 100644
index 0000000..0cab53c
--- /dev/null
+++ b/plat/rockchip/common/drivers/pmu/pmu_com.h
@@ -0,0 +1,122 @@
+/*
+ * Copyright (c) 2016, 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.
+ *
+ * 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 __PMU_COM_H__
+#define __PMU_COM_H__
+
+DEFINE_BAKERY_LOCK(rockchip_pd_lock);
+
+#define rockchip_pd_lock_get() bakery_lock_get(&rockchip_pd_lock)
+
+#define rockchip_pd_lock_rls() bakery_lock_release(&rockchip_pd_lock)
+
+#define rockchip_pd_lock_init() bakery_lock_init(&rockchip_pd_lock)
+/*****************************************************************************
+ * power domain on or off
+ *****************************************************************************/
+enum pmu_pd_state {
+	pmu_pd_on = 0,
+	pmu_pd_off = 1
+};
+
+#pragma weak plat_ic_get_pending_interrupt_id
+#pragma weak pmu_power_domain_ctr
+#pragma weak check_cpu_wfie
+
+static inline uint32_t pmu_power_domain_st(uint32_t pd)
+{
+	uint32_t pwrdn_st = mmio_read_32(PMU_BASE + PMU_PWRDN_ST) &  BIT(pd);
+
+	if (pwrdn_st)
+		return pmu_pd_off;
+	else
+		return pmu_pd_on;
+}
+
+static int pmu_power_domain_ctr(uint32_t pd, uint32_t pd_state)
+{
+	uint32_t val;
+	uint32_t loop = 0;
+	int ret = 0;
+
+	rockchip_pd_lock_get();
+
+	val = mmio_read_32(PMU_BASE + PMU_PWRDN_CON);
+	if (pd_state == pmu_pd_off)
+		val |=  BIT(pd);
+	else
+		val &= ~BIT(pd);
+
+	mmio_write_32(PMU_BASE + PMU_PWRDN_CON, val);
+	dsb();
+
+	while ((pmu_power_domain_st(pd) != pd_state) && (loop < PD_CTR_LOOP)) {
+		udelay(1);
+		loop++;
+	}
+
+	if (pmu_power_domain_st(pd) != pd_state) {
+		WARN("%s: %d, %d, error!\n", __func__, pd, pd_state);
+		ret = -EINVAL;
+	}
+
+	rockchip_pd_lock_rls();
+
+	return ret;
+}
+
+static int check_cpu_wfie(uint32_t cpu_id, uint32_t wfie_msk)
+{
+	uint32_t cluster_id, loop = 0;
+
+	if (cpu_id >= PLATFORM_CLUSTER0_CORE_COUNT) {
+		cluster_id = 1;
+		cpu_id -= PLATFORM_CLUSTER0_CORE_COUNT;
+	} else {
+		cluster_id = 0;
+	}
+
+	if (cluster_id)
+		wfie_msk <<= (clstb_cpu_wfe + cpu_id);
+	else
+		wfie_msk <<= (clstl_cpu_wfe + cpu_id);
+
+	while (!(mmio_read_32(PMU_BASE + PMU_CORE_PWR_ST) & wfie_msk) &&
+	       (loop < CHK_CPU_LOOP)) {
+		udelay(1);
+		loop++;
+	}
+
+	if ((mmio_read_32(PMU_BASE + PMU_CORE_PWR_ST) & wfie_msk) == 0) {
+		WARN("%s: %d, %d, %d, error!\n", __func__,
+		     cluster_id, cpu_id, wfie_msk);
+		return -EINVAL;
+	}
+
+	return 0;
+}
+
+#endif /* __PMU_COM_H__ */
diff --git a/plat/rockchip/common/include/plat_macros.S b/plat/rockchip/common/include/plat_macros.S
new file mode 100644
index 0000000..ce68cf1
--- /dev/null
+++ b/plat/rockchip/common/include/plat_macros.S
@@ -0,0 +1,151 @@
+/*
+ * Copyright (c) 2014-2016, 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 __ROCKCHIP_PLAT_MACROS_S__
+#define __ROCKCHIP_PLAT_MACROS_S__
+
+#include <cci.h>
+#include <gic_common.h>
+#include <gicv2.h>
+#include <gicv3.h>
+#include <platform_def.h>
+
+.section .rodata.gic_reg_name, "aS"
+/* Applicable only to GICv2 and GICv3 with SRE disabled (legacy mode) */
+gicc_regs:
+	.asciz "gicc_hppir", "gicc_ahppir", "gicc_ctlr", ""
+
+/* Applicable only to GICv3 with SRE enabled */
+icc_regs:
+	.asciz "icc_hppir0_el1", "icc_hppir1_el1", "icc_ctlr_el3", ""
+
+/* Registers common to both GICv2 and GICv3 */
+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 utility macro prints out relevant GIC
+	 * registers whenever an unhandled exception is
+	 * taken in BL31 on ARM standard platforms.
+	 * Expects: GICD base in x16, GICC base in x17
+	 * Clobbers: x0 - x10, sp
+	 * ---------------------------------------------
+	 */
+	.macro plat_print_gic_regs
+
+	mov_imm	x16, PLAT_RK_GICD_BASE
+	mov_imm	x17, PLAT_RK_GICC_BASE
+
+	/* Check for GICv3 system register access */
+	mrs	x7, id_aa64pfr0_el1
+	ubfx	x7, x7, #ID_AA64PFR0_GIC_SHIFT, #ID_AA64PFR0_GIC_WIDTH
+	cmp	x7, #1
+	b.ne	print_gicv2
+
+	/* Check for SRE enable */
+	mrs	x8, ICC_SRE_EL3
+	tst	x8, #ICC_SRE_SRE_BIT
+	b.eq	print_gicv2
+
+	/* Load the icc reg list to x6 */
+	adr	x6, icc_regs
+	/* Load the icc regs to gp regs used by str_in_crash_buf_print */
+	mrs	x8, ICC_HPPIR0_EL1
+	mrs	x9, ICC_HPPIR1_EL1
+	mrs	x10, ICC_CTLR_EL3
+	/* Store to the crash buf and print to console */
+	bl	str_in_crash_buf_print
+	b	print_gic_common
+
+print_gicv2:
+	/* Load the gicc reg list to x6 */
+	adr	x6, gicc_regs
+	/* 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_gic_common:
+	/* 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
+#if PLATFORM_CLUSTER_COUNT > 1
+	adr	x6, cci_iface_regs
+	/* Store in x7 the base address of the first interface */
+	mov_imm	x7, (PLAT_RK_CCI_BASE + SLAVE_IFACE_OFFSET(	\
+			PLAT_RK_CCI_CLUSTER0_SL_IFACE_IX))
+	ldr	w8, [x7, #SNOOP_CTRL_REG]
+	/* Store in x7 the base address of the second interface */
+	mov_imm	x7, (PLAT_RK_CCI_BASE + SLAVE_IFACE_OFFSET(	\
+			PLAT_RK_CCI_CLUSTER1_SL_IFACE_IX))
+	ldr	w9, [x7, #SNOOP_CTRL_REG]
+	/* Store to the crash buf and print to console */
+	bl	str_in_crash_buf_print
+#endif
+	.endm
+
+#endif /* __ROCKCHIP_PLAT_MACROS_S__ */
diff --git a/plat/rockchip/common/include/plat_private.h b/plat/rockchip/common/include/plat_private.h
new file mode 100644
index 0000000..67fb827
--- /dev/null
+++ b/plat/rockchip/common/include/plat_private.h
@@ -0,0 +1,127 @@
+/*
+ * Copyright (c) 2014-2016, ARM Limited and Contributors. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *
+ * Redistributions of source code must retain the above copyright notice, this
+ * list of conditions and the following disclaimer.
+ *
+ * Redistributions in binary form must reproduce the above copyright notice,
+ * this list of conditions and the following disclaimer in the documentation
+ * and/or other materials provided with the distribution.
+ *
+ * Neither the name of ARM nor the names of its contributors may be used
+ * to endorse or promote products derived from this software without specific
+ * prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
+ * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
+ * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
+ * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
+ * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ */
+
+#ifndef __PLAT_PRIVATE_H__
+#define __PLAT_PRIVATE_H__
+
+#ifndef __ASSEMBLY__
+#include <mmio.h>
+#include <stdint.h>
+#include <xlat_tables.h>
+
+/******************************************************************************
+ * For rockchip socs pm ops
+ ******************************************************************************/
+struct rockchip_pm_ops_cb {
+	int (*cores_pwr_dm_on)(unsigned long mpidr, uint64_t entrypoint);
+	int (*cores_pwr_dm_off)(void);
+	int (*cores_pwr_dm_on_finish)(void);
+	int (*cores_pwr_dm_suspend)(void);
+	int (*cores_pwr_dm_resume)(void);
+	int (*sys_pwr_dm_suspend)(void);
+	int (*sys_pwr_dm_resume)(void);
+	void (*sys_gbl_soft_reset)(void) __dead2;
+	void (*system_off)(void) __dead2;
+};
+
+/******************************************************************************
+ * The register have write-mask bits, it is mean, if you want to set the bits,
+ * you needs set the write-mask bits at the same time,
+ * The write-mask bits is in high 16-bits.
+ * The fllowing macro definition helps access write-mask bits reg efficient!
+ ******************************************************************************/
+#define REG_MSK_SHIFT	16
+
+#ifndef BIT
+#define BIT(nr)			(1 << (nr))
+#endif
+
+#ifndef WMSK_BIT
+#define WMSK_BIT(nr)		BIT((nr) + REG_MSK_SHIFT)
+#endif
+
+/* set one bit with write mask */
+#ifndef BIT_WITH_WMSK
+#define BIT_WITH_WMSK(nr)	(BIT(nr) | WMSK_BIT(nr))
+#endif
+
+#ifndef BITS_SHIFT
+#define BITS_SHIFT(bits, shift)	(bits << (shift))
+#endif
+
+#ifndef BITS_WITH_WMASK
+#define BITS_WITH_WMASK(msk, bits, shift)\
+	(BITS_SHIFT(bits, shift) | BITS_SHIFT(msk, (shift + REG_MSK_SHIFT)))
+#endif
+
+/******************************************************************************
+ * Function and variable prototypes
+ *****************************************************************************/
+void plat_configure_mmu_el3(unsigned long total_base,
+			    unsigned long total_size,
+			    unsigned long,
+			    unsigned long,
+			    unsigned long,
+			    unsigned long);
+
+void plat_cci_init(void);
+void plat_cci_enable(void);
+void plat_cci_disable(void);
+
+void plat_delay_timer_init(void);
+
+void plat_rockchip_gic_driver_init(void);
+void plat_rockchip_gic_init(void);
+void plat_rockchip_gic_cpuif_enable(void);
+void plat_rockchip_gic_cpuif_disable(void);
+void plat_rockchip_gic_pcpu_init(void);
+
+void plat_rockchip_pmusram_prepare(void);
+void plat_rockchip_pmu_init(void);
+void plat_rockchip_soc_init(void);
+void plat_setup_rockchip_pm_ops(struct rockchip_pm_ops_cb *ops);
+
+extern const unsigned char rockchip_power_domain_tree_desc[];
+
+extern void *pmu_cpuson_entrypoint_start;
+extern void *pmu_cpuson_entrypoint_end;
+extern uint64_t cpuson_entry_point[PLATFORM_CORE_COUNT];
+extern uint32_t cpuson_flags[PLATFORM_CORE_COUNT];
+
+extern const mmap_region_t plat_rk_mmap[];
+#endif /* __ASSEMBLY__ */
+
+/* only Cortex-A53 */
+#define RK_PLAT_CFG0	0
+
+/* include Cortex-A72 */
+#define RK_PLAT_CFG1	1
+
+#endif /* __PLAT_PRIVATE_H__ */
diff --git a/plat/rockchip/common/plat_delay_timer.c b/plat/rockchip/common/plat_delay_timer.c
new file mode 100644
index 0000000..797ce05
--- /dev/null
+++ b/plat/rockchip/common/plat_delay_timer.c
@@ -0,0 +1,54 @@
+/*
+ * Copyright (c) 2016, 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 <delay_timer.h>
+#include <platform_def.h>
+
+static uint32_t plat_get_timer_value(void)
+{
+	/*
+	 * Generic delay timer implementation expects the timer to be a down
+	 * counter. We apply bitwise NOT operator to the tick values returned
+	 * by read_cntpct_el0() to simulate the down counter.
+	 */
+	return (uint32_t)(~read_cntpct_el0());
+}
+
+static const timer_ops_t plat_timer_ops = {
+	.get_timer_value	= plat_get_timer_value,
+	.clk_mult		= 1,
+	.clk_div		= SYS_COUNTER_FREQ_IN_MHZ,
+};
+
+void plat_delay_timer_init(void)
+{
+	timer_init(&plat_timer_ops);
+}
diff --git a/plat/rockchip/common/plat_pm.c b/plat/rockchip/common/plat_pm.c
new file mode 100644
index 0000000..fcd47a8
--- /dev/null
+++ b/plat/rockchip/common/plat_pm.c
@@ -0,0 +1,286 @@
+/*
+ * Copyright (c) 2013-2016, 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 <console.h>
+#include <errno.h>
+#include <debug.h>
+#include <psci.h>
+#include <delay_timer.h>
+#include <platform_def.h>
+#include <plat_private.h>
+
+/* Macros to read the rk power domain state */
+#define RK_CORE_PWR_STATE(state) \
+	((state)->pwr_domain_state[MPIDR_AFFLVL0])
+#define RK_CLUSTER_PWR_STATE(state) \
+	((state)->pwr_domain_state[MPIDR_AFFLVL1])
+#define RK_SYSTEM_PWR_STATE(state) \
+	((state)->pwr_domain_state[PLAT_MAX_PWR_LVL])
+
+static uintptr_t rockchip_sec_entrypoint;
+
+static struct rockchip_pm_ops_cb *rockchip_ops;
+
+static void plat_rockchip_sys_pwr_domain_resume(void)
+{
+	plat_rockchip_gic_init();
+	if (rockchip_ops && rockchip_ops->sys_pwr_dm_resume)
+		rockchip_ops->sys_pwr_dm_resume();
+}
+
+static void plat_rockchip_cores_pwr_domain_resume(void)
+{
+	if (rockchip_ops && rockchip_ops->cores_pwr_dm_resume)
+		rockchip_ops->cores_pwr_dm_resume();
+
+	/* Enable the gic cpu interface */
+	plat_rockchip_gic_pcpu_init();
+	/* Program the gic per-cpu distributor or re-distributor interface */
+	plat_rockchip_gic_cpuif_enable();
+}
+
+/*******************************************************************************
+ * Rockchip standard platform handler called to check the validity of the power
+ * state parameter.
+ ******************************************************************************/
+int rockchip_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 probably 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;
+}
+
+void rockchip_get_sys_suspend_power_state(psci_power_state_t *req_state)
+{
+	int i;
+
+	for (i = MPIDR_AFFLVL0; i <= PLAT_MAX_PWR_LVL; i++)
+		req_state->pwr_domain_state[i] = PLAT_MAX_OFF_STATE;
+}
+
+/*******************************************************************************
+ * RockChip handler called when a CPU is about to enter standby.
+ ******************************************************************************/
+void rockchip_cpu_standby(plat_local_state_t cpu_state)
+{
+	unsigned int scr;
+
+	assert(cpu_state == PLAT_MAX_RET_STATE);
+
+	scr = read_scr_el3();
+	/* Enable PhysicalIRQ bit for NS world to wake the CPU */
+	write_scr_el3(scr | SCR_IRQ_BIT);
+	isb();
+	dsb();
+	wfi();
+
+	/*
+	 * Restore SCR to the original value, synchronisation of scr_el3 is
+	 * done by eret while el3_exit to save some execution cycles.
+	 */
+	write_scr_el3(scr);
+}
+
+/*******************************************************************************
+ * RockChip handler called when a power domain is about to be turned on. The
+ * mpidr determines the CPU to be turned on.
+ ******************************************************************************/
+int rockchip_pwr_domain_on(u_register_t mpidr)
+{
+	if (rockchip_ops && rockchip_ops->cores_pwr_dm_on)
+		rockchip_ops->cores_pwr_dm_on(mpidr, rockchip_sec_entrypoint);
+
+	return PSCI_E_SUCCESS;
+}
+
+/*******************************************************************************
+ * RockChip 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 rockchip_pwr_domain_off(const psci_power_state_t *target_state)
+{
+	assert(RK_CORE_PWR_STATE(target_state) == PLAT_MAX_OFF_STATE);
+
+	plat_rockchip_gic_cpuif_disable();
+
+	if (RK_CLUSTER_PWR_STATE(target_state) == PLAT_MAX_OFF_STATE)
+		plat_cci_disable();
+	if (rockchip_ops && rockchip_ops->cores_pwr_dm_off)
+		rockchip_ops->cores_pwr_dm_off();
+}
+
+/*******************************************************************************
+ * RockChip handler called when a power domain is about to be suspended. The
+ * target_state encodes the power state that each level should transition to.
+ ******************************************************************************/
+void rockchip_pwr_domain_suspend(const psci_power_state_t *target_state)
+{
+	if (RK_CORE_PWR_STATE(target_state) == PLAT_MAX_RET_STATE)
+		return;
+
+	assert(RK_CORE_PWR_STATE(target_state) == PLAT_MAX_OFF_STATE);
+
+	if (RK_SYSTEM_PWR_STATE(target_state) == PLAT_MAX_OFF_STATE) {
+		if (rockchip_ops && rockchip_ops->sys_pwr_dm_suspend)
+			rockchip_ops->sys_pwr_dm_suspend();
+	} else {
+		if (rockchip_ops && rockchip_ops->cores_pwr_dm_suspend)
+			rockchip_ops->cores_pwr_dm_suspend();
+	}
+
+	/* Prevent interrupts from spuriously waking up this cpu */
+	plat_rockchip_gic_cpuif_disable();
+
+	/* Perform the common cluster specific operations */
+	if (RK_CLUSTER_PWR_STATE(target_state) == PLAT_MAX_OFF_STATE)
+		plat_cci_disable();
+}
+
+/*******************************************************************************
+ * RockChip handler called when a power domain has just been powered on after
+ * being turned off earlier. The target_state encodes the low power state that
+ * each level has woken up from.
+ ******************************************************************************/
+void rockchip_pwr_domain_on_finish(const psci_power_state_t *target_state)
+{
+	assert(RK_CORE_PWR_STATE(target_state) == PLAT_MAX_OFF_STATE);
+
+	if (rockchip_ops && rockchip_ops->cores_pwr_dm_on_finish)
+		rockchip_ops->cores_pwr_dm_on_finish();
+
+	/* Perform the common cluster specific operations */
+	if (RK_CLUSTER_PWR_STATE(target_state) == PLAT_MAX_OFF_STATE) {
+		/* Enable coherency if this cluster was off */
+		plat_cci_enable();
+	}
+
+	/* Enable the gic cpu interface */
+	plat_rockchip_gic_pcpu_init();
+
+	/* Program the gic per-cpu distributor or re-distributor interface */
+	plat_rockchip_gic_cpuif_enable();
+}
+
+/*******************************************************************************
+ * RockChip handler called when a power domain has just been powered on after
+ * having been suspended earlier. The target_state encodes the low power state
+ * that each level has woken up from.
+ * TODO: At the moment we reuse the on finisher and reinitialize the secure
+ * context. Need to implement a separate suspend finisher.
+ ******************************************************************************/
+void rockchip_pwr_domain_suspend_finish(const psci_power_state_t *target_state)
+{
+	/* Nothing to be done on waking up from retention from CPU level */
+	if (RK_CORE_PWR_STATE(target_state) == PLAT_MAX_RET_STATE)
+		return;
+
+	/* Perform system domain restore if woken up from system suspend */
+	if (RK_SYSTEM_PWR_STATE(target_state) == PLAT_MAX_OFF_STATE)
+		plat_rockchip_sys_pwr_domain_resume();
+	else
+		plat_rockchip_cores_pwr_domain_resume();
+
+	/* Perform the common cluster specific operations */
+	if (RK_CLUSTER_PWR_STATE(target_state) == PLAT_MAX_OFF_STATE) {
+		/* Enable coherency if this cluster was off */
+		plat_cci_enable();
+	}
+}
+
+/*******************************************************************************
+ * RockChip handlers to reboot the system
+ ******************************************************************************/
+static void __dead2 rockchip_system_reset(void)
+{
+	assert(rockchip_ops && rockchip_ops->sys_gbl_soft_reset);
+
+	rockchip_ops->sys_gbl_soft_reset();
+}
+
+/*******************************************************************************
+ * Export the platform handlers via plat_rockchip_psci_pm_ops. The rockchip
+ * standard
+ * platform layer will take care of registering the handlers with PSCI.
+ ******************************************************************************/
+const plat_psci_ops_t plat_rockchip_psci_pm_ops = {
+	.cpu_standby = rockchip_cpu_standby,
+	.pwr_domain_on = rockchip_pwr_domain_on,
+	.pwr_domain_off = rockchip_pwr_domain_off,
+	.pwr_domain_suspend = rockchip_pwr_domain_suspend,
+	.pwr_domain_on_finish = rockchip_pwr_domain_on_finish,
+	.pwr_domain_suspend_finish = rockchip_pwr_domain_suspend_finish,
+	.system_reset = rockchip_system_reset,
+	.validate_power_state = rockchip_validate_power_state,
+	.get_sys_suspend_power_state = rockchip_get_sys_suspend_power_state
+};
+
+int plat_setup_psci_ops(uintptr_t sec_entrypoint,
+			const plat_psci_ops_t **psci_ops)
+{
+	*psci_ops = &plat_rockchip_psci_pm_ops;
+	rockchip_sec_entrypoint = sec_entrypoint;
+	return 0;
+}
+
+void plat_setup_rockchip_pm_ops(struct rockchip_pm_ops_cb *ops)
+{
+	rockchip_ops = ops;
+}
diff --git a/plat/rockchip/common/plat_topology.c b/plat/rockchip/common/plat_topology.c
new file mode 100644
index 0000000..911978a
--- /dev/null
+++ b/plat/rockchip/common/plat_topology.c
@@ -0,0 +1,55 @@
+/*
+ * Copyright (c) 2013-2016, 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 <platform_def.h>
+#include <plat_private.h>
+#include <psci.h>
+
+/*******************************************************************************
+ * This function returns the RockChip default topology tree information.
+ ******************************************************************************/
+const unsigned char *plat_get_power_domain_tree_desc(void)
+{
+	return rockchip_power_domain_tree_desc;
+}
+
+int plat_core_pos_by_mpidr(u_register_t mpidr)
+{
+	unsigned int cluster_id, cpu_id;
+
+	cpu_id = MPIDR_AFFLVL0_VAL(mpidr);
+	cluster_id = MPIDR_AFFLVL1_VAL(mpidr);
+
+	if (cluster_id >= PLATFORM_CLUSTER_COUNT)
+		return -1;
+
+	return ((cluster_id * PLATFORM_CLUSTER0_CORE_COUNT) + cpu_id);
+}
diff --git a/plat/rockchip/common/pmusram/pmu_sram.c b/plat/rockchip/common/pmusram/pmu_sram.c
new file mode 100644
index 0000000..bea4875
--- /dev/null
+++ b/plat/rockchip/common/pmusram/pmu_sram.c
@@ -0,0 +1,38 @@
+/*
+ * Copyright (c) 2016, 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.
+ *
+ * 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 <platform.h>
+
+/*****************************************************************************
+ * sram only surpport 32-bits access
+ ******************************************************************************/
+void u32_align_cpy(uint32_t *dst, const uint32_t *src, size_t bytes)
+{
+	uint32_t i;
+
+	for (i = 0; i < bytes; i++)
+		dst[i] = src[i];
+}
diff --git a/plat/rockchip/common/pmusram/pmu_sram.h b/plat/rockchip/common/pmusram/pmu_sram.h
new file mode 100644
index 0000000..a2ab460
--- /dev/null
+++ b/plat/rockchip/common/pmusram/pmu_sram.h
@@ -0,0 +1,91 @@
+/* Copyright (c) 2016, 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.
+ *
+ * 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 __PMU_SRAM_H__
+#define __PMU_SRAM_H__
+
+/*****************************************************************************
+ * cpu up status
+ *****************************************************************************/
+#define PMU_SYS_SLP_MODE	0xa5
+#define PMU_SYS_ON_MODE		0x0
+
+/*****************************************************************************
+ * define data offset in struct psram_data
+ *****************************************************************************/
+#define PSRAM_DT_SP		0x0
+#define PSRAM_DT_DDR_FUNC	0x8
+#define PSRAM_DT_DDR_DATA	0x10
+#define PSRAM_DT_DDRFLAG	0x18
+#define PSRAM_DT_SYS_MODE	0x1c
+#define PSRAM_DT_MPIDR		0x20
+#define PSRAM_DT_END		0x24
+/******************************************************************************
+ * Allocate data region for struct psram_data_t in pmusram
+ ******************************************************************************/
+/* Needed aligned 16 bytes for sp stack top */
+#define PSRAM_DT_SIZE		(((PSRAM_DT_END + 16) / 16) * 16)
+#define PSRAM_DT_BASE		((PMUSRAM_BASE + PMUSRAM_RSIZE) - PSRAM_DT_SIZE)
+#define PSRAM_SP_TOP		PSRAM_DT_BASE
+
+#ifndef __ASSEMBLY__
+
+/*
+ * The struct is used in pmu_cpus_on.S which
+ * gets the data of the struct by the following index
+ * #define PSRAM_DT_SP		0x0
+ * #define PSRAM_DT_DDR_FUNC	0x8
+ * #define PSRAM_DT_DDR_DATA	0x10
+ * #define PSRAM_DT_DDRFLAG	0x18
+ * #define PSRAM_DT_SYS_MODE	0x1c
+ * #define PSRAM_DT_MPIDR	0x20
+ */
+struct psram_data_t {
+	uint64_t sp;
+	uint64_t ddr_func;
+	uint64_t ddr_data;
+	uint32_t ddr_flag;
+	uint32_t sys_mode;
+	uint32_t boot_mpidr;
+};
+
+CASSERT(sizeof(struct psram_data_t) <= PSRAM_DT_SIZE,
+	assert_psram_dt_size_mismatch);
+CASSERT(__builtin_offsetof(struct psram_data_t, sp) == PSRAM_DT_SP,
+	assert_psram_dt_sp_offset_mistmatch);
+CASSERT(__builtin_offsetof(struct psram_data_t, ddr_func) == PSRAM_DT_DDR_FUNC,
+	assert_psram_dt_ddr_func_offset_mistmatch);
+CASSERT(__builtin_offsetof(struct psram_data_t, ddr_data) == PSRAM_DT_DDR_DATA,
+	assert_psram_dt_ddr_data_offset_mistmatch);
+CASSERT(__builtin_offsetof(struct psram_data_t, ddr_flag) == PSRAM_DT_DDRFLAG,
+	assert_psram_dt_ddr_flag_offset_mistmatch);
+CASSERT(__builtin_offsetof(struct psram_data_t, sys_mode) == PSRAM_DT_SYS_MODE,
+	assert_psram_dt_sys_mode_offset_mistmatch);
+CASSERT(__builtin_offsetof(struct psram_data_t, boot_mpidr) == PSRAM_DT_MPIDR,
+	assert_psram_dt_mpidr_offset_mistmatch);
+void u32_align_cpy(uint32_t *dst, const uint32_t *src, size_t bytes);
+#endif  /* __ASSEMBLY__ */
+
+#endif
diff --git a/plat/rockchip/common/pmusram/pmu_sram_cpus_on.S b/plat/rockchip/common/pmusram/pmu_sram_cpus_on.S
new file mode 100644
index 0000000..33a4646
--- /dev/null
+++ b/plat/rockchip/common/pmusram/pmu_sram_cpus_on.S
@@ -0,0 +1,83 @@
+/*
+ * Copyright (c) 2016, 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.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
+ * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
+ * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
+ * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
+ * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ */
+
+#include <arch.h>
+#include <asm_macros.S>
+#include <platform_def.h>
+#include <pmu_sram.h>
+
+	.globl pmu_cpuson_entrypoint_start
+	.globl pmu_cpuson_entrypoint_end
+
+func pmu_cpuson_entrypoint
+pmu_cpuson_entrypoint_start:
+	ldr	x5, psram_data
+	ldr	w0, [x5, #PSRAM_DT_SYS_MODE]
+	cmp	w0, #PMU_SYS_SLP_MODE
+	b.eq	check_wake_cpus
+	ldr	x6, warm_boot_func
+	br	x6
+check_wake_cpus:
+	mrs	x0, MPIDR_EL1
+	and	x1, x0, #MPIDR_CPU_MASK
+	and	x0, x0, #MPIDR_CLUSTER_MASK
+	orr	x0, x0, x1
+	/* primary_cpu */
+	ldr	w1, [x5, #PSRAM_DT_MPIDR]
+	cmp	w0, w1
+	b.eq	sys_wakeup
+	/*
+	 * If the core is not the primary cpu,
+	 * force the core into wfe.
+	 */
+wfe_loop:
+	wfe
+	b	wfe_loop
+sys_wakeup:
+	/* check ddr flag for resume ddr */
+	ldr	w2, [x5, #PSRAM_DT_DDRFLAG]
+	cmp	w2, #0x0
+	b.eq	sys_resume
+ddr_resume:
+	ldr	x2, [x5, #PSRAM_DT_SP]
+	mov	sp, x2
+	ldr	x1, [x5, #PSRAM_DT_DDR_FUNC]
+	ldr	x0, [x5, #PSRAM_DT_DDR_DATA]
+	blr	x1
+sys_resume:
+	ldr	x1, sys_wakeup_entry
+	br	x1
+
+	.align	3
+psram_data:
+	.quad	PSRAM_DT_BASE
+warm_boot_func:
+	.quad	platform_cpu_warmboot
+sys_wakeup_entry:
+	.quad	psci_entrypoint
+pmu_cpuson_entrypoint_end:
+	.word	0
+endfunc pmu_cpuson_entrypoint
diff --git a/plat/rockchip/common/rockchip_gicv2.c b/plat/rockchip/common/rockchip_gicv2.c
new file mode 100644
index 0000000..3e1fa91
--- /dev/null
+++ b/plat/rockchip/common/rockchip_gicv2.c
@@ -0,0 +1,103 @@
+/*
+ * Copyright (c) 2016, 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 <bl_common.h>
+#include <gicv2.h>
+#include <platform_def.h>
+
+/******************************************************************************
+ * The following functions are defined as weak to allow a platform to override
+ * the way the GICv2 driver is initialised and used.
+ *****************************************************************************/
+#pragma weak plat_rockchip_gic_driver_init
+#pragma weak plat_rockchip_gic_init
+#pragma weak plat_rockchip_gic_cpuif_enable
+#pragma weak plat_rockchip_gic_cpuif_disable
+#pragma weak plat_rockchip_gic_pcpu_init
+
+/******************************************************************************
+ * On a GICv2 system, the Group 1 secure interrupts are treated as Group 0
+ * interrupts.
+ *****************************************************************************/
+const unsigned int g0_interrupt_array[] = {
+	PLAT_RK_G1S_IRQS,
+};
+
+/*
+ * Ideally `rockchip_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 rockchip_gic_data = {
+	.gicd_base = PLAT_RK_GICD_BASE,
+	.gicc_base = PLAT_RK_GICC_BASE,
+	.g0_interrupt_num = ARRAY_SIZE(g0_interrupt_array),
+	.g0_interrupt_array = g0_interrupt_array,
+};
+
+/******************************************************************************
+ * RockChip common helper to initialize the GICv2 only driver.
+ *****************************************************************************/
+void plat_rockchip_gic_driver_init(void)
+{
+	gicv2_driver_init(&rockchip_gic_data);
+}
+
+void plat_rockchip_gic_init(void)
+{
+	gicv2_distif_init();
+	gicv2_pcpu_distif_init();
+	gicv2_cpuif_enable();
+}
+
+/******************************************************************************
+ * RockChip common helper to enable the GICv2 CPU interface
+ *****************************************************************************/
+void plat_rockchip_gic_cpuif_enable(void)
+{
+	gicv2_cpuif_enable();
+}
+
+/******************************************************************************
+ * RockChip common helper to disable the GICv2 CPU interface
+ *****************************************************************************/
+void plat_rockchip_gic_cpuif_disable(void)
+{
+	gicv2_cpuif_disable();
+}
+
+/******************************************************************************
+ * RockChip common helper to initialize the per cpu distributor interface
+ * in GICv2
+ *****************************************************************************/
+void plat_rockchip_gic_pcpu_init(void)
+{
+	gicv2_pcpu_distif_init();
+}
diff --git a/plat/rockchip/common/rockchip_gicv3.c b/plat/rockchip/common/rockchip_gicv3.c
new file mode 100644
index 0000000..d197aba
--- /dev/null
+++ b/plat/rockchip/common/rockchip_gicv3.c
@@ -0,0 +1,123 @@
+/*
+ * Copyright (c) 2016, 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 <bl_common.h>
+#include <gicv3.h>
+#include <platform.h>
+#include <platform_def.h>
+
+/******************************************************************************
+ * The following functions are defined as weak to allow a platform to override
+ * the way the GICv3 driver is initialised and used.
+ *****************************************************************************/
+#pragma weak plat_rockchip_gic_driver_init
+#pragma weak plat_rockchip_gic_init
+#pragma weak plat_rockchip_gic_cpuif_enable
+#pragma weak plat_rockchip_gic_cpuif_disable
+#pragma weak plat_rockchip_gic_pcpu_init
+
+/* The GICv3 driver only needs to be initialized in EL3 */
+uintptr_t rdistif_base_addrs[PLATFORM_CORE_COUNT];
+
+/* Array of Group1 secure interrupts to be configured by the gic driver */
+const unsigned int g1s_interrupt_array[] = {
+	PLAT_RK_G1S_IRQS
+};
+
+/* Array of Group0 interrupts to be configured by the gic driver */
+const unsigned int g0_interrupt_array[] = {
+	PLAT_RK_G0_IRQS
+};
+
+static unsigned int plat_rockchip_mpidr_to_core_pos(unsigned long mpidr)
+{
+	return (unsigned int)plat_core_pos_by_mpidr(mpidr);
+}
+
+const gicv3_driver_data_t rockchip_gic_data = {
+	.gicd_base = PLAT_RK_GICD_BASE,
+	.gicr_base = PLAT_RK_GICR_BASE,
+	.g0_interrupt_num = ARRAY_SIZE(g0_interrupt_array),
+	.g1s_interrupt_num = ARRAY_SIZE(g1s_interrupt_array),
+	.g0_interrupt_array = g0_interrupt_array,
+	.g1s_interrupt_array = g1s_interrupt_array,
+	.rdistif_num = PLATFORM_CORE_COUNT,
+	.rdistif_base_addrs = rdistif_base_addrs,
+	.mpidr_to_core_pos = plat_rockchip_mpidr_to_core_pos,
+};
+
+void plat_rockchip_gic_driver_init(void)
+{
+	/*
+	 * The GICv3 driver is initialized in EL3 and does not need
+	 * to be initialized again in SEL1. This is because the S-EL1
+	 * can use GIC system registers to manage interrupts and does
+	 * not need GIC interface base addresses to be configured.
+	 */
+#if IMAGE_BL31
+	gicv3_driver_init(&rockchip_gic_data);
+#endif
+}
+
+/******************************************************************************
+ * RockChip common helper to initialize the GIC. Only invoked
+ * by BL31
+ *****************************************************************************/
+void plat_rockchip_gic_init(void)
+{
+	gicv3_distif_init();
+	gicv3_rdistif_init(plat_my_core_pos());
+	gicv3_cpuif_enable(plat_my_core_pos());
+}
+
+/******************************************************************************
+ * RockChip common helper to enable the GIC CPU interface
+ *****************************************************************************/
+void plat_rockchip_gic_cpuif_enable(void)
+{
+	gicv3_cpuif_enable(plat_my_core_pos());
+}
+
+/******************************************************************************
+ * RockChip common helper to disable the GIC CPU interface
+ *****************************************************************************/
+void plat_rockchip_gic_cpuif_disable(void)
+{
+	gicv3_cpuif_disable(plat_my_core_pos());
+}
+
+/******************************************************************************
+ * RockChip common helper to initialize the per-cpu redistributor interface
+ * in GICv3
+ *****************************************************************************/
+void plat_rockchip_gic_pcpu_init(void)
+{
+	gicv3_rdistif_init(plat_my_core_pos());
+}