Merge pull request #1646 from Andre-ARM/allwinner/pmic-v2

Allwinner/pmic v2
diff --git a/drivers/allwinner/sunxi_rsb.c b/drivers/allwinner/sunxi_rsb.c
new file mode 100644
index 0000000..7075c67
--- /dev/null
+++ b/drivers/allwinner/sunxi_rsb.c
@@ -0,0 +1,136 @@
+/*
+ * Copyright (c) 2017-2018 ARM Limited and Contributors. All rights reserved.
+ *
+ * SPDX-License-Identifier: BSD-3-Clause
+ */
+
+#include <debug.h>
+#include <delay_timer.h>
+#include <errno.h>
+#include <mmio.h>
+#include <sunxi_mmap.h>
+
+#define RSB_CTRL	0x00
+#define RSB_CCR		0x04
+#define RSB_INTE	0x08
+#define RSB_STAT	0x0c
+#define RSB_DADDR0	0x10
+#define RSB_DLEN	0x18
+#define RSB_DATA0	0x1c
+#define RSB_LCR		0x24
+#define RSB_PMCR	0x28
+#define RSB_CMD		0x2c
+#define RSB_SADDR	0x30
+
+#define RSBCMD_SRTA	0xE8
+#define RSBCMD_RD8	0x8B
+#define RSBCMD_RD16	0x9C
+#define RSBCMD_RD32	0xA6
+#define RSBCMD_WR8	0x4E
+#define RSBCMD_WR16	0x59
+#define RSBCMD_WR32	0x63
+
+#define MAX_TRIES	100000
+
+static int rsb_wait_bit(const char *desc, unsigned int offset, uint32_t mask)
+{
+	uint32_t reg, tries = MAX_TRIES;
+
+	do
+		reg = mmio_read_32(SUNXI_R_RSB_BASE + offset);
+	while ((reg & mask) && --tries);	/* transaction in progress */
+	if (reg & mask) {
+		ERROR("%s: timed out\n", desc);
+		return -ETIMEDOUT;
+	}
+
+	return 0;
+}
+
+static int rsb_wait_stat(const char *desc)
+{
+	uint32_t reg;
+	int ret = rsb_wait_bit(desc, RSB_CTRL, BIT(7));
+
+	if (ret)
+		return ret;
+
+	reg = mmio_read_32(SUNXI_R_RSB_BASE + RSB_STAT);
+	if (reg == 0x01)
+		return 0;
+
+	ERROR("%s: 0x%x\n", desc, reg);
+	return -reg;
+}
+
+/* Initialize the RSB controller. */
+int rsb_init_controller(void)
+{
+	mmio_write_32(SUNXI_R_RSB_BASE + RSB_CTRL, 0x01); /* soft reset */
+
+	return rsb_wait_bit("RSB: reset controller", RSB_CTRL, BIT(0));
+}
+
+int rsb_read(uint8_t rt_addr, uint8_t reg_addr)
+{
+	int ret;
+
+	mmio_write_32(SUNXI_R_RSB_BASE + RSB_CMD, RSBCMD_RD8); /* read a byte */
+	mmio_write_32(SUNXI_R_RSB_BASE + RSB_SADDR, rt_addr << 16);
+	mmio_write_32(SUNXI_R_RSB_BASE + RSB_DADDR0, reg_addr);
+	mmio_write_32(SUNXI_R_RSB_BASE + RSB_CTRL, 0x80);/* start transaction */
+
+	ret = rsb_wait_stat("RSB: read command");
+	if (ret)
+		return ret;
+
+	return mmio_read_32(SUNXI_R_RSB_BASE + RSB_DATA0) & 0xff; /* result */
+}
+
+int rsb_write(uint8_t rt_addr, uint8_t reg_addr, uint8_t value)
+{
+	mmio_write_32(SUNXI_R_RSB_BASE + RSB_CMD, RSBCMD_WR8);	/* byte write */
+	mmio_write_32(SUNXI_R_RSB_BASE + RSB_SADDR, rt_addr << 16);
+	mmio_write_32(SUNXI_R_RSB_BASE + RSB_DADDR0, reg_addr);
+	mmio_write_32(SUNXI_R_RSB_BASE + RSB_DATA0, value);
+	mmio_write_32(SUNXI_R_RSB_BASE + RSB_CTRL, 0x80);/* start transaction */
+
+	return rsb_wait_stat("RSB: write command");
+}
+
+int rsb_set_device_mode(uint32_t device_mode)
+{
+	mmio_write_32(SUNXI_R_RSB_BASE + RSB_PMCR,
+		      (device_mode & 0x00ffffff) | BIT(31));
+
+	return rsb_wait_bit("RSB: set device to RSB", RSB_PMCR, BIT(31));
+}
+
+int rsb_set_bus_speed(uint32_t source_freq, uint32_t bus_freq)
+{
+	uint32_t reg;
+
+	if (bus_freq == 0)
+		return -EINVAL;
+
+	reg = source_freq / bus_freq;
+	if (reg < 2)
+		return -EINVAL;
+
+	reg = reg / 2 - 1;
+	reg |= (1U << 8);		/* one cycle of CD output delay */
+
+	mmio_write_32(SUNXI_R_RSB_BASE + RSB_CCR, reg);
+
+	return 0;
+}
+
+/* Initialize the RSB PMIC connection. */
+int rsb_assign_runtime_address(uint16_t hw_addr, uint8_t rt_addr)
+{
+	mmio_write_32(SUNXI_R_RSB_BASE + RSB_SADDR, hw_addr | (rt_addr << 16));
+	mmio_write_32(SUNXI_R_RSB_BASE + RSB_CMD, RSBCMD_SRTA);
+	mmio_write_32(SUNXI_R_RSB_BASE + RSB_CTRL, 0x80);
+
+	return rsb_wait_stat("RSB: set run-time address");
+}
diff --git a/include/drivers/allwinner/sunxi_rsb.h b/include/drivers/allwinner/sunxi_rsb.h
new file mode 100644
index 0000000..5a69d35
--- /dev/null
+++ b/include/drivers/allwinner/sunxi_rsb.h
@@ -0,0 +1,20 @@
+/*
+ * Copyright (c) 2017-2018 ARM Limited and Contributors. All rights reserved.
+ *
+ * SPDX-License-Identifier: BSD-3-Clause
+ */
+
+#ifndef SUNXI_RSB_H
+#define SUNXI_RSB_H
+
+#include <stdint.h>
+
+int rsb_init_controller(void);
+int rsb_set_bus_speed(uint32_t source_freq, uint32_t bus_freq);
+int rsb_set_device_mode(uint32_t device_mode);
+int rsb_assign_runtime_address(uint16_t hw_addr, uint8_t rt_addr);
+
+int rsb_read(uint8_t rt_addr, uint8_t reg_addr);
+int rsb_write(uint8_t rt_addr, uint8_t reg_addr, uint8_t value);
+
+#endif
diff --git a/plat/allwinner/common/allwinner-common.mk b/plat/allwinner/common/allwinner-common.mk
new file mode 100644
index 0000000..2dc058f
--- /dev/null
+++ b/plat/allwinner/common/allwinner-common.mk
@@ -0,0 +1,59 @@
+#
+# Copyright (c) 2017-2018, ARM Limited and Contributors. All rights reserved.
+#
+# SPDX-License-Identifier: BSD-3-Clause
+#
+
+include lib/xlat_tables_v2/xlat_tables.mk
+
+AW_PLAT			:=	plat/allwinner
+
+PLAT_INCLUDES		:=	-Iinclude/plat/arm/common		\
+				-Iinclude/plat/arm/common/aarch64	\
+				-I${AW_PLAT}/common/include		\
+				-I${AW_PLAT}/${PLAT}/include
+
+include lib/libfdt/libfdt.mk
+
+PLAT_BL_COMMON_SOURCES	:=	drivers/console/${ARCH}/console.S	\
+				drivers/ti/uart/${ARCH}/16550_console.S	\
+				${XLAT_TABLES_LIB_SRCS}			\
+				${AW_PLAT}/common/plat_helpers.S	\
+				${AW_PLAT}/common/sunxi_common.c
+
+BL31_SOURCES		+=	drivers/arm/gic/common/gic_common.c	\
+				drivers/arm/gic/v2/gicv2_helpers.c	\
+				drivers/arm/gic/v2/gicv2_main.c		\
+				drivers/delay_timer/delay_timer.c	\
+				drivers/delay_timer/generic_delay_timer.c \
+				lib/cpus/${ARCH}/cortex_a53.S		\
+				plat/common/plat_gicv2.c		\
+				plat/common/plat_psci_common.c		\
+				${AW_PLAT}/common/sunxi_bl31_setup.c	\
+				${AW_PLAT}/common/sunxi_cpu_ops.c	\
+				${AW_PLAT}/common/sunxi_pm.c		\
+				${AW_PLAT}/${PLAT}/sunxi_power.c	\
+				${AW_PLAT}/common/sunxi_security.c	\
+				${AW_PLAT}/common/sunxi_topology.c
+
+# The bootloader is guaranteed to only run on CPU 0 by the boot ROM.
+COLD_BOOT_SINGLE_CPU		:=	1
+
+# Enable workarounds for Cortex-A53 errata. Allwinner uses at least r0p4.
+ERRATA_A53_835769		:=	1
+ERRATA_A53_843419		:=	1
+ERRATA_A53_855873		:=	1
+
+MULTI_CONSOLE_API		:=	1
+
+# The reset vector can be changed for each CPU.
+PROGRAMMABLE_RESET_ADDRESS	:=	1
+
+# Allow mapping read-only data as execute-never.
+SEPARATE_CODE_AND_RODATA	:=	1
+
+# BL31 gets loaded alongside BL33 (U-Boot) by U-Boot's SPL
+RESET_TO_BL31			:=	1
+
+# We are short on memory, so save 3.5KB by not having an extra coherent page.
+USE_COHERENT_MEM		:=	0
diff --git a/plat/allwinner/common/arisc_off.S b/plat/allwinner/common/arisc_off.S
new file mode 100644
index 0000000..ed10832
--- /dev/null
+++ b/plat/allwinner/common/arisc_off.S
@@ -0,0 +1,115 @@
+# turn_off_core.S
+#
+# Copyright (c) 2018, Andre Przywara <osp@andrep.de>
+# SPDX-License-Identifier: BSD-3-Clause
+#
+# OpenRISC assembly to turn off an ARM core on an Allwinner SoC from
+# the arisc management controller.
+# Generate a binary representation with:
+# $ or1k-elf-as -c -o turn_off_core.o turn_off_core.S
+# $ or1k-elf-objcopy -O binary --reverse-bytes=4 turn_off_core.o \
+#   turn_off_core.bin
+# The encoded instructions go into an array defined in
+# plat/allwinner/sun50i_*/include/core_off_arisc.h, to be handed off to
+# the arisc processor.
+#
+# This routine is meant to be called directly from arisc reset (put the
+# start address in the reset vector), to be actually triggered by that
+# very ARM core to be turned off.
+# It expects the core number presented as a mask in the upper half of
+# r3, so to be patched in the lower 16 bits of the first instruction,
+# overwriting the 0 in this code here.
+# The code will do the following:
+# - Read the C_CPU_STATUS register, which contains the status of the WFI
+#   lines of each of the four A53 cores.
+# - Loop until the core in question reaches WFI.
+# - Using that mask, activate the core output clamps by setting the
+#   respective core bit in CPUX_PWROFF_GATING_REG (0x1f01500).
+#   Note that the clamp for core 0 covers more than just the core, activating
+#   it hangs the whole system. So we skip this step for core 0.
+# - Using the negated mask, assert the core's reset line by clearing the
+#   respective bit in C_RST_CTRL (0x1f01c30).
+# - Finally turn off the core's power switch by writing 0xff to the
+#   respective CPUx_PWR_SWITCH_REG (0x1f01540 ff.)
+# - Assert the arisc's own reset to end execution.
+#   This also signals other arisc users that the chip is free again.
+# So in C this would look like:
+#	while (!(readl(0x1700030) & (1U << core_nr)))
+#		;
+#	if (core_nr != 0)
+#		writel(readl(0x1f01500) | (1U << core_nr), 0x1f01500);
+#	writel(readl(0x1f01c30) & ~(1U << core_nr), 0x1f01c30);
+#	writel(0xff, 0x1f01540 + (core_nr * 4));
+# (using A64/H5 addresses)
+
+.text
+_start:
+	l.movhi	r3, 0				# FIXUP! with core mask
+	l.movhi r0, 0				# clear r0
+	l.movhi	r13, 0x170			# r13: CPU_CFG_BASE=0x01700000
+wait_wfi:
+	l.lwz	r5, 0x30(r13)			# load C_CPU_STATUS
+	l.and	r5, r5, r3			# mask requested core
+	l.sfeq	r5, r0				# is it not yet in WFI?
+	l.bf	wait_wfi			# try again
+
+	l.srli	r6, r3, 16			# move mask to lower 16 bits
+	l.sfeqi	r6, 1				# core 0 is special
+	l.bf	1f				# don't touch the bit for core 0
+	l.movhi	r13, 0x1f0			# address of R_CPUCFG (delay)
+	l.lwz	r5, 0x1500(r13)			# core output clamps
+	l.or	r5, r5, r6			# set bit to ...
+	l.sw	0x1500(r13), r5			# ... activate for our core
+
+1:	l.lwz	r5, 0x1c30(r13)			# CPU power-on reset
+	l.xori	r6, r6, -1			# negate core mask
+	l.and	r5, r5, r6			# clear bit to ...
+	l.sw	0x1c30(r13), r5			# ... assert for our core
+
+	l.ff1	r6, r3				# get core number from high mask
+	l.addi	r6, r6, -17			# convert to 0-3
+	l.slli	r6, r6, 2			# r5: core number*4 (0-12)
+	l.add	r6, r6, r13			# add to base address
+	l.ori	r5, r0, 0xff			# 0xff means all switches off
+	l.sw	0x1540(r6), r5			# core power switch registers
+
+reset:	l.sw	0x1c00(r13),r0			# pull down our own reset line
+
+	l.j	reset				# just in case ....
+	l.nop	0x0				# (delay slot)
+
+# same as above, but with the MMIO addresses matching the H6 SoC
+_start_h6:
+	l.movhi	r3, 0				# FIXUP! with core mask
+	l.movhi r0, 0				# clear r0
+	l.movhi	r13, 0x901			# r13: CPU_CFG_BASE=0x09010000
+1:
+	l.lwz	r5, 0x80(r13)			# load C_CPU_STATUS
+	l.and	r5, r5, r3			# mask requested core
+	l.sfeq	r5, r0				# is it not yet in WFI?
+	l.bf	1b				# try again
+
+	l.srli	r6, r3, 16			# move mask to lower 16 bits(ds)
+	l.sfeqi	r6, 1				# core 0 is special
+	l.bf	1f				# don't touch the bit for core 0
+	l.movhi	r13, 0x700			# address of R_CPUCFG (ds)
+	l.lwz	r5, 0x0444(r13)			# core output clamps
+	l.or	r5, r5, r6			# set bit to ...
+	l.sw	0x0444(r13), r5			# ... activate for our core
+
+1:	l.lwz	r5, 0x0440(r13)			# CPU power-on reset
+	l.xori	r6, r6, -1			# negate core mask
+	l.and	r5, r5, r6			# clear bit to ...
+	l.sw	0x0440(r13), r5			# ... assert for our core
+
+	l.ff1	r6, r3				# get core number from high mask
+	l.addi	r6, r6, -17			# convert to 0-3
+	l.slli	r6, r6, 2			# r5: core number*4 (0-12)
+	l.add	r6, r6, r13			# add to base address
+	l.ori	r5, r0, 0xff			# 0xff means all switches off
+	l.sw	0x0450(r6), r5			# core power switch registers
+
+1:	l.sw	0x0400(r13),r0			# pull down our own reset line
+
+	l.j	1b				# just in case ...
+	l.nop	0x0				# (delay slot)
diff --git a/plat/allwinner/common/include/platform_def.h b/plat/allwinner/common/include/platform_def.h
index b46d410..08eb5cf 100644
--- a/plat/allwinner/common/include/platform_def.h
+++ b/plat/allwinner/common/include/platform_def.h
@@ -18,11 +18,17 @@
 /* The traditional U-Boot load address is 160MB into DRAM, so at 0x4a000000 */
 #define PLAT_SUNXI_NS_IMAGE_OFFSET	(SUNXI_DRAM_BASE + (160U << 20))
 
+/* How much memory to reserve as secure for BL32, if configured */
+#define SUNXI_DRAM_SEC_SIZE		(32U << 20)
+
+/* How much DRAM to map (to map BL33, for fetching the DTB from U-Boot) */
+#define SUNXI_DRAM_MAP_SIZE		(64U << 20)
+
 #define CACHE_WRITEBACK_SHIFT		6
 #define CACHE_WRITEBACK_GRANULE		(1 << CACHE_WRITEBACK_SHIFT)
 
-#define MAX_MMAP_REGIONS		(4 + PLATFORM_MMAP_REGIONS)
-#define MAX_XLAT_TABLES			2
+#define MAX_MMAP_REGIONS		(3 + PLATFORM_MMAP_REGIONS)
+#define MAX_XLAT_TABLES			1
 
 #define PLAT_MAX_PWR_LVL_STATES		U(2)
 #define PLAT_MAX_RET_STATE		U(1)
@@ -34,13 +40,13 @@
 					 PLATFORM_CORE_COUNT)
 
 #define PLAT_PHY_ADDR_SPACE_SIZE	(1ULL << 32)
-#define PLAT_VIRT_ADDR_SPACE_SIZE	(1ULL << 32)
+#define PLAT_VIRT_ADDR_SPACE_SIZE	(1ULL << 28)
 
 #define PLATFORM_CLUSTER_COUNT		1
 #define PLATFORM_CORE_COUNT		(PLATFORM_CLUSTER_COUNT * \
 					 PLATFORM_MAX_CPUS_PER_CLUSTER)
 #define PLATFORM_MAX_CPUS_PER_CLUSTER	4
-#define PLATFORM_MMAP_REGIONS		3
+#define PLATFORM_MMAP_REGIONS		4
 #define PLATFORM_STACK_SIZE		(0x1000 / PLATFORM_CORE_COUNT)
 
 #ifndef SPD_none
diff --git a/plat/allwinner/common/include/sunxi_def.h b/plat/allwinner/common/include/sunxi_def.h
index e68fbe4..da87b23 100644
--- a/plat/allwinner/common/include/sunxi_def.h
+++ b/plat/allwinner/common/include/sunxi_def.h
@@ -14,4 +14,8 @@
 #define SUNXI_UART0_BAUDRATE		115200
 #define SUNXI_UART0_CLK_IN_HZ		SUNXI_OSC24M_CLK_IN_HZ
 
+#define SUNXI_SOC_A64			0x1689
+#define SUNXI_SOC_H5			0x1718
+#define SUNXI_SOC_H6			0x1728
+
 #endif /* __SUNXI_DEF_H__ */
diff --git a/plat/allwinner/common/include/sunxi_private.h b/plat/allwinner/common/include/sunxi_private.h
new file mode 100644
index 0000000..1e1b0a4
--- /dev/null
+++ b/plat/allwinner/common/include/sunxi_private.h
@@ -0,0 +1,26 @@
+/*
+ * Copyright (c) 2017-2018, ARM Limited and Contributors. All rights reserved.
+ *
+ * SPDX-License-Identifier: BSD-3-Clause
+ */
+
+#ifndef SUNXI_PRIVATE_H
+#define SUNXI_PRIVATE_H
+
+void sunxi_configure_mmu_el3(int flags);
+
+void sunxi_cpu_on(unsigned int cluster, unsigned int core);
+void sunxi_cpu_off(unsigned int cluster, unsigned int core);
+void sunxi_disable_secondary_cpus(unsigned int primary_cpu);
+void __dead2 sunxi_power_down(void);
+
+int sunxi_pmic_setup(uint16_t socid, const void *fdt);
+void sunxi_security_setup(void);
+
+uint16_t sunxi_read_soc_id(void);
+void sunxi_set_gpio_out(char port, int pin, bool level_high);
+int sunxi_init_platform_r_twi(uint16_t socid, bool use_rsb);
+void sunxi_execute_arisc_code(uint32_t *code, size_t size,
+			      int patch_offset, uint16_t param);
+
+#endif /* SUNXI_PRIVATE_H */
diff --git a/plat/allwinner/common/sunxi_bl31_setup.c b/plat/allwinner/common/sunxi_bl31_setup.c
index 7e11cec..8f597c3 100644
--- a/plat/allwinner/common/sunxi_bl31_setup.c
+++ b/plat/allwinner/common/sunxi_bl31_setup.c
@@ -10,13 +10,14 @@
 #include <debug.h>
 #include <generic_delay_timer.h>
 #include <gicv2.h>
+#include <libfdt.h>
 #include <platform.h>
 #include <platform_def.h>
 #include <sunxi_def.h>
 #include <sunxi_mmap.h>
+#include <sunxi_private.h>
 #include <uart_16550.h>
 
-#include "sunxi_private.h"
 
 static entry_point_info_t bl32_image_ep_info;
 static entry_point_info_t bl33_image_ep_info;
@@ -28,6 +29,47 @@
 	.gicc_base = SUNXI_GICC_BASE,
 };
 
+/*
+ * Try to find a DTB loaded in memory by previous stages.
+ *
+ * At the moment we implement a heuristic to find the DTB attached to U-Boot:
+ * U-Boot appends its DTB to the end of the image. Assuming that BL33 is
+ * U-Boot, try to find the size of the U-Boot image to learn the DTB address.
+ * The generic ARMv8 U-Boot image contains the load address and its size
+ * as u64 variables at the beginning of the image. There might be padding
+ * or other headers before that data, so scan the first 2KB after the BL33
+ * entry point to find the load address, which should be followed by the
+ * size. Adding those together gives us the address of the DTB.
+ */
+static void *sunxi_find_dtb(void)
+{
+	uint64_t *u_boot_base;
+	int i;
+
+	u_boot_base = (void *)(SUNXI_DRAM_VIRT_BASE + SUNXI_DRAM_SEC_SIZE);
+
+	for (i = 0; i < 2048 / sizeof(uint64_t); i++) {
+		uint32_t *dtb_base;
+
+		if (u_boot_base[i] != PLAT_SUNXI_NS_IMAGE_OFFSET)
+			continue;
+
+		/* Does the suspected U-Boot size look anyhow reasonable? */
+		if (u_boot_base[i + 1] >= 256 * 1024 * 1024)
+			continue;
+
+		/* end of the image: base address + size */
+		dtb_base = (void *)((char *)u_boot_base + u_boot_base[i + 1]);
+
+		if (fdt_check_header(dtb_base) != 0)
+			continue;
+
+		return dtb_base;
+	}
+
+	return NULL;
+}
+
 void bl31_early_platform_setup2(u_register_t arg0, u_register_t arg1,
 				u_register_t arg2, u_register_t arg3)
 {
@@ -66,15 +108,16 @@
 {
 	const char *soc_name;
 	uint16_t soc_id = sunxi_read_soc_id();
+	void *fdt;
 
 	switch (soc_id) {
-	case 0x1689:
+	case SUNXI_SOC_A64:
 		soc_name = "A64/H64/R18";
 		break;
-	case 0x1718:
+	case SUNXI_SOC_H5:
 		soc_name = "H5";
 		break;
-	case 0x1728:
+	case SUNXI_SOC_H6:
 		soc_name = "H6";
 		break;
 	default:
@@ -85,6 +128,18 @@
 
 	generic_delay_timer_init();
 
+	fdt = sunxi_find_dtb();
+	if (fdt) {
+		const char *model;
+		int length;
+
+		model = fdt_getprop(fdt, 0, "model", &length);
+		NOTICE("BL31: Found U-Boot DTB at %p, model: %s\n", fdt,
+		     model ?: "unknown");
+	} else {
+		NOTICE("BL31: No DTB found.\n");
+	}
+
 	/* Configure the interrupt controller */
 	gicv2_driver_init(&sunxi_gic_data);
 	gicv2_distif_init();
@@ -93,7 +148,7 @@
 
 	sunxi_security_setup();
 
-	sunxi_pmic_setup();
+	sunxi_pmic_setup(soc_id, fdt);
 
 	INFO("BL31: Platform setup done\n");
 }
diff --git a/plat/allwinner/common/sunxi_common.c b/plat/allwinner/common/sunxi_common.c
index fc9bf20..2eb26a9 100644
--- a/plat/allwinner/common/sunxi_common.c
+++ b/plat/allwinner/common/sunxi_common.c
@@ -4,21 +4,28 @@
  * SPDX-License-Identifier: BSD-3-Clause
  */
 
+#include <arch_helpers.h>
+#include <debug.h>
+#include <errno.h>
 #include <mmio.h>
 #include <platform.h>
 #include <platform_def.h>
 #include <sunxi_def.h>
+#include <sunxi_mmap.h>
+#include <sunxi_private.h>
 #include <xlat_tables_v2.h>
 
-#include "sunxi_private.h"
-
 static mmap_region_t sunxi_mmap[PLATFORM_MMAP_REGIONS + 1] = {
 	MAP_REGION_FLAT(SUNXI_SRAM_BASE, SUNXI_SRAM_SIZE,
 			MT_MEMORY | MT_RW | MT_SECURE),
 	MAP_REGION_FLAT(SUNXI_DEV_BASE, SUNXI_DEV_SIZE,
 			MT_DEVICE | MT_RW | MT_SECURE),
-	MAP_REGION_FLAT(SUNXI_DRAM_BASE, SUNXI_DRAM_SIZE,
-			MT_MEMORY | MT_RW | MT_NS),
+	MAP_REGION(SUNXI_DRAM_BASE, SUNXI_DRAM_VIRT_BASE, SUNXI_DRAM_SEC_SIZE,
+			MT_MEMORY | MT_RW | MT_SECURE),
+	MAP_REGION(PLAT_SUNXI_NS_IMAGE_OFFSET,
+		   SUNXI_DRAM_VIRT_BASE + SUNXI_DRAM_SEC_SIZE,
+		   SUNXI_DRAM_MAP_SIZE,
+		   MT_MEMORY | MT_RO | MT_NS),
 	{},
 };
 
@@ -47,9 +54,6 @@
 	mmap_add_region(BL_RO_DATA_BASE, BL_RO_DATA_BASE,
 			BL_RO_DATA_END - BL_RO_DATA_BASE,
 			MT_RO_DATA | MT_SECURE);
-	mmap_add_region(BL_COHERENT_RAM_BASE, BL_COHERENT_RAM_BASE,
-			BL_COHERENT_RAM_END - BL_COHERENT_RAM_BASE,
-			MT_DEVICE | MT_RW | MT_SECURE);
 	mmap_add(sunxi_mmap);
 	init_xlat_tables();
 
@@ -71,3 +75,136 @@
 
 	return reg >> 16;
 }
+
+/*
+ * Configure a given pin to the GPIO-OUT function and sets its level.
+ * The port is given as a capital letter, the pin is the number within
+ * this port group.
+ * So to set pin PC7 to high, use: sunxi_set_gpio_out('C', 7, true);
+ */
+void sunxi_set_gpio_out(char port, int pin, bool level_high)
+{
+	uintptr_t port_base;
+
+	if (port < 'A' || port > 'L')
+		return;
+	if (port == 'L')
+		port_base = SUNXI_R_PIO_BASE;
+	else
+		port_base = SUNXI_PIO_BASE + (port - 'A') * 0x24;
+
+	/* Set the new level first before configuring the pin. */
+	if (level_high)
+		mmio_setbits_32(port_base + 0x10, BIT(pin));
+	else
+		mmio_clrbits_32(port_base + 0x10, BIT(pin));
+
+	/* configure pin as GPIO out (4(3) bits per pin, 1: GPIO out */
+	mmio_clrsetbits_32(port_base + (pin / 8) * 4,
+			   0x7 << ((pin % 8) * 4),
+			   0x1 << ((pin % 8) * 4));
+}
+
+int sunxi_init_platform_r_twi(uint16_t socid, bool use_rsb)
+{
+	uint32_t pin_func = 0x77;
+	uint32_t device_bit;
+	unsigned int reset_offset = 0xb0;
+
+	switch (socid) {
+	case SUNXI_SOC_H5:
+		if (use_rsb)
+			return -ENODEV;
+		pin_func = 0x22;
+		device_bit = BIT(6);
+		break;
+	case SUNXI_SOC_H6:
+		if (use_rsb)
+			return -ENODEV;
+		pin_func = 0x33;
+		device_bit = BIT(16);
+		reset_offset = 0x19c;
+		break;
+	case SUNXI_SOC_A64:
+		pin_func = use_rsb ? 0x22 : 0x33;
+		device_bit = use_rsb ? BIT(3) : BIT(6);
+		break;
+	default:
+		INFO("R_I2C/RSB on Allwinner 0x%x SoC not supported\n", socid);
+		return -ENODEV;
+	}
+
+	/* un-gate R_PIO clock */
+	if (socid != SUNXI_SOC_H6)
+		mmio_setbits_32(SUNXI_R_PRCM_BASE + 0x28, BIT(0));
+
+	/* switch pins PL0 and PL1 to the desired function */
+	mmio_clrsetbits_32(SUNXI_R_PIO_BASE + 0x00, 0xffU, pin_func);
+
+	/* level 2 drive strength */
+	mmio_clrsetbits_32(SUNXI_R_PIO_BASE + 0x14, 0x0fU, 0xaU);
+
+	/* set both pins to pull-up */
+	mmio_clrsetbits_32(SUNXI_R_PIO_BASE + 0x1c, 0x0fU, 0x5U);
+
+	/* assert, then de-assert reset of I2C/RSB controller */
+	mmio_clrbits_32(SUNXI_R_PRCM_BASE + reset_offset, device_bit);
+	mmio_setbits_32(SUNXI_R_PRCM_BASE + reset_offset, device_bit);
+
+	/* un-gate clock */
+	if (socid != SUNXI_SOC_H6)
+		mmio_setbits_32(SUNXI_R_PRCM_BASE + 0x28, device_bit);
+	else
+		mmio_setbits_32(SUNXI_R_PRCM_BASE + 0x19c, device_bit | BIT(0));
+
+	return 0;
+}
+
+/* This lock synchronises access to the arisc management processor. */
+DEFINE_BAKERY_LOCK(arisc_lock);
+
+/*
+ * Tell the "arisc" SCP core (an OpenRISC core) to execute some code.
+ * We don't have any service running there, so we place some OpenRISC code
+ * in SRAM, put the address of that into the reset vector and release the
+ * arisc reset line. The SCP will execute that code and pull the line up again.
+ */
+void sunxi_execute_arisc_code(uint32_t *code, size_t size,
+			      int patch_offset, uint16_t param)
+{
+	uintptr_t arisc_reset_vec = SUNXI_SRAM_A2_BASE - 0x4000 + 0x100;
+
+	do {
+		bakery_lock_get(&arisc_lock);
+		/* Wait until the arisc is in reset state. */
+		if (!(mmio_read_32(SUNXI_R_CPUCFG_BASE) & BIT(0)))
+			break;
+
+		bakery_lock_release(&arisc_lock);
+	} while (1);
+
+	/* Patch up the code to feed in an input parameter. */
+	if (patch_offset >= 0 && patch_offset <= (size - 4))
+		code[patch_offset] = (code[patch_offset] & ~0xffff) | param;
+	clean_dcache_range((uintptr_t)code, size);
+
+	/*
+	 * The OpenRISC unconditional branch has opcode 0, the branch offset
+	 * is in the lower 26 bits, containing the distance to the target,
+	 * in instruction granularity (32 bits).
+	 */
+	mmio_write_32(arisc_reset_vec, ((uintptr_t)code - arisc_reset_vec) / 4);
+	clean_dcache_range(arisc_reset_vec, 4);
+
+	/* De-assert the arisc reset line to let it run. */
+	mmio_setbits_32(SUNXI_R_CPUCFG_BASE, BIT(0));
+
+	/*
+	 * We release the lock here, although the arisc is still busy.
+	 * But as long as it runs, the reset line is high, so other users
+	 * won't leave the loop above.
+	 * Once it has finished, the code is supposed to clear the reset line,
+	 * to signal this to other users.
+	 */
+	bakery_lock_release(&arisc_lock);
+}
diff --git a/plat/allwinner/common/sunxi_cpu_ops.c b/plat/allwinner/common/sunxi_cpu_ops.c
index aaee65c..3b732b5 100644
--- a/plat/allwinner/common/sunxi_cpu_ops.c
+++ b/plat/allwinner/common/sunxi_cpu_ops.c
@@ -4,15 +4,19 @@
  * SPDX-License-Identifier: BSD-3-Clause
  */
 
+#include <arch_helpers.h>
+#include <assert.h>
+#include <core_off_arisc.h>
 #include <debug.h>
+#include <delay_timer.h>
 #include <mmio.h>
+#include <platform.h>
 #include <platform_def.h>
-#include <sunxi_mmap.h>
 #include <sunxi_cpucfg.h>
+#include <sunxi_mmap.h>
+#include <sunxi_private.h>
 #include <utils_def.h>
 
-#include "sunxi_private.h"
-
 static void sunxi_cpu_disable_power(unsigned int cluster, unsigned int core)
 {
 	if (mmio_read_32(SUNXI_CPU_POWER_CLAMP_REG(cluster, core)) == 0xff)
@@ -40,16 +44,37 @@
 
 void sunxi_cpu_off(unsigned int cluster, unsigned int core)
 {
+	int corenr = cluster * PLATFORM_MAX_CPUS_PER_CLUSTER + core;
+
 	VERBOSE("PSCI: Powering off cluster %d core %d\n", cluster, core);
 
 	/* Deassert DBGPWRDUP */
 	mmio_clrbits_32(SUNXI_CPUCFG_DBG_REG0, BIT(core));
-	/* Activate the core output clamps */
-	mmio_setbits_32(SUNXI_POWEROFF_GATING_REG(cluster), BIT(core));
-	/* Assert CPU power-on reset */
-	mmio_clrbits_32(SUNXI_POWERON_RST_REG(cluster), BIT(core));
-	/* Remove power from the CPU */
-	sunxi_cpu_disable_power(cluster, core);
+
+	/* We can't turn ourself off like this, but it works for other cores. */
+	if (plat_my_core_pos() != corenr) {
+		/* Activate the core output clamps, but not for core 0. */
+		if (corenr != 0)
+			mmio_setbits_32(SUNXI_POWEROFF_GATING_REG(cluster),
+					BIT(core));
+		/* Assert CPU power-on reset */
+		mmio_clrbits_32(SUNXI_POWERON_RST_REG(cluster), BIT(core));
+		/* Remove power from the CPU */
+		sunxi_cpu_disable_power(cluster, core);
+
+		return;
+	}
+
+	/* Simplifies assembly, all SoCs so far are single cluster anyway. */
+	assert(cluster == 0);
+
+	/*
+	 * If we are supposed to turn ourself off, tell the arisc SCP
+	 * to do that work for us. The code expects the core mask to be
+	 * patched into the first instruction.
+	 */
+	sunxi_execute_arisc_code(arisc_core_off, sizeof(arisc_core_off),
+				 0, BIT_32(core));
 }
 
 void sunxi_cpu_on(unsigned int cluster, unsigned int core)
diff --git a/plat/allwinner/common/sunxi_pm.c b/plat/allwinner/common/sunxi_pm.c
index e4bb582..7d13cda 100644
--- a/plat/allwinner/common/sunxi_pm.c
+++ b/plat/allwinner/common/sunxi_pm.c
@@ -13,15 +13,14 @@
 #include <platform.h>
 #include <platform_def.h>
 #include <psci.h>
-#include <sunxi_mmap.h>
 #include <sunxi_cpucfg.h>
+#include <sunxi_mmap.h>
+#include <sunxi_private.h>
 
 #define SUNXI_WDOG0_CTRL_REG		(SUNXI_WDOG_BASE + 0x0010)
 #define SUNXI_WDOG0_CFG_REG		(SUNXI_WDOG_BASE + 0x0014)
 #define SUNXI_WDOG0_MODE_REG		(SUNXI_WDOG_BASE + 0x0018)
 
-#include "sunxi_private.h"
-
 #define mpidr_is_valid(mpidr) ( \
 	MPIDR_AFFLVL3_VAL(mpidr) == 0 && \
 	MPIDR_AFFLVL2_VAL(mpidr) == 0 && \
@@ -43,6 +42,16 @@
 	gicv2_cpuif_disable();
 }
 
+static void __dead2 sunxi_pwr_down_wfi(const psci_power_state_t *target_state)
+{
+	u_register_t mpidr = read_mpidr();
+
+	sunxi_cpu_off(MPIDR_AFFLVL1_VAL(mpidr), MPIDR_AFFLVL0_VAL(mpidr));
+
+	while (1)
+		wfi();
+}
+
 static void sunxi_pwr_domain_on_finish(const psci_power_state_t *target_state)
 {
 	gicv2_pcpu_distif_init();
@@ -83,6 +92,7 @@
 static plat_psci_ops_t sunxi_psci_ops = {
 	.pwr_domain_on			= sunxi_pwr_domain_on,
 	.pwr_domain_off			= sunxi_pwr_domain_off,
+	.pwr_domain_pwr_down_wfi	= sunxi_pwr_down_wfi,
 	.pwr_domain_on_finish		= sunxi_pwr_domain_on_finish,
 	.system_off			= sunxi_system_off,
 	.system_reset			= sunxi_system_reset,
diff --git a/plat/allwinner/common/sunxi_private.h b/plat/allwinner/common/sunxi_private.h
deleted file mode 100644
index 20fa23e..0000000
--- a/plat/allwinner/common/sunxi_private.h
+++ /dev/null
@@ -1,22 +0,0 @@
-/*
- * Copyright (c) 2017-2018, ARM Limited and Contributors. All rights reserved.
- *
- * SPDX-License-Identifier: BSD-3-Clause
- */
-
-#ifndef __SUNXI_PRIVATE_H__
-#define __SUNXI_PRIVATE_H__
-
-void sunxi_configure_mmu_el3(int flags);
-void sunxi_cpu_off(unsigned int cluster, unsigned int core);
-void sunxi_cpu_on(unsigned int cluster, unsigned int core);
-void sunxi_disable_secondary_cpus(unsigned int primary_cpu);
-
-uint16_t sunxi_read_soc_id(void);
-
-void sunxi_pmic_setup(void);
-void sunxi_security_setup(void);
-
-void __dead2 sunxi_power_down(void);
-
-#endif /* __SUNXI_PRIVATE_H__ */
diff --git a/plat/allwinner/common/sunxi_security.c b/plat/allwinner/common/sunxi_security.c
index 80fed6a..9053728 100644
--- a/plat/allwinner/common/sunxi_security.c
+++ b/plat/allwinner/common/sunxi_security.c
@@ -7,6 +7,7 @@
 #include <debug.h>
 #include <mmio.h>
 #include <sunxi_mmap.h>
+#include <sunxi_private.h>
 
 #ifdef SUNXI_SPC_BASE
 #define SPC_DECPORT_STA_REG(p)	(SUNXI_SPC_BASE + ((p) * 0x0c) + 0x4)
diff --git a/plat/allwinner/sun50i_a64/include/core_off_arisc.h b/plat/allwinner/sun50i_a64/include/core_off_arisc.h
new file mode 100644
index 0000000..ae436ca
--- /dev/null
+++ b/plat/allwinner/sun50i_a64/include/core_off_arisc.h
@@ -0,0 +1,39 @@
+/*
+ * Copyright (c) 2018, ARM Limited and Contributors. All rights reserved.
+ *
+ * SPDX-License-Identifier: BSD-3-Clause
+ */
+
+static uint32_t arisc_core_off[] = {
+	0x18600000, /* l.movhi	r3, <corenr>	*/
+	0x18000000, /* l.movhi	r0, 0x0		*/
+	0x19a00170, /* l.movhi	r13, 0x170	*/
+	0x84ad0030, /* l.lwz	r5, 0x30(r13)	*/
+	0xe0a51803, /* l.and	r5, r5, r3	*/
+	0xe4050000, /* l.sfeq	r5, r0		*/
+	0x13fffffd, /* l.bf	-12		*/
+
+	0xb8c30050, /* l.srli	r6, r3, 16	*/
+	0xbc060001, /* l.sfeqi	r6, 1		*/
+	0x10000005, /* l.bf	+20		*/
+	0x19a001f0, /* l.movhi	r13, 0x1f0	*/
+	0x84ad1500, /* l.lwz	r5, 0x1500(r13)	*/
+	0xe0a53004, /* l.or	r5, r5, r6	*/
+	0xd44d2d00, /* l.sw	0x1500(r13), r5	*/
+
+	0x84ad1c30, /* l.lwz	r5, 0x1c30(r13)	*/
+	0xacc6ffff, /* l.xori	r6, r6, -1	*/
+	0xe0a53003, /* l.and	r5, r5, r6	*/
+	0xd46d2c30, /* l.sw	0x1c30(r13), r5	*/
+
+	0xe0c3000f, /* l.ff1	r6, r3		*/
+	0x9cc6ffef, /* l.addi	r6, r6, -17	*/
+	0xb8c60002, /* l.slli	r6, r6, 2	*/
+	0xe0c66800, /* l.add	r6, r6, r13	*/
+	0xa8a000ff, /* l.ori	r5, r0, 0xff	*/
+	0xd4462d40, /* l.sw	0x1540(r6), r5	*/
+
+	0xd46d0400, /* l.sw	0x1c00(r13), r0	*/
+	0x03ffffff, /* l.j	-1		*/
+	0x15000000, /* l.nop			*/
+};
diff --git a/plat/allwinner/sun50i_a64/include/sunxi_mmap.h b/plat/allwinner/sun50i_a64/include/sunxi_mmap.h
index 7d46487..28b1dd3 100644
--- a/plat/allwinner/sun50i_a64/include/sunxi_mmap.h
+++ b/plat/allwinner/sun50i_a64/include/sunxi_mmap.h
@@ -21,7 +21,7 @@
 #define SUNXI_DEV_BASE			0x01000000
 #define SUNXI_DEV_SIZE			0x01000000
 #define SUNXI_DRAM_BASE			0x40000000
-#define SUNXI_DRAM_SIZE			0x80000000
+#define SUNXI_DRAM_VIRT_BASE		0x02000000
 
 /* Memory-mapped devices */
 #define SUNXI_CPU_MBIST_BASE		0x01502000
diff --git a/plat/allwinner/sun50i_a64/platform.mk b/plat/allwinner/sun50i_a64/platform.mk
index 2216654..b46fbc2 100644
--- a/plat/allwinner/sun50i_a64/platform.mk
+++ b/plat/allwinner/sun50i_a64/platform.mk
@@ -4,51 +4,7 @@
 # SPDX-License-Identifier: BSD-3-Clause
 #
 
-include lib/xlat_tables_v2/xlat_tables.mk
-
-AW_PLAT			:=	plat/allwinner
-
-PLAT_INCLUDES		:=	-Iinclude/plat/arm/common/		\
-				-Iinclude/plat/arm/common/aarch64	\
-				-I${AW_PLAT}/common/include		\
-				-I${AW_PLAT}/${PLAT}/include
-
-PLAT_BL_COMMON_SOURCES	:=	drivers/console/${ARCH}/console.S	\
-				drivers/ti/uart/${ARCH}/16550_console.S	\
-				${XLAT_TABLES_LIB_SRCS}			\
-				${AW_PLAT}/common/plat_helpers.S	\
-				${AW_PLAT}/common/sunxi_common.c
-
-BL31_SOURCES		+=	drivers/arm/gic/common/gic_common.c	\
-				drivers/arm/gic/v2/gicv2_helpers.c	\
-				drivers/arm/gic/v2/gicv2_main.c		\
-				drivers/delay_timer/delay_timer.c	\
-				drivers/delay_timer/generic_delay_timer.c \
-				lib/cpus/${ARCH}/cortex_a53.S		\
-				plat/common/plat_gicv2.c		\
-				plat/common/plat_psci_common.c		\
-				${AW_PLAT}/common/sunxi_bl31_setup.c	\
-				${AW_PLAT}/common/sunxi_cpu_ops.c	\
-				${AW_PLAT}/common/sunxi_pm.c		\
-				${AW_PLAT}/sun50i_a64/sunxi_power.c	\
-				${AW_PLAT}/common/sunxi_security.c	\
-				${AW_PLAT}/common/sunxi_topology.c
-
-# The bootloader is guaranteed to only run on CPU 0 by the boot ROM.
-COLD_BOOT_SINGLE_CPU		:=	1
-
-# Enable workarounds for Cortex-A53 errata. Allwinner uses at least r0p4.
-ERRATA_A53_835769		:=	1
-ERRATA_A53_843419		:=	1
-ERRATA_A53_855873		:=	1
-
-MULTI_CONSOLE_API		:=	1
-
-# The reset vector can be changed for each CPU.
-PROGRAMMABLE_RESET_ADDRESS	:=	1
-
-# Allow mapping read-only data as execute-never.
-SEPARATE_CODE_AND_RODATA	:=	1
+# The differences between the platform are covered by the include files.
+include plat/allwinner/common/allwinner-common.mk
 
-# BL31 gets loaded alongside BL33 (U-Boot) by U-Boot's SPL
-RESET_TO_BL31			:=	1
+PLAT_BL_COMMON_SOURCES	+=	drivers/allwinner/sunxi_rsb.c
diff --git a/plat/allwinner/sun50i_a64/sunxi_power.c b/plat/allwinner/sun50i_a64/sunxi_power.c
index c1907d6..af30477 100644
--- a/plat/allwinner/sun50i_a64/sunxi_power.c
+++ b/plat/allwinner/sun50i_a64/sunxi_power.c
@@ -5,20 +5,350 @@
  * SPDX-License-Identifier: BSD-3-Clause
  */
 
+#include <allwinner/sunxi_rsb.h>
 #include <arch_helpers.h>
 #include <debug.h>
+#include <delay_timer.h>
+#include <errno.h>
+#include <libfdt.h>
+#include <mmio.h>
+#include <platform_def.h>
+#include <sunxi_def.h>
+#include <sunxi_mmap.h>
+#include <sunxi_private.h>
 
-int sunxi_pmic_setup(void)
+static enum pmic_type {
+	GENERIC_H5,
+	GENERIC_A64,
+	REF_DESIGN_H5,	/* regulators controlled by GPIO pins on port L */
+	AXP803_RSB,	/* PMIC connected via RSB on most A64 boards */
+} pmic;
+
+#define AXP803_HW_ADDR	0x3a3
+#define AXP803_RT_ADDR	0x2d
+
+/*
+ * On boards without a proper PMIC we struggle to turn off the system properly.
+ * Try to turn off as much off the system as we can, to reduce power
+ * consumption. This should be entered with only one core running and SMP
+ * disabled.
+ * This function only cares about peripherals.
+ */
+void sunxi_turn_off_soc(uint16_t socid)
+{
+	int i;
+
+	/** Turn off most peripherals, most importantly DRAM users. **/
+	/* Keep DRAM controller running for now. */
+	mmio_clrbits_32(SUNXI_CCU_BASE + 0x2c0, ~BIT_32(14));
+	mmio_clrbits_32(SUNXI_CCU_BASE + 0x60, ~BIT_32(14));
+	/* Contains msgbox (bit 21) and spinlock (bit 22) */
+	mmio_write_32(SUNXI_CCU_BASE + 0x2c4, 0);
+	mmio_write_32(SUNXI_CCU_BASE + 0x64, 0);
+	mmio_write_32(SUNXI_CCU_BASE + 0x2c8, 0);
+	/* Keep PIO controller running for now. */
+	mmio_clrbits_32(SUNXI_CCU_BASE + 0x68, ~(BIT_32(5)));
+	mmio_write_32(SUNXI_CCU_BASE + 0x2d0, 0);
+	/* Contains UART0 (bit 16) */
+	mmio_write_32(SUNXI_CCU_BASE + 0x2d8, 0);
+	mmio_write_32(SUNXI_CCU_BASE + 0x6c, 0);
+	mmio_write_32(SUNXI_CCU_BASE + 0x70, 0);
+
+	/** Turn off DRAM controller. **/
+	mmio_clrbits_32(SUNXI_CCU_BASE + 0x2c0, BIT_32(14));
+	mmio_clrbits_32(SUNXI_CCU_BASE + 0x60, BIT_32(14));
+
+	/** Migrate CPU and bus clocks away from the PLLs. **/
+	/* AHB1: use OSC24M/1, APB1 = AHB1 / 2 */
+	mmio_write_32(SUNXI_CCU_BASE + 0x54, 0x1000);
+	/* APB2: use OSC24M */
+	mmio_write_32(SUNXI_CCU_BASE + 0x58, 0x1000000);
+	/* AHB2: use AHB1 clock */
+	mmio_write_32(SUNXI_CCU_BASE + 0x5c, 0);
+	/* CPU: use OSC24M */
+	mmio_write_32(SUNXI_CCU_BASE + 0x50, 0x10000);
+
+	/** Turn off PLLs. **/
+	for (i = 0; i < 6; i++)
+		mmio_clrbits_32(SUNXI_CCU_BASE + i * 8, BIT(31));
+	switch (socid) {
+	case SUNXI_SOC_H5:
+		mmio_clrbits_32(SUNXI_CCU_BASE + 0x44, BIT(31));
+		break;
+	case SUNXI_SOC_A64:
+		mmio_clrbits_32(SUNXI_CCU_BASE + 0x2c, BIT(31));
+		mmio_clrbits_32(SUNXI_CCU_BASE + 0x4c, BIT(31));
+		break;
+	}
+}
+
+static int rsb_init(void)
+{
+	int ret;
+
+	ret = rsb_init_controller();
+	if (ret)
+		return ret;
+
+	/* Start with 400 KHz to issue the I2C->RSB switch command. */
+	ret = rsb_set_bus_speed(SUNXI_OSC24M_CLK_IN_HZ, 400000);
+	if (ret)
+		return ret;
+
+	/*
+	 * Initiate an I2C transaction to write 0x7c into register 0x3e,
+	 * switching the PMIC to RSB mode.
+	 */
+	ret = rsb_set_device_mode(0x7c3e00);
+	if (ret)
+		return ret;
+
+	/* Now in RSB mode, switch to the recommended 3 MHz. */
+	ret = rsb_set_bus_speed(SUNXI_OSC24M_CLK_IN_HZ, 3000000);
+	if (ret)
+		return ret;
+
+	/* Associate the 8-bit runtime address with the 12-bit bus address. */
+	return rsb_assign_runtime_address(AXP803_HW_ADDR,
+					  AXP803_RT_ADDR);
+}
+
+static int axp_write(uint8_t reg, uint8_t val)
 {
-	/* STUB */
-	NOTICE("BL31: STUB PMIC setup code called\n");
+	return rsb_write(AXP803_RT_ADDR, reg, val);
+}
+
+static int axp_setbits(uint8_t reg, uint8_t set_mask)
+{
+	uint8_t regval;
+	int ret;
+
+	ret = rsb_read(AXP803_RT_ADDR, reg);
+	if (ret < 0)
+		return ret;
+
+	regval = ret | set_mask;
+
+	return rsb_write(AXP803_RT_ADDR, reg, regval);
+}
+
+static bool should_enable_regulator(const void *fdt, int node)
+{
+	if (fdt_getprop(fdt, node, "phandle", NULL) != NULL)
+		return true;
+	if (fdt_getprop(fdt, node, "regulator-always-on", NULL) != NULL)
+		return true;
+	return false;
+}
+
+/*
+ * Retrieve the voltage from a given regulator DTB node.
+ * Both the regulator-{min,max}-microvolt properties must be present and
+ * have the same value. Return that value in millivolts.
+ */
+static int fdt_get_regulator_millivolt(const void *fdt, int node)
+{
+	const fdt32_t *prop;
+	uint32_t min_volt;
+
+	prop = fdt_getprop(fdt, node, "regulator-min-microvolt", NULL);
+	if (prop == NULL)
+		return -EINVAL;
+	min_volt = fdt32_to_cpu(*prop);
+
+	prop = fdt_getprop(fdt, node, "regulator-max-microvolt", NULL);
+	if (prop == NULL)
+		return -EINVAL;
+
+	if (fdt32_to_cpu(*prop) != min_volt)
+		return -EINVAL;
+
+	return min_volt / 1000;
+}
+
+#define NO_SPLIT 0xff
+
+struct axp_regulator {
+	char *dt_name;
+	uint16_t min_volt;
+	uint16_t max_volt;
+	uint16_t step;
+	unsigned char split;
+	unsigned char volt_reg;
+	unsigned char switch_reg;
+	unsigned char switch_bit;
+} regulators[] = {
+	{"dcdc1", 1600, 3400, 100, NO_SPLIT, 0x20, 0xff, 9},
+	{"dcdc5",  800, 1840,  10,       32, 0x24, 0xff, 9},
+	{"dldo1",  700, 3300, 100, NO_SPLIT, 0x15, 0x12, 3},
+	{"dldo2",  700, 4200, 100,       27, 0x16, 0x12, 4},
+	{"dldo3",  700, 3300, 100, NO_SPLIT, 0x17, 0x12, 5},
+	{"fldo1",  700, 1450,  50, NO_SPLIT, 0x1c, 0x13, 2},
+	{}
+};
+
+static int setup_regulator(const void *fdt, int node,
+			   const struct axp_regulator *reg)
+{
+	int mvolt;
+	uint8_t regval;
+
+	if (!should_enable_regulator(fdt, node))
+		return -ENOENT;
+
+	mvolt = fdt_get_regulator_millivolt(fdt, node);
+	if (mvolt < reg->min_volt || mvolt > reg->max_volt)
+		return -EINVAL;
+
+	regval = (mvolt / reg->step) - (reg->min_volt / reg->step);
+	if (regval > reg->split)
+		regval = ((regval - reg->split) / 2) + reg->split;
+
+	axp_write(reg->volt_reg, regval);
+	if (reg->switch_reg < 0xff)
+		axp_setbits(reg->switch_reg, BIT(reg->switch_bit));
+
+	INFO("PMIC: AXP803: %s voltage: %d.%03dV\n", reg->dt_name,
+	     mvolt / 1000, mvolt % 1000);
 
 	return 0;
 }
 
+static void setup_axp803_rails(const void *fdt)
+{
+	int node;
+	bool dc1sw = false;
+
+	/* locate the PMIC DT node, bail out if not found */
+	node = fdt_node_offset_by_compatible(fdt, -1, "x-powers,axp803");
+	if (node == -FDT_ERR_NOTFOUND) {
+		WARN("BL31: PMIC: No AXP803 DT node, skipping initial setup.\n");
+		return;
+	}
+
+	if (fdt_getprop(fdt, node, "x-powers,drive-vbus-en", NULL))
+		axp_setbits(0x8f, BIT(4));
+
+	/* descend into the "regulators" subnode */
+	node = fdt_first_subnode(fdt, node);
+
+	/* iterate over all regulators to find used ones */
+	for (node = fdt_first_subnode(fdt, node);
+	     node != -FDT_ERR_NOTFOUND;
+	     node = fdt_next_subnode(fdt, node)) {
+		struct axp_regulator *reg;
+		const char *name;
+		int length;
+
+		/* We only care if it's always on or referenced. */
+		if (!should_enable_regulator(fdt, node))
+			continue;
+
+		name = fdt_get_name(fdt, node, &length);
+		for (reg = regulators; reg->dt_name; reg++) {
+			if (!strncmp(name, reg->dt_name, length)) {
+				setup_regulator(fdt, node, reg);
+				break;
+			}
+		}
+
+		if (!strncmp(name, "dc1sw", length)) {
+			/* Delay DC1SW enablement to avoid overheating. */
+			dc1sw = true;
+			continue;
+		}
+	}
+	/*
+	 * If DLDO2 is enabled after DC1SW, the PMIC overheats and shuts
+	 * down. So always enable DC1SW as the very last regulator.
+	 */
+	if (dc1sw) {
+		INFO("PMIC: AXP803: Enabling DC1SW\n");
+		axp_setbits(0x12, BIT(7));
+	}
+}
+
+int sunxi_pmic_setup(uint16_t socid, const void *fdt)
+{
+	int ret;
+
+	switch (socid) {
+	case SUNXI_SOC_H5:
+		pmic = REF_DESIGN_H5;
+		NOTICE("BL31: PMIC: Defaulting to PortL GPIO according to H5 reference design.\n");
+		break;
+	case SUNXI_SOC_A64:
+		pmic = GENERIC_A64;
+		ret = sunxi_init_platform_r_twi(socid, true);
+		if (ret)
+			return ret;
+
+		ret = rsb_init();
+		if (ret)
+			return ret;
+
+		pmic = AXP803_RSB;
+		NOTICE("BL31: PMIC: Detected AXP803 on RSB.\n");
+
+		if (fdt)
+			setup_axp803_rails(fdt);
+
+		break;
+	default:
+		NOTICE("BL31: PMIC: No support for Allwinner %x SoC.\n", socid);
+		return -ENODEV;
+	}
+	return 0;
+}
+
 void __dead2 sunxi_power_down(void)
 {
-	ERROR("PSCI: Full shutdown not implemented, halting\n");
+	switch (pmic) {
+	case GENERIC_H5:
+		/* Turn off as many peripherals and clocks as we can. */
+		sunxi_turn_off_soc(SUNXI_SOC_H5);
+		/* Turn off the pin controller now. */
+		mmio_write_32(SUNXI_CCU_BASE + 0x68, 0);
+		break;
+	case GENERIC_A64:
+		/* Turn off as many peripherals and clocks as we can. */
+		sunxi_turn_off_soc(SUNXI_SOC_A64);
+		/* Turn off the pin controller now. */
+		mmio_write_32(SUNXI_CCU_BASE + 0x68, 0);
+		break;
+	case REF_DESIGN_H5:
+		sunxi_turn_off_soc(SUNXI_SOC_H5);
+
+		/*
+		 * Switch PL pins to power off the board:
+		 * - PL5 (VCC_IO) -> high
+		 * - PL8 (PWR-STB = CPU power supply) -> low
+		 * - PL9 (PWR-DRAM) ->low
+		 * - PL10 (power LED) -> low
+		 * Note: Clearing PL8 will reset the board, so keep it up.
+		 */
+		sunxi_set_gpio_out('L', 5, 1);
+		sunxi_set_gpio_out('L', 9, 0);
+		sunxi_set_gpio_out('L', 10, 0);
+
+		/* Turn off pin controller now. */
+		mmio_write_32(SUNXI_CCU_BASE + 0x68, 0);
+
+		break;
+	case AXP803_RSB:
+		/* (Re-)init RSB in case the rich OS has disabled it. */
+		sunxi_init_platform_r_twi(SUNXI_SOC_A64, true);
+		rsb_init();
+
+		/* Set "power disable control" bit */
+		axp_setbits(0x32, BIT(7));
+		break;
+	default:
+		break;
+	}
+
+	udelay(1000);
+	ERROR("PSCI: Cannot turn off system, halting.\n");
 	wfi();
 	panic();
 }
diff --git a/plat/allwinner/sun50i_h6/include/core_off_arisc.h b/plat/allwinner/sun50i_h6/include/core_off_arisc.h
new file mode 100644
index 0000000..63a5d8d
--- /dev/null
+++ b/plat/allwinner/sun50i_h6/include/core_off_arisc.h
@@ -0,0 +1,39 @@
+/*
+ * Copyright (c) 2018, ARM Limited and Contributors. All rights reserved.
+ *
+ * SPDX-License-Identifier: BSD-3-Clause
+ */
+
+static uint32_t arisc_core_off[] = {
+	0x18600000, /* l.movhi	r3, <corenr>	*/
+	0x18000000, /* l.movhi	r0, 0x0		*/
+	0x19a00901, /* l.movhi	r13, 0x901	*/
+	0x84ad0080, /* l.lwz	r5, 0x80(r13)	*/
+	0xe0a51803, /* l.and	r5, r5, r3	*/
+	0xe4050000, /* l.sfeq	r5, r0		*/
+	0x13fffffd, /* l.bf	-12		*/
+	0xb8c30050, /* l.srli	r6, r3, 16	*/
+
+	0xbc060001, /* l.sfeqi	r6, 1		*/
+	0x10000005, /* l.bf	+20		*/
+	0x19a00700, /* l.movhi	r13, 0x700	*/
+	0x84ad0444, /* l.lwz	r5, 0x0444(r13)	*/
+	0xe0a53004, /* l.or	r5, r5, r6	*/
+	0xd40d2c44, /* l.sw	0x0444(r13), r5	*/
+
+	0x84ad0440, /* l.lwz	r5, 0x0440(r13)	*/
+	0xacc6ffff, /* l.xori	r6, r6, -1	*/
+	0xe0a53003, /* l.and	r5, r5, r6	*/
+	0xd40d2c40, /* l.sw	0x0440(r13), r5	*/
+
+	0xe0c3000f, /* l.ff1	r6, r3		*/
+	0x9cc6ffef, /* l.addi	r6, r6, -17	*/
+	0xb8c60002, /* l.slli	r6, r6, 2	*/
+	0xe0c66800, /* l.add	r6, r6, r13	*/
+	0xa8a000ff, /* l.ori	r5, r0, 0xff	*/
+	0xd4062c50, /* l.sw	0x0450(r6), r5	*/
+
+	0xd40d0400, /* l.sw	0x0400(r13), r0	*/
+	0x03ffffff, /* l.j	-1		*/
+	0x15000000, /* l.nop			*/
+};
diff --git a/plat/allwinner/sun50i_h6/include/sunxi_mmap.h b/plat/allwinner/sun50i_h6/include/sunxi_mmap.h
index f2d5aed..ff1eb61 100644
--- a/plat/allwinner/sun50i_h6/include/sunxi_mmap.h
+++ b/plat/allwinner/sun50i_h6/include/sunxi_mmap.h
@@ -11,7 +11,7 @@
 #define SUNXI_ROM_BASE			0x00000000
 #define SUNXI_ROM_SIZE			0x00010000
 #define SUNXI_SRAM_BASE			0x00020000
-#define SUNXI_SRAM_SIZE			0x00098000
+#define SUNXI_SRAM_SIZE			0x000f8000
 #define SUNXI_SRAM_A1_BASE		0x00020000
 #define SUNXI_SRAM_A1_SIZE		0x00008000
 #define SUNXI_SRAM_A2_BASE		0x00104000
@@ -21,7 +21,7 @@
 #define SUNXI_DEV_BASE			0x01000000
 #define SUNXI_DEV_SIZE			0x09000000
 #define SUNXI_DRAM_BASE			0x40000000
-#define SUNXI_DRAM_SIZE			0xc0000000
+#define SUNXI_DRAM_VIRT_BASE		0x0a000000
 
 /* Memory-mapped devices */
 #define SUNXI_SYSCON_BASE		0x03000000
diff --git a/plat/allwinner/sun50i_h6/platform.mk b/plat/allwinner/sun50i_h6/platform.mk
index 4fb8986..5c21ead 100644
--- a/plat/allwinner/sun50i_h6/platform.mk
+++ b/plat/allwinner/sun50i_h6/platform.mk
@@ -4,53 +4,7 @@
 # SPDX-License-Identifier: BSD-3-Clause
 #
 
-include lib/xlat_tables_v2/xlat_tables.mk
-
-AW_PLAT			:=	plat/allwinner
-AW_DRIVERS		:=	drivers/allwinner
-
-PLAT_INCLUDES		:=	-Iinclude/plat/arm/common		\
-				-Iinclude/plat/arm/common/aarch64	\
-				-I${AW_PLAT}/common/include		\
-				-I${AW_PLAT}/${PLAT}/include
-
-PLAT_BL_COMMON_SOURCES	:=	drivers/console/${ARCH}/console.S	\
-				drivers/mentor/i2c/mi2cv.c		\
-				drivers/ti/uart/${ARCH}/16550_console.S	\
-				${XLAT_TABLES_LIB_SRCS}			\
-				${AW_PLAT}/common/plat_helpers.S	\
-				${AW_PLAT}/common/sunxi_common.c
-
-BL31_SOURCES		+=	drivers/arm/gic/common/gic_common.c	\
-				drivers/arm/gic/v2/gicv2_helpers.c	\
-				drivers/arm/gic/v2/gicv2_main.c		\
-				drivers/delay_timer/delay_timer.c	\
-				drivers/delay_timer/generic_delay_timer.c \
-				lib/cpus/${ARCH}/cortex_a53.S		\
-				plat/common/plat_gicv2.c		\
-				plat/common/plat_psci_common.c		\
-				${AW_PLAT}/common/sunxi_bl31_setup.c	\
-				${AW_PLAT}/common/sunxi_cpu_ops.c	\
-				${AW_PLAT}/common/sunxi_pm.c		\
-				${AW_PLAT}/sun50i_h6/sunxi_power.c	\
-				${AW_PLAT}/common/sunxi_security.c	\
-				${AW_PLAT}/common/sunxi_topology.c
-
-# The bootloader is guaranteed to only run on CPU 0 by the boot ROM.
-COLD_BOOT_SINGLE_CPU		:=	1
-
-# Enable workarounds for Cortex-A53 errata. Allwinner uses at least r0p4.
-ERRATA_A53_835769		:=	1
-ERRATA_A53_843419		:=	1
-ERRATA_A53_855873		:=	1
-
-MULTI_CONSOLE_API		:=	1
-
-# The reset vector can be changed for each CPU.
-PROGRAMMABLE_RESET_ADDRESS	:=	1
-
-# Allow mapping read-only data as execute-never.
-SEPARATE_CODE_AND_RODATA	:=	1
+# The differences between the platform are covered by the include files.
+include plat/allwinner/common/allwinner-common.mk
 
-# BL31 gets loaded alongside BL33 (U-Boot) by U-Boot's SPL
-RESET_TO_BL31			:=	1
+PLAT_BL_COMMON_SOURCES	+=	drivers/mentor/i2c/mi2cv.c
diff --git a/plat/allwinner/sun50i_h6/sunxi_power.c b/plat/allwinner/sun50i_h6/sunxi_power.c
index 12438b3..7bdac8a 100644
--- a/plat/allwinner/sun50i_h6/sunxi_power.c
+++ b/plat/allwinner/sun50i_h6/sunxi_power.c
@@ -12,7 +12,9 @@
 #include <mmio.h>
 #include <mentor/mi2cv.h>
 #include <string.h>
+#include <sunxi_def.h>
 #include <sunxi_mmap.h>
+#include <sunxi_private.h>
 
 #define AXP805_ADDR	0x36
 #define AXP805_ID	0x03
@@ -24,36 +26,6 @@
 
 enum pmic_type pmic;
 
-static int sunxi_init_r_i2c(void)
-{
-	uint32_t reg;
-
-	/* switch pins PL0 and PL1 to I2C */
-	reg = mmio_read_32(SUNXI_R_PIO_BASE + 0x00);
-	mmio_write_32(SUNXI_R_PIO_BASE + 0x00, (reg & ~0xff) | 0x33);
-
-	/* level 2 drive strength */
-	reg = mmio_read_32(SUNXI_R_PIO_BASE + 0x14);
-	mmio_write_32(SUNXI_R_PIO_BASE + 0x14, (reg & ~0x0f) | 0xa);
-
-	/* set both ports to pull-up */
-	reg = mmio_read_32(SUNXI_R_PIO_BASE + 0x1c);
-	mmio_write_32(SUNXI_R_PIO_BASE + 0x1c, (reg & ~0x0f) | 0x5);
-
-	/* assert & de-assert reset of R_I2C */
-	reg = mmio_read_32(SUNXI_R_PRCM_BASE + 0x19c);
-	mmio_write_32(SUNXI_R_PRCM_BASE + 0x19c, reg & ~BIT(16));
-	mmio_write_32(SUNXI_R_PRCM_BASE + 0x19c, reg | BIT(16));
-
-	/* un-gate R_I2C clock */
-	mmio_write_32(SUNXI_R_PRCM_BASE + 0x19c, reg | BIT(16) | BIT(0));
-
-	/* call mi2cv driver */
-	i2c_init((void *)SUNXI_R_I2C_BASE);
-
-	return 0;
-}
-
 int axp_i2c_read(uint8_t chip, uint8_t reg, uint8_t *val)
 {
 	int ret;
@@ -96,11 +68,13 @@
 	return 0;
 }
 
-int sunxi_pmic_setup(void)
+int sunxi_pmic_setup(uint16_t socid, const void *fdt)
 {
 	int ret;
 
-	sunxi_init_r_i2c();
+	sunxi_init_platform_r_twi(SUNXI_SOC_H6, false);
+	/* initialise mi2cv driver */
+	i2c_init((void *)SUNXI_R_I2C_BASE);
 
 	NOTICE("PMIC: Probing AXP805\n");
 	pmic = AXP805;
@@ -120,7 +94,10 @@
 
 	switch (pmic) {
 	case AXP805:
-		sunxi_init_r_i2c();
+		/* Re-initialise after rich OS might have used it. */
+		sunxi_init_platform_r_twi(SUNXI_SOC_H6, false);
+		/* initialise mi2cv driver */
+		i2c_init((void *)SUNXI_R_I2C_BASE);
 		axp_i2c_read(AXP805_ADDR, 0x32, &val);
 		axp_i2c_write(AXP805_ADDR, 0x32, val | 0x80);
 		break;