Merge changes I93ecff4d,I30dd9a95,I8207eea9,Id4197b07,Ib810125b, ... into integration

* changes:
  mediatek: mt8183: add MTK MCDI driver
  mediatek: mt8183: add MTK SSPM driver
  mediatek: mt8183: add MTK SPM driver
  mediatek: mt8183: add MTK uart driver for controlling clock gate
  mediatek: mt8183: configure MCUSYS DCM
  mediatek: mt8173: refactor RTC and PMIC drivers
diff --git a/plat/mediatek/mt8173/drivers/pmic/pmic_wrap_init.c b/plat/mediatek/mt8173/drivers/pmic/pmic_wrap_init.c
deleted file mode 100644
index 8120d99..0000000
--- a/plat/mediatek/mt8173/drivers/pmic/pmic_wrap_init.c
+++ /dev/null
@@ -1,165 +0,0 @@
-/*
- * Copyright (c) 2015, ARM Limited and Contributors. All rights reserved.
- *
- * SPDX-License-Identifier: BSD-3-Clause
- */
-
-#include <common/debug.h>
-#include <drivers/delay_timer.h>
-#include <lib/mmio.h>
-
-#include <mt8173_def.h>
-#include <pmic_wrap_init.h>
-
-/* pmic wrap module wait_idle and read polling interval (in microseconds) */
-enum {
-	WAIT_IDLE_POLLING_DELAY_US	= 1,
-	READ_POLLING_DELAY_US		= 2
-};
-
-static inline uint32_t wait_for_state_idle(uint32_t timeout_us,
-					   void *wacs_register,
-					   void *wacs_vldclr_register,
-					   uint32_t *read_reg)
-{
-	uint32_t reg_rdata;
-	uint32_t retry;
-
-	retry = (timeout_us + WAIT_IDLE_POLLING_DELAY_US) /
-		WAIT_IDLE_POLLING_DELAY_US;
-
-	do {
-		udelay(WAIT_IDLE_POLLING_DELAY_US);
-		reg_rdata = mmio_read_32((uintptr_t)wacs_register);
-		/* if last read command timeout,clear vldclr bit
-		   read command state machine:FSM_REQ-->wfdle-->WFVLDCLR;
-		   write:FSM_REQ-->idle */
-		switch (((reg_rdata >> RDATA_WACS_FSM_SHIFT) &
-			RDATA_WACS_FSM_MASK)) {
-		case WACS_FSM_WFVLDCLR:
-			mmio_write_32((uintptr_t)wacs_vldclr_register, 1);
-			ERROR("WACS_FSM = PMIC_WRAP_WACS_VLDCLR\n");
-			break;
-		case WACS_FSM_WFDLE:
-			ERROR("WACS_FSM = WACS_FSM_WFDLE\n");
-			break;
-		case WACS_FSM_REQ:
-			ERROR("WACS_FSM = WACS_FSM_REQ\n");
-			break;
-		case WACS_FSM_IDLE:
-			goto done;
-		default:
-			break;
-		}
-
-		retry--;
-	} while (retry);
-
-done:
-	if (!retry)	/* timeout */
-		return E_PWR_WAIT_IDLE_TIMEOUT;
-
-	if (read_reg)
-		*read_reg = reg_rdata;
-	return 0;
-}
-
-static inline uint32_t wait_for_state_ready(uint32_t timeout_us,
-					    void *wacs_register,
-					    uint32_t *read_reg)
-{
-	uint32_t reg_rdata;
-	uint32_t retry;
-
-	retry = (timeout_us + READ_POLLING_DELAY_US) / READ_POLLING_DELAY_US;
-
-	do {
-		udelay(READ_POLLING_DELAY_US);
-		reg_rdata = mmio_read_32((uintptr_t)wacs_register);
-
-		if (((reg_rdata >> RDATA_WACS_FSM_SHIFT) & RDATA_WACS_FSM_MASK)
-		    == WACS_FSM_WFVLDCLR)
-			break;
-
-		retry--;
-	} while (retry);
-
-	if (!retry) {	/* timeout */
-		ERROR("timeout when waiting for idle\n");
-		return E_PWR_WAIT_IDLE_TIMEOUT_READ;
-	}
-
-	if (read_reg)
-		*read_reg = reg_rdata;
-	return 0;
-}
-
-static int32_t pwrap_wacs2(uint32_t write,
-		    uint32_t adr,
-		    uint32_t wdata,
-		    uint32_t *rdata,
-		    uint32_t init_check)
-{
-	uint32_t reg_rdata = 0;
-	uint32_t wacs_write = 0;
-	uint32_t wacs_adr = 0;
-	uint32_t wacs_cmd = 0;
-	uint32_t return_value = 0;
-
-	if (init_check) {
-		reg_rdata = mmio_read_32((uintptr_t)&mt8173_pwrap->wacs2_rdata);
-		/* Prevent someone to used pwrap before pwrap init */
-		if (((reg_rdata >> RDATA_INIT_DONE_SHIFT) &
-		    RDATA_INIT_DONE_MASK) != WACS_INIT_DONE) {
-			ERROR("initialization isn't finished\n");
-			return E_PWR_NOT_INIT_DONE;
-		}
-	}
-	reg_rdata = 0;
-	/* Check IDLE in advance */
-	return_value = wait_for_state_idle(TIMEOUT_WAIT_IDLE,
-				&mt8173_pwrap->wacs2_rdata,
-				&mt8173_pwrap->wacs2_vldclr,
-				0);
-	if (return_value != 0) {
-		ERROR("wait_for_fsm_idle fail,return_value=%d\n", return_value);
-		goto FAIL;
-	}
-	wacs_write = write << 31;
-	wacs_adr = (adr >> 1) << 16;
-	wacs_cmd = wacs_write | wacs_adr | wdata;
-
-	mmio_write_32((uintptr_t)&mt8173_pwrap->wacs2_cmd, wacs_cmd);
-	if (write == 0) {
-		if (NULL == rdata) {
-			ERROR("rdata is a NULL pointer\n");
-			return_value = E_PWR_INVALID_ARG;
-			goto FAIL;
-		}
-		return_value = wait_for_state_ready(TIMEOUT_READ,
-					&mt8173_pwrap->wacs2_rdata,
-					&reg_rdata);
-		if (return_value != 0) {
-			ERROR("wait_for_fsm_vldclr fail,return_value=%d\n",
-				 return_value);
-			goto FAIL;
-		}
-		*rdata = ((reg_rdata >> RDATA_WACS_RDATA_SHIFT)
-			  & RDATA_WACS_RDATA_MASK);
-		mmio_write_32((uintptr_t)&mt8173_pwrap->wacs2_vldclr, 1);
-	}
-FAIL:
-	return return_value;
-}
-
-/* external API for pmic_wrap user */
-
-int32_t pwrap_read(uint32_t adr, uint32_t *rdata)
-{
-	return pwrap_wacs2(0, adr, 0, rdata, 1);
-}
-
-int32_t pwrap_write(uint32_t adr, uint32_t wdata)
-{
-	return pwrap_wacs2(1, adr, wdata, 0, 1);
-}
diff --git a/plat/mediatek/mt8173/drivers/pmic/pmic_wrap_init.h b/plat/mediatek/mt8173/drivers/pmic/pmic_wrap_init.h
index 0f09771..0dffc23 100644
--- a/plat/mediatek/mt8173/drivers/pmic/pmic_wrap_init.h
+++ b/plat/mediatek/mt8173/drivers/pmic/pmic_wrap_init.h
@@ -7,11 +7,13 @@
 #ifndef PMIC_WRAP_INIT_H
 #define PMIC_WRAP_INIT_H
 
+#include <platform_def.h>
+
 /* external API */
 int32_t pwrap_read(uint32_t adr, uint32_t *rdata);
 int32_t pwrap_write(uint32_t adr, uint32_t wdata);
 
-static struct mt8173_pmic_wrap_regs *const mt8173_pwrap =
+static struct mt8173_pmic_wrap_regs *const mtk_pwrap =
 	(void *)PMIC_WRAP_BASE;
 
 /* timeout setting */
diff --git a/plat/mediatek/mt8173/drivers/rtc/rtc.c b/plat/mediatek/mt8173/drivers/rtc/rtc.c
index 2b9033e..587886c 100644
--- a/plat/mediatek/mt8173/drivers/rtc/rtc.c
+++ b/plat/mediatek/mt8173/drivers/rtc/rtc.c
@@ -5,66 +5,11 @@
  */
 
 #include <assert.h>
-
 #include <common/debug.h>
-#include <drivers/delay_timer.h>
 
 #include <mt8173_def.h>
-#include <pmic_wrap_init.h>
 #include <rtc.h>
 
-/* RTC busy status polling interval and retry count */
-enum {
-	RTC_WRTGR_POLLING_DELAY_MS	= 10,
-	RTC_WRTGR_POLLING_CNT		= 100
-};
-
-static uint16_t RTC_Read(uint32_t addr)
-{
-	uint32_t rdata = 0;
-
-	pwrap_read((uint32_t)addr, &rdata);
-	return (uint16_t)rdata;
-}
-
-static void RTC_Write(uint32_t addr, uint16_t data)
-{
-	pwrap_write((uint32_t)addr, (uint32_t)data);
-}
-
-static inline int32_t rtc_busy_wait(void)
-{
-	uint64_t retry = RTC_WRTGR_POLLING_CNT;
-
-	do {
-		mdelay(RTC_WRTGR_POLLING_DELAY_MS);
-		if (!(RTC_Read(RTC_BBPU) & RTC_BBPU_CBUSY))
-			return 1;
-		retry--;
-	} while (retry);
-
-	ERROR("[RTC] rtc cbusy time out!\n");
-	return 0;
-}
-
-static int32_t Write_trigger(void)
-{
-	RTC_Write(RTC_WRTGR, 1);
-	return rtc_busy_wait();
-}
-
-static int32_t Writeif_unlock(void)
-{
-	RTC_Write(RTC_PROT, RTC_PROT_UNLOCK1);
-	if (!Write_trigger())
-		return 0;
-	RTC_Write(RTC_PROT, RTC_PROT_UNLOCK2);
-	if (!Write_trigger())
-		return 0;
-
-	return 1;
-}
-
 void rtc_bbpu_power_down(void)
 {
 	uint16_t bbpu;
@@ -73,7 +18,7 @@
 	bbpu = RTC_BBPU_KEY | RTC_BBPU_AUTO | RTC_BBPU_PWREN;
 	if (Writeif_unlock()) {
 		RTC_Write(RTC_BBPU, bbpu);
-		if (!Write_trigger())
+		if (!RTC_Write_Trigger())
 			assert(0);
 	} else {
 		assert(0);
diff --git a/plat/mediatek/mt8173/drivers/rtc/rtc.h b/plat/mediatek/mt8173/drivers/rtc/rtc.h
index 9c4ca49..f60a4c1 100644
--- a/plat/mediatek/mt8173/drivers/rtc/rtc.h
+++ b/plat/mediatek/mt8173/drivers/rtc/rtc.h
@@ -49,6 +49,12 @@
 	RTC_BBPU_KEY	= 0x43 << 8
 };
 
+/* external API */
+uint16_t RTC_Read(uint32_t addr);
+void RTC_Write(uint32_t addr, uint16_t data);
+int32_t rtc_busy_wait(void);
+int32_t RTC_Write_Trigger(void);
+int32_t Writeif_unlock(void);
 void rtc_bbpu_power_down(void);
 
 #endif /* RTC_H */
diff --git a/plat/mediatek/mt8173/platform.mk b/plat/mediatek/mt8173/platform.mk
index e5eca9f..a66c49b 100644
--- a/plat/mediatek/mt8173/platform.mk
+++ b/plat/mediatek/mt8173/platform.mk
@@ -35,6 +35,8 @@
 				lib/cpus/aarch64/cortex_a53.S			\
 				lib/cpus/aarch64/cortex_a57.S			\
 				lib/cpus/aarch64/cortex_a72.S			\
+				${MTK_PLAT}/common/drivers/pmic_wrap/pmic_wrap_init.c	\
+				${MTK_PLAT}/common/drivers/rtc/rtc_common.c	\
 				${MTK_PLAT}/common/mtk_plat_common.c		\
 				${MTK_PLAT}/common/mtk_sip_svc.c		\
 				${MTK_PLAT_SOC}/aarch64/plat_helpers.S		\
@@ -42,7 +44,6 @@
 				${MTK_PLAT_SOC}/bl31_plat_setup.c		\
 				${MTK_PLAT_SOC}/drivers/crypt/crypt.c		\
 				${MTK_PLAT_SOC}/drivers/mtcmos/mtcmos.c		\
-				${MTK_PLAT_SOC}/drivers/pmic/pmic_wrap_init.c	\
 				${MTK_PLAT_SOC}/drivers/rtc/rtc.c		\
 				${MTK_PLAT_SOC}/drivers/spm/spm.c		\
 				${MTK_PLAT_SOC}/drivers/spm/spm_hotplug.c	\
diff --git a/plat/mediatek/mt8183/bl31_plat_setup.c b/plat/mediatek/mt8183/bl31_plat_setup.c
index 337470a..ec387f4 100644
--- a/plat/mediatek/mt8183/bl31_plat_setup.c
+++ b/plat/mediatek/mt8183/bl31_plat_setup.c
@@ -16,6 +16,7 @@
 #include <mt_gic_v3.h>
 #include <lib/coreboot.h>
 #include <lib/mmio.h>
+#include <mtk_mcdi.h>
 #include <mtk_plat_common.h>
 #include <mtspmc.h>
 #include <plat_debug.h>
@@ -23,6 +24,7 @@
 #include <plat_private.h>
 #include <platform_def.h>
 #include <scu.h>
+#include <spm.h>
 #include <drivers/ti/uart/uart_16550.h>
 
 static entry_point_info_t bl32_ep_info;
@@ -32,15 +34,49 @@
 {
 	mmio_write_32((uintptr_t)&mt8183_mcucfg->mp0_rw_rsvd0, 0x00000001);
 
-	VERBOSE("addr of cci_adb400_dcm_config: 0x%x\n",
-		mmio_read_32((uintptr_t)&mt8183_mcucfg->cci_adb400_dcm_config));
-	VERBOSE("addr of sync_dcm_config: 0x%x\n",
-		mmio_read_32((uintptr_t)&mt8183_mcucfg->sync_dcm_config));
-
-	VERBOSE("mp0_spmc: 0x%x\n",
-		mmio_read_32((uintptr_t)&mt8183_mcucfg->mp0_cputop_spmc_ctl));
-	VERBOSE("mp1_spmc: 0x%x\n",
-		mmio_read_32((uintptr_t)&mt8183_mcucfg->mp1_cputop_spmc_ctl));
+	/* Mcusys dcm control */
+	/* Enable pll plldiv dcm */
+	mmio_setbits_32((uintptr_t)&mt8183_mcucfg->bus_pll_divider_cfg,
+		BUS_PLLDIV_DCM);
+	mmio_setbits_32((uintptr_t)&mt8183_mcucfg->mp0_pll_divider_cfg,
+		MP0_PLLDIV_DCM);
+	mmio_setbits_32((uintptr_t)&mt8183_mcucfg->mp2_pll_divider_cfg,
+		MP2_PLLDIV_DCM);
+	/* Enable mscib dcm  */
+	mmio_clrsetbits_32((uintptr_t)&mt8183_mcucfg->mscib_dcm_en,
+		MCSIB_CACTIVE_SEL_MASK, MCSIB_CACTIVE_SEL);
+	mmio_clrsetbits_32((uintptr_t)&mt8183_mcucfg->mscib_dcm_en,
+		MCSIB_DCM_MASK, MCSIB_DCM);
+	/* Enable adb400 dcm */
+	mmio_clrsetbits_32((uintptr_t)&mt8183_mcucfg->cci_adb400_dcm_config,
+		CCI_ADB400_DCM_MASK, CCI_ADB400_DCM);
+	/* Enable bus clock dcm */
+	mmio_setbits_32((uintptr_t)&mt8183_mcucfg->cci_clk_ctrl,
+		MCU_BUS_DCM);
+	/* Enable bus fabric dcm */
+	mmio_clrsetbits_32(
+		(uintptr_t)&mt8183_mcucfg->mcusys_bus_fabric_dcm_ctrl,
+		MCUSYS_BUS_FABRIC_DCM_MASK,
+		MCUSYS_BUS_FABRIC_DCM);
+	/* Enable l2c sram dcm */
+	mmio_setbits_32((uintptr_t)&mt8183_mcucfg->l2c_sram_ctrl,
+		L2C_SRAM_DCM);
+	/* Enable busmp0 sync dcm */
+	mmio_clrsetbits_32((uintptr_t)&mt8183_mcucfg->sync_dcm_config,
+		SYNC_DCM_MASK, SYNC_DCM);
+	/* Enable cntvalue dcm */
+	mmio_setbits_32((uintptr_t)&mt8183_mcucfg->mcu_misc_dcm_ctrl,
+		CNTVALUEB_DCM);
+	/* Enable dcm cluster stall */
+	mmio_clrsetbits_32(
+		(uintptr_t)&mt8183_mcucfg->sync_dcm_cluster_config,
+		MCUSYS_MAX_ACCESS_LATENCY_MASK,
+		MCUSYS_MAX_ACCESS_LATENCY);
+	mmio_setbits_32((uintptr_t)&mt8183_mcucfg->sync_dcm_cluster_config,
+		MCU0_SYNC_DCM_STALL_WR_EN);
+	/* Enable rgu dcm */
+	mmio_setbits_32((uintptr_t)&mt8183_mcucfg->mp0_rgu_dcm_config,
+		CPUSYS_RGU_DCM_CINFIG);
 }
 
 /*******************************************************************************
@@ -112,6 +148,8 @@
 #if SPMC_MODE == 1
 	spmc_init();
 #endif
+	spm_boot_init();
+	mcdi_init();
 }
 
 /*******************************************************************************
diff --git a/plat/mediatek/mt8183/drivers/mcdi/mtk_mcdi.c b/plat/mediatek/mt8183/drivers/mcdi/mtk_mcdi.c
new file mode 100644
index 0000000..29eebcb
--- /dev/null
+++ b/plat/mediatek/mt8183/drivers/mcdi/mtk_mcdi.c
@@ -0,0 +1,259 @@
+/*
+ * Copyright (c) 2019, ARM Limited and Contributors. All rights reserved.
+ *
+ * SPDX-License-Identifier: BSD-3-Clause
+ */
+
+#include <common/debug.h>
+#include <drivers/delay_timer.h>
+#include <lib/mmio.h>
+#include <sspm_reg.h>
+#include <mtk_mcdi.h>
+
+static inline uint32_t mcdi_mbox_read(uint32_t id)
+{
+	return mmio_read_32(SSPM_MBOX_3_BASE + (id << 2));
+}
+
+static inline void mcdi_mbox_write(uint32_t id, uint32_t val)
+{
+	mmio_write_32(SSPM_MBOX_3_BASE + (id << 2), val);
+}
+
+void sspm_set_bootaddr(uint32_t bootaddr)
+{
+	mcdi_mbox_write(MCDI_MBOX_BOOTADDR, bootaddr);
+}
+
+void sspm_cluster_pwr_off_notify(uint32_t cluster)
+{
+	mcdi_mbox_write(MCDI_MBOX_CLUSTER_0_ATF_ACTION_DONE + cluster, 1);
+}
+
+void sspm_cluster_pwr_on_notify(uint32_t cluster)
+{
+	mcdi_mbox_write(MCDI_MBOX_CLUSTER_0_ATF_ACTION_DONE + cluster, 0);
+}
+
+void sspm_standbywfi_irq_enable(uint32_t cpu_idx)
+{
+	mmio_write_32(SSPM_CFGREG_ACAO_INT_SET, STANDBYWFI_EN(cpu_idx));
+}
+
+uint32_t mcdi_avail_cpu_mask_read(void)
+{
+	return mcdi_mbox_read(MCDI_MBOX_AVAIL_CPU_MASK);
+}
+
+uint32_t mcdi_avail_cpu_mask_write(uint32_t mask)
+{
+	mcdi_mbox_write(MCDI_MBOX_AVAIL_CPU_MASK, mask);
+
+	return mask;
+}
+
+uint32_t mcdi_avail_cpu_mask_set(uint32_t mask)
+{
+	uint32_t m;
+
+	m = mcdi_mbox_read(MCDI_MBOX_AVAIL_CPU_MASK);
+	m |= mask;
+	mcdi_mbox_write(MCDI_MBOX_AVAIL_CPU_MASK, m);
+
+	return m;
+}
+
+uint32_t mcdi_avail_cpu_mask_clr(uint32_t mask)
+{
+	uint32_t m;
+
+	m = mcdi_mbox_read(MCDI_MBOX_AVAIL_CPU_MASK);
+	m &= ~mask;
+	mcdi_mbox_write(MCDI_MBOX_AVAIL_CPU_MASK, m);
+
+	return m;
+}
+
+uint32_t mcdi_cpu_cluster_pwr_stat_read(void)
+{
+	return mcdi_mbox_read(MCDI_MBOX_CPU_CLUSTER_PWR_STAT);
+}
+
+#define PAUSE_BIT		1
+#define CLUSTER_OFF_OFS		20
+#define CPU_OFF_OFS		24
+#define CLUSTER_ON_OFS		4
+#define CPU_ON_OFS		8
+
+static uint32_t target_mask(int cluster, int cpu_idx, bool on)
+{
+	uint32_t t = 0;
+
+	if (on) {
+		if (cluster >= 0)
+			t |= BIT(cluster + CLUSTER_ON_OFS);
+
+		if (cpu_idx >= 0)
+			t |= BIT(cpu_idx + CPU_ON_OFS);
+	} else {
+		if (cluster >= 0)
+			t |= BIT(cluster + CLUSTER_OFF_OFS);
+
+		if (cpu_idx >= 0)
+			t |= BIT(cpu_idx + CPU_OFF_OFS);
+	}
+
+	return t;
+}
+
+void mcdi_pause_clr(int cluster, int cpu_idx, bool on)
+{
+	uint32_t tgt = target_mask(cluster, cpu_idx, on);
+	uint32_t m = mcdi_mbox_read(MCDI_MBOX_PAUSE_ACTION);
+
+	m &= ~tgt;
+	mcdi_mbox_write(MCDI_MBOX_PAUSE_ACTION, m);
+}
+
+void mcdi_pause_set(int cluster, int cpu_idx, bool on)
+{
+	uint32_t tgt = target_mask(cluster, cpu_idx, on);
+	uint32_t m = mcdi_mbox_read(MCDI_MBOX_PAUSE_ACTION);
+	uint32_t tgtn = target_mask(-1, cpu_idx, !on);
+
+	/* request on and off at the same time to ensure it can be paused */
+	m |= tgt | tgtn;
+	mcdi_mbox_write(MCDI_MBOX_PAUSE_ACTION, m);
+
+	/* wait pause_ack */
+	while (!mcdi_mbox_read(MCDI_MBOX_PAUSE_ACK))
+		;
+
+	/* clear non-requested operation */
+	m &= ~tgtn;
+	mcdi_mbox_write(MCDI_MBOX_PAUSE_ACTION, m);
+}
+
+void mcdi_pause(void)
+{
+	uint32_t m = mcdi_mbox_read(MCDI_MBOX_PAUSE_ACTION) | BIT(PAUSE_BIT);
+
+	mcdi_mbox_write(MCDI_MBOX_PAUSE_ACTION, m);
+
+	/* wait pause_ack */
+	while (!mcdi_mbox_read(MCDI_MBOX_PAUSE_ACK))
+		;
+}
+
+void mcdi_unpause(void)
+{
+	uint32_t m = mcdi_mbox_read(MCDI_MBOX_PAUSE_ACTION) & ~BIT(PAUSE_BIT);
+
+	mcdi_mbox_write(MCDI_MBOX_PAUSE_ACTION, m);
+}
+
+void mcdi_hotplug_wait_ack(int cluster, int cpu_idx, bool on)
+{
+	uint32_t tgt = target_mask(cluster, cpu_idx, on);
+	uint32_t ack = mcdi_mbox_read(MCDI_MBOX_HP_ACK);
+
+	/* wait until ack */
+	while (!(ack & tgt))
+		ack = mcdi_mbox_read(MCDI_MBOX_HP_ACK);
+}
+
+void mcdi_hotplug_clr(int cluster, int cpu_idx, bool on)
+{
+	uint32_t tgt = target_mask(cluster, cpu_idx, on);
+	uint32_t tgt_cpu = target_mask(-1, cpu_idx, on);
+	uint32_t cmd = mcdi_mbox_read(MCDI_MBOX_HP_CMD);
+	uint32_t ack = mcdi_mbox_read(MCDI_MBOX_HP_ACK);
+
+	if (!(cmd & tgt))
+		return;
+
+	/* wait until ack */
+	while (!(ack & tgt_cpu))
+		ack = mcdi_mbox_read(MCDI_MBOX_HP_ACK);
+
+	cmd &= ~tgt;
+	mcdi_mbox_write(MCDI_MBOX_HP_CMD, cmd);
+}
+
+void mcdi_hotplug_set(int cluster, int cpu_idx, bool on)
+{
+	uint32_t tgt = target_mask(cluster, cpu_idx, on);
+	uint32_t tgt_cpu = target_mask(-1, cpu_idx, on);
+	uint32_t cmd = mcdi_mbox_read(MCDI_MBOX_HP_CMD);
+	uint32_t ack = mcdi_mbox_read(MCDI_MBOX_HP_ACK);
+
+	if ((cmd & tgt) == tgt)
+		return;
+
+	/* wait until ack clear */
+	while (ack & tgt_cpu)
+		ack = mcdi_mbox_read(MCDI_MBOX_HP_ACK);
+
+	cmd |= tgt;
+	mcdi_mbox_write(MCDI_MBOX_HP_CMD, cmd);
+}
+
+bool check_mcdi_ctl_stat(void)
+{
+	uint32_t clk_regs[] = {0x100010ac, 0x100010c8};
+	uint32_t clk_mask[] = {0x00028000, 0x00000018};
+	uint32_t tgt = target_mask(0, 0, true);
+	uint32_t m;
+	int i;
+
+	/* check clk status */
+	for (i = 0; i < ARRAY_SIZE(clk_regs); i++) {
+		if (mmio_read_32(clk_regs[i]) & clk_mask[i]) {
+			WARN("mcdi: clk check fail.\n");
+			return false;
+		}
+	}
+
+	/* check mcdi cmd handling */
+	m = mcdi_mbox_read(MCDI_MBOX_PAUSE_ACTION) | BIT(PAUSE_BIT);
+	mcdi_mbox_write(MCDI_MBOX_PAUSE_ACTION, m);
+
+	i = 500;
+	while (!mcdi_mbox_read(MCDI_MBOX_PAUSE_ACK) && --i > 0)
+		udelay(10);
+
+	m = mcdi_mbox_read(MCDI_MBOX_PAUSE_ACTION) & ~BIT(PAUSE_BIT);
+	mcdi_mbox_write(MCDI_MBOX_PAUSE_ACTION, m);
+
+	if (i == 0) {
+		WARN("mcdi: pause_action fail.\n");
+		return false;
+	}
+
+	/* check mcdi cmd handling */
+	if (mcdi_mbox_read(MCDI_MBOX_HP_CMD) ||
+			mcdi_mbox_read(MCDI_MBOX_HP_ACK)) {
+		WARN("mcdi: hp_cmd fail.\n");
+		return false;
+	}
+
+	mcdi_mbox_write(MCDI_MBOX_HP_CMD, tgt);
+
+	i = 500;
+	while ((mcdi_mbox_read(MCDI_MBOX_HP_ACK) & tgt) != tgt && --i > 0)
+		udelay(10);
+
+	mcdi_mbox_write(MCDI_MBOX_HP_CMD, 0);
+
+	if (i == 0) {
+		WARN("mcdi: hp_ack fail.\n");
+		return false;
+	}
+
+	return true;
+}
+
+void mcdi_init(void)
+{
+	mcdi_avail_cpu_mask_write(0x01); /* cpu0 default on */
+}
diff --git a/plat/mediatek/mt8183/drivers/mcdi/mtk_mcdi.h b/plat/mediatek/mt8183/drivers/mcdi/mtk_mcdi.h
new file mode 100644
index 0000000..9a40df1
--- /dev/null
+++ b/plat/mediatek/mt8183/drivers/mcdi/mtk_mcdi.h
@@ -0,0 +1,34 @@
+/*
+ * Copyright (c) 2019, ARM Limited and Contributors. All rights reserved.
+ *
+ * SPDX-License-Identifier: BSD-3-Clause
+ */
+
+#ifndef __MTK_MCDI_H__
+#define __MTK_MCDI_H__
+
+#include <stdbool.h>
+
+void sspm_set_bootaddr(uint32_t bootaddr);
+void sspm_standbywfi_irq_enable(uint32_t cpu_idx);
+void sspm_cluster_pwr_off_notify(uint32_t cluster);
+void sspm_cluster_pwr_on_notify(uint32_t cluster);
+
+uint32_t mcdi_avail_cpu_mask_read(void);
+uint32_t mcdi_avail_cpu_mask_write(uint32_t mask);
+uint32_t mcdi_avail_cpu_mask_set(uint32_t mask);
+uint32_t mcdi_avail_cpu_mask_clr(uint32_t mask);
+uint32_t mcdi_cpu_cluster_pwr_stat_read(void);
+
+void mcdi_pause(void);
+void mcdi_unpause(void);
+void mcdi_pause_set(int cluster, int cpu_idx, bool on);
+void mcdi_pause_clr(int cluster, int cpu_idx, bool on);
+void mcdi_hotplug_set(int cluster, int cpu_idx, bool on);
+void mcdi_hotplug_clr(int cluster, int cpu_idx, bool on);
+void mcdi_hotplug_wait_ack(int cluster, int cpu_idx, bool on);
+
+bool check_mcdi_ctl_stat(void);
+void mcdi_init(void);
+
+#endif /* __MTK_MCDI_H__ */
diff --git a/plat/mediatek/mt8183/drivers/pmic/pmic.c b/plat/mediatek/mt8183/drivers/pmic/pmic.c
index 818c149..b0f898e 100644
--- a/plat/mediatek/mt8183/drivers/pmic/pmic.c
+++ b/plat/mediatek/mt8183/drivers/pmic/pmic.c
@@ -7,6 +7,24 @@
 #include <pmic_wrap_init.h>
 #include <pmic.h>
 
+void bcpu_enable(uint32_t en)
+{
+	pwrap_write(PMIC_VPROC11_OP_EN, 0x1);
+	if (en)
+		pwrap_write(PMIC_VPROC11_CON0, 1);
+	else
+		pwrap_write(PMIC_VPROC11_CON0, 0);
+}
+
+void bcpu_sram_enable(uint32_t en)
+{
+	pwrap_write(PMIC_VSRAM_PROC11_OP_EN, 0x1);
+	if (en)
+		pwrap_write(PMIC_VSRAM_PROC11_CON0, 1);
+	else
+		pwrap_write(PMIC_VSRAM_PROC11_CON0, 0);
+}
+
 void wk_pmic_enable_sdn_delay(void)
 {
 	uint32_t con;
diff --git a/plat/mediatek/mt8183/drivers/pmic/pmic.h b/plat/mediatek/mt8183/drivers/pmic/pmic.h
index d62c6da..f19f9f6 100644
--- a/plat/mediatek/mt8183/drivers/pmic/pmic.h
+++ b/plat/mediatek/mt8183/drivers/pmic/pmic.h
@@ -10,7 +10,11 @@
 enum {
 	PMIC_TMA_KEY = 0x03a8,
 	PMIC_PWRHOLD = 0x0a08,
-	PMIC_PSEQ_ELR11 = 0x0a62
+	PMIC_PSEQ_ELR11 = 0x0a62,
+	PMIC_VPROC11_CON0 = 0x1388,
+	PMIC_VPROC11_OP_EN = 0x1390,
+	PMIC_VSRAM_PROC11_CON0 = 0x1b46,
+	PMIC_VSRAM_PROC11_OP_EN = 0x1b4e
 };
 
 enum {
@@ -18,6 +22,8 @@
 };
 
 /* external API */
+void bcpu_enable(uint32_t en);
+void bcpu_sram_enable(uint32_t en);
 void wk_pmic_enable_sdn_delay(void);
 void pmic_power_off(void);
 
diff --git a/plat/mediatek/mt8183/drivers/spm/spm.c b/plat/mediatek/mt8183/drivers/spm/spm.c
new file mode 100644
index 0000000..dcafd55
--- /dev/null
+++ b/plat/mediatek/mt8183/drivers/spm/spm.c
@@ -0,0 +1,328 @@
+/*
+ * Copyright (c) 2019, ARM Limited and Contributors. All rights reserved.
+ *
+ * SPDX-License-Identifier: BSD-3-Clause
+ */
+#include <lib/bakery_lock.h>
+#include <common/debug.h>
+#include <drivers/delay_timer.h>
+#include <lib/mmio.h>
+#include <spm.h>
+#include <spm_pmic_wrap.h>
+
+DEFINE_BAKERY_LOCK(spm_lock);
+
+const char *wakeup_src_str[32] = {
+	[0] = "R12_PCM_TIMER",
+	[1] = "R12_SSPM_WDT_EVENT_B",
+	[2] = "R12_KP_IRQ_B",
+	[3] = "R12_APWDT_EVENT_B",
+	[4] = "R12_APXGPT1_EVENT_B",
+	[5] = "R12_CONN2AP_SPM_WAKEUP_B",
+	[6] = "R12_EINT_EVENT_B",
+	[7] = "R12_CONN_WDT_IRQ_B",
+	[8] = "R12_CCIF0_EVENT_B",
+	[9] = "R12_LOWBATTERY_IRQ_B",
+	[10] = "R12_SSPM_SPM_IRQ_B",
+	[11] = "R12_SCP_SPM_IRQ_B",
+	[12] = "R12_SCP_WDT_EVENT_B",
+	[13] = "R12_PCM_WDT_WAKEUP_B",
+	[14] = "R12_USB_CDSC_B ",
+	[15] = "R12_USB_POWERDWN_B",
+	[16] = "R12_SYS_TIMER_EVENT_B",
+	[17] = "R12_EINT_EVENT_SECURE_B",
+	[18] = "R12_CCIF1_EVENT_B",
+	[19] = "R12_UART0_IRQ_B",
+	[20] = "R12_AFE_IRQ_MCU_B",
+	[21] = "R12_THERM_CTRL_EVENT_B",
+	[22] = "R12_SYS_CIRQ_IRQ_B",
+	[23] = "R12_MD2AP_PEER_EVENT_B",
+	[24] = "R12_CSYSPWREQ_B",
+	[25] = "R12_MD1_WDT_B ",
+	[26] = "R12_CLDMA_EVENT_B",
+	[27] = "R12_SEJ_WDT_GPT_B",
+	[28] = "R12_ALL_SSPM_WAKEUP_B",
+	[29] = "R12_CPU_IRQ_B",
+	[30] = "R12_CPU_WFI_AND_B"
+};
+
+const char *spm_get_firmware_version(void)
+{
+	return "DYNAMIC_SPM_FW_VERSION";
+}
+
+void spm_lock_init(void)
+{
+	bakery_lock_init(&spm_lock);
+}
+
+void spm_lock_get(void)
+{
+	bakery_lock_get(&spm_lock);
+}
+
+void spm_lock_release(void)
+{
+	bakery_lock_release(&spm_lock);
+}
+
+void spm_set_bootaddr(unsigned long bootaddr)
+{
+	/* initialize core4~7 boot entry address */
+	mmio_write_32(SW2SPM_MAILBOX_3, bootaddr);
+}
+
+void spm_set_cpu_status(int cpu)
+{
+	if (cpu >= 0 && cpu < 4) {
+		mmio_write_32(ROOT_CPUTOP_ADDR, 0x10006204);
+		mmio_write_32(ROOT_CORE_ADDR, 0x10006208 + (cpu * 0x4));
+	} else if (cpu >= 4 && cpu < 8) {
+		mmio_write_32(ROOT_CPUTOP_ADDR, 0x10006218);
+		mmio_write_32(ROOT_CORE_ADDR, 0x1000621c + ((cpu - 4) * 0x4));
+	} else {
+		ERROR("%s: error cpu number %d\n", __func__, cpu);
+	}
+}
+
+void spm_set_power_control(const struct pwr_ctrl *pwrctrl)
+{
+	mmio_write_32(SPM_AP_STANDBY_CON,
+		      ((pwrctrl->wfi_op & 0x1) << 0) |
+		      ((pwrctrl->mp0_cputop_idle_mask & 0x1) << 1) |
+		      ((pwrctrl->mp1_cputop_idle_mask & 0x1) << 2) |
+		      ((pwrctrl->mcusys_idle_mask & 0x1) << 4) |
+		      ((pwrctrl->mm_mask_b & 0x3) << 16) |
+		      ((pwrctrl->md_ddr_en_0_dbc_en & 0x1) << 18) |
+		      ((pwrctrl->md_ddr_en_1_dbc_en & 0x1) << 19) |
+		      ((pwrctrl->md_mask_b & 0x3) << 20) |
+		      ((pwrctrl->sspm_mask_b & 0x1) << 22) |
+		      ((pwrctrl->scp_mask_b & 0x1) << 23) |
+		      ((pwrctrl->srcclkeni_mask_b & 0x1) << 24) |
+		      ((pwrctrl->md_apsrc_1_sel & 0x1) << 25) |
+		      ((pwrctrl->md_apsrc_0_sel & 0x1) << 26) |
+		      ((pwrctrl->conn_ddr_en_dbc_en & 0x1) << 27) |
+		      ((pwrctrl->conn_mask_b & 0x1) << 28) |
+		      ((pwrctrl->conn_apsrc_sel & 0x1) << 29));
+
+	mmio_write_32(SPM_SRC_REQ,
+		      ((pwrctrl->spm_apsrc_req & 0x1) << 0) |
+		      ((pwrctrl->spm_f26m_req & 0x1) << 1) |
+		      ((pwrctrl->spm_infra_req & 0x1) << 3) |
+		      ((pwrctrl->spm_vrf18_req & 0x1) << 4) |
+		      ((pwrctrl->spm_ddren_req & 0x1) << 7) |
+		      ((pwrctrl->spm_rsv_src_req & 0x7) << 8) |
+		      ((pwrctrl->spm_ddren_2_req & 0x1) << 11) |
+		      ((pwrctrl->cpu_md_dvfs_sop_force_on & 0x1) << 16));
+
+	mmio_write_32(SPM_SRC_MASK,
+		      ((pwrctrl->csyspwreq_mask & 0x1) << 0) |
+		      ((pwrctrl->ccif0_md_event_mask_b & 0x1) << 1) |
+		      ((pwrctrl->ccif0_ap_event_mask_b & 0x1) << 2) |
+		      ((pwrctrl->ccif1_md_event_mask_b & 0x1) << 3) |
+		      ((pwrctrl->ccif1_ap_event_mask_b & 0x1) << 4) |
+		      ((pwrctrl->ccif2_md_event_mask_b & 0x1) << 5) |
+		      ((pwrctrl->ccif2_ap_event_mask_b & 0x1) << 6) |
+		      ((pwrctrl->ccif3_md_event_mask_b & 0x1) << 7) |
+		      ((pwrctrl->ccif3_ap_event_mask_b & 0x1) << 8) |
+		      ((pwrctrl->md_srcclkena_0_infra_mask_b & 0x1) << 9) |
+		      ((pwrctrl->md_srcclkena_1_infra_mask_b & 0x1) << 10) |
+		      ((pwrctrl->conn_srcclkena_infra_mask_b & 0x1) << 11) |
+		      ((pwrctrl->ufs_infra_req_mask_b & 0x1) << 12) |
+		      ((pwrctrl->srcclkeni_infra_mask_b & 0x1) << 13) |
+		      ((pwrctrl->md_apsrc_req_0_infra_mask_b & 0x1) << 14) |
+		      ((pwrctrl->md_apsrc_req_1_infra_mask_b & 0x1) << 15) |
+		      ((pwrctrl->conn_apsrcreq_infra_mask_b & 0x1) << 16) |
+		      ((pwrctrl->ufs_srcclkena_mask_b & 0x1) << 17) |
+		      ((pwrctrl->md_vrf18_req_0_mask_b & 0x1) << 18) |
+		      ((pwrctrl->md_vrf18_req_1_mask_b & 0x1) << 19) |
+		      ((pwrctrl->ufs_vrf18_req_mask_b & 0x1) << 20) |
+		      ((pwrctrl->gce_vrf18_req_mask_b & 0x1) << 21) |
+		      ((pwrctrl->conn_infra_req_mask_b & 0x1) << 22) |
+		      ((pwrctrl->gce_apsrc_req_mask_b & 0x1) << 23) |
+		      ((pwrctrl->disp0_apsrc_req_mask_b & 0x1) << 24) |
+		      ((pwrctrl->disp1_apsrc_req_mask_b & 0x1) << 25) |
+		      ((pwrctrl->mfg_req_mask_b & 0x1) << 26) |
+		      ((pwrctrl->vdec_req_mask_b & 0x1) << 27));
+
+	mmio_write_32(SPM_SRC2_MASK,
+		      ((pwrctrl->md_ddr_en_0_mask_b & 0x1) << 0) |
+		      ((pwrctrl->md_ddr_en_1_mask_b & 0x1) << 1) |
+		      ((pwrctrl->conn_ddr_en_mask_b & 0x1) << 2) |
+		      ((pwrctrl->ddren_sspm_apsrc_req_mask_b & 0x1) << 3) |
+		      ((pwrctrl->ddren_scp_apsrc_req_mask_b & 0x1) << 4) |
+		      ((pwrctrl->disp0_ddren_mask_b & 0x1) << 5) |
+		      ((pwrctrl->disp1_ddren_mask_b & 0x1) << 6) |
+		      ((pwrctrl->gce_ddren_mask_b & 0x1) << 7) |
+		      ((pwrctrl->ddren_emi_self_refresh_ch0_mask_b & 0x1)
+		       << 8) |
+		      ((pwrctrl->ddren_emi_self_refresh_ch1_mask_b & 0x1)
+		       << 9));
+
+	mmio_write_32(SPM_WAKEUP_EVENT_MASK,
+		      ((pwrctrl->spm_wakeup_event_mask & 0xffffffff) << 0));
+
+	mmio_write_32(SPM_WAKEUP_EVENT_EXT_MASK,
+		      ((pwrctrl->spm_wakeup_event_ext_mask & 0xffffffff)
+		       << 0));
+
+	mmio_write_32(SPM_SRC3_MASK,
+		      ((pwrctrl->md_ddr_en_2_0_mask_b & 0x1) << 0) |
+		      ((pwrctrl->md_ddr_en_2_1_mask_b & 0x1) << 1) |
+		      ((pwrctrl->conn_ddr_en_2_mask_b & 0x1) << 2) |
+		      ((pwrctrl->ddren2_sspm_apsrc_req_mask_b & 0x1) << 3) |
+		      ((pwrctrl->ddren2_scp_apsrc_req_mask_b & 0x1) << 4) |
+		      ((pwrctrl->disp0_ddren2_mask_b & 0x1) << 5) |
+		      ((pwrctrl->disp1_ddren2_mask_b & 0x1) << 6) |
+		      ((pwrctrl->gce_ddren2_mask_b & 0x1) << 7) |
+		      ((pwrctrl->ddren2_emi_self_refresh_ch0_mask_b & 0x1)
+		       << 8) |
+		      ((pwrctrl->ddren2_emi_self_refresh_ch1_mask_b & 0x1)
+		       << 9));
+
+	mmio_write_32(MP0_CPU0_WFI_EN,
+		      ((pwrctrl->mp0_cpu0_wfi_en & 0x1) << 0));
+	mmio_write_32(MP0_CPU1_WFI_EN,
+		      ((pwrctrl->mp0_cpu1_wfi_en & 0x1) << 0));
+	mmio_write_32(MP0_CPU2_WFI_EN,
+		      ((pwrctrl->mp0_cpu2_wfi_en & 0x1) << 0));
+	mmio_write_32(MP0_CPU3_WFI_EN,
+		      ((pwrctrl->mp0_cpu3_wfi_en & 0x1) << 0));
+
+	mmio_write_32(MP1_CPU0_WFI_EN,
+		      ((pwrctrl->mp1_cpu0_wfi_en & 0x1) << 0));
+	mmio_write_32(MP1_CPU1_WFI_EN,
+		      ((pwrctrl->mp1_cpu1_wfi_en & 0x1) << 0));
+	mmio_write_32(MP1_CPU2_WFI_EN,
+		      ((pwrctrl->mp1_cpu2_wfi_en & 0x1) << 0));
+	mmio_write_32(MP1_CPU3_WFI_EN,
+		      ((pwrctrl->mp1_cpu3_wfi_en & 0x1) << 0));
+}
+
+void spm_disable_pcm_timer(void)
+{
+	mmio_clrsetbits_32(PCM_CON1, PCM_TIMER_EN_LSB, SPM_REGWR_CFG_KEY);
+}
+
+void spm_set_wakeup_event(const struct pwr_ctrl *pwrctrl)
+{
+	uint32_t val, mask, isr;
+
+	val = pwrctrl->timer_val ? pwrctrl->timer_val : PCM_TIMER_MAX;
+	mmio_write_32(PCM_TIMER_VAL, val);
+	mmio_setbits_32(PCM_CON1, SPM_REGWR_CFG_KEY | PCM_TIMER_EN_LSB);
+
+	mask = pwrctrl->wake_src;
+
+	if (pwrctrl->csyspwreq_mask)
+		mask &= ~WAKE_SRC_R12_CSYSPWREQ_B;
+
+	mmio_write_32(SPM_WAKEUP_EVENT_MASK, ~mask);
+
+	isr = mmio_read_32(SPM_IRQ_MASK) & SPM_TWAM_IRQ_MASK_LSB;
+	mmio_write_32(SPM_IRQ_MASK, isr | ISRM_RET_IRQ_AUX);
+}
+
+void spm_set_pcm_flags(const struct pwr_ctrl *pwrctrl)
+{
+	mmio_write_32(SPM_SW_FLAG, pwrctrl->pcm_flags);
+	mmio_write_32(SPM_SW_RSV_2, pwrctrl->pcm_flags1);
+}
+
+void spm_set_pcm_wdt(int en)
+{
+	if (en) {
+		mmio_clrsetbits_32(PCM_CON1, PCM_WDT_WAKE_MODE_LSB,
+				   SPM_REGWR_CFG_KEY);
+
+		if (mmio_read_32(PCM_TIMER_VAL) > PCM_TIMER_MAX)
+			mmio_write_32(PCM_TIMER_VAL, PCM_TIMER_MAX);
+		mmio_write_32(PCM_WDT_VAL,
+			      mmio_read_32(PCM_TIMER_VAL) + PCM_WDT_TIMEOUT);
+		mmio_setbits_32(PCM_CON1, SPM_REGWR_CFG_KEY | PCM_WDT_EN_LSB);
+	} else {
+		mmio_clrsetbits_32(PCM_CON1, PCM_WDT_EN_LSB,
+				   SPM_REGWR_CFG_KEY);
+	}
+}
+
+void spm_send_cpu_wakeup_event(void)
+{
+	mmio_write_32(PCM_REG_DATA_INI, 0);
+	mmio_write_32(SPM_CPU_WAKEUP_EVENT, 1);
+}
+
+void spm_get_wakeup_status(struct wake_status *wakesta)
+{
+	wakesta->assert_pc = mmio_read_32(PCM_REG_DATA_INI);
+	wakesta->r12 = mmio_read_32(SPM_SW_RSV_0);
+	wakesta->r12_ext = mmio_read_32(PCM_REG12_EXT_DATA);
+	wakesta->raw_sta = mmio_read_32(SPM_WAKEUP_STA);
+	wakesta->raw_ext_sta = mmio_read_32(SPM_WAKEUP_EXT_STA);
+	wakesta->wake_misc = mmio_read_32(SPM_BSI_D0_SR);
+	wakesta->timer_out = mmio_read_32(SPM_BSI_D1_SR);
+	wakesta->r13 = mmio_read_32(PCM_REG13_DATA);
+	wakesta->idle_sta = mmio_read_32(SUBSYS_IDLE_STA);
+	wakesta->req_sta = mmio_read_32(SRC_REQ_STA);
+	wakesta->sw_flag = mmio_read_32(SPM_SW_FLAG);
+	wakesta->sw_flag1 = mmio_read_32(SPM_SW_RSV_2);
+	wakesta->r15 = mmio_read_32(PCM_REG15_DATA);
+	wakesta->debug_flag = mmio_read_32(SPM_SW_DEBUG);
+	wakesta->debug_flag1 = mmio_read_32(WDT_LATCH_SPARE0_FIX);
+	wakesta->event_reg = mmio_read_32(SPM_BSI_D2_SR);
+	wakesta->isr = mmio_read_32(SPM_IRQ_STA);
+}
+
+void spm_clean_after_wakeup(void)
+{
+	mmio_write_32(SPM_SW_RSV_0,
+		      mmio_read_32(SPM_WAKEUP_STA) |
+		      mmio_read_32(SPM_SW_RSV_0));
+	mmio_write_32(SPM_CPU_WAKEUP_EVENT, 0);
+	mmio_write_32(SPM_WAKEUP_EVENT_MASK, ~0);
+	mmio_setbits_32(SPM_IRQ_MASK, ISRM_ALL_EXC_TWAM);
+	mmio_write_32(SPM_IRQ_STA, ISRC_ALL_EXC_TWAM);
+	mmio_write_32(SPM_SWINT_CLR, PCM_SW_INT_ALL);
+}
+
+void spm_output_wake_reason(struct wake_status *wakesta, const char *scenario)
+{
+	uint32_t i;
+
+	if (wakesta->assert_pc != 0) {
+		INFO("%s: PCM ASSERT AT %u, ULPOSC_CON = 0x%x\n",
+		     scenario, wakesta->assert_pc, mmio_read_32(ULPOSC_CON));
+		goto spm_debug_flags;
+	}
+
+	for (i = 0; i <= 31; i++) {
+		if (wakesta->r12 & (1U << i)) {
+			INFO("%s: wake up by %s, timer_out = %u\n",
+			     scenario, wakeup_src_str[i], wakesta->timer_out);
+			break;
+		}
+	}
+
+spm_debug_flags:
+	INFO("r15 = 0x%x, r13 = 0x%x, debug_flag = 0x%x 0x%x\n",
+	     wakesta->r15, wakesta->r13, wakesta->debug_flag,
+	     wakesta->debug_flag1);
+	INFO("sw_flag = 0x%x 0x%x, r12 = 0x%x, r12_ext = 0x%x\n",
+	     wakesta->sw_flag, wakesta->sw_flag1, wakesta->r12,
+	     wakesta->r12_ext);
+	INFO("idle_sta = 0x%x, req_sta =  0x%x, event_reg = 0x%x\n",
+	     wakesta->idle_sta, wakesta->req_sta, wakesta->event_reg);
+	INFO("isr = 0x%x, raw_sta = 0x%x, raw_ext_sta = 0x%x\n",
+	     wakesta->isr, wakesta->raw_sta, wakesta->raw_ext_sta);
+	INFO("wake_misc = 0x%x\n", wakesta->wake_misc);
+}
+
+void spm_boot_init(void)
+{
+	NOTICE("%s() start\n", __func__);
+
+	spm_lock_init();
+	mt_spm_pmic_wrap_set_phase(PMIC_WRAP_PHASE_ALLINONE);
+
+	NOTICE("%s() end\n", __func__);
+}
diff --git a/plat/mediatek/mt8183/drivers/spm/spm.h b/plat/mediatek/mt8183/drivers/spm/spm.h
new file mode 100644
index 0000000..b2e83dc
--- /dev/null
+++ b/plat/mediatek/mt8183/drivers/spm/spm.h
@@ -0,0 +1,2552 @@
+/*
+ * Copyright (c) 2019, MediaTek Inc. All rights reserved.
+ *
+ * SPDX-License-Identifier: BSD-3-Clause
+ */
+
+#ifndef SPM_H
+#define SPM_H
+
+/**************************************
+ * Define and Declare
+ **************************************/
+
+#define POWERON_CONFIG_EN              (SPM_BASE + 0x000)
+#define SPM_POWER_ON_VAL0              (SPM_BASE + 0x004)
+#define SPM_POWER_ON_VAL1              (SPM_BASE + 0x008)
+#define SPM_CLK_CON                    (SPM_BASE + 0x00C)
+#define SPM_CLK_SETTLE                 (SPM_BASE + 0x010)
+#define SPM_AP_STANDBY_CON             (SPM_BASE + 0x014)
+#define PCM_CON0                       (SPM_BASE + 0x018)
+#define PCM_CON1                       (SPM_BASE + 0x01C)
+#define PCM_IM_PTR                     (SPM_BASE + 0x020)
+#define PCM_IM_LEN                     (SPM_BASE + 0x024)
+#define PCM_REG_DATA_INI               (SPM_BASE + 0x028)
+#define PCM_PWR_IO_EN                  (SPM_BASE + 0x02C)
+#define PCM_TIMER_VAL                  (SPM_BASE + 0x030)
+#define PCM_WDT_VAL                    (SPM_BASE + 0x034)
+#define PCM_IM_HOST_RW_PTR             (SPM_BASE + 0x038)
+#define PCM_IM_HOST_RW_DAT             (SPM_BASE + 0x03C)
+#define PCM_EVENT_VECTOR0              (SPM_BASE + 0x040)
+#define PCM_EVENT_VECTOR1              (SPM_BASE + 0x044)
+#define PCM_EVENT_VECTOR2              (SPM_BASE + 0x048)
+#define PCM_EVENT_VECTOR3              (SPM_BASE + 0x04C)
+#define PCM_EVENT_VECTOR4              (SPM_BASE + 0x050)
+#define PCM_EVENT_VECTOR5              (SPM_BASE + 0x054)
+#define PCM_EVENT_VECTOR6              (SPM_BASE + 0x058)
+#define PCM_EVENT_VECTOR7              (SPM_BASE + 0x05C)
+#define PCM_EVENT_VECTOR8              (SPM_BASE + 0x060)
+#define PCM_EVENT_VECTOR9              (SPM_BASE + 0x064)
+#define PCM_EVENT_VECTOR10             (SPM_BASE + 0x068)
+#define PCM_EVENT_VECTOR11             (SPM_BASE + 0x06C)
+#define PCM_EVENT_VECTOR12             (SPM_BASE + 0x070)
+#define PCM_EVENT_VECTOR13             (SPM_BASE + 0x074)
+#define PCM_EVENT_VECTOR14             (SPM_BASE + 0x078)
+#define PCM_EVENT_VECTOR15             (SPM_BASE + 0x07C)
+#define PCM_EVENT_VECTOR_EN            (SPM_BASE + 0x080)
+#define SPM_SRAM_RSV_CON               (SPM_BASE + 0x088)
+#define SPM_SWINT                      (SPM_BASE + 0x08C)
+#define SPM_SWINT_SET                  (SPM_BASE + 0x090)
+#define SPM_SWINT_CLR                  (SPM_BASE + 0x094)
+#define SPM_SCP_MAILBOX                (SPM_BASE + 0x098)
+#define SCP_SPM_MAILBOX                (SPM_BASE + 0x09C)
+#define SPM_TWAM_CON                   (SPM_BASE + 0x0A0)
+#define SPM_TWAM_WINDOW_LEN            (SPM_BASE + 0x0A4)
+#define SPM_TWAM_IDLE_SEL              (SPM_BASE + 0x0A8)
+#define SPM_SCP_IRQ                    (SPM_BASE + 0x0AC)
+#define SPM_CPU_WAKEUP_EVENT           (SPM_BASE + 0x0B0)
+#define SPM_IRQ_MASK                   (SPM_BASE + 0x0B4)
+#define SPM_SRC_REQ                    (SPM_BASE + 0x0B8)
+#define SPM_SRC_MASK                   (SPM_BASE + 0x0BC)
+#define SPM_SRC2_MASK                  (SPM_BASE + 0x0C0)
+#define SPM_WAKEUP_EVENT_MASK          (SPM_BASE + 0x0C4)
+#define SPM_WAKEUP_EVENT_EXT_MASK      (SPM_BASE + 0x0C8)
+#define SPM_TWAM_EVENT_CLEAR           (SPM_BASE + 0x0CC)
+#define SCP_CLK_CON                    (SPM_BASE + 0x0D0)
+#define PCM_DEBUG_CON                  (SPM_BASE + 0x0D4)
+#define DDR_EN_DBC_LEN                 (SPM_BASE + 0x0D8)
+#define AHB_BUS_CON                    (SPM_BASE + 0x0DC)
+#define SPM_SRC3_MASK                  (SPM_BASE + 0x0E0)
+#define DDR_EN_EMI_DBC_CON             (SPM_BASE + 0x0E4)
+#define SSPM_CLK_CON                   (SPM_BASE + 0x0E8)
+#define PCM_REG0_DATA                  (SPM_BASE + 0x100)
+#define PCM_REG1_DATA                  (SPM_BASE + 0x104)
+#define PCM_REG2_DATA                  (SPM_BASE + 0x108)
+#define PCM_REG3_DATA                  (SPM_BASE + 0x10C)
+#define PCM_REG4_DATA                  (SPM_BASE + 0x110)
+#define PCM_REG5_DATA                  (SPM_BASE + 0x114)
+#define PCM_REG6_DATA                  (SPM_BASE + 0x118)
+#define PCM_REG7_DATA                  (SPM_BASE + 0x11C)
+#define PCM_REG8_DATA                  (SPM_BASE + 0x120)
+#define PCM_REG9_DATA                  (SPM_BASE + 0x124)
+#define PCM_REG10_DATA                 (SPM_BASE + 0x128)
+#define PCM_REG11_DATA                 (SPM_BASE + 0x12C)
+#define PCM_REG12_DATA                 (SPM_BASE + 0x130)
+#define PCM_REG13_DATA                 (SPM_BASE + 0x134)
+#define PCM_REG14_DATA                 (SPM_BASE + 0x138)
+#define PCM_REG15_DATA                 (SPM_BASE + 0x13C)
+#define PCM_REG12_MASK_B_STA           (SPM_BASE + 0x140)
+#define PCM_REG12_EXT_DATA             (SPM_BASE + 0x144)
+#define PCM_REG12_EXT_MASK_B_STA       (SPM_BASE + 0x148)
+#define PCM_EVENT_REG_STA              (SPM_BASE + 0x14C)
+#define PCM_TIMER_OUT                  (SPM_BASE + 0x150)
+#define PCM_WDT_OUT                    (SPM_BASE + 0x154)
+#define SPM_IRQ_STA                    (SPM_BASE + 0x158)
+#define SPM_WAKEUP_STA                 (SPM_BASE + 0x15C)
+#define SPM_WAKEUP_EXT_STA             (SPM_BASE + 0x160)
+#define SPM_WAKEUP_MISC                (SPM_BASE + 0x164)
+#define BUS_PROTECT_RDY                (SPM_BASE + 0x168)
+#define BUS_PROTECT2_RDY               (SPM_BASE + 0x16C)
+#define SUBSYS_IDLE_STA                (SPM_BASE + 0x170)
+#define CPU_IDLE_STA                   (SPM_BASE + 0x174)
+#define PCM_FSM_STA                    (SPM_BASE + 0x178)
+#define SRC_REQ_STA                    (SPM_BASE + 0x17C)
+#define PWR_STATUS                     (SPM_BASE + 0x180)
+#define PWR_STATUS_2ND                 (SPM_BASE + 0x184)
+#define CPU_PWR_STATUS                 (SPM_BASE + 0x188)
+#define CPU_PWR_STATUS_2ND             (SPM_BASE + 0x18C)
+#define MISC_STA                       (SPM_BASE + 0x190)
+#define SPM_SRC_RDY_STA                (SPM_BASE + 0x194)
+#define DRAMC_DBG_LATCH                (SPM_BASE + 0x19C)
+#define SPM_TWAM_LAST_STA0             (SPM_BASE + 0x1A0)
+#define SPM_TWAM_LAST_STA1             (SPM_BASE + 0x1A4)
+#define SPM_TWAM_LAST_STA2             (SPM_BASE + 0x1A8)
+#define SPM_TWAM_LAST_STA3             (SPM_BASE + 0x1AC)
+#define SPM_TWAM_CURR_STA0             (SPM_BASE + 0x1B0)
+#define SPM_TWAM_CURR_STA1             (SPM_BASE + 0x1B4)
+#define SPM_TWAM_CURR_STA2             (SPM_BASE + 0x1B8)
+#define SPM_TWAM_CURR_STA3             (SPM_BASE + 0x1BC)
+#define SPM_TWAM_TIMER_OUT             (SPM_BASE + 0x1C0)
+#define SPM_DVFS_STA                   (SPM_BASE + 0x1C8)
+#define BUS_PROTECT3_RDY               (SPM_BASE + 0x1CC)
+#define SRC_DDREN_STA                  (SPM_BASE + 0x1E0)
+#define MCU_PWR_CON                    (SPM_BASE + 0x200)
+#define MP0_CPUTOP_PWR_CON             (SPM_BASE + 0x204)
+#define MP0_CPU0_PWR_CON               (SPM_BASE + 0x208)
+#define MP0_CPU1_PWR_CON               (SPM_BASE + 0x20C)
+#define MP0_CPU2_PWR_CON               (SPM_BASE + 0x210)
+#define MP0_CPU3_PWR_CON               (SPM_BASE + 0x214)
+#define MP1_CPUTOP_PWR_CON             (SPM_BASE + 0x218)
+#define MP1_CPU0_PWR_CON               (SPM_BASE + 0x21C)
+#define MP1_CPU1_PWR_CON               (SPM_BASE + 0x220)
+#define MP1_CPU2_PWR_CON               (SPM_BASE + 0x224)
+#define MP1_CPU3_PWR_CON               (SPM_BASE + 0x228)
+#define MP0_CPUTOP_L2_PDN              (SPM_BASE + 0x240)
+#define MP0_CPUTOP_L2_SLEEP_B          (SPM_BASE + 0x244)
+#define MP0_CPU0_L1_PDN                (SPM_BASE + 0x248)
+#define MP0_CPU1_L1_PDN                (SPM_BASE + 0x24C)
+#define MP0_CPU2_L1_PDN                (SPM_BASE + 0x250)
+#define MP0_CPU3_L1_PDN                (SPM_BASE + 0x254)
+#define MP1_CPUTOP_L2_PDN              (SPM_BASE + 0x258)
+#define MP1_CPUTOP_L2_SLEEP_B          (SPM_BASE + 0x25C)
+#define MP1_CPU0_L1_PDN                (SPM_BASE + 0x260)
+#define MP1_CPU1_L1_PDN                (SPM_BASE + 0x264)
+#define MP1_CPU2_L1_PDN                (SPM_BASE + 0x268)
+#define MP1_CPU3_L1_PDN                (SPM_BASE + 0x26C)
+#define CPU_EXT_BUCK_ISO               (SPM_BASE + 0x290)
+#define DUMMY1_PWR_CON                 (SPM_BASE + 0x2B0)
+#define BYPASS_SPMC                    (SPM_BASE + 0x2B4)
+#define SPMC_DORMANT_ENABLE            (SPM_BASE + 0x2B8)
+#define ARMPLL_CLK_CON                 (SPM_BASE + 0x2BC)
+#define SPMC_IN_RET                    (SPM_BASE + 0x2C0)
+#define VDE_PWR_CON                    (SPM_BASE + 0x300)
+#define VEN_PWR_CON                    (SPM_BASE + 0x304)
+#define ISP_PWR_CON                    (SPM_BASE + 0x308)
+#define DIS_PWR_CON                    (SPM_BASE + 0x30C)
+#define MFG_CORE1_PWR_CON              (SPM_BASE + 0x310)
+#define AUDIO_PWR_CON                  (SPM_BASE + 0x314)
+#define IFR_PWR_CON                    (SPM_BASE + 0x318)
+#define DPY_PWR_CON                    (SPM_BASE + 0x31C)
+#define MD1_PWR_CON                    (SPM_BASE + 0x320)
+#define VPU_TOP_PWR_CON                (SPM_BASE + 0x324)
+#define CONN_PWR_CON                   (SPM_BASE + 0x32C)
+#define VPU_CORE2_PWR_CON              (SPM_BASE + 0x330)
+#define MFG_ASYNC_PWR_CON              (SPM_BASE + 0x334)
+#define MFG_PWR_CON                    (SPM_BASE + 0x338)
+#define VPU_CORE0_PWR_CON              (SPM_BASE + 0x33C)
+#define VPU_CORE1_PWR_CON              (SPM_BASE + 0x340)
+#define CAM_PWR_CON                    (SPM_BASE + 0x344)
+#define MFG_2D_PWR_CON                 (SPM_BASE + 0x348)
+#define MFG_CORE0_PWR_CON              (SPM_BASE + 0x34C)
+#define SYSRAM_CON                     (SPM_BASE + 0x350)
+#define SYSROM_CON                     (SPM_BASE + 0x354)
+#define SSPM_SRAM_CON                  (SPM_BASE + 0x358)
+#define SCP_SRAM_CON                   (SPM_BASE + 0x35C)
+#define UFS_SRAM_CON                   (SPM_BASE + 0x36C)
+#define DUMMY_SRAM_CON                 (SPM_BASE + 0x380)
+#define MD_EXT_BUCK_ISO_CON            (SPM_BASE + 0x390)
+#define MD_SRAM_ISO_CON                (SPM_BASE + 0x394)
+#define MD_EXTRA_PWR_CON               (SPM_BASE + 0x398)
+#define EXT_BUCK_CON                   (SPM_BASE + 0x3A0)
+#define MBIST_EFUSE_REPAIR_ACK_STA     (SPM_BASE + 0x3D0)
+#define SPM_DVFS_CON                   (SPM_BASE + 0x400)
+#define SPM_MDBSI_CON                  (SPM_BASE + 0x404)
+#define SPM_MAS_PAUSE_MASK_B           (SPM_BASE + 0x408)
+#define SPM_MAS_PAUSE2_MASK_B          (SPM_BASE + 0x40C)
+#define SPM_BSI_GEN                    (SPM_BASE + 0x410)
+#define SPM_BSI_EN_SR                  (SPM_BASE + 0x414)
+#define SPM_BSI_CLK_SR                 (SPM_BASE + 0x418)
+#define SPM_BSI_D0_SR                  (SPM_BASE + 0x41C)
+#define SPM_BSI_D1_SR                  (SPM_BASE + 0x420)
+#define SPM_BSI_D2_SR                  (SPM_BASE + 0x424)
+#define SPM_AP_SEMA                    (SPM_BASE + 0x428)
+#define SPM_SPM_SEMA                   (SPM_BASE + 0x42C)
+#define AP_MDSRC_REQ                   (SPM_BASE + 0x430)
+#define SPM2MD_DVFS_CON                (SPM_BASE + 0x438)
+#define MD2SPM_DVFS_CON                (SPM_BASE + 0x43C)
+#define DRAMC_DPY_CLK_SW_CON_RSV       (SPM_BASE + 0x440)
+#define DPY_LP_CON                     (SPM_BASE + 0x444)
+#define CPU_DVFS_REQ                   (SPM_BASE + 0x448)
+#define SPM_PLL_CON                    (SPM_BASE + 0x44C)
+#define SPM_EMI_BW_MODE                (SPM_BASE + 0x450)
+#define AP2MD_PEER_WAKEUP              (SPM_BASE + 0x454)
+#define ULPOSC_CON                     (SPM_BASE + 0x458)
+#define SPM2MM_CON                     (SPM_BASE + 0x45C)
+#define DRAMC_DPY_CLK_SW_CON_SEL       (SPM_BASE + 0x460)
+#define DRAMC_DPY_CLK_SW_CON           (SPM_BASE + 0x464)
+#define SPM_S1_MODE_CH                 (SPM_BASE + 0x468)
+#define EMI_SELF_REFRESH_CH_STA        (SPM_BASE + 0x46C)
+#define DRAMC_DPY_CLK_SW_CON_SEL2      (SPM_BASE + 0x470)
+#define DRAMC_DPY_CLK_SW_CON2          (SPM_BASE + 0x474)
+#define DRAMC_DMYRD_CON                (SPM_BASE + 0x478)
+#define SPM_DRS_CON                    (SPM_BASE + 0x47C)
+#define SPM_SEMA_M0                    (SPM_BASE + 0x480)
+#define SPM_SEMA_M1                    (SPM_BASE + 0x484)
+#define SPM_SEMA_M2                    (SPM_BASE + 0x488)
+#define SPM_SEMA_M3                    (SPM_BASE + 0x48C)
+#define SPM_SEMA_M4                    (SPM_BASE + 0x490)
+#define SPM_SEMA_M5                    (SPM_BASE + 0x494)
+#define SPM_SEMA_M6                    (SPM_BASE + 0x498)
+#define SPM_SEMA_M7                    (SPM_BASE + 0x49C)
+#define SPM_MAS_PAUSE_MM_MASK_B        (SPM_BASE + 0x4A0)
+#define SPM_MAS_PAUSE_MCU_MASK_B       (SPM_BASE + 0x4A4)
+#define SRAM_DREQ_ACK                  (SPM_BASE + 0x4AC)
+#define SRAM_DREQ_CON                  (SPM_BASE + 0x4B0)
+#define SRAM_DREQ_CON_SET              (SPM_BASE + 0x4B4)
+#define SRAM_DREQ_CON_CLR              (SPM_BASE + 0x4B8)
+#define SPM2EMI_ENTER_ULPM             (SPM_BASE + 0x4BC)
+#define SPM_SSPM_IRQ                   (SPM_BASE + 0x4C0)
+#define SPM2PMCU_INT                   (SPM_BASE + 0x4C4)
+#define SPM2PMCU_INT_SET               (SPM_BASE + 0x4C8)
+#define SPM2PMCU_INT_CLR               (SPM_BASE + 0x4CC)
+#define SPM2PMCU_MAILBOX_0             (SPM_BASE + 0x4D0)
+#define SPM2PMCU_MAILBOX_1             (SPM_BASE + 0x4D4)
+#define SPM2PMCU_MAILBOX_2             (SPM_BASE + 0x4D8)
+#define SPM2PMCU_MAILBOX_3             (SPM_BASE + 0x4DC)
+#define PMCU2SPM_INT                   (SPM_BASE + 0x4E0)
+#define PMCU2SPM_INT_SET               (SPM_BASE + 0x4E4)
+#define PMCU2SPM_INT_CLR               (SPM_BASE + 0x4E8)
+#define PMCU2SPM_MAILBOX_0             (SPM_BASE + 0x4EC)
+#define PMCU2SPM_MAILBOX_1             (SPM_BASE + 0x4F0)
+#define PMCU2SPM_MAILBOX_2             (SPM_BASE + 0x4F4)
+#define PMCU2SPM_MAILBOX_3             (SPM_BASE + 0x4F8)
+#define PMCU2SPM_CFG                   (SPM_BASE + 0x4FC)
+#define MP0_CPU0_IRQ_MASK              (SPM_BASE + 0x500)
+#define MP0_CPU1_IRQ_MASK              (SPM_BASE + 0x504)
+#define MP0_CPU2_IRQ_MASK              (SPM_BASE + 0x508)
+#define MP0_CPU3_IRQ_MASK              (SPM_BASE + 0x50C)
+#define MP1_CPU0_IRQ_MASK              (SPM_BASE + 0x510)
+#define MP1_CPU1_IRQ_MASK              (SPM_BASE + 0x514)
+#define MP1_CPU2_IRQ_MASK              (SPM_BASE + 0x518)
+#define MP1_CPU3_IRQ_MASK              (SPM_BASE + 0x51C)
+#define MP0_CPU0_WFI_EN                (SPM_BASE + 0x530)
+#define MP0_CPU1_WFI_EN                (SPM_BASE + 0x534)
+#define MP0_CPU2_WFI_EN                (SPM_BASE + 0x538)
+#define MP0_CPU3_WFI_EN                (SPM_BASE + 0x53C)
+#define MP1_CPU0_WFI_EN                (SPM_BASE + 0x540)
+#define MP1_CPU1_WFI_EN                (SPM_BASE + 0x544)
+#define MP1_CPU2_WFI_EN                (SPM_BASE + 0x548)
+#define MP1_CPU3_WFI_EN                (SPM_BASE + 0x54C)
+#define MP0_L2CFLUSH                   (SPM_BASE + 0x554)
+#define MP1_L2CFLUSH                   (SPM_BASE + 0x558)
+#define CPU_PTPOD2_CON                 (SPM_BASE + 0x560)
+#define ROOT_CPUTOP_ADDR               (SPM_BASE + 0x570)
+#define ROOT_CORE_ADDR                 (SPM_BASE + 0x574)
+#define CPU_SPARE_CON                  (SPM_BASE + 0x580)
+#define CPU_SPARE_CON_SET              (SPM_BASE + 0x584)
+#define CPU_SPARE_CON_CLR              (SPM_BASE + 0x588)
+#define SPM2SW_MAILBOX_0               (SPM_BASE + 0x5D0)
+#define SPM2SW_MAILBOX_1               (SPM_BASE + 0x5D4)
+#define SPM2SW_MAILBOX_2               (SPM_BASE + 0x5D8)
+#define SPM2SW_MAILBOX_3               (SPM_BASE + 0x5DC)
+#define SW2SPM_INT                     (SPM_BASE + 0x5E0)
+#define SW2SPM_INT_SET                 (SPM_BASE + 0x5E4)
+#define SW2SPM_INT_CLR                 (SPM_BASE + 0x5E8)
+#define SW2SPM_MAILBOX_0               (SPM_BASE + 0x5EC)
+#define SW2SPM_MAILBOX_1               (SPM_BASE + 0x5F0)
+#define SW2SPM_MAILBOX_2               (SPM_BASE + 0x5F4)
+#define SW2SPM_MAILBOX_3               (SPM_BASE + 0x5F8)
+#define SW2SPM_CFG                     (SPM_BASE + 0x5FC)
+#define SPM_SW_FLAG                    (SPM_BASE + 0x600)
+#define SPM_SW_DEBUG                   (SPM_BASE + 0x604)
+#define SPM_SW_RSV_0                   (SPM_BASE + 0x608)
+#define SPM_SW_RSV_1                   (SPM_BASE + 0x60C)
+#define SPM_SW_RSV_2                   (SPM_BASE + 0x610)
+#define SPM_SW_RSV_3                   (SPM_BASE + 0x614)
+#define SPM_SW_RSV_4                   (SPM_BASE + 0x618)
+#define SPM_SW_RSV_5                   (SPM_BASE + 0x61C)
+#define SPM_RSV_CON                    (SPM_BASE + 0x620)
+#define SPM_RSV_STA                    (SPM_BASE + 0x624)
+#define SPM_RSV_CON1                   (SPM_BASE + 0x628)
+#define SPM_RSV_STA1                   (SPM_BASE + 0x62C)
+#define SPM_PASR_DPD_0                 (SPM_BASE + 0x630)
+#define SPM_PASR_DPD_1                 (SPM_BASE + 0x634)
+#define SPM_PASR_DPD_2                 (SPM_BASE + 0x638)
+#define SPM_PASR_DPD_3                 (SPM_BASE + 0x63C)
+#define SPM_SPARE_CON                  (SPM_BASE + 0x640)
+#define SPM_SPARE_CON_SET              (SPM_BASE + 0x644)
+#define SPM_SPARE_CON_CLR              (SPM_BASE + 0x648)
+#define SPM_SW_RSV_6                   (SPM_BASE + 0x64C)
+#define SPM_SW_RSV_7                   (SPM_BASE + 0x650)
+#define SPM_SW_RSV_8                   (SPM_BASE + 0x654)
+#define SPM_SW_RSV_9                   (SPM_BASE + 0x658)
+#define SPM_SW_RSV_10                  (SPM_BASE + 0x65C)
+#define SPM_SW_RSV_18                  (SPM_BASE + 0x67C)
+#define SPM_SW_RSV_19                  (SPM_BASE + 0x680)
+#define DVFSRC_EVENT_MASK_CON          (SPM_BASE + 0x690)
+#define DVFSRC_EVENT_FORCE_ON          (SPM_BASE + 0x694)
+#define DVFSRC_EVENT_SEL               (SPM_BASE + 0x698)
+#define SPM_DVFS_EVENT_STA             (SPM_BASE + 0x69C)
+#define SPM_DVFS_EVENT_STA1            (SPM_BASE + 0x6A0)
+#define SPM_DVFS_LEVEL                 (SPM_BASE + 0x6A4)
+#define DVFS_ABORT_STA                 (SPM_BASE + 0x6A8)
+#define DVFS_ABORT_OTHERS_MASK         (SPM_BASE + 0x6AC)
+#define SPM_DFS_LEVEL                  (SPM_BASE + 0x6B0)
+#define SPM_DVS_LEVEL                  (SPM_BASE + 0x6B4)
+#define SPM_DVFS_MISC                  (SPM_BASE + 0x6B8)
+#define SPARE_SRC_REQ_MASK             (SPM_BASE + 0x6C0)
+#define SCP_VCORE_LEVEL                (SPM_BASE + 0x6C4)
+#define SC_MM_CK_SEL_CON               (SPM_BASE + 0x6C8)
+#define SPARE_ACK_STA                  (SPM_BASE + 0x6F0)
+#define SPARE_ACK_MASK                 (SPM_BASE + 0x6F4)
+#define SPM_DVFS_CON1                  (SPM_BASE + 0x700)
+#define SPM_DVFS_CON1_STA              (SPM_BASE + 0x704)
+#define SPM_DVFS_CMD0                  (SPM_BASE + 0x710)
+#define SPM_DVFS_CMD1                  (SPM_BASE + 0x714)
+#define SPM_DVFS_CMD2                  (SPM_BASE + 0x718)
+#define SPM_DVFS_CMD3                  (SPM_BASE + 0x71C)
+#define SPM_DVFS_CMD4                  (SPM_BASE + 0x720)
+#define SPM_DVFS_CMD5                  (SPM_BASE + 0x724)
+#define SPM_DVFS_CMD6                  (SPM_BASE + 0x728)
+#define SPM_DVFS_CMD7                  (SPM_BASE + 0x72C)
+#define SPM_DVFS_CMD8                  (SPM_BASE + 0x730)
+#define SPM_DVFS_CMD9                  (SPM_BASE + 0x734)
+#define SPM_DVFS_CMD10                 (SPM_BASE + 0x738)
+#define SPM_DVFS_CMD11                 (SPM_BASE + 0x73C)
+#define SPM_DVFS_CMD12                 (SPM_BASE + 0x740)
+#define SPM_DVFS_CMD13                 (SPM_BASE + 0x744)
+#define SPM_DVFS_CMD14                 (SPM_BASE + 0x748)
+#define SPM_DVFS_CMD15                 (SPM_BASE + 0x74C)
+#define WDT_LATCH_SPARE0_FIX           (SPM_BASE + 0x780)
+#define WDT_LATCH_SPARE1_FIX           (SPM_BASE + 0x784)
+#define WDT_LATCH_SPARE2_FIX           (SPM_BASE + 0x788)
+#define WDT_LATCH_SPARE3_FIX           (SPM_BASE + 0x78C)
+#define SPARE_ACK_IN_FIX               (SPM_BASE + 0x790)
+#define DCHA_LATCH_RSV0_FIX            (SPM_BASE + 0x794)
+#define DCHB_LATCH_RSV0_FIX            (SPM_BASE + 0x798)
+#define PCM_WDT_LATCH_0                (SPM_BASE + 0x800)
+#define PCM_WDT_LATCH_1                (SPM_BASE + 0x804)
+#define PCM_WDT_LATCH_2                (SPM_BASE + 0x808)
+#define PCM_WDT_LATCH_3                (SPM_BASE + 0x80C)
+#define PCM_WDT_LATCH_4                (SPM_BASE + 0x810)
+#define PCM_WDT_LATCH_5                (SPM_BASE + 0x814)
+#define PCM_WDT_LATCH_6                (SPM_BASE + 0x818)
+#define PCM_WDT_LATCH_7                (SPM_BASE + 0x81C)
+#define PCM_WDT_LATCH_8                (SPM_BASE + 0x820)
+#define PCM_WDT_LATCH_9                (SPM_BASE + 0x824)
+#define WDT_LATCH_SPARE0               (SPM_BASE + 0x828)
+#define WDT_LATCH_SPARE1               (SPM_BASE + 0x82C)
+#define WDT_LATCH_SPARE2               (SPM_BASE + 0x830)
+#define WDT_LATCH_SPARE3               (SPM_BASE + 0x834)
+#define PCM_WDT_LATCH_10               (SPM_BASE + 0x838)
+#define PCM_WDT_LATCH_11               (SPM_BASE + 0x83C)
+#define DCHA_GATING_LATCH_0            (SPM_BASE + 0x840)
+#define DCHA_GATING_LATCH_1            (SPM_BASE + 0x844)
+#define DCHA_GATING_LATCH_2            (SPM_BASE + 0x848)
+#define DCHA_GATING_LATCH_3            (SPM_BASE + 0x84C)
+#define DCHA_GATING_LATCH_4            (SPM_BASE + 0x850)
+#define DCHA_GATING_LATCH_5            (SPM_BASE + 0x854)
+#define DCHA_GATING_LATCH_6            (SPM_BASE + 0x858)
+#define DCHA_GATING_LATCH_7            (SPM_BASE + 0x85C)
+#define DCHB_GATING_LATCH_0            (SPM_BASE + 0x860)
+#define DCHB_GATING_LATCH_1            (SPM_BASE + 0x864)
+#define DCHB_GATING_LATCH_2            (SPM_BASE + 0x868)
+#define DCHB_GATING_LATCH_3            (SPM_BASE + 0x86C)
+#define DCHB_GATING_LATCH_4            (SPM_BASE + 0x870)
+#define DCHB_GATING_LATCH_5            (SPM_BASE + 0x874)
+#define DCHB_GATING_LATCH_6            (SPM_BASE + 0x878)
+#define DCHB_GATING_LATCH_7            (SPM_BASE + 0x87C)
+#define DCHA_LATCH_RSV0                (SPM_BASE + 0x880)
+#define DCHB_LATCH_RSV0                (SPM_BASE + 0x884)
+#define PCM_WDT_LATCH_12               (SPM_BASE + 0x888)
+#define PCM_WDT_LATCH_13               (SPM_BASE + 0x88C)
+#define SPM_PC_TRACE_CON               (SPM_BASE + 0x8C0)
+#define SPM_PC_TRACE_G0                (SPM_BASE + 0x8C4)
+#define SPM_PC_TRACE_G1                (SPM_BASE + 0x8C8)
+#define SPM_PC_TRACE_G2                (SPM_BASE + 0x8CC)
+#define SPM_PC_TRACE_G3                (SPM_BASE + 0x8D0)
+#define SPM_PC_TRACE_G4                (SPM_BASE + 0x8D4)
+#define SPM_PC_TRACE_G5                (SPM_BASE + 0x8D8)
+#define SPM_PC_TRACE_G6                (SPM_BASE + 0x8DC)
+#define SPM_PC_TRACE_G7                (SPM_BASE + 0x8E0)
+#define SPM_ACK_CHK_CON                (SPM_BASE + 0x900)
+#define SPM_ACK_CHK_PC                 (SPM_BASE + 0x904)
+#define SPM_ACK_CHK_SEL                (SPM_BASE + 0x908)
+#define SPM_ACK_CHK_TIMER              (SPM_BASE + 0x90C)
+#define SPM_ACK_CHK_STA                (SPM_BASE + 0x910)
+#define SPM_ACK_CHK_LATCH              (SPM_BASE + 0x914)
+#define SPM_ACK_CHK_CON2               (SPM_BASE + 0x920)
+#define SPM_ACK_CHK_PC2                (SPM_BASE + 0x924)
+#define SPM_ACK_CHK_SEL2               (SPM_BASE + 0x928)
+#define SPM_ACK_CHK_TIMER2             (SPM_BASE + 0x92C)
+#define SPM_ACK_CHK_STA2               (SPM_BASE + 0x930)
+#define SPM_ACK_CHK_LATCH2             (SPM_BASE + 0x934)
+#define SPM_ACK_CHK_CON3               (SPM_BASE + 0x940)
+#define SPM_ACK_CHK_PC3                (SPM_BASE + 0x944)
+#define SPM_ACK_CHK_SEL3               (SPM_BASE + 0x948)
+#define SPM_ACK_CHK_TIMER3             (SPM_BASE + 0x94C)
+#define SPM_ACK_CHK_STA3               (SPM_BASE + 0x950)
+#define SPM_ACK_CHK_LATCH3             (SPM_BASE + 0x954)
+#define SPM_ACK_CHK_CON4               (SPM_BASE + 0x960)
+#define SPM_ACK_CHK_PC4                (SPM_BASE + 0x964)
+#define SPM_ACK_CHK_SEL4               (SPM_BASE + 0x968)
+#define SPM_ACK_CHK_TIMER4             (SPM_BASE + 0x96C)
+#define SPM_ACK_CHK_STA4               (SPM_BASE + 0x970)
+#define SPM_ACK_CHK_LATCH4             (SPM_BASE + 0x974)
+
+/* POWERON_CONFIG_EN (0x10006000+0x000) */
+#define BCLK_CG_EN_LSB                      (1U << 0)       /* 1b */
+#define MD_BCLK_CG_EN_LSB                   (1U << 1)       /* 1b */
+#define PROJECT_CODE_LSB                    (1U << 16)      /* 16b */
+/* SPM_POWER_ON_VAL0 (0x10006000+0x004) */
+#define POWER_ON_VAL0_LSB                   (1U << 0)       /* 32b */
+/* SPM_POWER_ON_VAL1 (0x10006000+0x008) */
+#define POWER_ON_VAL1_LSB                   (1U << 0)       /* 32b */
+/* SPM_CLK_CON (0x10006000+0x00C) */
+#define SYSCLK0_EN_CTRL_LSB                 (1U << 0)       /* 2b */
+#define SYSCLK1_EN_CTRL_LSB                 (1U << 2)       /* 2b */
+#define SYS_SETTLE_SEL_LSB                  (1U << 4)       /* 1b */
+#define SPM_LOCK_INFRA_DCM_LSB              (1U << 5)       /* 1b */
+#define EXT_SRCCLKEN_MASK_LSB               (1U << 6)       /* 3b */
+#define CXO32K_REMOVE_EN_MD1_LSB            (1U << 9)       /* 1b */
+#define CXO32K_REMOVE_EN_MD2_LSB            (1U << 10)      /* 1b */
+#define CLKSQ0_SEL_CTRL_LSB                 (1U << 11)      /* 1b */
+#define CLKSQ1_SEL_CTRL_LSB                 (1U << 12)      /* 1b */
+#define SRCLKEN0_EN_LSB                     (1U << 13)      /* 1b */
+#define SRCLKEN1_EN_LSB                     (1U << 14)      /* 1b */
+#define SCP_DCM_EN_LSB                      (1U << 15)      /* 1b */
+#define SYSCLK0_SRC_MASK_B_LSB              (1U << 16)      /* 7b */
+#define SYSCLK1_SRC_MASK_B_LSB              (1U << 23)      /* 7b */
+/* SPM_CLK_SETTLE (0x10006000+0x010) */
+#define SYSCLK_SETTLE_LSB                   (1U << 0)       /* 28b */
+/* SPM_AP_STANDBY_CON (0x10006000+0x014) */
+#define WFI_OP_LSB                          (1U << 0)       /* 1b */
+#define MP0_CPUTOP_IDLE_MASK_LSB            (1U << 1)       /* 1b */
+#define MP1_CPUTOP_IDLE_MASK_LSB            (1U << 2)       /* 1b */
+#define MCUSYS_IDLE_MASK_LSB                (1U << 4)       /* 1b */
+#define MM_MASK_B_LSB                       (1U << 16)      /* 2b */
+#define MD_DDR_EN_0_DBC_EN_LSB              (1U << 18)      /* 1b */
+#define MD_DDR_EN_1_DBC_EN_LSB              (1U << 19)      /* 1b */
+#define MD_MASK_B_LSB                       (1U << 20)      /* 2b */
+#define SSPM_MASK_B_LSB                     (1U << 22)      /* 1b */
+#define SCP_MASK_B_LSB                      (1U << 23)      /* 1b */
+#define SRCCLKENI_MASK_B_LSB                (1U << 24)      /* 1b */
+#define MD_APSRC_1_SEL_LSB                  (1U << 25)      /* 1b */
+#define MD_APSRC_0_SEL_LSB                  (1U << 26)      /* 1b */
+#define CONN_DDR_EN_DBC_EN_LSB              (1U << 27)      /* 1b */
+#define CONN_MASK_B_LSB                     (1U << 28)      /* 1b */
+#define CONN_APSRC_SEL_LSB                  (1U << 29)      /* 1b */
+/* PCM_CON0 (0x10006000+0x018) */
+#define PCM_KICK_L_LSB                      (1U << 0)       /* 1b */
+#define IM_KICK_L_LSB                       (1U << 1)       /* 1b */
+#define PCM_CK_EN_LSB                       (1U << 2)       /* 1b */
+#define EN_IM_SLEEP_DVS_LSB                 (1U << 3)       /* 1b */
+#define IM_AUTO_PDN_EN_LSB                  (1U << 4)       /* 1b */
+#define PCM_SW_RESET_LSB                    (1U << 15)      /* 1b */
+#define PROJECT_CODE_LSB                    (1U << 16)      /* 16b */
+/* PCM_CON1 (0x10006000+0x01C) */
+#define IM_SLAVE_LSB                        (1U << 0)       /* 1b */
+#define IM_SLEEP_LSB                        (1U << 1)       /* 1b */
+#define MIF_APBEN_LSB                       (1U << 3)       /* 1b */
+#define IM_PDN_LSB                          (1U << 4)       /* 1b */
+#define PCM_TIMER_EN_LSB                    (1U << 5)       /* 1b */
+#define IM_NONRP_EN_LSB                     (1U << 6)       /* 1b */
+#define DIS_MIF_PROT_LSB                    (1U << 7)       /* 1b */
+#define PCM_WDT_EN_LSB                      (1U << 8)       /* 1b */
+#define PCM_WDT_WAKE_MODE_LSB               (1U << 9)       /* 1b */
+#define SPM_SRAM_SLEEP_B_LSB                (1U << 10)      /* 1b */
+#define SPM_SRAM_ISOINT_B_LSB               (1U << 11)      /* 1b */
+#define EVENT_LOCK_EN_LSB                   (1U << 12)      /* 1b */
+#define SRCCLKEN_FAST_RESP_LSB              (1U << 13)      /* 1b */
+#define SCP_APB_INTERNAL_EN_LSB             (1U << 14)      /* 1b */
+#define PROJECT_CODE_LSB                    (1U << 16)      /* 16b */
+/* PCM_IM_PTR (0x10006000+0x020) */
+#define PCM_IM_PTR_LSB                      (1U << 0)       /* 32b */
+/* PCM_IM_LEN (0x10006000+0x024) */
+#define PCM_IM_LEN_LSB                      (1U << 0)       /* 13b */
+/* PCM_REG_DATA_INI (0x10006000+0x028) */
+#define PCM_REG_DATA_INI_LSB                (1U << 0)       /* 32b */
+/* PCM_PWR_IO_EN (0x10006000+0x02C) */
+#define PCM_PWR_IO_EN_LSB                   (1U << 0)       /* 8b */
+#define PCM_RF_SYNC_EN_LSB                  (1U << 16)      /* 8b */
+/* PCM_TIMER_VAL (0x10006000+0x030) */
+#define PCM_TIMER_VAL_LSB                   (1U << 0)       /* 32b */
+/* PCM_WDT_VAL (0x10006000+0x034) */
+#define PCM_WDT_VAL_LSB                     (1U << 0)       /* 32b */
+/* PCM_IM_HOST_RW_PTR (0x10006000+0x038) */
+#define PCM_IM_HOST_RW_PTR_LSB              (1U << 0)       /* 12b */
+#define PCM_IM_HOST_W_EN_LSB                (1U << 30)      /* 1b */
+#define PCM_IM_HOST_EN_LSB                  (1U << 31)      /* 1b */
+/* PCM_IM_HOST_RW_DAT (0x10006000+0x03C) */
+#define PCM_IM_HOST_RW_DAT_LSB              (1U << 0)       /* 32b */
+/* PCM_EVENT_VECTOR0 (0x10006000+0x040) */
+#define PCM_EVENT_VECTOR_0_LSB              (1U << 0)       /* 6b */
+#define PCM_EVENT_RESUME_0_LSB              (1U << 6)       /* 1b */
+#define PCM_EVENT_IMMEDIA_0_LSB             (1U << 7)       /* 1b */
+#define PCM_EVENT_VECTPC_0_LSB              (1U << 16)      /* 11b */
+/* PCM_EVENT_VECTOR1 (0x10006000+0x044) */
+#define PCM_EVENT_VECTOR_1_LSB              (1U << 0)       /* 6b */
+#define PCM_EVENT_RESUME_1_LSB              (1U << 6)       /* 1b */
+#define PCM_EVENT_IMMEDIA_1_LSB             (1U << 7)       /* 1b */
+#define PCM_EVENT_VECTPC_1_LSB              (1U << 16)      /* 11b */
+/* PCM_EVENT_VECTOR2 (0x10006000+0x048) */
+#define PCM_EVENT_VECTOR_2_LSB              (1U << 0)       /* 6b */
+#define PCM_EVENT_RESUME_2_LSB              (1U << 6)       /* 1b */
+#define PCM_EVENT_IMMEDIA_2_LSB             (1U << 7)       /* 1b */
+#define PCM_EVENT_VECTPC_2_LSB              (1U << 16)      /* 11b */
+/* PCM_EVENT_VECTOR3 (0x10006000+0x04C) */
+#define PCM_EVENT_VECTOR_3_LSB              (1U << 0)       /* 6b */
+#define PCM_EVENT_RESUME_3_LSB              (1U << 6)       /* 1b */
+#define PCM_EVENT_IMMEDIA_3_LSB             (1U << 7)       /* 1b */
+#define PCM_EVENT_VECTPC_3_LSB              (1U << 16)      /* 11b */
+/* PCM_EVENT_VECTOR4 (0x10006000+0x050) */
+#define PCM_EVENT_VECTOR_4_LSB              (1U << 0)       /* 6b */
+#define PCM_EVENT_RESUME_4_LSB              (1U << 6)       /* 1b */
+#define PCM_EVENT_IMMEDIA_4_LSB             (1U << 7)       /* 1b */
+#define PCM_EVENT_VECTPC_4_LSB              (1U << 16)      /* 11b */
+/* PCM_EVENT_VECTOR5 (0x10006000+0x054) */
+#define PCM_EVENT_VECTOR_5_LSB              (1U << 0)       /* 6b */
+#define PCM_EVENT_RESUME_5_LSB              (1U << 6)       /* 1b */
+#define PCM_EVENT_IMMEDIA_5_LSB             (1U << 7)       /* 1b */
+#define PCM_EVENT_VECTPC_5_LSB              (1U << 16)      /* 11b */
+/* PCM_EVENT_VECTOR6 (0x10006000+0x058) */
+#define PCM_EVENT_VECTOR_6_LSB              (1U << 0)       /* 6b */
+#define PCM_EVENT_RESUME_6_LSB              (1U << 6)       /* 1b */
+#define PCM_EVENT_IMMEDIA_6_LSB             (1U << 7)       /* 1b */
+#define PCM_EVENT_VECTPC_6_LSB              (1U << 16)      /* 11b */
+/* PCM_EVENT_VECTOR7 (0x10006000+0x05C) */
+#define PCM_EVENT_VECTOR_7_LSB              (1U << 0)       /* 6b */
+#define PCM_EVENT_RESUME_7_LSB              (1U << 6)       /* 1b */
+#define PCM_EVENT_IMMEDIA_7_LSB             (1U << 7)       /* 1b */
+#define PCM_EVENT_VECTPC_7_LSB              (1U << 16)      /* 11b */
+/* PCM_EVENT_VECTOR8 (0x10006000+0x060) */
+#define PCM_EVENT_VECTOR_8_LSB              (1U << 0)       /* 6b */
+#define PCM_EVENT_RESUME_8_LSB              (1U << 6)       /* 1b */
+#define PCM_EVENT_IMMEDIA_8_LSB             (1U << 7)       /* 1b */
+#define PCM_EVENT_VECTPC_8_LSB              (1U << 16)      /* 11b */
+/* PCM_EVENT_VECTOR9 (0x10006000+0x064) */
+#define PCM_EVENT_VECTOR_9_LSB              (1U << 0)       /* 6b */
+#define PCM_EVENT_RESUME_9_LSB              (1U << 6)       /* 1b */
+#define PCM_EVENT_IMMEDIA_9_LSB             (1U << 7)       /* 1b */
+#define PCM_EVENT_VECTPC_9_LSB              (1U << 16)      /* 11b */
+/* PCM_EVENT_VECTOR10 (0x10006000+0x068) */
+#define PCM_EVENT_VECTOR_10_LSB             (1U << 0)       /* 6b */
+#define PCM_EVENT_RESUME_10_LSB             (1U << 6)       /* 1b */
+#define PCM_EVENT_IMMEDIA_10_LSB            (1U << 7)       /* 1b */
+#define PCM_EVENT_VECTPC_10_LSB             (1U << 16)      /* 11b */
+/* PCM_EVENT_VECTOR11 (0x10006000+0x06C) */
+#define PCM_EVENT_VECTOR_11_LSB             (1U << 0)       /* 6b */
+#define PCM_EVENT_RESUME_11_LSB             (1U << 6)       /* 1b */
+#define PCM_EVENT_IMMEDIA_11_LSB            (1U << 7)       /* 1b */
+#define PCM_EVENT_VECTPC_11_LSB             (1U << 16)      /* 11b */
+/* PCM_EVENT_VECTOR12 (0x10006000+0x070) */
+#define PCM_EVENT_VECTOR_12_LSB             (1U << 0)       /* 6b */
+#define PCM_EVENT_RESUME_12_LSB             (1U << 6)       /* 1b */
+#define PCM_EVENT_IMMEDIA_12_LSB            (1U << 7)       /* 1b */
+#define PCM_EVENT_VECTPC_12_LSB             (1U << 16)      /* 11b */
+/* PCM_EVENT_VECTOR13 (0x10006000+0x074) */
+#define PCM_EVENT_VECTOR_13_LSB             (1U << 0)       /* 6b */
+#define PCM_EVENT_RESUME_13_LSB             (1U << 6)       /* 1b */
+#define PCM_EVENT_IMMEDIA_13_LSB            (1U << 7)       /* 1b */
+#define PCM_EVENT_VECTPC_13_LSB             (1U << 16)      /* 11b */
+/* PCM_EVENT_VECTOR14 (0x10006000+0x078) */
+#define PCM_EVENT_VECTOR_14_LSB             (1U << 0)       /* 6b */
+#define PCM_EVENT_RESUME_14_LSB             (1U << 6)       /* 1b */
+#define PCM_EVENT_IMMEDIA_14_LSB            (1U << 7)       /* 1b */
+#define PCM_EVENT_VECTPC_14_LSB             (1U << 16)      /* 11b */
+/* PCM_EVENT_VECTOR15 (0x10006000+0x07C) */
+#define PCM_EVENT_VECTOR_15_LSB             (1U << 0)       /* 6b */
+#define PCM_EVENT_RESUME_15_LSB             (1U << 6)       /* 1b */
+#define PCM_EVENT_IMMEDIA_15_LSB            (1U << 7)       /* 1b */
+#define PCM_EVENT_VECTPC_15_LSB             (1U << 16)      /* 11b */
+/* PCM_EVENT_VECTOR_EN (0x10006000+0x080) */
+#define PCM_EVENT_VECTOR_EN_LSB             (1U << 0)       /* 16b */
+/* SPM_SRAM_RSV_CON (0x10006000+0x088) */
+#define SPM_SRAM_SLEEP_B_ECO_EN_LSB         (1U << 0)       /* 1b */
+/* SPM_SWINT (0x10006000+0x08C) */
+#define SPM_SWINT_LSB                       (1U << 0)       /* 10b */
+/* SPM_SWINT_SET (0x10006000+0x090) */
+#define SPM_SWINT_SET_LSB                   (1U << 0)       /* 10b */
+/* SPM_SWINT_CLR (0x10006000+0x094) */
+#define SPM_SWINT_CLR_LSB                   (1U << 0)       /* 10b */
+/* SPM_SCP_MAILBOX (0x10006000+0x098) */
+#define SPM_SCP_MAILBOX_LSB                 (1U << 0)       /* 32b */
+/* SCP_SPM_MAILBOX (0x10006000+0x09C) */
+#define SCP_SPM_MAILBOX_LSB                 (1U << 0)       /* 32b */
+/* SPM_TWAM_CON (0x10006000+0x0A0) */
+#define TWAM_ENABLE_LSB                     (1U << 0)       /* 1b */
+#define TWAM_SPEED_MODE_ENABLE_LSB          (1U << 1)       /* 1b */
+#define TWAM_SW_RST_LSB                     (1U << 2)       /* 1b */
+#define TWAM_MON_TYPE0_LSB                  (1U << 4)       /* 2b */
+#define TWAM_MON_TYPE1_LSB                  (1U << 6)       /* 2b */
+#define TWAM_MON_TYPE2_LSB                  (1U << 8)       /* 2b */
+#define TWAM_MON_TYPE3_LSB                  (1U << 10)      /* 2b */
+#define TWAM_SIGNAL_SEL0_LSB                (1U << 12)      /* 5b */
+#define TWAM_SIGNAL_SEL1_LSB                (1U << 17)      /* 5b */
+#define TWAM_SIGNAL_SEL2_LSB                (1U << 22)      /* 5b */
+#define TWAM_SIGNAL_SEL3_LSB                (1U << 27)      /* 5b */
+/* SPM_TWAM_WINDOW_LEN (0x10006000+0x0A4) */
+#define TWAM_WINDOW_LEN_LSB                 (1U << 0)       /* 32b */
+/* SPM_TWAM_IDLE_SEL (0x10006000+0x0A8) */
+#define TWAM_IDLE_SEL_LSB                   (1U << 0)       /* 5b */
+/* SPM_SCP_IRQ (0x10006000+0x0AC) */
+#define SPM_SCP_IRQ_LSB                     (1U << 0)       /* 1b */
+#define SPM_SCP_IRQ_SEL_LSB                 (1U << 4)       /* 1b */
+/* SPM_CPU_WAKEUP_EVENT (0x10006000+0x0B0) */
+#define SPM_CPU_WAKEUP_EVENT_LSB            (1U << 0)       /* 1b */
+/* SPM_IRQ_MASK (0x10006000+0x0B4) */
+#define SPM_TWAM_IRQ_MASK_LSB               (1U << 2)       /* 1b */
+#define PCM_IRQ_ROOT_MASK_LSB               (1U << 3)       /* 1b */
+#define SPM_IRQ_MASK_LSB                    (1U << 8)       /* 10b */
+/* SPM_SRC_REQ (0x10006000+0x0B8) */
+#define SPM_APSRC_REQ_LSB                   (1U << 0)       /* 1b */
+#define SPM_F26M_REQ_LSB                    (1U << 1)       /* 1b */
+#define SPM_INFRA_REQ_LSB                   (1U << 3)       /* 1b */
+#define SPM_VRF18_REQ_LSB                   (1U << 4)       /* 1b */
+#define SPM_DDREN_REQ_LSB                   (1U << 7)       /* 1b */
+#define SPM_RSV_SRC_REQ_LSB                 (1U << 8)       /* 3b */
+#define SPM_DDREN_2_REQ_LSB                 (1U << 11)      /* 1b */
+#define CPU_MD_DVFS_SOP_FORCE_ON_LSB        (1U << 16)      /* 1b */
+/* SPM_SRC_MASK (0x10006000+0x0BC) */
+#define CSYSPWREQ_MASK_LSB                  (1U << 0)       /* 1b */
+#define CCIF0_MD_EVENT_MASK_B_LSB           (1U << 1)       /* 1b */
+#define CCIF0_AP_EVENT_MASK_B_LSB           (1U << 2)       /* 1b */
+#define CCIF1_MD_EVENT_MASK_B_LSB           (1U << 3)       /* 1b */
+#define CCIF1_AP_EVENT_MASK_B_LSB           (1U << 4)       /* 1b */
+#define CCIF2_MD_EVENT_MASK_B_LSB           (1U << 5)       /* 1b */
+#define CCIF2_AP_EVENT_MASK_B_LSB           (1U << 6)       /* 1b */
+#define CCIF3_MD_EVENT_MASK_B_LSB           (1U << 7)       /* 1b */
+#define CCIF3_AP_EVENT_MASK_B_LSB           (1U << 8)       /* 1b */
+#define MD_SRCCLKENA_0_INFRA_MASK_B_LSB     (1U << 9)       /* 1b */
+#define MD_SRCCLKENA_1_INFRA_MASK_B_LSB     (1U << 10)      /* 1b */
+#define CONN_SRCCLKENA_INFRA_MASK_B_LSB     (1U << 11)      /* 1b */
+#define UFS_INFRA_REQ_MASK_B_LSB            (1U << 12)      /* 1b */
+#define SRCCLKENI_INFRA_MASK_B_LSB          (1U << 13)      /* 1b */
+#define MD_APSRC_REQ_0_INFRA_MASK_B_LSB     (1U << 14)      /* 1b */
+#define MD_APSRC_REQ_1_INFRA_MASK_B_LSB     (1U << 15)      /* 1b */
+#define CONN_APSRCREQ_INFRA_MASK_B_LSB      (1U << 16)      /* 1b */
+#define UFS_SRCCLKENA_MASK_B_LSB            (1U << 17)      /* 1b */
+#define MD_VRF18_REQ_0_MASK_B_LSB           (1U << 18)      /* 1b */
+#define MD_VRF18_REQ_1_MASK_B_LSB           (1U << 19)      /* 1b */
+#define UFS_VRF18_REQ_MASK_B_LSB            (1U << 20)      /* 1b */
+#define GCE_VRF18_REQ_MASK_B_LSB            (1U << 21)      /* 1b */
+#define CONN_INFRA_REQ_MASK_B_LSB           (1U << 22)      /* 1b */
+#define GCE_APSRC_REQ_MASK_B_LSB            (1U << 23)      /* 1b */
+#define DISP0_APSRC_REQ_MASK_B_LSB          (1U << 24)      /* 1b */
+#define DISP1_APSRC_REQ_MASK_B_LSB          (1U << 25)      /* 1b */
+#define MFG_REQ_MASK_B_LSB                  (1U << 26)      /* 1b */
+#define VDEC_REQ_MASK_B_LSB                 (1U << 27)      /* 1b */
+/* SPM_SRC2_MASK (0x10006000+0x0C0) */
+#define MD_DDR_EN_0_MASK_B_LSB              (1U << 0)       /* 1b */
+#define MD_DDR_EN_1_MASK_B_LSB              (1U << 1)       /* 1b */
+#define CONN_DDR_EN_MASK_B_LSB              (1U << 2)       /* 1b */
+#define DDREN_SSPM_APSRC_REQ_MASK_B_LSB     (1U << 3)       /* 1b */
+#define DDREN_SCP_APSRC_REQ_MASK_B_LSB      (1U << 4)       /* 1b */
+#define DISP0_DDREN_MASK_B_LSB              (1U << 5)       /* 1b */
+#define DISP1_DDREN_MASK_B_LSB              (1U << 6)       /* 1b */
+#define GCE_DDREN_MASK_B_LSB                (1U << 7)       /* 1b */
+#define DDREN_EMI_SELF_REFRESH_CH0_MASK_B_LSB (1U << 8)       /* 1b */
+#define DDREN_EMI_SELF_REFRESH_CH1_MASK_B_LSB (1U << 9)       /* 1b */
+/* SPM_WAKEUP_EVENT_MASK (0x10006000+0x0C4) */
+#define SPM_WAKEUP_EVENT_MASK_LSB           (1U << 0)       /* 32b */
+/* SPM_WAKEUP_EVENT_EXT_MASK (0x10006000+0x0C8) */
+#define SPM_WAKEUP_EVENT_EXT_MASK_LSB       (1U << 0)       /* 32b */
+/* SPM_TWAM_EVENT_CLEAR (0x10006000+0x0CC) */
+#define SPM_TWAM_EVENT_CLEAR_LSB            (1U << 0)       /* 1b */
+/* SCP_CLK_CON (0x10006000+0x0D0) */
+#define SCP_26M_CK_SEL_LSB                  (1U << 0)       /* 1b */
+#define SCP_SECURE_V_REQ_MASK_LSB           (1U << 1)       /* 1b */
+#define SCP_SLP_REQ_LSB                     (1U << 2)       /* 1b */
+#define SCP_SLP_ACK_LSB                     (1U << 3)       /* 1b */
+/* PCM_DEBUG_CON (0x10006000+0x0D4) */
+#define PCM_DEBUG_OUT_ENABLE_LSB            (1U << 0)       /* 1b */
+/* DDR_EN_DBC_LEN (0x10006000+0x0D8) */
+#define MD_DDR_EN_0_DBC_LEN_LSB             (1U << 0)       /* 10b */
+#define MD_DDR_EN_1_DBC_LEN_LSB             (1U << 10)      /* 10b */
+#define CONN_DDR_EN_DBC_LEN_LSB             (1U << 20)      /* 10b */
+/* AHB_BUS_CON (0x10006000+0x0DC) */
+#define AHB_HADDR_EXT_LSB                   (1U << 0)       /* 2b */
+#define REG_AHB_LOCK_LSB                    (1U << 8)       /* 1b */
+/* SPM_SRC3_MASK (0x10006000+0x0E0) */
+#define MD_DDR_EN_2_0_MASK_B_LSB            (1U << 0)       /* 1b */
+#define MD_DDR_EN_2_1_MASK_B_LSB            (1U << 1)       /* 1b */
+#define CONN_DDR_EN_2_MASK_B_LSB            (1U << 2)       /* 1b */
+#define DDREN2_SSPM_APSRC_REQ_MASK_B_LSB    (1U << 3)       /* 1b */
+#define DDREN2_SCP_APSRC_REQ_MASK_B_LSB     (1U << 4)       /* 1b */
+#define DISP0_DDREN2_MASK_B_LSB             (1U << 5)       /* 1b */
+#define DISP1_DDREN2_MASK_B_LSB             (1U << 6)       /* 1b */
+#define GCE_DDREN2_MASK_B_LSB               (1U << 7)       /* 1b */
+#define DDREN2_EMI_SELF_REFRESH_CH0_MASK_B_LSB (1U << 8)       /* 1b */
+#define DDREN2_EMI_SELF_REFRESH_CH1_MASK_B_LSB (1U << 9)       /* 1b */
+/* DDR_EN_EMI_DBC_CON (0x10006000+0x0E4) */
+#define EMI_SELF_REFRESH_CH0_DBC_LEN_LSB    (1U << 0)       /* 10b */
+#define EMI_SELF_REFRESH_CH0_DBC_EN_LSB     (1U << 10)      /* 1b */
+#define EMI_SELF_REFRESH_CH1_DBC_LEN_LSB    (1U << 16)      /* 10b */
+#define EMI_SELF_REFRESH_CH1_DBC_EN_LSB     (1U << 26)      /* 1b */
+/* SSPM_CLK_CON (0x10006000+0x0E8) */
+#define SSPM_26M_CK_SEL_LSB                 (1U << 0)       /* 1b */
+/* PCM_REG0_DATA (0x10006000+0x100) */
+#define PCM_REG0_DATA_LSB                   (1U << 0)       /* 32b */
+/* PCM_REG1_DATA (0x10006000+0x104) */
+#define PCM_REG1_DATA_LSB                   (1U << 0)       /* 32b */
+/* PCM_REG2_DATA (0x10006000+0x108) */
+#define PCM_REG2_DATA_LSB                   (1U << 0)       /* 32b */
+/* PCM_REG3_DATA (0x10006000+0x10C) */
+#define PCM_REG3_DATA_LSB                   (1U << 0)       /* 32b */
+/* PCM_REG4_DATA (0x10006000+0x110) */
+#define PCM_REG4_DATA_LSB                   (1U << 0)       /* 32b */
+/* PCM_REG5_DATA (0x10006000+0x114) */
+#define PCM_REG5_DATA_LSB                   (1U << 0)       /* 32b */
+/* PCM_REG6_DATA (0x10006000+0x118) */
+#define PCM_REG6_DATA_LSB                   (1U << 0)       /* 32b */
+/* PCM_REG7_DATA (0x10006000+0x11C) */
+#define PCM_REG7_DATA_LSB                   (1U << 0)       /* 32b */
+/* PCM_REG8_DATA (0x10006000+0x120) */
+#define PCM_REG8_DATA_LSB                   (1U << 0)       /* 32b */
+/* PCM_REG9_DATA (0x10006000+0x124) */
+#define PCM_REG9_DATA_LSB                   (1U << 0)       /* 32b */
+/* PCM_REG10_DATA (0x10006000+0x128) */
+#define PCM_REG10_DATA_LSB                  (1U << 0)       /* 32b */
+/* PCM_REG11_DATA (0x10006000+0x12C) */
+#define PCM_REG11_DATA_LSB                  (1U << 0)       /* 32b */
+/* PCM_REG12_DATA (0x10006000+0x130) */
+#define PCM_REG12_DATA_LSB                  (1U << 0)       /* 32b */
+/* PCM_REG13_DATA (0x10006000+0x134) */
+#define PCM_REG13_DATA_LSB                  (1U << 0)       /* 32b */
+/* PCM_REG14_DATA (0x10006000+0x138) */
+#define PCM_REG14_DATA_LSB                  (1U << 0)       /* 32b */
+/* PCM_REG15_DATA (0x10006000+0x13C) */
+#define PCM_REG15_DATA_LSB                  (1U << 0)       /* 32b */
+/* PCM_REG12_MASK_B_STA (0x10006000+0x140) */
+#define PCM_REG12_MASK_B_STA_LSB            (1U << 0)       /* 32b */
+/* PCM_REG12_EXT_DATA (0x10006000+0x144) */
+#define PCM_REG12_EXT_DATA_LSB              (1U << 0)       /* 32b */
+/* PCM_REG12_EXT_MASK_B_STA (0x10006000+0x148) */
+#define PCM_REG12_EXT_MASK_B_STA_LSB        (1U << 0)       /* 32b */
+/* PCM_EVENT_REG_STA (0x10006000+0x14C) */
+#define PCM_EVENT_REG_STA_LSB               (1U << 0)       /* 32b */
+/* PCM_TIMER_OUT (0x10006000+0x150) */
+#define PCM_TIMER_OUT_LSB                   (1U << 0)       /* 32b */
+/* PCM_WDT_OUT (0x10006000+0x154) */
+#define PCM_WDT_OUT_LSB                     (1U << 0)       /* 32b */
+/* SPM_IRQ_STA (0x10006000+0x158) */
+#define SPM_ACK_CHK_WAKEUP_LSB              (1U << 1)       /* 1b */
+#define TWAM_IRQ_LSB                        (1U << 2)       /* 1b */
+#define PCM_IRQ_LSB                         (1U << 3)       /* 1b */
+/* #define SPM_SWINT_LSB                    (1U << 4) */       /* 10b */
+/* SPM_WAKEUP_STA (0x10006000+0x15C) */
+#define SPM_WAKEUP_EVENT_STA_LSB            (1U << 0)       /* 32b */
+/* SPM_WAKEUP_EXT_STA (0x10006000+0x160) */
+#define SPM_WAKEUP_EVENT_EXT_STA_LSB        (1U << 0)       /* 32b */
+/* SPM_WAKEUP_MISC (0x10006000+0x164) */
+#define SPM_WAKEUP_EVENT_MISC_LSB           (1U << 0)       /* 30b */
+#define SPM_PWRAP_IRQ_ACK_LSB               (1U << 30)      /* 1b */
+#define SPM_PWRAP_IRQ_LSB                   (1U << 31)      /* 1b */
+/* BUS_PROTECT_RDY (0x10006000+0x168) */
+#define BUS_PROTECT_RDY_LSB                 (1U << 0)       /* 32b */
+/* BUS_PROTECT2_RDY (0x10006000+0x16C) */
+#define BUS_PROTECT2_RDY_LSB                (1U << 0)       /* 32b */
+/* SUBSYS_IDLE_STA (0x10006000+0x170) */
+#define SUBSYS_IDLE_STA_LSB                 (1U << 0)       /* 32b */
+/* CPU_IDLE_STA (0x10006000+0x174) */
+#define MP0_CPU0_STANDBYWFI_AFTER_SEL_LSB   (1U << 0)       /* 1b */
+#define MP0_CPU1_STANDBYWFI_AFTER_SEL_LSB   (1U << 1)       /* 1b */
+#define MP0_CPU2_STANDBYWFI_AFTER_SEL_LSB   (1U << 2)       /* 1b */
+#define MP0_CPU3_STANDBYWFI_AFTER_SEL_LSB   (1U << 3)       /* 1b */
+#define MP1_CPU0_STANDBYWFI_AFTER_SEL_LSB   (1U << 4)       /* 1b */
+#define MP1_CPU1_STANDBYWFI_AFTER_SEL_LSB   (1U << 5)       /* 1b */
+#define MP1_CPU2_STANDBYWFI_AFTER_SEL_LSB   (1U << 6)       /* 1b */
+#define MP1_CPU3_STANDBYWFI_AFTER_SEL_LSB   (1U << 7)       /* 1b */
+#define MP0_CPU0_STANDBYWFI_LSB             (1U << 10)      /* 1b */
+#define MP0_CPU1_STANDBYWFI_LSB             (1U << 11)      /* 1b */
+#define MP0_CPU2_STANDBYWFI_LSB             (1U << 12)      /* 1b */
+#define MP0_CPU3_STANDBYWFI_LSB             (1U << 13)      /* 1b */
+#define MP1_CPU0_STANDBYWFI_LSB             (1U << 14)      /* 1b */
+#define MP1_CPU1_STANDBYWFI_LSB             (1U << 15)      /* 1b */
+#define MP1_CPU2_STANDBYWFI_LSB             (1U << 16)      /* 1b */
+#define MP1_CPU3_STANDBYWFI_LSB             (1U << 17)      /* 1b */
+#define MP0_CPUTOP_IDLE_LSB                 (1U << 20)      /* 1b */
+#define MP1_CPUTOP_IDLE_LSB                 (1U << 21)      /* 1b */
+#define MCU_BIU_IDLE_LSB                    (1U << 22)      /* 1b */
+#define MCUSYS_IDLE_LSB                     (1U << 23)      /* 1b */
+/* PCM_FSM_STA (0x10006000+0x178) */
+#define EXEC_INST_OP_LSB                    (1U << 0)       /* 4b */
+#define PC_STATE_LSB                        (1U << 4)       /* 3b */
+#define IM_STATE_LSB                        (1U << 7)       /* 3b */
+#define MASTER_STATE_LSB                    (1U << 10)      /* 5b */
+#define EVENT_FSM_LSB                       (1U << 15)      /* 3b */
+#define PCM_CLK_SEL_STA_LSB                 (1U << 18)      /* 3b */
+#define PCM_KICK_LSB                        (1U << 21)      /* 1b */
+#define IM_KICK_LSB                         (1U << 22)      /* 1b */
+#define EXT_SRCCLKEN_STA_LSB                (1U << 23)      /* 2b */
+#define EXT_SRCVOLTEN_STA_LSB               (1U << 25)      /* 1b */
+/* SRC_REQ_STA (0x10006000+0x17C) */
+#define SRC_REQ_STA_LSB                     (1U << 0)       /* 32b */
+/* PWR_STATUS (0x10006000+0x180) */
+#define PWR_STATUS_LSB                      (1U << 0)       /* 32b */
+/* PWR_STATUS_2ND (0x10006000+0x184) */
+#define PWR_STATUS_2ND_LSB                  (1U << 0)       /* 32b */
+/* CPU_PWR_STATUS (0x10006000+0x188) */
+#define CPU_PWR_STATUS_LSB                  (1U << 0)       /* 32b */
+/* CPU_PWR_STATUS_2ND (0x10006000+0x18C) */
+#define CPU_PWR_STATUS_2ND_LSB              (1U << 0)       /* 32b */
+/* MISC_STA (0x10006000+0x190) */
+#define MM_DVFS_HALT_AF_MASK_LSB            (1U << 0)       /* 5b */
+/* SPM_SRC_RDY_STA (0x10006000+0x194) */
+#define SPM_INFRA_SRC_ACK_LSB               (1U << 0)       /* 1b */
+#define SPM_VRF18_SRC_ACK_LSB               (1U << 1)       /* 1b */
+/* DRAMC_DBG_LATCH (0x10006000+0x19C) */
+#define DRAMC_DEBUG_LATCH_STATUS_LSB        (1U << 0)       /* 32b */
+/* SPM_TWAM_LAST_STA0 (0x10006000+0x1A0) */
+#define SPM_TWAM_LAST_STA0_LSB              (1U << 0)       /* 32b */
+/* SPM_TWAM_LAST_STA1 (0x10006000+0x1A4) */
+#define SPM_TWAM_LAST_STA1_LSB              (1U << 0)       /* 32b */
+/* SPM_TWAM_LAST_STA2 (0x10006000+0x1A8) */
+#define SPM_TWAM_LAST_STA2_LSB              (1U << 0)       /* 32b */
+/* SPM_TWAM_LAST_STA3 (0x10006000+0x1AC) */
+#define SPM_TWAM_LAST_STA3_LSB              (1U << 0)       /* 32b */
+/* SPM_TWAM_CURR_STA0 (0x10006000+0x1B0) */
+#define SPM_TWAM_CURR_STA0_LSB              (1U << 0)       /* 32b */
+/* SPM_TWAM_CURR_STA1 (0x10006000+0x1B4) */
+#define SPM_TWAM_CURR_STA1_LSB              (1U << 0)       /* 32b */
+/* SPM_TWAM_CURR_STA2 (0x10006000+0x1B8) */
+#define SPM_TWAM_CURR_STA2_LSB              (1U << 0)       /* 32b */
+/* SPM_TWAM_CURR_STA3 (0x10006000+0x1BC) */
+#define SPM_TWAM_CURR_STA3_LSB              (1U << 0)       /* 32b */
+/* SPM_TWAM_TIMER_OUT (0x10006000+0x1C0) */
+#define SPM_TWAM_TIMER_OUT_LSB              (1U << 0)       /* 32b */
+/* SPM_DVFS_STA (0x10006000+0x1C8) */
+#define MD_DVFS_ERROR_STATUS_LSB            (1U << 0)       /* 1b */
+/* BUS_PROTECT3_RDY (0x10006000+0x1CC) */
+#define BUS_PROTECT_MM_RDY_LSB              (1U << 0)       /* 16b */
+#define BUS_PROTECT_MCU_RDY_LSB             (1U << 16)      /* 16b */
+/* SRC_DDREN_STA (0x10006000+0x1E0) */
+#define SRC_DDREN_STA_LSB                   (1U << 0)       /* 32b */
+/* MCU_PWR_CON (0x10006000+0x200) */
+#define MCU_PWR_RST_B_LSB                   (1U << 0)       /* 1b */
+#define MCU_PWR_ISO_LSB                     (1U << 1)       /* 1b */
+#define MCU_PWR_ON_LSB                      (1U << 2)       /* 1b */
+#define MCU_PWR_ON_2ND_LSB                  (1U << 3)       /* 1b */
+#define MCU_PWR_CLK_DIS_LSB                 (1U << 4)       /* 1b */
+#define MCU_SRAM_CKISO_LSB                  (1U << 5)       /* 1b */
+#define MCU_SRAM_ISOINT_B_LSB               (1U << 6)       /* 1b */
+#define MCU_SRAM_PD_SLPB_CLAMP_LSB          (1U << 7)       /* 1b */
+#define MCU_SRAM_PDN_LSB                    (1U << 8)       /* 1b */
+#define MCU_SRAM_SLEEP_B_LSB                (1U << 12)      /* 1b */
+#define SC_MCU_SRAM_PDN_ACK_LSB             (1U << 24)      /* 1b */
+#define SC_MCU_SRAM_SLEEP_B_ACK_LSB         (1U << 28)      /* 1b */
+/* MP0_CPUTOP_PWR_CON (0x10006000+0x204) */
+#define MP0_CPUTOP_PWR_RST_B_LSB            (1U << 0)       /* 1b */
+#define MP0_CPUTOP_PWR_ISO_LSB              (1U << 1)       /* 1b */
+#define MP0_CPUTOP_PWR_ON_LSB               (1U << 2)       /* 1b */
+#define MP0_CPUTOP_PWR_ON_2ND_LSB           (1U << 3)       /* 1b */
+#define MP0_CPUTOP_PWR_CLK_DIS_LSB          (1U << 4)       /* 1b */
+#define MP0_CPUTOP_SRAM_CKISO_LSB           (1U << 5)       /* 1b */
+#define MP0_CPUTOP_SRAM_ISOINT_B_LSB        (1U << 6)       /* 1b */
+#define MP0_CPUTOP_SRAM_PD_SLPB_CLAMP_LSB   (1U << 7)       /* 1b */
+#define MP0_CPUTOP_SRAM_PDN_LSB             (1U << 8)       /* 1b */
+#define MP0_CPUTOP_SRAM_SLEEP_B_LSB         (1U << 12)      /* 1b */
+#define SC_MP0_CPUTOP_SRAM_PDN_ACK_LSB      (1U << 24)      /* 1b */
+#define SC_MP0_CPUTOP_SRAM_SLEEP_B_ACK_LSB  (1U << 28)      /* 1b */
+/* MP0_CPU0_PWR_CON (0x10006000+0x208) */
+#define MP0_CPU0_PWR_RST_B_LSB              (1U << 0)       /* 1b */
+#define MP0_CPU0_PWR_ISO_LSB                (1U << 1)       /* 1b */
+#define MP0_CPU0_PWR_ON_LSB                 (1U << 2)       /* 1b */
+#define MP0_CPU0_PWR_ON_2ND_LSB             (1U << 3)       /* 1b */
+#define MP0_CPU0_PWR_CLK_DIS_LSB            (1U << 4)       /* 1b */
+#define MP0_CPU0_SRAM_CKISO_LSB             (1U << 5)       /* 1b */
+#define MP0_CPU0_SRAM_ISOINT_B_LSB          (1U << 6)       /* 1b */
+#define MP0_CPU0_SRAM_PD_SLPB_CLAMP_LSB     (1U << 7)       /* 1b */
+#define MP0_CPU0_SRAM_PDN_LSB               (1U << 8)       /* 1b */
+#define MP0_CPU0_SRAM_SLEEP_B_LSB           (1U << 12)      /* 1b */
+#define SC_MP0_CPU0_SRAM_PDN_ACK_LSB        (1U << 24)      /* 1b */
+#define SC_MP0_CPU0_SRAM_SLEEP_B_ACK_LSB    (1U << 28)      /* 1b */
+/* MP0_CPU1_PWR_CON (0x10006000+0x20C) */
+#define MP0_CPU1_PWR_RST_B_LSB              (1U << 0)       /* 1b */
+#define MP0_CPU1_PWR_ISO_LSB                (1U << 1)       /* 1b */
+#define MP0_CPU1_PWR_ON_LSB                 (1U << 2)       /* 1b */
+#define MP0_CPU1_PWR_ON_2ND_LSB             (1U << 3)       /* 1b */
+#define MP0_CPU1_PWR_CLK_DIS_LSB            (1U << 4)       /* 1b */
+#define MP0_CPU1_SRAM_CKISO_LSB             (1U << 5)       /* 1b */
+#define MP0_CPU1_SRAM_ISOINT_B_LSB          (1U << 6)       /* 1b */
+#define MP0_CPU1_SRAM_PD_SLPB_CLAMP_LSB     (1U << 7)       /* 1b */
+#define MP0_CPU1_SRAM_PDN_LSB               (1U << 8)       /* 1b */
+#define MP0_CPU1_SRAM_SLEEP_B_LSB           (1U << 12)      /* 1b */
+#define SC_MP0_CPU1_SRAM_PDN_ACK_LSB        (1U << 24)      /* 1b */
+#define SC_MP0_CPU1_SRAM_SLEEP_B_ACK_LSB    (1U << 28)      /* 1b */
+/* MP0_CPU2_PWR_CON (0x10006000+0x210) */
+#define MP0_CPU2_PWR_RST_B_LSB              (1U << 0)       /* 1b */
+#define MP0_CPU2_PWR_ISO_LSB                (1U << 1)       /* 1b */
+#define MP0_CPU2_PWR_ON_LSB                 (1U << 2)       /* 1b */
+#define MP0_CPU2_PWR_ON_2ND_LSB             (1U << 3)       /* 1b */
+#define MP0_CPU2_PWR_CLK_DIS_LSB            (1U << 4)       /* 1b */
+#define MP0_CPU2_SRAM_CKISO_LSB             (1U << 5)       /* 1b */
+#define MP0_CPU2_SRAM_ISOINT_B_LSB          (1U << 6)       /* 1b */
+#define MP0_CPU2_SRAM_PD_SLPB_CLAMP_LSB     (1U << 7)       /* 1b */
+#define MP0_CPU2_SRAM_PDN_LSB               (1U << 8)       /* 1b */
+#define MP0_CPU2_SRAM_SLEEP_B_LSB           (1U << 12)      /* 1b */
+#define SC_MP0_CPU2_SRAM_PDN_ACK_LSB        (1U << 24)      /* 1b */
+#define SC_MP0_CPU2_SRAM_SLEEP_B_ACK_LSB    (1U << 28)      /* 1b */
+/* MP0_CPU3_PWR_CON (0x10006000+0x214) */
+#define MP0_CPU3_PWR_RST_B_LSB              (1U << 0)       /* 1b */
+#define MP0_CPU3_PWR_ISO_LSB                (1U << 1)       /* 1b */
+#define MP0_CPU3_PWR_ON_LSB                 (1U << 2)       /* 1b */
+#define MP0_CPU3_PWR_ON_2ND_LSB             (1U << 3)       /* 1b */
+#define MP0_CPU3_PWR_CLK_DIS_LSB            (1U << 4)       /* 1b */
+#define MP0_CPU3_SRAM_CKISO_LSB             (1U << 5)       /* 1b */
+#define MP0_CPU3_SRAM_ISOINT_B_LSB          (1U << 6)       /* 1b */
+#define MP0_CPU3_SRAM_PD_SLPB_CLAMP_LSB     (1U << 7)       /* 1b */
+#define MP0_CPU3_SRAM_PDN_LSB               (1U << 8)       /* 1b */
+#define MP0_CPU3_SRAM_SLEEP_B_LSB           (1U << 12)      /* 1b */
+#define SC_MP0_CPU3_SRAM_PDN_ACK_LSB        (1U << 24)      /* 1b */
+#define SC_MP0_CPU3_SRAM_SLEEP_B_ACK_LSB    (1U << 28)      /* 1b */
+/* MP1_CPUTOP_PWR_CON (0x10006000+0x218) */
+#define MP1_CPUTOP_PWR_RST_B_LSB            (1U << 0)       /* 1b */
+#define MP1_CPUTOP_PWR_ISO_LSB              (1U << 1)       /* 1b */
+#define MP1_CPUTOP_PWR_ON_LSB               (1U << 2)       /* 1b */
+#define MP1_CPUTOP_PWR_ON_2ND_LSB           (1U << 3)       /* 1b */
+#define MP1_CPUTOP_PWR_CLK_DIS_LSB          (1U << 4)       /* 1b */
+#define MP1_CPUTOP_SRAM_CKISO_LSB           (1U << 5)       /* 1b */
+#define MP1_CPUTOP_SRAM_ISOINT_B_LSB        (1U << 6)       /* 1b */
+#define MP1_CPUTOP_SRAM_PD_SLPB_CLAMP_LSB   (1U << 7)       /* 1b */
+#define MP1_CPUTOP_SRAM_PDN_LSB             (1U << 8)       /* 1b */
+#define MP1_CPUTOP_SRAM_SLEEP_B_LSB         (1U << 12)      /* 1b */
+#define SC_MP1_CPUTOP_SRAM_PDN_ACK_LSB      (1U << 24)      /* 1b */
+#define SC_MP1_CPUTOP_SRAM_SLEEP_B_ACK_LSB  (1U << 28)      /* 1b */
+/* MP1_CPU0_PWR_CON (0x10006000+0x21C) */
+#define MP1_CPU0_PWR_RST_B_LSB              (1U << 0)       /* 1b */
+#define MP1_CPU0_PWR_ISO_LSB                (1U << 1)       /* 1b */
+#define MP1_CPU0_PWR_ON_LSB                 (1U << 2)       /* 1b */
+#define MP1_CPU0_PWR_ON_2ND_LSB             (1U << 3)       /* 1b */
+#define MP1_CPU0_PWR_CLK_DIS_LSB            (1U << 4)       /* 1b */
+#define MP1_CPU0_SRAM_CKISO_LSB             (1U << 5)       /* 1b */
+#define MP1_CPU0_SRAM_ISOINT_B_LSB          (1U << 6)       /* 1b */
+#define MP1_CPU0_SRAM_PD_SLPB_CLAMP_LSB     (1U << 7)       /* 1b */
+#define MP1_CPU0_SRAM_PDN_LSB               (1U << 8)       /* 1b */
+#define MP1_CPU0_SRAM_SLEEP_B_LSB           (1U << 12)      /* 1b */
+#define SC_MP1_CPU0_SRAM_PDN_ACK_LSB        (1U << 24)      /* 1b */
+#define SC_MP1_CPU0_SRAM_SLEEP_B_ACK_LSB    (1U << 28)      /* 1b */
+/* MP1_CPU1_PWR_CON (0x10006000+0x220) */
+#define MP1_CPU1_PWR_RST_B_LSB              (1U << 0)       /* 1b */
+#define MP1_CPU1_PWR_ISO_LSB                (1U << 1)       /* 1b */
+#define MP1_CPU1_PWR_ON_LSB                 (1U << 2)       /* 1b */
+#define MP1_CPU1_PWR_ON_2ND_LSB             (1U << 3)       /* 1b */
+#define MP1_CPU1_PWR_CLK_DIS_LSB            (1U << 4)       /* 1b */
+#define MP1_CPU1_SRAM_CKISO_LSB             (1U << 5)       /* 1b */
+#define MP1_CPU1_SRAM_ISOINT_B_LSB          (1U << 6)       /* 1b */
+#define MP1_CPU1_SRAM_PD_SLPB_CLAMP_LSB     (1U << 7)       /* 1b */
+#define MP1_CPU1_SRAM_PDN_LSB               (1U << 8)       /* 1b */
+#define MP1_CPU1_SRAM_SLEEP_B_LSB           (1U << 12)      /* 1b */
+#define SC_MP1_CPU1_SRAM_PDN_ACK_LSB        (1U << 24)      /* 1b */
+#define SC_MP1_CPU1_SRAM_SLEEP_B_ACK_LSB    (1U << 28)      /* 1b */
+/* MP1_CPU2_PWR_CON (0x10006000+0x224) */
+#define MP1_CPU2_PWR_RST_B_LSB              (1U << 0)       /* 1b */
+#define MP1_CPU2_PWR_ISO_LSB                (1U << 1)       /* 1b */
+#define MP1_CPU2_PWR_ON_LSB                 (1U << 2)       /* 1b */
+#define MP1_CPU2_PWR_ON_2ND_LSB             (1U << 3)       /* 1b */
+#define MP1_CPU2_PWR_CLK_DIS_LSB            (1U << 4)       /* 1b */
+#define MP1_CPU2_SRAM_CKISO_LSB             (1U << 5)       /* 1b */
+#define MP1_CPU2_SRAM_ISOINT_B_LSB          (1U << 6)       /* 1b */
+#define MP1_CPU2_SRAM_PD_SLPB_CLAMP_LSB     (1U << 7)       /* 1b */
+#define MP1_CPU2_SRAM_PDN_LSB               (1U << 8)       /* 1b */
+#define MP1_CPU2_SRAM_SLEEP_B_LSB           (1U << 12)      /* 1b */
+#define SC_MP1_CPU2_SRAM_PDN_ACK_LSB        (1U << 24)      /* 1b */
+#define SC_MP1_CPU2_SRAM_SLEEP_B_ACK_LSB    (1U << 28)      /* 1b */
+/* MP1_CPU3_PWR_CON (0x10006000+0x228) */
+#define MP1_CPU3_PWR_RST_B_LSB              (1U << 0)       /* 1b */
+#define MP1_CPU3_PWR_ISO_LSB                (1U << 1)       /* 1b */
+#define MP1_CPU3_PWR_ON_LSB                 (1U << 2)       /* 1b */
+#define MP1_CPU3_PWR_ON_2ND_LSB             (1U << 3)       /* 1b */
+#define MP1_CPU3_PWR_CLK_DIS_LSB            (1U << 4)       /* 1b */
+#define MP1_CPU3_SRAM_CKISO_LSB             (1U << 5)       /* 1b */
+#define MP1_CPU3_SRAM_ISOINT_B_LSB          (1U << 6)       /* 1b */
+#define MP1_CPU3_SRAM_PD_SLPB_CLAMP_LSB     (1U << 7)       /* 1b */
+#define MP1_CPU3_SRAM_PDN_LSB               (1U << 8)       /* 1b */
+#define MP1_CPU3_SRAM_SLEEP_B_LSB           (1U << 12)      /* 1b */
+#define SC_MP1_CPU3_SRAM_PDN_ACK_LSB        (1U << 24)      /* 1b */
+#define SC_MP1_CPU3_SRAM_SLEEP_B_ACK_LSB    (1U << 28)      /* 1b */
+/* MP0_CPUTOP_L2_PDN (0x10006000+0x240) */
+#define MP0_CPUTOP_L2_SRAM_PDN_LSB          (1U << 0)       /* 1b */
+#define MP0_CPUTOP_L2_SRAM_PDN_ACK_LSB      (1U << 8)       /* 1b */
+/* MP0_CPUTOP_L2_SLEEP_B (0x10006000+0x244) */
+#define MP0_CPUTOP_L2_SRAM_SLEEP_B_LSB      (1U << 0)       /* 1b */
+#define MP0_CPUTOP_L2_SRAM_SLEEP_B_ACK_LSB  (1U << 8)       /* 1b */
+/* MP0_CPU0_L1_PDN (0x10006000+0x248) */
+#define MP0_CPU0_L1_PDN_LSB                 (1U << 0)       /* 1b */
+#define MP0_CPU0_L1_PDN_ACK_LSB             (1U << 8)       /* 1b */
+/* MP0_CPU1_L1_PDN (0x10006000+0x24C) */
+#define MP0_CPU1_L1_PDN_LSB                 (1U << 0)       /* 1b */
+#define MP0_CPU1_L1_PDN_ACK_LSB             (1U << 8)       /* 1b */
+/* MP0_CPU2_L1_PDN (0x10006000+0x250) */
+#define MP0_CPU2_L1_PDN_LSB                 (1U << 0)       /* 1b */
+#define MP0_CPU2_L1_PDN_ACK_LSB             (1U << 8)       /* 1b */
+/* MP0_CPU3_L1_PDN (0x10006000+0x254) */
+#define MP0_CPU3_L1_PDN_LSB                 (1U << 0)       /* 1b */
+#define MP0_CPU3_L1_PDN_ACK_LSB             (1U << 8)       /* 1b */
+/* MP1_CPUTOP_L2_PDN (0x10006000+0x258) */
+#define MP1_CPUTOP_L2_SRAM_PDN_LSB          (1U << 0)       /* 1b */
+#define MP1_CPUTOP_L2_SRAM_PDN_ACK_LSB      (1U << 8)       /* 1b */
+/* MP1_CPUTOP_L2_SLEEP_B (0x10006000+0x25C) */
+#define MP1_CPUTOP_L2_SRAM_SLEEP_B_LSB      (1U << 0)       /* 1b */
+#define MP1_CPUTOP_L2_SRAM_SLEEP_B_ACK_LSB  (1U << 8)       /* 1b */
+/* MP1_CPU0_L1_PDN (0x10006000+0x260) */
+#define MP1_CPU0_L1_PDN_LSB                 (1U << 0)       /* 1b */
+#define MP1_CPU0_L1_PDN_ACK_LSB             (1U << 8)       /* 1b */
+/* MP1_CPU1_L1_PDN (0x10006000+0x264) */
+#define MP1_CPU1_L1_PDN_LSB                 (1U << 0)       /* 1b */
+#define MP1_CPU1_L1_PDN_ACK_LSB             (1U << 8)       /* 1b */
+/* MP1_CPU2_L1_PDN (0x10006000+0x268) */
+#define MP1_CPU2_L1_PDN_LSB                 (1U << 0)       /* 1b */
+#define MP1_CPU2_L1_PDN_ACK_LSB             (1U << 8)       /* 1b */
+/* MP1_CPU3_L1_PDN (0x10006000+0x26C) */
+#define MP1_CPU3_L1_PDN_LSB                 (1U << 0)       /* 1b */
+#define MP1_CPU3_L1_PDN_ACK_LSB             (1U << 8)       /* 1b */
+/* CPU_EXT_BUCK_ISO (0x10006000+0x290) */
+#define MP0_EXT_BUCK_ISO_LSB                (1U << 0)       /* 1b */
+#define MP1_EXT_BUCK_ISO_LSB                (1U << 1)       /* 1b */
+#define MP_EXT_BUCK_ISO_LSB                 (1U << 2)       /* 1b */
+/* DUMMY1_PWR_CON (0x10006000+0x2B0) */
+#define DUMMY1_PWR_RST_B_LSB                (1U << 0)       /* 1b */
+#define DUMMY1_PWR_ISO_LSB                  (1U << 1)       /* 1b */
+#define DUMMY1_PWR_ON_LSB                   (1U << 2)       /* 1b */
+#define DUMMY1_PWR_ON_2ND_LSB               (1U << 3)       /* 1b */
+#define DUMMY1_PWR_CLK_DIS_LSB              (1U << 4)       /* 1b */
+/* BYPASS_SPMC (0x10006000+0x2B4) */
+#define BYPASS_CPU_SPMC_MODE_LSB            (1U << 0)       /* 1b */
+/* SPMC_DORMANT_ENABLE (0x10006000+0x2B8) */
+#define MP0_SPMC_SRAM_DORMANT_EN_LSB        (1U << 0)       /* 1b */
+#define MP1_SPMC_SRAM_DORMANT_EN_LSB        (1U << 1)       /* 1b */
+/* ARMPLL_CLK_CON (0x10006000+0x2BC) */
+#define REG_SC_ARM_FHC_PAUSE_LSB            (1U << 0)       /* 3b */
+#define REG_SC_ARM_CLK_OFF_LSB              (1U << 3)       /* 3b */
+#define REG_SC_ARMPLLOUT_OFF_LSB            (1U << 6)       /* 3b */
+#define REG_SC_ARMPLL_OFF_LSB               (1U << 9)       /* 3b */
+#define REG_SC_ARMPLL_S_OFF_LSB             (1U << 12)      /* 3b */
+/* SPMC_IN_RET (0x10006000+0x2C0) */
+#define SPMC_STATUS_LSB                     (1U << 0)       /* 8b */
+/* VDE_PWR_CON (0x10006000+0x300) */
+#define VDE_PWR_RST_B_LSB                   (1U << 0)       /* 1b */
+#define VDE_PWR_ISO_LSB                     (1U << 1)       /* 1b */
+#define VDE_PWR_ON_LSB                      (1U << 2)       /* 1b */
+#define VDE_PWR_ON_2ND_LSB                  (1U << 3)       /* 1b */
+#define VDE_PWR_CLK_DIS_LSB                 (1U << 4)       /* 1b */
+#define VDE_SRAM_PDN_LSB                    (1U << 8)       /* 4b */
+#define VDE_SRAM_PDN_ACK_LSB                (1U << 12)      /* 4b */
+/* VEN_PWR_CON (0x10006000+0x304) */
+#define VEN_PWR_RST_B_LSB                   (1U << 0)       /* 1b */
+#define VEN_PWR_ISO_LSB                     (1U << 1)       /* 1b */
+#define VEN_PWR_ON_LSB                      (1U << 2)       /* 1b */
+#define VEN_PWR_ON_2ND_LSB                  (1U << 3)       /* 1b */
+#define VEN_PWR_CLK_DIS_LSB                 (1U << 4)       /* 1b */
+#define VEN_SRAM_PDN_LSB                    (1U << 8)       /* 4b */
+#define VEN_SRAM_PDN_ACK_LSB                (1U << 12)      /* 4b */
+/* ISP_PWR_CON (0x10006000+0x308) */
+#define ISP_PWR_RST_B_LSB                   (1U << 0)       /* 1b */
+#define ISP_PWR_ISO_LSB                     (1U << 1)       /* 1b */
+#define ISP_PWR_ON_LSB                      (1U << 2)       /* 1b */
+#define ISP_PWR_ON_2ND_LSB                  (1U << 3)       /* 1b */
+#define ISP_PWR_CLK_DIS_LSB                 (1U << 4)       /* 1b */
+#define ISP_SRAM_PDN_LSB                    (1U << 8)       /* 4b */
+#define ISP_SRAM_PDN_ACK_LSB                (1U << 12)      /* 4b */
+/* DIS_PWR_CON (0x10006000+0x30C) */
+#define DIS_PWR_RST_B_LSB                   (1U << 0)       /* 1b */
+#define DIS_PWR_ISO_LSB                     (1U << 1)       /* 1b */
+#define DIS_PWR_ON_LSB                      (1U << 2)       /* 1b */
+#define DIS_PWR_ON_2ND_LSB                  (1U << 3)       /* 1b */
+#define DIS_PWR_CLK_DIS_LSB                 (1U << 4)       /* 1b */
+#define DIS_SRAM_PDN_LSB                    (1U << 8)       /* 4b */
+#define DIS_SRAM_PDN_ACK_LSB                (1U << 12)      /* 4b */
+/* MFG_CORE1_PWR_CON (0x10006000+0x310) */
+#define MFG_CORE1_PWR_RST_B_LSB             (1U << 0)       /* 1b */
+#define MFG_CORE1_PWR_ISO_LSB               (1U << 1)       /* 1b */
+#define MFG_CORE1_PWR_ON_LSB                (1U << 2)       /* 1b */
+#define MFG_CORE1_PWR_ON_2ND_LSB            (1U << 3)       /* 1b */
+#define MFG_CORE1_PWR_CLK_DIS_LSB           (1U << 4)       /* 1b */
+#define MFG_CORE1_SRAM_PDN_LSB              (1U << 8)       /* 4b */
+#define MFG_CORE1_SRAM_PDN_ACK_LSB          (1U << 12)      /* 4b */
+/* AUDIO_PWR_CON (0x10006000+0x314) */
+#define AUD_PWR_RST_B_LSB                   (1U << 0)       /* 1b */
+#define AUD_PWR_ISO_LSB                     (1U << 1)       /* 1b */
+#define AUD_PWR_ON_LSB                      (1U << 2)       /* 1b */
+#define AUD_PWR_ON_2ND_LSB                  (1U << 3)       /* 1b */
+#define AUD_PWR_CLK_DIS_LSB                 (1U << 4)       /* 1b */
+#define AUD_SRAM_PDN_LSB                    (1U << 8)       /* 4b */
+#define AUD_SRAM_PDN_ACK_LSB                (1U << 12)      /* 4b */
+/* IFR_PWR_CON (0x10006000+0x318) */
+#define IFR_PWR_RST_B_LSB                   (1U << 0)       /* 1b */
+#define IFR_PWR_ISO_LSB                     (1U << 1)       /* 1b */
+#define IFR_PWR_ON_LSB                      (1U << 2)       /* 1b */
+#define IFR_PWR_ON_2ND_LSB                  (1U << 3)       /* 1b */
+#define IFR_PWR_CLK_DIS_LSB                 (1U << 4)       /* 1b */
+#define IFR_SRAM_PDN_LSB                    (1U << 8)       /* 4b */
+#define IFR_SRAM_PDN_ACK_LSB                (1U << 12)      /* 4b */
+/* DPY_PWR_CON (0x10006000+0x31C) */
+#define DPY_PWR_RST_B_LSB                   (1U << 0)       /* 1b */
+#define DPY_PWR_ISO_LSB                     (1U << 1)       /* 1b */
+#define DPY_PWR_ON_LSB                      (1U << 2)       /* 1b */
+#define DPY_PWR_ON_2ND_LSB                  (1U << 3)       /* 1b */
+#define DPY_PWR_CLK_DIS_LSB                 (1U << 4)       /* 1b */
+#define DPY_SRAM_PDN_LSB                    (1U << 8)       /* 4b */
+#define DPY_SRAM_PDN_ACK_LSB                (1U << 12)      /* 4b */
+/* MD1_PWR_CON (0x10006000+0x320) */
+#define MD1_PWR_RST_B_LSB                   (1U << 0)       /* 1b */
+#define MD1_PWR_ISO_LSB                     (1U << 1)       /* 1b */
+#define MD1_PWR_ON_LSB                      (1U << 2)       /* 1b */
+#define MD1_PWR_ON_2ND_LSB                  (1U << 3)       /* 1b */
+#define MD1_PWR_CLK_DIS_LSB                 (1U << 4)       /* 1b */
+#define MD1_SRAM_PDN_LSB                    (1U << 8)       /* 1b */
+/* VPU_TOP_PWR_CON (0x10006000+0x324) */
+#define VPU_TOP_PWR_RST_B_LSB               (1U << 0)       /* 1b */
+#define VPU_TOP_PWR_ISO_LSB                 (1U << 1)       /* 1b */
+#define VPU_TOP_PWR_ON_LSB                  (1U << 2)       /* 1b */
+#define VPU_TOP_PWR_ON_2ND_LSB              (1U << 3)       /* 1b */
+#define VPU_TOP_PWR_CLK_DIS_LSB             (1U << 4)       /* 1b */
+#define VPU_TOP_SRAM_CKISO_LSB              (1U << 5)       /* 1b */
+#define VPU_TOP_SRAM_ISOINT_B_LSB           (1U << 6)       /* 1b */
+#define VPU_TOP_SRAM_PDN_LSB                (1U << 8)       /* 4b */
+#define VPU_TOP_SRAM_PDN_ACK_LSB            (1U << 12)      /* 4b */
+#define VPU_TOP_SRAM_SLPB_LSB               (1U << 16)      /* 4b */
+#define VPU_TOP_SRAM_SLPB_ACK_LSB           (1U << 28)      /* 4b */
+/* CONN_PWR_CON (0x10006000+0x32C) */
+#define CONN_PWR_RST_B_LSB                  (1U << 0)       /* 1b */
+#define CONN_PWR_ISO_LSB                    (1U << 1)       /* 1b */
+#define CONN_PWR_ON_LSB                     (1U << 2)       /* 1b */
+#define CONN_PWR_ON_2ND_LSB                 (1U << 3)       /* 1b */
+#define CONN_PWR_CLK_DIS_LSB                (1U << 4)       /* 1b */
+#define CONN_SRAM_PDN_LSB                   (1U << 8)       /* 1b */
+#define CONN_SRAM_PDN_ACK_LSB               (1U << 12)      /* 1b */
+/* VPU_CORE2_PWR_CON (0x10006000+0x330) */
+#define VPU_CORE2_PWR_RST_B_LSB             (1U << 0)       /* 1b */
+#define VPU_CORE2_PWR_ISO_LSB               (1U << 1)       /* 1b */
+#define VPU_CORE2_PWR_ON_LSB                (1U << 2)       /* 1b */
+#define VPU_CORE2_PWR_ON_2ND_LSB            (1U << 3)       /* 1b */
+#define VPU_CORE2_PWR_CLK_DIS_LSB           (1U << 4)       /* 1b */
+#define VPU_CORE2_SRAM_CKISO_LSB            (1U << 5)       /* 1b */
+#define VPU_CORE2_SRAM_ISOINT_B_LSB         (1U << 6)       /* 1b */
+#define VPU_CORE2_SRAM_PDN_LSB              (1U << 8)       /* 4b */
+#define VPU_CORE2_SRAM_PDN_ACK_LSB          (1U << 12)      /* 4b */
+#define VPU_CORE2_SRAM_SLPB_LSB             (1U << 16)      /* 4b */
+#define VPU_CORE2_SRAM_SLPB_ACK_LSB         (1U << 28)      /* 4b */
+/* MFG_ASYNC_PWR_CON (0x10006000+0x334) */
+#define MFG_ASYNC_PWR_RST_B_LSB             (1U << 0)       /* 1b */
+#define MFG_ASYNC_PWR_ISO_LSB               (1U << 1)       /* 1b */
+#define MFG_ASYNC_PWR_ON_LSB                (1U << 2)       /* 1b */
+#define MFG_ASYNC_PWR_ON_2ND_LSB            (1U << 3)       /* 1b */
+#define MFG_ASYNC_PWR_CLK_DIS_LSB           (1U << 4)       /* 1b */
+#define MFG_ASYNC_SRAM_PDN_LSB              (1U << 8)       /* 4b */
+#define MFG_ASYNC_SRAM_PDN_ACK_LSB          (1U << 12)      /* 4b */
+/* MFG_PWR_CON (0x10006000+0x338) */
+#define MFG_PWR_RST_B_LSB                   (1U << 0)       /* 1b */
+#define MFG_PWR_ISO_LSB                     (1U << 1)       /* 1b */
+#define MFG_PWR_ON_LSB                      (1U << 2)       /* 1b */
+#define MFG_PWR_ON_2ND_LSB                  (1U << 3)       /* 1b */
+#define MFG_PWR_CLK_DIS_LSB                 (1U << 4)       /* 1b */
+#define MFG_SRAM_PDN_LSB                    (1U << 8)       /* 4b */
+#define MFG_SRAM_PDN_ACK_LSB                (1U << 12)      /* 4b */
+/* VPU_CORE0_PWR_CON (0x10006000+0x33C) */
+#define VPU_CORE0_PWR_RST_B_LSB             (1U << 0)       /* 1b */
+#define VPU_CORE0_PWR_ISO_LSB               (1U << 1)       /* 1b */
+#define VPU_CORE0_PWR_ON_LSB                (1U << 2)       /* 1b */
+#define VPU_CORE0_ON_2ND_LSB                (1U << 3)       /* 1b */
+#define VPU_CORE0_CLK_DIS_LSB               (1U << 4)       /* 1b */
+#define VPU_CORE0_SRAM_CKISO_LSB            (1U << 5)       /* 1b */
+#define VPU_CORE0_SRAM_ISOINT_B_LSB         (1U << 6)       /* 1b */
+#define VPU_CORE0_SRAM_PDN_LSB              (1U << 8)       /* 4b */
+#define VPU_CORE0_SRAM_PDN_ACK_LSB          (1U << 12)      /* 4b */
+#define VPU_CORE0_SRAM_SLPB_LSB             (1U << 16)      /* 4b */
+#define VPU_CORE0_SRAM_SLPB_ACK_LSB         (1U << 28)      /* 4b */
+/* VPU_CORE1_PWR_CON (0x10006000+0x340) */
+#define VPU_CORE1_PWR_RST_B_LSB             (1U << 0)       /* 1b */
+#define VPU_CORE1_PWR_ISO_LSB               (1U << 1)       /* 1b */
+#define VPU_CORE1_PWR_ON_LSB                (1U << 2)       /* 1b */
+#define VPU_CORE1_ON_2ND_LSB                (1U << 3)       /* 1b */
+#define VPU_CORE1_CLK_DIS_LSB               (1U << 4)       /* 1b */
+#define VPU_CORE1_SRAM_CKISO_LSB            (1U << 5)       /* 1b */
+#define VPU_CORE1_SRAM_ISOINT_B_LSB         (1U << 6)       /* 1b */
+#define VPU_CORE1_SRAM_PDN_LSB              (1U << 8)       /* 4b */
+#define VPU_CORE1_SRAM_PDN_ACK_LSB          (1U << 12)      /* 4b */
+#define VPU_CORE1_SRAM_SLPB_LSB             (1U << 16)      /* 4b */
+#define VPU_CORE1_SRAM_SLPB_ACK_LSB         (1U << 28)      /* 4b */
+/* CAM_PWR_CON (0x10006000+0x344) */
+#define CAM_PWR_RST_B_LSB                   (1U << 0)       /* 1b */
+#define CAM_PWR_ISO_LSB                     (1U << 1)       /* 1b */
+#define CAM_PWR_ON_LSB                      (1U << 2)       /* 1b */
+#define CAM_PWR_ON_2ND_LSB                  (1U << 3)       /* 1b */
+#define CAM_PWR_CLK_DIS_LSB                 (1U << 4)       /* 1b */
+#define CAM_SRAM_PDN_LSB                    (1U << 8)       /* 4b */
+#define CAM_SRAM_PDN_ACK_LSB                (1U << 12)      /* 4b */
+/* MFG_2D_PWR_CON (0x10006000+0x348) */
+#define MFG_2D_PWR_RST_B_LSB                (1U << 0)       /* 1b */
+#define MFG_2D_PWR_ISO_LSB                  (1U << 1)       /* 1b */
+#define MFG_2D_PWR_ON_LSB                   (1U << 2)       /* 1b */
+#define MFG_2D_PWR_ON_2ND_LSB               (1U << 3)       /* 1b */
+#define MFG_2D_PWR_CLK_DIS_LSB              (1U << 4)       /* 1b */
+#define MFG_2D_SRAM_PDN_LSB                 (1U << 8)       /* 4b */
+#define MFG_2D_SRAM_PDN_ACK_LSB             (1U << 12)      /* 4b */
+/* MFG_CORE0_PWR_CON (0x10006000+0x34C) */
+#define MFG_CORE0_PWR_RST_B_LSB             (1U << 0)       /* 1b */
+#define MFG_CORE0_PWR_ISO_LSB               (1U << 1)       /* 1b */
+#define MFG_CORE0_PWR_ON_LSB                (1U << 2)       /* 1b */
+#define MFG_CORE0_PWR_ON_2ND_LSB            (1U << 3)       /* 1b */
+#define MFG_CORE0_PWR_CLK_DIS_LSB           (1U << 4)       /* 1b */
+#define MFG_CORE0_SRAM_PDN_LSB              (1U << 8)       /* 4b */
+#define MFG_CORE0_SRAM_PDN_ACK_LSB          (1U << 12)      /* 4b */
+/* SYSRAM_CON (0x10006000+0x350) */
+#define IFR_SRAMROM_SRAM_CKISO_LSB          (1U << 0)       /* 1b */
+#define IFR_SRAMROM_SRAM_ISOINT_B_LSB       (1U << 1)       /* 1b */
+#define IFR_SRAMROM_SRAM_SLEEP_B_LSB        (1U << 4)       /* 8b */
+#define IFR_SRAMROM_SRAM_PDN_LSB            (1U << 16)      /* 8b */
+/* SYSROM_CON (0x10006000+0x354) */
+#define IFR_SRAMROM_ROM_PDN_LSB             (1U << 0)       /* 6b */
+/* SSPM_SRAM_CON (0x10006000+0x358) */
+#define SSPM_SRAM_CKISO_LSB                 (1U << 0)       /* 1b */
+#define SSPM_SRAM_ISOINT_B_LSB              (1U << 1)       /* 1b */
+#define SSPM_SRAM_SLEEP_B_LSB               (1U << 4)       /* 1b */
+#define SSPM_SRAM_PDN_LSB                   (1U << 16)      /* 1b */
+/* SCP_SRAM_CON (0x10006000+0x35C) */
+#define SCP_SRAM_CKISO_LSB                  (1U << 0)       /* 1b */
+#define SCP_SRAM_ISOINT_B_LSB               (1U << 1)       /* 1b */
+#define SCP_SRAM_SLEEP_B_LSB                (1U << 4)       /* 1b */
+#define SCP_SRAM_PDN_LSB                    (1U << 16)      /* 1b */
+/* UFS_SRAM_CON (0x10006000+0x36C) */
+#define UFS_SRAM_CKISO_LSB                  (1U << 0)       /* 1b */
+#define UFS_SRAM_ISOINT_B_LSB               (1U << 1)       /* 1b */
+#define UFS_SRAM_SLEEP_B_LSB                (1U << 4)       /* 5b */
+#define UFS_SRAM_PDN_LSB                    (1U << 16)      /* 5b */
+/* DUMMY_SRAM_CON (0x10006000+0x380) */
+#define DUMMY_SRAM_CKISO_LSB                (1U << 0)       /* 1b */
+#define DUMMY_SRAM_ISOINT_B_LSB             (1U << 1)       /* 1b */
+#define DUMMY_SRAM_SLEEP_B_LSB              (1U << 4)       /* 8b */
+#define DUMMY_SRAM_PDN_LSB                  (1U << 16)      /* 8b */
+/* MD_EXT_BUCK_ISO_CON (0x10006000+0x390) */
+#define VMODEM_BUCK_ELS_EN_LSB              (1U << 0)       /* 1b */
+#define VMD_BUCK_ELS_EN_LSB                 (1U << 1)       /* 1b */
+/* MD_SRAM_ISO_CON (0x10006000+0x394) */
+#define MD1_SRAM_ISOINT_B_LSB               (1U << 0)       /* 1b */
+/* MD_EXTRA_PWR_CON (0x10006000+0x398) */
+#define MD1_PWR_PROT_REQ_STA_LSB            (1U << 0)       /* 1b */
+#define MD2_PWR_PROT_REQ_STA_LSB            (1U << 1)       /* 1b */
+/* EXT_BUCK_CON (0x10006000+0x3A0) */
+#define RG_VA09_ON_LSB                      (1U << 0)       /* 1b */
+/* MBIST_EFUSE_REPAIR_ACK_STA (0x10006000+0x3D0) */
+#define MBIST_EFUSE_REPAIR_ACK_STA_LSB      (1U << 0)       /* 32b */
+/* SPM_DVFS_CON (0x10006000+0x400) */
+#define SPM_DVFS_CON_LSB                    (1U << 0)       /* 4b */
+#define SPM_DVFS_ACK_LSB                    (1U << 30)      /* 2b */
+/* SPM_MDBSI_CON (0x10006000+0x404) */
+#define SPM_MDBSI_CON_LSB                   (1U << 0)       /* 3b */
+/* SPM_MAS_PAUSE_MASK_B (0x10006000+0x408) */
+#define SPM_MAS_PAUSE_MASK_B_LSB            (1U << 0)       /* 32b */
+/* SPM_MAS_PAUSE2_MASK_B (0x10006000+0x40C) */
+#define SPM_MAS_PAUSE2_MASK_B_LSB           (1U << 0)       /* 32b */
+/* SPM_BSI_GEN (0x10006000+0x410) */
+#define SPM_BSI_START_LSB                   (1U << 0)       /* 1b */
+/* SPM_BSI_EN_SR (0x10006000+0x414) */
+#define SPM_BSI_EN_SR_LSB                   (1U << 0)       /* 32b */
+/* SPM_BSI_CLK_SR (0x10006000+0x418) */
+#define SPM_BSI_CLK_SR_LSB                  (1U << 0)       /* 32b */
+/* SPM_BSI_D0_SR (0x10006000+0x41C) */
+#define SPM_BSI_D0_SR_LSB                   (1U << 0)       /* 32b */
+/* SPM_BSI_D1_SR (0x10006000+0x420) */
+#define SPM_BSI_D1_SR_LSB                   (1U << 0)       /* 32b */
+/* SPM_BSI_D2_SR (0x10006000+0x424) */
+#define SPM_BSI_D2_SR_LSB                   (1U << 0)       /* 32b */
+/* SPM_AP_SEMA (0x10006000+0x428) */
+#define SPM_AP_SEMA_LSB                     (1U << 0)       /* 1b */
+/* SPM_SPM_SEMA (0x10006000+0x42C) */
+#define SPM_SPM_SEMA_LSB                    (1U << 0)       /* 1b */
+/* AP_MDSRC_REQ (0x10006000+0x430) */
+#define AP_MDSMSRC_REQ_LSB                  (1U << 0)       /* 1b */
+#define AP_L1SMSRC_REQ_LSB                  (1U << 1)       /* 1b */
+#define AP_MD2SRC_REQ_LSB                   (1U << 2)       /* 1b */
+#define AP_MDSMSRC_ACK_LSB                  (1U << 4)       /* 1b */
+#define AP_L1SMSRC_ACK_LSB                  (1U << 5)       /* 1b */
+#define AP_MD2SRC_ACK_LSB                   (1U << 6)       /* 1b */
+/* SPM2MD_DVFS_CON (0x10006000+0x438) */
+#define SPM2MD_DVFS_CON_LSB                 (1U << 0)       /* 32b */
+/* MD2SPM_DVFS_CON (0x10006000+0x43C) */
+#define MD2SPM_DVFS_CON_LSB                 (1U << 0)       /* 32b */
+/* DRAMC_DPY_CLK_SW_CON_RSV (0x10006000+0x440) */
+#define SPM2DRAMC_SHUFFLE_START_LSB         (1U << 0)       /* 1b */
+#define SPM2DRAMC_SHUFFLE_SWITCH_LSB        (1U << 1)       /* 1b */
+#define SPM2DPY_DIV2_SYNC_LSB               (1U << 2)       /* 1b */
+#define SPM2DPY_1PLL_SWITCH_LSB             (1U << 3)       /* 1b */
+#define SPM2DPY_TEST_CK_MUX_LSB             (1U << 4)       /* 1b */
+#define SPM2DPY_ASYNC_MODE_LSB              (1U << 5)       /* 1b */
+#define SPM2TOP_ASYNC_MODE_LSB              (1U << 6)       /* 1b */
+/* DPY_LP_CON (0x10006000+0x444) */
+#define SC_DDRPHY_LP_SIGNALS_LSB            (1U << 0)       /* 3b */
+/* CPU_DVFS_REQ (0x10006000+0x448) */
+#define CPU_DVFS_REQ_LSB                    (1U << 0)       /* 32b */
+/* SPM_PLL_CON (0x10006000+0x44C) */
+#define SC_MAINPLLOUT_OFF_LSB               (1U << 0)       /* 1b */
+#define SC_UNIPLLOUT_OFF_LSB                (1U << 1)       /* 1b */
+#define SC_MAINPLL_OFF_LSB                  (1U << 4)       /* 1b */
+#define SC_UNIPLL_OFF_LSB                   (1U << 5)       /* 1b */
+#define SC_MAINPLL_S_OFF_LSB                (1U << 8)       /* 1b */
+#define SC_UNIPLL_S_OFF_LSB                 (1U << 9)       /* 1b */
+#define SC_SMI_CK_OFF_LSB                   (1U << 16)      /* 1b */
+#define SC_SSPMK_CK_OFF_LSB                 (1U << 17)      /* 1b */
+/* SPM_EMI_BW_MODE (0x10006000+0x450) */
+#define EMI_BW_MODE_LSB                     (1U << 0)       /* 1b */
+#define EMI_BOOST_MODE_LSB                  (1U << 1)       /* 1b */
+#define EMI_BW_MODE_2_LSB                   (1U << 2)       /* 1b */
+#define EMI_BOOST_MODE_2_LSB                (1U << 3)       /* 1b */
+/* AP2MD_PEER_WAKEUP (0x10006000+0x454) */
+#define AP2MD_PEER_WAKEUP_LSB               (1U << 0)       /* 1b */
+/* ULPOSC_CON (0x10006000+0x458) */
+#define ULPOSC_EN_LSB                       (1U << 0)       /* 1b */
+#define ULPOSC_RST_LSB                      (1U << 1)       /* 1b */
+#define ULPOSC_CG_EN_LSB                    (1U << 2)       /* 1b */
+#define ULPOSC_CLK_SEL_LSB                  (1U << 3)       /* 1b */
+/* SPM2MM_CON (0x10006000+0x45C) */
+#define SPM2MM_FORCE_ULTRA_LSB              (1U << 0)       /* 1b */
+#define SPM2MM_DBL_OSTD_ACT_LSB             (1U << 1)       /* 1b */
+#define SPM2MM_ULTRAREQ_LSB                 (1U << 2)       /* 1b */
+#define SPM2MD_ULTRAREQ_LSB                 (1U << 3)       /* 1b */
+#define SPM2ISP_ULTRAREQ_LSB                (1U << 4)       /* 1b */
+#define MM2SPM_FORCE_ULTRA_ACK_LSB          (1U << 16)      /* 1b */
+#define MM2SPM_DBL_OSTD_ACT_ACK_LSB         (1U << 17)      /* 1b */
+#define SPM2ISP_ULTRAACK_D2T_LSB            (1U << 18)      /* 1b */
+#define SPM2MM_ULTRAACK_D2T_LSB             (1U << 19)      /* 1b */
+#define SPM2MD_ULTRAACK_D2T_LSB             (1U << 20)      /* 1b */
+/* DRAMC_DPY_CLK_SW_CON_SEL (0x10006000+0x460) */
+#define SW_DR_GATE_RETRY_EN_SEL_LSB         (1U << 0)       /* 2b */
+#define SW_EMI_CLK_OFF_SEL_LSB              (1U << 2)       /* 2b */
+#define SW_DPY_MODE_SW_SEL_LSB              (1U << 4)       /* 2b */
+#define SW_DMSUS_OFF_SEL_LSB                (1U << 6)       /* 2b */
+#define SW_MEM_CK_OFF_SEL_LSB               (1U << 8)       /* 2b */
+#define SW_DPY_2ND_DLL_EN_SEL_LSB           (1U << 10)      /* 2b */
+#define SW_DPY_DLL_EN_SEL_LSB               (1U << 12)      /* 2b */
+#define SW_DPY_DLL_CK_EN_SEL_LSB            (1U << 14)      /* 2b */
+#define SW_DPY_VREF_EN_SEL_LSB              (1U << 16)      /* 2b */
+#define SW_PHYPLL_EN_SEL_LSB                (1U << 18)      /* 2b */
+#define SW_DDRPHY_FB_CK_EN_SEL_LSB          (1U << 20)      /* 2b */
+#define SEPERATE_PHY_PWR_SEL_LSB            (1U << 23)      /* 1b */
+#define SW_DMDRAMCSHU_ACK_SEL_LSB           (1U << 24)      /* 2b */
+#define SW_EMI_CLK_OFF_ACK_SEL_LSB          (1U << 26)      /* 2b */
+#define SW_DR_SHORT_QUEUE_ACK_SEL_LSB       (1U << 28)      /* 2b */
+#define SW_DRAMC_DFS_STA_SEL_LSB            (1U << 30)      /* 2b */
+/* DRAMC_DPY_CLK_SW_CON (0x10006000+0x464) */
+#define SW_DR_GATE_RETRY_EN_LSB             (1U << 0)       /* 2b */
+#define SW_EMI_CLK_OFF_LSB                  (1U << 2)       /* 2b */
+#define SW_DPY_MODE_SW_LSB                  (1U << 4)       /* 2b */
+#define SW_DMSUS_OFF_LSB                    (1U << 6)       /* 2b */
+#define SW_MEM_CK_OFF_LSB                   (1U << 8)       /* 2b */
+#define SW_DPY_2ND_DLL_EN_LSB               (1U << 10)      /* 2b */
+#define SW_DPY_DLL_EN_LSB                   (1U << 12)      /* 2b */
+#define SW_DPY_DLL_CK_EN_LSB                (1U << 14)      /* 2b */
+#define SW_DPY_VREF_EN_LSB                  (1U << 16)      /* 2b */
+#define SW_PHYPLL_EN_LSB                    (1U << 18)      /* 2b */
+#define SW_DDRPHY_FB_CK_EN_LSB              (1U << 20)      /* 2b */
+#define SC_DR_SHU_EN_ACK_LSB                (1U << 24)      /* 2b */
+#define EMI_CLK_OFF_ACK_LSB                 (1U << 26)      /* 2b */
+#define SC_DR_SHORT_QUEUE_ACK_LSB           (1U << 28)      /* 2b */
+#define SC_DRAMC_DFS_STA_LSB                (1U << 30)      /* 2b */
+/* SPM_S1_MODE_CH (0x10006000+0x468) */
+#define SPM_S1_MODE_CH_LSB                  (1U << 0)       /* 2b */
+#define S1_EMI_CK_SWITCH_LSB                (1U << 8)       /* 2b */
+/* EMI_SELF_REFRESH_CH_STA (0x10006000+0x46C) */
+#define EMI_SELF_REFRESH_CH_LSB             (1U << 0)       /* 2b */
+/* DRAMC_DPY_CLK_SW_CON_SEL2 (0x10006000+0x470) */
+#define SW_PHYPLL_SHU_EN_SEL_LSB            (1U << 0)       /* 1b */
+#define SW_PHYPLL2_SHU_EN_SEL_LSB           (1U << 1)       /* 1b */
+#define SW_PHYPLL_MODE_SW_SEL_LSB           (1U << 2)       /* 1b */
+#define SW_PHYPLL2_MODE_SW_SEL_LSB          (1U << 3)       /* 1b */
+#define SW_DR_SHORT_QUEUE_SEL_LSB           (1U << 4)       /* 1b */
+#define SW_DR_SHU_EN_SEL_LSB                (1U << 5)       /* 1b */
+#define SW_DR_SHU_LEVEL_SEL_LSB             (1U << 6)       /* 1b */
+#define SW_DPY_BCLK_ENABLE_SEL_LSB          (1U << 8)       /* 2b */
+#define SW_SHU_RESTORE_SEL_LSB              (1U << 10)      /* 2b */
+#define SW_DPHY_PRECAL_UP_SEL_LSB           (1U << 12)      /* 2b */
+#define SW_DPHY_RXDLY_TRACK_EN_SEL_LSB      (1U << 14)      /* 2b */
+#define SW_TX_TRACKING_DIS_SEL_LSB          (1U << 16)      /* 2b */
+/* DRAMC_DPY_CLK_SW_CON2 (0x10006000+0x474) */
+#define SW_PHYPLL_SHU_EN_LSB                (1U << 0)       /* 1b */
+#define SW_PHYPLL2_SHU_EN_LSB               (1U << 1)       /* 1b */
+#define SW_PHYPLL_MODE_SW_LSB               (1U << 2)       /* 1b */
+#define SW_PHYPLL2_MODE_SW_LSB              (1U << 3)       /* 1b */
+#define SW_DR_SHORT_QUEUE_LSB               (1U << 4)       /* 1b */
+#define SW_DR_SHU_EN_LSB                    (1U << 5)       /* 1b */
+#define SW_DR_SHU_LEVEL_LSB                 (1U << 6)       /* 2b */
+#define SW_DPY_BCLK_ENABLE_LSB              (1U << 8)       /* 2b */
+#define SW_SHU_RESTORE_LSB                  (1U << 10)      /* 2b */
+#define SW_DPHY_PRECAL_UP_LSB               (1U << 12)      /* 2b */
+#define SW_DPHY_RXDLY_TRACK_EN_LSB          (1U << 14)      /* 2b */
+#define SW_TX_TRACKING_DIS_LSB              (1U << 16)      /* 2b */
+/* DRAMC_DMYRD_CON (0x10006000+0x478) */
+#define DRAMC_DMYRD_EN_CH0_LSB              (1U << 0)       /* 1b */
+#define DRAMC_DMYRD_INTV_SEL_CH0_LSB        (1U << 1)       /* 1b */
+#define DRAMC_DMYRD_EN_MOD_SEL_CH0_LSB      (1U << 2)       /* 1b */
+#define DRAMC_DMYRD_EN_CH1_LSB              (1U << 8)       /* 1b */
+#define DRAMC_DMYRD_INTV_SEL_CH1_LSB        (1U << 9)       /* 1b */
+#define DRAMC_DMYRD_EN_MOD_SEL_CH1_LSB      (1U << 10)      /* 1b */
+/* SPM_DRS_CON (0x10006000+0x47C) */
+#define SPM_DRS_DIS_REQ_CH0_LSB             (1U << 0)       /* 1b */
+#define SPM_DRS_DIS_REQ_CH1_LSB             (1U << 1)       /* 1b */
+#define SPM_DRS_DIS_ACK_CH0_LSB             (1U << 8)       /* 1b */
+#define SPM_DRS_DIS_ACK_CH1_LSB             (1U << 9)       /* 1b */
+/* SPM_SEMA_M0 (0x10006000+0x480) */
+#define SPM_SEMA_M0_LSB                     (1U << 0)       /* 8b */
+/* SPM_SEMA_M1 (0x10006000+0x484) */
+#define SPM_SEMA_M1_LSB                     (1U << 0)       /* 8b */
+/* SPM_SEMA_M2 (0x10006000+0x488) */
+#define SPM_SEMA_M2_LSB                     (1U << 0)       /* 8b */
+/* SPM_SEMA_M3 (0x10006000+0x48C) */
+#define SPM_SEMA_M3_LSB                     (1U << 0)       /* 8b */
+/* SPM_SEMA_M4 (0x10006000+0x490) */
+#define SPM_SEMA_M4_LSB                     (1U << 0)       /* 8b */
+/* SPM_SEMA_M5 (0x10006000+0x494) */
+#define SPM_SEMA_M5_LSB                     (1U << 0)       /* 8b */
+/* SPM_SEMA_M6 (0x10006000+0x498) */
+#define SPM_SEMA_M6_LSB                     (1U << 0)       /* 8b */
+/* SPM_SEMA_M7 (0x10006000+0x49C) */
+#define SPM_SEMA_M7_LSB                     (1U << 0)       /* 8b */
+/* SPM_MAS_PAUSE_MM_MASK_B (0x10006000+0x4A0) */
+#define SPM_MAS_PAUSE_MM_MASK_B_LSB         (1U << 0)       /* 16b */
+/* SPM_MAS_PAUSE_MCU_MASK_B (0x10006000+0x4A4) */
+#define SPM_MAS_PAUSE_MCU_MASK_B_LSB        (1U << 0)       /* 16b */
+/* SRAM_DREQ_ACK (0x10006000+0x4AC) */
+#define SRAM_DREQ_ACK_LSB                   (1U << 0)       /* 16b */
+/* SRAM_DREQ_CON (0x10006000+0x4B0) */
+#define SRAM_DREQ_CON_LSB                   (1U << 0)       /* 16b */
+/* SRAM_DREQ_CON_SET (0x10006000+0x4B4) */
+#define SRAM_DREQ_CON_SET_LSB               (1U << 0)       /* 16b */
+/* SRAM_DREQ_CON_CLR (0x10006000+0x4B8) */
+#define SRAM_DREQ_CON_CLR_LSB               (1U << 0)       /* 16b */
+/* SPM2EMI_ENTER_ULPM (0x10006000+0x4BC) */
+#define SPM2EMI_ENTER_ULPM_LSB              (1U << 0)       /* 1b */
+/* SPM_SSPM_IRQ (0x10006000+0x4C0) */
+#define SPM_SSPM_IRQ_LSB                    (1U << 0)       /* 1b */
+#define SPM_SSPM_IRQ_SEL_LSB                (1U << 4)       /* 1b */
+/* SPM2PMCU_INT (0x10006000+0x4C4) */
+#define SPM2PMCU_INT_LSB                    (1U << 0)       /* 4b */
+/* SPM2PMCU_INT_SET (0x10006000+0x4C8) */
+#define SPM2PMCU_INT_SET_LSB                (1U << 0)       /* 4b */
+/* SPM2PMCU_INT_CLR (0x10006000+0x4CC) */
+#define SPM2PMCU_INT_CLR_LSB                (1U << 0)       /* 4b */
+/* SPM2PMCU_MAILBOX_0 (0x10006000+0x4D0) */
+#define SPM2PMCU_MAILBOX_0_LSB              (1U << 0)       /* 32b */
+/* SPM2PMCU_MAILBOX_1 (0x10006000+0x4D4) */
+#define SPM2PMCU_MAILBOX_1_LSB              (1U << 0)       /* 32b */
+/* SPM2PMCU_MAILBOX_2 (0x10006000+0x4D8) */
+#define SPM2PMCU_MAILBOX_2_LSB              (1U << 0)       /* 32b */
+/* SPM2PMCU_MAILBOX_3 (0x10006000+0x4DC) */
+#define SPM2PMCU_MAILBOX_3_LSB              (1U << 0)       /* 32b */
+/* PMCU2SPM_INT (0x10006000+0x4E0) */
+#define PMCU2SPM_INT_LSB                    (1U << 0)       /* 4b */
+/* PMCU2SPM_INT_SET (0x10006000+0x4E4) */
+#define PMCU2SPM_INT_SET_LSB                (1U << 0)       /* 4b */
+/* PMCU2SPM_INT_CLR (0x10006000+0x4E8) */
+#define PMCU2SPM_INT_CLR_LSB                (1U << 0)       /* 4b */
+/* PMCU2SPM_MAILBOX_0 (0x10006000+0x4EC) */
+#define PMCU2SPM_MAILBOX_0_LSB              (1U << 0)       /* 32b */
+/* PMCU2SPM_MAILBOX_1 (0x10006000+0x4F0) */
+#define PMCU2SPM_MAILBOX_1_LSB              (1U << 0)       /* 32b */
+/* PMCU2SPM_MAILBOX_2 (0x10006000+0x4F4) */
+#define PMCU2SPM_MAILBOX_2_LSB              (1U << 0)       /* 32b */
+/* PMCU2SPM_MAILBOX_3 (0x10006000+0x4F8) */
+#define PMCU2SPM_MAILBOX_3_LSB              (1U << 0)       /* 32b */
+/* PMCU2SPM_CFG (0x10006000+0x4FC) */
+#define PMCU2SPM_INT_MASK_B_LSB             (1U << 0)       /* 4b */
+#define SPM_PMCU_MAILBOX_REQ_LSB            (1U << 8)       /* 1b */
+/* MP0_CPU0_IRQ_MASK (0x10006000+0x500) */
+#define MP0_CPU0_IRQ_MASK_LSB               (1U << 0)       /* 1b */
+#define MP0_CPU0_AUX_LSB                    (1U << 8)       /* 11b */
+/* MP0_CPU1_IRQ_MASK (0x10006000+0x504) */
+#define MP0_CPU1_IRQ_MASK_LSB               (1U << 0)       /* 1b */
+#define MP0_CPU1_AUX_LSB                    (1U << 8)       /* 11b */
+/* MP0_CPU2_IRQ_MASK (0x10006000+0x508) */
+#define MP0_CPU2_IRQ_MASK_LSB               (1U << 0)       /* 1b */
+#define MP0_CPU2_AUX_LSB                    (1U << 8)       /* 11b */
+/* MP0_CPU3_IRQ_MASK (0x10006000+0x50C) */
+#define MP0_CPU3_IRQ_MASK_LSB               (1U << 0)       /* 1b */
+#define MP0_CPU3_AUX_LSB                    (1U << 8)       /* 11b */
+/* MP1_CPU0_IRQ_MASK (0x10006000+0x510) */
+#define MP1_CPU0_IRQ_MASK_LSB               (1U << 0)       /* 1b */
+#define MP1_CPU0_AUX_LSB                    (1U << 8)       /* 11b */
+/* MP1_CPU1_IRQ_MASK (0x10006000+0x514) */
+#define MP1_CPU1_IRQ_MASK_LSB               (1U << 0)       /* 1b */
+#define MP1_CPU1_AUX_LSB                    (1U << 8)       /* 11b */
+/* MP1_CPU2_IRQ_MASK (0x10006000+0x518) */
+#define MP1_CPU2_IRQ_MASK_LSB               (1U << 0)       /* 1b */
+#define MP1_CPU2_AUX_LSB                    (1U << 8)       /* 11b */
+/* MP1_CPU3_IRQ_MASK (0x10006000+0x51C) */
+#define MP1_CPU3_IRQ_MASK_LSB               (1U << 0)       /* 1b */
+#define MP1_CPU3_AUX_LSB                    (1U << 8)       /* 11b */
+/* MP0_CPU0_WFI_EN (0x10006000+0x530) */
+#define MP0_CPU0_WFI_EN_LSB                 (1U << 0)       /* 1b */
+/* MP0_CPU1_WFI_EN (0x10006000+0x534) */
+#define MP0_CPU1_WFI_EN_LSB                 (1U << 0)       /* 1b */
+/* MP0_CPU2_WFI_EN (0x10006000+0x538) */
+#define MP0_CPU2_WFI_EN_LSB                 (1U << 0)       /* 1b */
+/* MP0_CPU3_WFI_EN (0x10006000+0x53C) */
+#define MP0_CPU3_WFI_EN_LSB                 (1U << 0)       /* 1b */
+/* MP1_CPU0_WFI_EN (0x10006000+0x540) */
+#define MP1_CPU0_WFI_EN_LSB                 (1U << 0)       /* 1b */
+/* MP1_CPU1_WFI_EN (0x10006000+0x544) */
+#define MP1_CPU1_WFI_EN_LSB                 (1U << 0)       /* 1b */
+/* MP1_CPU2_WFI_EN (0x10006000+0x548) */
+#define MP1_CPU2_WFI_EN_LSB                 (1U << 0)       /* 1b */
+/* MP1_CPU3_WFI_EN (0x10006000+0x54C) */
+#define MP1_CPU3_WFI_EN_LSB                 (1U << 0)       /* 1b */
+/* MP0_L2CFLUSH (0x10006000+0x554) */
+#define MP0_L2CFLUSH_REQ_LSB                (1U << 0)       /* 1b */
+#define MP0_L2CFLUSH_DONE_LSB               (1U << 4)       /* 1b */
+/* MP1_L2CFLUSH (0x10006000+0x558) */
+#define MP1_L2CFLUSH_REQ_LSB                (1U << 0)       /* 1b */
+#define MP1_L2CFLUSH_DONE_LSB               (1U << 4)       /* 1b */
+/* CPU_PTPOD2_CON (0x10006000+0x560) */
+#define MP0_PTPOD2_FBB_EN_LSB               (1U << 0)       /* 1b */
+#define MP1_PTPOD2_FBB_EN_LSB               (1U << 1)       /* 1b */
+#define MP0_PTPOD2_SPARK_EN_LSB             (1U << 2)       /* 1b */
+#define MP1_PTPOD2_SPARK_EN_LSB             (1U << 3)       /* 1b */
+#define MP0_PTPOD2_FBB_ACK_LSB              (1U << 4)       /* 1b */
+#define MP1_PTPOD2_FBB_ACK_LSB              (1U << 5)       /* 1b */
+/* ROOT_CPUTOP_ADDR (0x10006000+0x570) */
+#define ROOT_CPUTOP_ADDR_LSB                (1U << 0)       /* 32b */
+/* ROOT_CORE_ADDR (0x10006000+0x574) */
+#define ROOT_CORE_ADDR_LSB                  (1U << 0)       /* 32b */
+/* CPU_SPARE_CON (0x10006000+0x580) */
+#define CPU_SPARE_CON_LSB                   (1U << 0)       /* 32b */
+/* CPU_SPARE_CON_SET (0x10006000+0x584) */
+#define CPU_SPARE_CON_SET_LSB               (1U << 0)       /* 32b */
+/* CPU_SPARE_CON_CLR (0x10006000+0x588) */
+#define CPU_SPARE_CON_CLR_LSB               (1U << 0)       /* 32b */
+/* SPM2SW_MAILBOX_0 (0x10006000+0x5D0) */
+#define SPM2SW_MAILBOX_0_LSB                (1U << 0)       /* 32b */
+/* SPM2SW_MAILBOX_1 (0x10006000+0x5D4) */
+#define SPM2SW_MAILBOX_1_LSB                (1U << 0)       /* 32b */
+/* SPM2SW_MAILBOX_2 (0x10006000+0x5D8) */
+#define SPM2SW_MAILBOX_2_LSB                (1U << 0)       /* 32b */
+/* SPM2SW_MAILBOX_3 (0x10006000+0x5DC) */
+#define SPM2SW_MAILBOX_3_LSB                (1U << 0)       /* 32b */
+/* SW2SPM_INT (0x10006000+0x5E0) */
+#define SW2SPM_INT_LSB                      (1U << 0)       /* 4b */
+/* SW2SPM_INT_SET (0x10006000+0x5E4) */
+#define SW2SPM_INT_SET_LSB                  (1U << 0)       /* 4b */
+/* SW2SPM_INT_CLR (0x10006000+0x5E8) */
+#define SW2SPM_INT_CLR_LSB                  (1U << 0)       /* 4b */
+/* SW2SPM_MAILBOX_0 (0x10006000+0x5EC) */
+#define SW2SPM_MAILBOX_0_LSB                (1U << 0)       /* 32b */
+/* SW2SPM_MAILBOX_1 (0x10006000+0x5F0) */
+#define SW2SPM_MAILBOX_1_LSB                (1U << 0)       /* 32b */
+/* SW2SPM_MAILBOX_2 (0x10006000+0x5F4) */
+#define SW2SPM_MAILBOX_2_LSB                (1U << 0)       /* 32b */
+/* SW2SPM_MAILBOX_3 (0x10006000+0x5F8) */
+#define SW2SPM_MAILBOX_3_LSB                (1U << 0)       /* 32b */
+/* SW2SPM_CFG (0x10006000+0x5FC) */
+#define SWU2SPM_INT_MASK_B_LSB              (1U << 0)       /* 4b */
+#define SPM_SW_MAILBOX_REQ_LSB              (1U << 8)       /* 1b */
+/* SPM_SW_FLAG (0x10006000+0x600) */
+#define SPM_SW_FLAG_LSB                     (1U << 0)       /* 32b */
+/* SPM_SW_DEBUG (0x10006000+0x604) */
+#define SPM_SW_DEBUG_LSB                    (1U << 0)       /* 32b */
+/* SPM_SW_RSV_0 (0x10006000+0x608) */
+#define SPM_SW_RSV_0_LSB                    (1U << 0)       /* 32b */
+/* SPM_SW_RSV_1 (0x10006000+0x60C) */
+#define SPM_SW_RSV_1_LSB                    (1U << 0)       /* 32b */
+/* SPM_SW_RSV_2 (0x10006000+0x610) */
+#define SPM_SW_RSV_2_LSB                    (1U << 0)       /* 32b */
+/* SPM_SW_RSV_3 (0x10006000+0x614) */
+#define SPM_SW_RSV_3_LSB                    (1U << 0)       /* 32b */
+/* SPM_SW_RSV_4 (0x10006000+0x618) */
+#define SPM_SW_RSV_4_LSB                    (1U << 0)       /* 32b */
+/* SPM_SW_RSV_5 (0x10006000+0x61C) */
+#define SPM_SW_RSV_5_LSB                    (1U << 0)       /* 32b */
+/* SPM_RSV_CON (0x10006000+0x620) */
+#define SPM_RSV_CON_LSB                     (1U << 0)       /* 16b */
+/* SPM_RSV_STA (0x10006000+0x624) */
+#define SPM_RSV_STA_LSB                     (1U << 0)       /* 16b */
+/* SPM_RSV_CON1 (0x10006000+0x628) */
+#define SPM_RSV_CON1_LSB                    (1U << 0)       /* 16b */
+/* SPM_RSV_STA1 (0x10006000+0x62C) */
+#define SPM_RSV_STA1_LSB                    (1U << 0)       /* 16b */
+/* SPM_PASR_DPD_0 (0x10006000+0x630) */
+#define SPM_PASR_DPD_0_LSB                  (1U << 0)       /* 32b */
+/* SPM_PASR_DPD_1 (0x10006000+0x634) */
+#define SPM_PASR_DPD_1_LSB                  (1U << 0)       /* 32b */
+/* SPM_PASR_DPD_2 (0x10006000+0x638) */
+#define SPM_PASR_DPD_2_LSB                  (1U << 0)       /* 32b */
+/* SPM_PASR_DPD_3 (0x10006000+0x63C) */
+#define SPM_PASR_DPD_3_LSB                  (1U << 0)       /* 32b */
+/* SPM_SPARE_CON (0x10006000+0x640) */
+#define SPM_SPARE_CON_LSB                   (1U << 0)       /* 32b */
+/* SPM_SPARE_CON_SET (0x10006000+0x644) */
+#define SPM_SPARE_CON_SET_LSB               (1U << 0)       /* 32b */
+/* SPM_SPARE_CON_CLR (0x10006000+0x648) */
+#define SPM_SPARE_CON_CLR_LSB               (1U << 0)       /* 32b */
+/* SPM_SW_RSV_6 (0x10006000+0x64C) */
+#define SPM_SW_RSV_6_LSB                    (1U << 0)       /* 32b */
+/* SPM_SW_RSV_7 (0x10006000+0x650) */
+#define SPM_SW_RSV_7_LSB                    (1U << 0)       /* 32b */
+/* SPM_SW_RSV_8 (0x10006000+0x654) */
+#define SPM_SW_RSV_8_LSB                    (1U << 0)       /* 32b */
+/* SPM_SW_RSV_9 (0x10006000+0x658) */
+#define SPM_SW_RSV_9_LSB                    (1U << 0)       /* 32b */
+/* SPM_SW_RSV_10 (0x10006000+0x65C) */
+#define SPM_SW_RSV_10_LSB                   (1U << 0)       /* 32b */
+/* SPM_SW_RSV_18 (0x10006000+0x67C) */
+#define SPM_SW_RSV_18_LSB                   (1U << 0)       /* 32b */
+/* SPM_SW_RSV_19 (0x10006000+0x680) */
+#define SPM_SW_RSV_19_LSB                   (1U << 0)       /* 32b */
+/* DVFSRC_EVENT_MASK_CON (0x10006000+0x690) */
+#define DVFSRC_EVENT_MASK_B_LSB             (1U << 0)       /* 16b */
+#define DVFSRC_EVENT_TRIGGER_MASK_B_LSB     (1U << 16)      /* 1b */
+/* DVFSRC_EVENT_FORCE_ON (0x10006000+0x694) */
+#define DVFSRC_EVENT_FORCE_ON_LSB           (1U << 0)       /* 16b */
+#define DVFSRC_EVENT_TRIGGER_FORCE_ON_LSB   (1U << 16)      /* 1b */
+/* DVFSRC_EVENT_SEL (0x10006000+0x698) */
+#define DVFSRC_EVENT_SEL_LSB                (1U << 0)       /* 16b */
+/* SPM_DVFS_EVENT_STA (0x10006000+0x69C) */
+#define SPM_DVFS_EVENT_STA_LSB              (1U << 0)       /* 32b */
+/* SPM_DVFS_EVENT_STA1 (0x10006000+0x6A0) */
+#define SPM_DVFS_EVENT_STA1_LSB             (1U << 0)       /* 32b */
+/* SPM_DVFS_LEVEL (0x10006000+0x6A4) */
+#define SPM_DVFS_LEVEL_LSB                  (1U << 0)       /* 16b */
+/* DVFS_ABORT_STA (0x10006000+0x6A8) */
+#define RC2SPM_EVENT_ABORT_D2T_LSB          (1U << 0)       /* 16b */
+#define RC2SPM_EVENT_ABORT_MASK_OR_LSB      (1U << 16)      /* 1b */
+/* DVFS_ABORT_OTHERS_MASK (0x10006000+0x6AC) */
+#define DVFS_ABORT_OTHERS_MASK_B_LSB        (1U << 0)       /* 16b */
+/* SPM_DFS_LEVEL (0x10006000+0x6B0) */
+#define SPM_DFS_LEVEL_LSB                   (1U << 0)       /* 4b */
+/* SPM_DVS_LEVEL (0x10006000+0x6B4) */
+#define SPM_VCORE_LEVEL_LSB                 (1U << 0)       /* 8b */
+#define SPM_VSRAM_LEVEL_LSB                 (1U << 8)       /* 8b */
+#define SPM_VMODEM_LEVEL_LSB                (1U << 16)      /* 8b */
+/* SPM_DVFS_MISC (0x10006000+0x6B8) */
+#define MSDC_DVFS_REQUEST_LSB               (1U << 0)       /* 1b */
+#define MSDC_DVFS_LEVEL_LSB                 (1U << 1)       /* 4b */
+#define SDIO_READY_TO_SPM_LSB               (1U << 7)       /* 1b */
+#define MD2AP_CENTRAL_BUCK_GEAR_REQ_D2T_LSB (1U << 8)       /* 1b */
+#define MD2AP_CENTRAL_BUCK_GEAR_RDY_D2T_LSB (1U << 9)       /* 1b */
+/* SPARE_SRC_REQ_MASK (0x10006000+0x6C0) */
+#define SPARE1_DDREN_MASK_B_LSB             (1U << 0)       /* 1b */
+#define SPARE1_APSRC_REQ_MASK_B_LSB         (1U << 1)       /* 1b */
+#define SPARE1_VRF18_REQ_MASK_B_LSB         (1U << 2)       /* 1b */
+#define SPARE1_INFRA_REQ_MASK_B_LSB         (1U << 3)       /* 1b */
+#define SPARE1_SRCCLKENA_MASK_B_LSB         (1U << 4)       /* 1b */
+#define SPARE1_DDREN_2_MASK_B_LSB           (1U << 5)       /* 1b */
+#define SPARE2_DDREN_MASK_B_LSB             (1U << 8)       /* 1b */
+#define SPARE2_APSRC_REQ_MASK_B_LSB         (1U << 9)       /* 1b */
+#define SPARE2_VRF18_REQ_MASK_B_LSB         (1U << 10)      /* 1b */
+#define SPARE2_INFRA_REQ_MASK_B_LSB         (1U << 11)      /* 1b */
+#define SPARE2_SRCCLKENA_MASK_B_LSB         (1U << 12)      /* 1b */
+#define SPARE2_DDREN_2_MASK_B_LSB           (1U << 13)      /* 1b */
+/* SCP_VCORE_LEVEL (0x10006000+0x6C4) */
+#define SCP_VCORE_LEVEL_LSB                 (1U << 0)       /* 8b */
+/* SC_MM_CK_SEL_CON (0x10006000+0x6C8) */
+#define SC_MM_CK_SEL_LSB                    (1U << 0)       /* 4b */
+#define SC_MM_CK_SEL_EN_LSB                 (1U << 4)       /* 1b */
+/* SPARE_ACK_STA (0x10006000+0x6F0) */
+#define SPARE_ACK_SYNC_LSB                  (1U << 0)       /* 32b */
+/* SPARE_ACK_MASK (0x10006000+0x6F4) */
+#define SPARE_ACK_MASK_B_LSB                (1U << 0)       /* 32b */
+/* SPM_DVFS_CON1 (0x10006000+0x700) */
+#define SPM_DVFS_CON1_LSB                   (1U << 0)       /* 32b */
+/* SPM_DVFS_CON1_STA (0x10006000+0x704) */
+#define SPM_DVFS_CON1_STA_LSB               (1U << 0)       /* 32b */
+/* SPM_DVFS_CMD0 (0x10006000+0x710) */
+#define SPM_DVFS_CMD0_LSB                   (1U << 0)       /* 32b */
+/* SPM_DVFS_CMD1 (0x10006000+0x714) */
+#define SPM_DVFS_CMD1_LSB                   (1U << 0)       /* 32b */
+/* SPM_DVFS_CMD2 (0x10006000+0x718) */
+#define SPM_DVFS_CMD2_LSB                   (1U << 0)       /* 32b */
+/* SPM_DVFS_CMD3 (0x10006000+0x71C) */
+#define SPM_DVFS_CMD3_LSB                   (1U << 0)       /* 32b */
+/* SPM_DVFS_CMD4 (0x10006000+0x720) */
+#define SPM_DVFS_CMD4_LSB                   (1U << 0)       /* 32b */
+/* SPM_DVFS_CMD5 (0x10006000+0x724) */
+#define SPM_DVFS_CMD5_LSB                   (1U << 0)       /* 32b */
+/* SPM_DVFS_CMD6 (0x10006000+0x728) */
+#define SPM_DVFS_CMD6_LSB                   (1U << 0)       /* 32b */
+/* SPM_DVFS_CMD7 (0x10006000+0x72C) */
+#define SPM_DVFS_CMD7_LSB                   (1U << 0)       /* 32b */
+/* SPM_DVFS_CMD8 (0x10006000+0x730) */
+#define SPM_DVFS_CMD8_LSB                   (1U << 0)       /* 32b */
+/* SPM_DVFS_CMD9 (0x10006000+0x734) */
+#define SPM_DVFS_CMD9_LSB                   (1U << 0)       /* 32b */
+/* SPM_DVFS_CMD10 (0x10006000+0x738) */
+#define SPM_DVFS_CMD10_LSB                  (1U << 0)       /* 32b */
+/* SPM_DVFS_CMD11 (0x10006000+0x73C) */
+#define SPM_DVFS_CMD11_LSB                  (1U << 0)       /* 32b */
+/* SPM_DVFS_CMD12 (0x10006000+0x740) */
+#define SPM_DVFS_CMD12_LSB                  (1U << 0)       /* 32b */
+/* SPM_DVFS_CMD13 (0x10006000+0x744) */
+#define SPM_DVFS_CMD13_LSB                  (1U << 0)       /* 32b */
+/* SPM_DVFS_CMD14 (0x10006000+0x748) */
+#define SPM_DVFS_CMD14_LSB                  (1U << 0)       /* 32b */
+/* SPM_DVFS_CMD15 (0x10006000+0x74C) */
+#define SPM_DVFS_CMD15_LSB                  (1U << 0)       /* 32b */
+/* WDT_LATCH_SPARE0_FIX (0x10006000+0x780) */
+#define WDT_LATCH_SPARE0_FIX_LSB            (1U << 0)       /* 32b */
+/* WDT_LATCH_SPARE1_FIX (0x10006000+0x784) */
+#define WDT_LATCH_SPARE1_FIX_LSB            (1U << 0)       /* 32b */
+/* WDT_LATCH_SPARE2_FIX (0x10006000+0x788) */
+#define WDT_LATCH_SPARE2_FIX_LSB            (1U << 0)       /* 32b */
+/* WDT_LATCH_SPARE3_FIX (0x10006000+0x78C) */
+#define WDT_LATCH_SPARE3_FIX_LSB            (1U << 0)       /* 32b */
+/* SPARE_ACK_IN_FIX (0x10006000+0x790) */
+#define SPARE_ACK_IN_FIX_LSB                (1U << 0)       /* 32b */
+/* DCHA_LATCH_RSV0_FIX (0x10006000+0x794) */
+#define DCHA_LATCH_RSV0_FIX_LSB             (1U << 0)       /* 32b */
+/* DCHB_LATCH_RSV0_FIX (0x10006000+0x798) */
+#define DCHB_LATCH_RSV0_FIX_LSB             (1U << 0)       /* 32b */
+/* PCM_WDT_LATCH_0 (0x10006000+0x800) */
+#define PCM_WDT_LATCH_0_LSB                 (1U << 0)       /* 32b */
+/* PCM_WDT_LATCH_1 (0x10006000+0x804) */
+#define PCM_WDT_LATCH_1_LSB                 (1U << 0)       /* 32b */
+/* PCM_WDT_LATCH_2 (0x10006000+0x808) */
+#define PCM_WDT_LATCH_2_LSB                 (1U << 0)       /* 32b */
+/* PCM_WDT_LATCH_3 (0x10006000+0x80C) */
+#define PCM_WDT_LATCH_3_LSB                 (1U << 0)       /* 32b */
+/* PCM_WDT_LATCH_4 (0x10006000+0x810) */
+#define PCM_WDT_LATCH_4_LSB                 (1U << 0)       /* 32b */
+/* PCM_WDT_LATCH_5 (0x10006000+0x814) */
+#define PCM_WDT_LATCH_5_LSB                 (1U << 0)       /* 32b */
+/* PCM_WDT_LATCH_6 (0x10006000+0x818) */
+#define PCM_WDT_LATCH_6_LSB                 (1U << 0)       /* 32b */
+/* PCM_WDT_LATCH_7 (0x10006000+0x81C) */
+#define PCM_WDT_LATCH_7_LSB                 (1U << 0)       /* 32b */
+/* PCM_WDT_LATCH_8 (0x10006000+0x820) */
+#define PCM_WDT_LATCH_8_LSB                 (1U << 0)       /* 32b */
+/* PCM_WDT_LATCH_9 (0x10006000+0x824) */
+#define PCM_WDT_LATCH_9_LSB                 (1U << 0)       /* 32b */
+/* WDT_LATCH_SPARE0 (0x10006000+0x828) */
+#define WDT_LATCH_SPARE0_LSB                (1U << 0)       /* 32b */
+/* WDT_LATCH_SPARE1 (0x10006000+0x82C) */
+#define WDT_LATCH_SPARE1_LSB                (1U << 0)       /* 32b */
+/* WDT_LATCH_SPARE2 (0x10006000+0x830) */
+#define WDT_LATCH_SPARE2_LSB                (1U << 0)       /* 32b */
+/* WDT_LATCH_SPARE3 (0x10006000+0x834) */
+#define WDT_LATCH_SPARE3_LSB                (1U << 0)       /* 32b */
+/* PCM_WDT_LATCH_10 (0x10006000+0x838) */
+#define PCM_WDT_LATCH_10_LSB                (1U << 0)       /* 32b */
+/* PCM_WDT_LATCH_11 (0x10006000+0x83C) */
+#define PCM_WDT_LATCH_11_LSB                (1U << 0)       /* 32b */
+/* DCHA_GATING_LATCH_0 (0x10006000+0x840) */
+#define DCHA_GATING_LATCH_0_LSB             (1U << 0)       /* 32b */
+/* DCHA_GATING_LATCH_1 (0x10006000+0x844) */
+#define DCHA_GATING_LATCH_1_LSB             (1U << 0)       /* 32b */
+/* DCHA_GATING_LATCH_2 (0x10006000+0x848) */
+#define DCHA_GATING_LATCH_2_LSB             (1U << 0)       /* 32b */
+/* DCHA_GATING_LATCH_3 (0x10006000+0x84C) */
+#define DCHA_GATING_LATCH_3_LSB             (1U << 0)       /* 32b */
+/* DCHA_GATING_LATCH_4 (0x10006000+0x850) */
+#define DCHA_GATING_LATCH_4_LSB             (1U << 0)       /* 32b */
+/* DCHA_GATING_LATCH_5 (0x10006000+0x854) */
+#define DCHA_GATING_LATCH_5_LSB             (1U << 0)       /* 32b */
+/* DCHA_GATING_LATCH_6 (0x10006000+0x858) */
+#define DCHA_GATING_LATCH_6_LSB             (1U << 0)       /* 32b */
+/* DCHA_GATING_LATCH_7 (0x10006000+0x85C) */
+#define DCHA_GATING_LATCH_7_LSB             (1U << 0)       /* 32b */
+/* DCHB_GATING_LATCH_0 (0x10006000+0x860) */
+#define DCHB_GATING_LATCH_0_LSB             (1U << 0)       /* 32b */
+/* DCHB_GATING_LATCH_1 (0x10006000+0x864) */
+#define DCHB_GATING_LATCH_1_LSB             (1U << 0)       /* 32b */
+/* DCHB_GATING_LATCH_2 (0x10006000+0x868) */
+#define DCHB_GATING_LATCH_2_LSB             (1U << 0)       /* 32b */
+/* DCHB_GATING_LATCH_3 (0x10006000+0x86C) */
+#define DCHB_GATING_LATCH_3_LSB             (1U << 0)       /* 32b */
+/* DCHB_GATING_LATCH_4 (0x10006000+0x870) */
+#define DCHB_GATING_LATCH_4_LSB             (1U << 0)       /* 32b */
+/* DCHB_GATING_LATCH_5 (0x10006000+0x874) */
+#define DCHB_GATING_LATCH_5_LSB             (1U << 0)       /* 32b */
+/* DCHB_GATING_LATCH_6 (0x10006000+0x878) */
+#define DCHB_GATING_LATCH_6_LSB             (1U << 0)       /* 32b */
+/* DCHB_GATING_LATCH_7 (0x10006000+0x87C) */
+#define DCHB_GATING_LATCH_7_LSB             (1U << 0)       /* 32b */
+/* DCHA_LATCH_RSV0 (0x10006000+0x880) */
+#define DCHA_LATCH_RSV0_LSB                 (1U << 0)       /* 32b */
+/* DCHB_LATCH_RSV0 (0x10006000+0x884) */
+#define DCHB_LATCH_RSV0_LSB                 (1U << 0)       /* 32b */
+/* PCM_WDT_LATCH_12 (0x10006000+0x888) */
+#define PCM_WDT_LATCH_12_LSB                (1U << 0)       /* 32b */
+/* PCM_WDT_LATCH_13 (0x10006000+0x88C) */
+#define PCM_WDT_LATCH_13_LSB                (1U << 0)       /* 32b */
+/* SPM_PC_TRACE_CON (0x10006000+0x8C0) */
+#define SPM_PC_TRACE_OFFSET_LSB             (1U << 0)       /* 12b */
+#define SPM_PC_TRACE_HW_EN_LSB              (1U << 16)      /* 1b */
+#define SPM_PC_TRACE_SW_LSB                 (1U << 17)      /* 1b */
+/* SPM_PC_TRACE_G0 (0x10006000+0x8C4) */
+#define SPM_PC_TRACE0_LSB                   (1U << 0)       /* 12b */
+#define SPM_PC_TRACE1_LSB                   (1U << 16)      /* 12b */
+/* SPM_PC_TRACE_G1 (0x10006000+0x8C8) */
+#define SPM_PC_TRACE2_LSB                   (1U << 0)       /* 12b */
+#define SPM_PC_TRACE3_LSB                   (1U << 16)      /* 12b */
+/* SPM_PC_TRACE_G2 (0x10006000+0x8CC) */
+#define SPM_PC_TRACE4_LSB                   (1U << 0)       /* 12b */
+#define SPM_PC_TRACE5_LSB                   (1U << 16)      /* 12b */
+/* SPM_PC_TRACE_G3 (0x10006000+0x8D0) */
+#define SPM_PC_TRACE6_LSB                   (1U << 0)       /* 12b */
+#define SPM_PC_TRACE7_LSB                   (1U << 16)      /* 12b */
+/* SPM_PC_TRACE_G4 (0x10006000+0x8D4) */
+#define SPM_PC_TRACE8_LSB                   (1U << 0)       /* 12b */
+#define SPM_PC_TRACE9_LSB                   (1U << 16)      /* 12b */
+/* SPM_PC_TRACE_G5 (0x10006000+0x8D8) */
+#define SPM_PC_TRACE10_LSB                  (1U << 0)       /* 12b */
+#define SPM_PC_TRACE11_LSB                  (1U << 16)      /* 12b */
+/* SPM_PC_TRACE_G6 (0x10006000+0x8DC) */
+#define SPM_PC_TRACE12_LSB                  (1U << 0)       /* 12b */
+#define SPM_PC_TRACE13_LSB                  (1U << 16)      /* 12b */
+/* SPM_PC_TRACE_G7 (0x10006000+0x8E0) */
+#define SPM_PC_TRACE14_LSB                  (1U << 0)       /* 12b */
+#define SPM_PC_TRACE15_LSB                  (1U << 16)      /* 12b */
+/* SPM_ACK_CHK_CON (0x10006000+0x900) */
+#define SPM_ACK_CHK_SW_EN_LSB               (1U << 0)       /* 1b */
+#define SPM_ACK_CHK_CLR_ALL_LSB             (1U << 1)       /* 1b */
+#define SPM_ACK_CHK_CLR_TIMER_LSB           (1U << 2)       /* 1b */
+#define SPM_ACK_CHK_CLR_IRQ_LSB             (1U << 3)       /* 1b */
+#define SPM_ACK_CHK_STA_EN_LSB              (1U << 4)       /* 1b */
+#define SPM_ACK_CHK_WAKEUP_EN_LSB           (1U << 5)       /* 1b */
+#define SPM_ACK_CHK_WDT_EN_LSB              (1U << 6)       /* 1b */
+#define SPM_ACK_CHK_LOCK_PC_TRACE_EN_LSB    (1U << 7)       /* 1b */
+#define SPM_ACK_CHK_HW_EN_LSB               (1U << 8)       /* 1b */
+#define SPM_ACK_CHK_HW_MODE_LSB             (1U << 9)       /* 3b */
+#define SPM_ACK_CHK_FAIL_LSB                (1U << 15)      /* 1b */
+#define SPM_ACK_CHK_SWINT_EN_LSB            (1U << 16)      /* 16b */
+/* SPM_ACK_CHK_PC (0x10006000+0x904) */
+#define SPM_ACK_CHK_HW_TRIG_PC_VAL_LSB      (1U << 0)       /* 16b */
+#define SPM_ACK_CHK_HW_TARG_PC_VAL_LSB      (1U << 16)      /* 16b */
+/* SPM_ACK_CHK_SEL (0x10006000+0x908) */
+#define SPM_ACK_CHK_HW_TRIG_SIGNAL_SEL_LSB  (1U << 0)       /* 5b */
+#define SPM_ACK_CHK_HW_TRIG_GROUP_SEL_LSB   (1U << 5)       /* 3b */
+#define SPM_ACK_CHK_HW_TARG_SIGNAL_SEL_LSB  (1U << 16)      /* 5b */
+#define SPM_ACK_CHK_HW_TARG_GROUP_SEL_LSB   (1U << 21)      /* 3b */
+/* SPM_ACK_CHK_TIMER (0x10006000+0x90C) */
+#define SPM_ACK_CHK_TIMER_VAL_LSB           (1U << 0)       /* 16b */
+#define SPM_ACK_CHK_TIMER_LSB               (1U << 16)      /* 16b */
+/* SPM_ACK_CHK_STA (0x10006000+0x910) */
+#define SPM_ACK_CHK_STA_LSB                 (1U << 0)       /* 32b */
+/* SPM_ACK_CHK_LATCH (0x10006000+0x914) */
+#define SPM_ACK_CHK_LATCH_LSB               (1U << 0)       /* 32b */
+/* SPM_ACK_CHK_CON2 (0x10006000+0x920) */
+#define SPM_ACK_CHK_SW_EN2_LSB              (1U << 0)       /* 1b */
+#define SPM_ACK_CHK_CLR_ALL2_LSB            (1U << 1)       /* 1b */
+#define SPM_ACK_CHK_CLR_TIMER2_LSB          (1U << 2)       /* 1b */
+#define SPM_ACK_CHK_CLR_IRQ2_LSB            (1U << 3)       /* 1b */
+#define SPM_ACK_CHK_STA_EN2_LSB             (1U << 4)       /* 1b */
+#define SPM_ACK_CHK_WAKEUP_EN2_LSB          (1U << 5)       /* 1b */
+#define SPM_ACK_CHK_WDT_EN2_LSB             (1U << 6)       /* 1b */
+#define SPM_ACK_CHK_LOCK_PC_TRACE_EN2_LSB   (1U << 7)       /* 1b */
+#define SPM_ACK_CHK_HW_EN2_LSB              (1U << 8)       /* 1b */
+#define SPM_ACK_CHK_HW_MODE2_LSB            (1U << 9)       /* 3b */
+#define SPM_ACK_CHK_FAIL2_LSB               (1U << 15)      /* 1b */
+#define SPM_ACK_CHK_SWINT_EN2_LSB           (1U << 16)      /* 16b */
+/* SPM_ACK_CHK_PC2 (0x10006000+0x924) */
+#define SPM_ACK_CHK_HW_TRIG_PC_VAL2_LSB     (1U << 0)       /* 16b */
+#define SPM_ACK_CHK_HW_TARG_PC_VAL2_LSB     (1U << 16)      /* 16b */
+/* SPM_ACK_CHK_SEL2 (0x10006000+0x928) */
+#define SPM_ACK_CHK_HW_TRIG_SIGNAL_SEL2_LSB (1U << 0)       /* 5b */
+#define SPM_ACK_CHK_HW_TRIG_GROUP_SEL2_LSB  (1U << 5)       /* 3b */
+#define SPM_ACK_CHK_HW_TARG_SIGNAL_SEL2_LSB (1U << 16)      /* 5b */
+#define SPM_ACK_CHK_HW_TARG_GROUP_SEL2_LSB  (1U << 21)      /* 3b */
+/* SPM_ACK_CHK_TIMER2 (0x10006000+0x92C) */
+#define SPM_ACK_CHK_TIMER_VAL2_LSB          (1U << 0)       /* 16b */
+#define SPM_ACK_CHK_TIMER2_LSB              (1U << 16)      /* 16b */
+/* SPM_ACK_CHK_STA2 (0x10006000+0x930) */
+#define SPM_ACK_CHK_STA2_LSB                (1U << 0)       /* 32b */
+/* SPM_ACK_CHK_LATCH2 (0x10006000+0x934) */
+#define SPM_ACK_CHK_LATCH2_LSB              (1U << 0)       /* 32b */
+/* SPM_ACK_CHK_CON3 (0x10006000+0x940) */
+#define SPM_ACK_CHK_SW_EN3_LSB              (1U << 0)       /* 1b */
+#define SPM_ACK_CHK_CLR_ALL3_LSB            (1U << 1)       /* 1b */
+#define SPM_ACK_CHK_CLR_TIMER3_LSB          (1U << 2)       /* 1b */
+#define SPM_ACK_CHK_CLR_IRQ3_LSB            (1U << 3)       /* 1b */
+#define SPM_ACK_CHK_STA_EN3_LSB             (1U << 4)       /* 1b */
+#define SPM_ACK_CHK_WAKEUP_EN3_LSB          (1U << 5)       /* 1b */
+#define SPM_ACK_CHK_WDT_EN3_LSB             (1U << 6)       /* 1b */
+#define SPM_ACK_CHK_LOCK_PC_TRACE_EN3_LSB   (1U << 7)       /* 1b */
+#define SPM_ACK_CHK_HW_EN3_LSB              (1U << 8)       /* 1b */
+#define SPM_ACK_CHK_HW_MODE3_LSB            (1U << 9)       /* 3b */
+#define SPM_ACK_CHK_FAIL3_LSB               (1U << 15)      /* 1b */
+#define SPM_ACK_CHK_SWINT_EN3_LSB           (1U << 16)      /* 16b */
+/* SPM_ACK_CHK_PC3 (0x10006000+0x944) */
+#define SPM_ACK_CHK_HW_TRIG_PC_VAL3_LSB     (1U << 0)       /* 16b */
+#define SPM_ACK_CHK_HW_TARG_PC_VAL3_LSB     (1U << 16)      /* 16b */
+/* SPM_ACK_CHK_SEL3 (0x10006000+0x948) */
+#define SPM_ACK_CHK_HW_TRIG_SIGNAL_SEL3_LSB (1U << 0)       /* 5b */
+#define SPM_ACK_CHK_HW_TRIG_GROUP_SEL3_LSB  (1U << 5)       /* 3b */
+#define SPM_ACK_CHK_HW_TARG_SIGNAL_SEL3_LSB (1U << 16)      /* 5b */
+#define SPM_ACK_CHK_HW_TARG_GROUP_SEL3_LSB  (1U << 21)      /* 3b */
+/* SPM_ACK_CHK_TIMER3 (0x10006000+0x94C) */
+#define SPM_ACK_CHK_TIMER_VAL3_LSB          (1U << 0)       /* 16b */
+#define SPM_ACK_CHK_TIMER3_LSB              (1U << 16)      /* 16b */
+/* SPM_ACK_CHK_STA3 (0x10006000+0x950) */
+#define SPM_ACK_CHK_STA3_LSB                (1U << 0)       /* 32b */
+/* SPM_ACK_CHK_LATCH3 (0x10006000+0x954) */
+#define SPM_ACK_CHK_LATCH3_LSB              (1U << 0)       /* 32b */
+/* SPM_ACK_CHK_CON4 (0x10006000+0x960) */
+#define SPM_ACK_CHK_SW_EN4_LSB              (1U << 0)       /* 1b */
+#define SPM_ACK_CHK_CLR_ALL4_LSB            (1U << 1)       /* 1b */
+#define SPM_ACK_CHK_CLR_TIMER4_LSB          (1U << 2)       /* 1b */
+#define SPM_ACK_CHK_CLR_IRQ4_LSB            (1U << 3)       /* 1b */
+#define SPM_ACK_CHK_STA_EN4_LSB             (1U << 4)       /* 1b */
+#define SPM_ACK_CHK_WAKEUP_EN4_LSB          (1U << 5)       /* 1b */
+#define SPM_ACK_CHK_WDT_EN4_LSB             (1U << 6)       /* 1b */
+#define SPM_ACK_CHK_LOCK_PC_TRACE_EN4_LSB   (1U << 7)       /* 1b */
+#define SPM_ACK_CHK_HW_EN4_LSB              (1U << 8)       /* 1b */
+#define SPM_ACK_CHK_HW_MODE4_LSB            (1U << 9)       /* 3b */
+#define SPM_ACK_CHK_FAIL4_LSB               (1U << 15)      /* 1b */
+#define SPM_ACK_CHK_SWINT_EN4_LSB           (1U << 16)      /* 16b */
+/* SPM_ACK_CHK_PC4 (0x10006000+0x964) */
+#define SPM_ACK_CHK_HW_TRIG_PC_VAL4_LSB     (1U << 0)       /* 16b */
+#define SPM_ACK_CHK_HW_TARG_PC_VAL4_LSB     (1U << 16)      /* 16b */
+/* SPM_ACK_CHK_SEL4 (0x10006000+0x968) */
+#define SPM_ACK_CHK_HW_TRIG_SIGNAL_SEL4_LSB (1U << 0)       /* 5b */
+#define SPM_ACK_CHK_HW_TRIG_GROUP_SEL4_LSB  (1U << 5)       /* 3b */
+#define SPM_ACK_CHK_HW_TARG_SIGNAL_SEL4_LSB (1U << 16)      /* 5b */
+#define SPM_ACK_CHK_HW_TARG_GROUP_SEL4_LSB  (1U << 21)      /* 3b */
+/* SPM_ACK_CHK_TIMER4 (0x10006000+0x96C) */
+#define SPM_ACK_CHK_TIMER_VAL4_LSB          (1U << 0)       /* 16b */
+#define SPM_ACK_CHK_TIMER4_LSB              (1U << 16)      /* 16b */
+/* SPM_ACK_CHK_STA4 (0x10006000+0x970) */
+#define SPM_ACK_CHK_STA4_LSB                (1U << 0)       /* 32b */
+/* SPM_ACK_CHK_LATCH4 (0x10006000+0x974) */
+#define SPM_ACK_CHK_LATCH4_LSB              (1U << 0)       /* 32b */
+
+/* --- SPM Flag Define --- */
+#define SPM_FLAG_DIS_CPU_PDN                  (1U << 0)
+#define SPM_FLAG_DIS_INFRA_PDN                (1U << 1)
+#define SPM_FLAG_DIS_DDRPHY_PDN               (1U << 2)
+#define SPM_FLAG_DIS_VCORE_DVS                (1U << 3)
+#define SPM_FLAG_DIS_VCORE_DFS                (1U << 4)
+#define SPM_FLAG_DIS_COMMON_SCENARIO          (1U << 5)
+#define SPM_FLAG_DIS_BUS_CLOCK_OFF            (1U << 6)
+#define SPM_FLAG_DIS_ATF_ABORT                (1U << 7)
+#define SPM_FLAG_KEEP_CSYSPWRUPACK_HIGH       (1U << 8)
+#define SPM_FLAG_DIS_VPROC_VSRAM_DVS          (1U << 9)
+#define SPM_FLAG_RUN_COMMON_SCENARIO          (1U << 10)
+#define SPM_FLAG_EN_MET_DEBUG_USAGE           (1U << 11)
+#define SPM_FLAG_SODI_CG_MODE                 (1U << 12)
+#define SPM_FLAG_SODI_NO_EVENT                (1U << 13)
+#define SPM_FLAG_ENABLE_SODI3                 (1U << 14)
+#define SPM_FLAG_DISABLE_MMSYS_DVFS           (1U << 15)
+#define SPM_FLAG_DIS_SYSRAM_SLEEP             (1U << 16)
+#define SPM_FLAG_DIS_SSPM_SRAM_SLEEP          (1U << 17)
+#define SPM_FLAG_DIS_VMODEM_DVS               (1U << 18)
+#define SPM_FLAG_SUSPEND_OPTION               (1U << 19)
+#define SPM_FLAG_DEEPIDLE_OPTION              (1U << 20)
+#define SPM_FLAG_SODI_OPTION                  (1U << 21)
+#define SPM_FLAG_SPM_FLAG_DONT_TOUCH_BIT22    (1U << 22)
+#define SPM_FLAG_SPM_FLAG_DONT_TOUCH_BIT23    (1U << 23)
+#define SPM_FLAG_SPM_FLAG_DONT_TOUCH_BIT24    (1U << 24)
+#define SPM_FLAG_SPM_FLAG_DONT_TOUCH_BIT25    (1U << 25)
+#define SPM_FLAG_SPM_FLAG_DONT_TOUCH_BIT26    (1U << 26)
+#define SPM_FLAG_SPM_FLAG_DONT_TOUCH_BIT27    (1U << 27)
+#define SPM_FLAG_SPM_FLAG_DONT_TOUCH_BIT28    (1U << 28)
+#define SPM_FLAG_SPM_FLAG_DONT_TOUCH_BIT29    (1U << 29)
+#define SPM_FLAG_SPM_FLAG_DONT_TOUCH_BIT30    (1U << 30)
+#define SPM_FLAG_SPM_FLAG_DONT_TOUCH_BIT31    (1U << 31)
+
+/* --- SPM Flag1 Define --- */
+#define SPM_FLAG1_RESERVED_BIT0               (1U << 0)
+#define SPM_FLAG1_ENABLE_CPU_DORMANT          (1U << 1)
+#define SPM_FLAG1_ENABLE_CPU_SLEEP_VOLT       (1U << 2)
+#define SPM_FLAG1_DISABLE_PWRAP_CLK_SWITCH    (1U << 3)
+#define SPM_FLAG1_DISABLE_ULPOSC_OFF          (1U << 4)
+#define SPM_FLAG1_VCORE_LP_0P7V               (1U << 5)
+#define SPM_FLAG1_DISABLE_MCDSR               (1U << 6)
+#define SPM_FLAG1_DISABLE_NO_RESUME           (1U << 7)
+#define SPM_FLAG1_BIG_BUCK_OFF_ENABLE         (1U << 8)
+#define SPM_FLAG1_BIG_BUCK_ON_ENABLE          (1U << 9)
+#define SPM_FLAG1_RESERVED_BIT10              (1U << 10)
+#define SPM_FLAG1_RESERVED_BIT11              (1U << 11)
+#define SPM_FLAG1_RESERVED_BIT12              (1U << 12)
+#define SPM_FLAG1_RESERVED_BIT13              (1U << 13)
+#define SPM_FLAG1_RESERVED_BIT14              (1U << 14)
+#define SPM_FLAG1_DIS_ARMPLL_OFF              (1U << 15)
+#define SPM_FLAG1_DIS_AXI_BUS_TO_26M          (1U << 16)
+#define SPM_FLAG1_DIS_IMP_DIS                 (1U << 17)
+#define SPM_FLAG1_DIS_IMP_COPY                (1U << 18)
+#define SPM_FLAG1_DIS_EMI_TOGGLE_WORKAROUND   (1U << 19)
+#define SPM_FLAG1_DIS_DRAM_ENTER_SREF         (1U << 20)
+#define SPM_FLAG1_DIS_DRAM_DLL_OFF            (1U << 21)
+#define SPM_FLAG1_DIS_PHYPLL_OFF              (1U << 22)
+#define SPM_FLAG1_DIS_MPLL_OFF                (1U << 23)
+#define SPM_FLAG1_DIS_SYSPLL_OFF              (1U << 24)
+#define SPM_FLAG1_DIS_TOP_AXI_CLK_OFF         (1U << 25)
+#define SPM_FLAG1_DIS_PCM_26M_SWITCH          (1U << 26)
+#define SPM_FLAG1_DIS_CKSQ_OFF                (1U << 27)
+#define SPM_FLAG1_DIS_SRCVOLTEN_OFF           (1U << 28)
+#define SPM_FLAG1_DIS_CHB_CG_FREE_EN          (1U << 29)
+#define SPM_FLAG1_DIS_CHA_DCM_RES             (1U << 30)
+#define SPM_FLAG1_DIS_SW_MR4                  (1U << 31)
+
+/* --- SPM DEBUG Define --- */
+#define SPM_DBG_DEBUG_IDX_26M_WAKE            (1U << 0)
+#define SPM_DBG_DEBUG_IDX_26M_SLEEP           (1U << 1)
+#define SPM_DBG_DEBUG_IDX_INFRA_WAKE          (1U << 2)
+#define SPM_DBG_DEBUG_IDX_INFRA_SLEEP         (1U << 3)
+#define SPM_DBG_DEBUG_IDX_APSRC_WAKE          (1U << 4)
+#define SPM_DBG_DEBUG_IDX_APSRC_SLEEP         (1U << 5)
+#define SPM_DBG_DEBUG_IDX_VRF18_WAKE          (1U << 6)
+#define SPM_DBG_DEBUG_IDX_VRF18_SLEEP         (1U << 7)
+#define SPM_DBG_DEBUG_IDX_DDREN_WAKE          (1U << 8)
+#define SPM_DBG_DEBUG_IDX_DDREN_SLEEP         (1U << 9)
+#define SPM_DBG_DEBUG_IDX_NFC_CKBUF_ON        (1U << 10)
+#define SPM_DBG_DEBUG_IDX_NFC_CKBUF_OFF       (1U << 11)
+#define SPM_DBG_DEBUG_IDX_CPU_PDN             (1U << 12)
+#define SPM_DBG_DEBUG_IDX_DPD                 (1U << 13)
+#define SPM_DBG_DEBUG_IDX_CONN_CKBUF_ON       (1U << 14)
+#define SPM_DBG_DEBUG_IDX_CONN_CKBUF_OFF      (1U << 15)
+#define SPM_DBG_DEBUG_IDX_VCORE_DVFS_START    (1U << 16)
+#define SPM_DBG_DEBUG_IDX_DDREN2_WAKE         (1U << 17)
+#define SPM_DBG_DEBUG_IDX_DDREN2_SLEEP        (1U << 18)
+#define SPM_DBG_DEBUG_IDX_SSPM_WFI            (1U << 19)
+#define SPM_DBG_DEBUG_IDX_SSPM_SRAM_SLP       (1U << 20)
+#define SPM_DBG_RESERVED_BIT21                (1U << 21)
+#define SPM_DBG_RESERVED_BIT22                (1U << 22)
+#define SPM_DBG_RESERVED_BIT23                (1U << 23)
+#define SPM_DBG_RESERVED_BIT24                (1U << 24)
+#define SPM_DBG_RESERVED_BIT25                (1U << 25)
+#define SPM_DBG_RESERVED_BIT26                (1U << 26)
+#define SPM_DBG_SODI1_FLAG                    (1U << 27)
+#define SPM_DBG_SODI3_FLAG                    (1U << 28)
+#define SPM_DBG_VCORE_DVFS_FLAG               (1U << 29)
+#define SPM_DBG_DEEPIDLE_FLAG                 (1U << 30)
+#define SPM_DBG_SUSPEND_FLAG                  (1U << 31)
+
+/* --- SPM DEBUG1 Define --- */
+#define SPM_DBG1_DRAM_SREF_ACK_TO             (1U << 0)
+#define SPM_DBG1_PWRAP_SLEEP_ACK_TO           (1U << 1)
+#define SPM_DBG1_PWRAP_SPI_ACK_TO             (1U << 2)
+#define SPM_DBG1_DRAM_GATE_ERR_DDREN_WAKEUP   (1U << 3)
+#define SPM_DBG1_DRAM_GATE_ERR_LEAVE_LP_SCN   (1U << 4)
+#define SPM_DBG1_RESERVED_BIT5                (1U << 5)
+#define SPM_DBG1_RESERVED_BIT6                (1U << 6)
+#define SPM_DBG1_RESERVED_BIT7                (1U << 7)
+#define SPM_DBG1_RESERVED_BIT8                (1U << 8)
+#define SPM_DBG1_RESERVED_BIT9                (1U << 9)
+#define SPM_DBG1_RESERVED_BIT10               (1U << 10)
+#define SPM_DBG1_RESERVED_BIT11               (1U << 11)
+#define SPM_DBG1_RESERVED_BIT12               (1U << 12)
+#define SPM_DBG1_RESERVED_BIT13               (1U << 13)
+#define SPM_DBG1_RESERVED_BIT14               (1U << 14)
+#define SPM_DBG1_RESERVED_BIT15               (1U << 15)
+#define SPM_DBG1_RESERVED_BIT16               (1U << 16)
+#define SPM_DBG1_RESERVED_BIT17               (1U << 17)
+#define SPM_DBG1_RESERVED_BIT18               (1U << 18)
+#define SPM_DBG1_RESERVED_BIT19               (1U << 19)
+#define SPM_DBG1_RESERVED_BIT20               (1U << 20)
+#define SPM_DBG1_RESERVED_BIT21               (1U << 21)
+#define SPM_DBG1_RESERVED_BIT22               (1U << 22)
+#define SPM_DBG1_RESERVED_BIT23               (1U << 23)
+#define SPM_DBG1_RESERVED_BIT24               (1U << 24)
+#define SPM_DBG1_RESERVED_BIT25               (1U << 25)
+#define SPM_DBG1_RESERVED_BIT26               (1U << 26)
+#define SPM_DBG1_RESERVED_BIT27               (1U << 27)
+#define SPM_DBG1_RESERVED_BIT28               (1U << 28)
+#define SPM_DBG1_RESERVED_BIT29               (1U << 29)
+#define SPM_DBG1_RESERVED_BIT30               (1U << 30)
+#define SPM_DBG1_RESERVED_BIT31               (1U << 31)
+
+/* --- R0 Define --- */
+#define R0_SC_26M_CK_OFF                      (1U << 0)
+#define R0_BIT1                               (1U << 1)
+#define R0_SC_MEM_CK_OFF                      (1U << 2)
+#define R0_SC_AXI_CK_OFF                      (1U << 3)
+#define R0_SC_DR_GATE_RETRY_EN_PCM            (1U << 4)
+#define R0_SC_MD26M_CK_OFF                    (1U << 5)
+#define R0_SC_DPY_MODE_SW_PCM                 (1U << 6)
+#define R0_SC_DMSUS_OFF_PCM                   (1U << 7)
+#define R0_SC_DPY_2ND_DLL_EN_PCM              (1U << 8)
+#define R0_BIT9                               (1U << 9)
+#define R0_SC_MPLLOUT_OFF                     (1U << 10)
+#define R0_SC_TX_TRACKING_DIS                 (1U << 11)
+#define R0_SC_DPY_DLL_EN_PCM                  (1U << 12)
+#define R0_SC_DPY_DLL_CK_EN_PCM               (1U << 13)
+#define R0_SC_DPY_VREF_EN_PCM                 (1U << 14)
+#define R0_SC_PHYPLL_EN_PCM                   (1U << 15)
+#define R0_SC_DDRPHY_FB_CK_EN_PCM             (1U << 16)
+#define R0_SC_DPY_BCLK_ENABLE                 (1U << 17)
+#define R0_SC_MPLL_OFF                        (1U << 18)
+#define R0_SC_SHU_RESTORE                     (1U << 19)
+#define R0_SC_CKSQ0_OFF                       (1U << 20)
+#define R0_SC_CKSQ1_OFF                       (1U << 21)
+#define R0_SC_DR_SHU_EN_PCM                   (1U << 22)
+#define R0_SC_DPHY_PRECAL_UP                  (1U << 23)
+#define R0_SC_MPLL_S_OFF                      (1U << 24)
+#define R0_SC_DPHY_RXDLY_TRACK_EN             (1U << 25)
+#define R0_SC_PHYPLL_SHU_EN_PCM               (1U << 26)
+#define R0_SC_PHYPLL2_SHU_EN_PCM              (1U << 27)
+#define R0_SC_PHYPLL_MODE_SW_PCM              (1U << 28)
+#define R0_SC_PHYPLL2_MODE_SW_PCM             (1U << 29)
+#define R0_SC_DR_SHU_LEVEL_PCM0               (1U << 30)
+#define R0_SC_DR_SHU_LEVEL_PCM1               (1U << 31)
+
+/* --- R7 Define --- */
+#define R7_PWRAP_SLEEP_REQ                    (1U << 0)
+#define R7_EMI_CLK_OFF_REQ                    (1U << 1)
+#define R7_TOP_MAS_PAU_REQ                    (1U << 2)
+#define R7_SPM2CKSYS_MEM_CK_MUX_UPDATE        (1U << 3)
+#define R7_PCM_CK_SEL0                        (1U << 4)
+#define R7_PCM_CK_SEL1                        (1U << 5)
+#define R7_SPM2RC_DVS_DONE                    (1U << 6)
+#define R7_FREQH_PAUSE_MPLL                   (1U << 7)
+#define R7_SC_26M_CK_SEL                      (1U << 8)
+#define R7_PCM_TIMER_SET                      (1U << 9)
+#define R7_PCM_TIMER_CLR                      (1U << 10)
+#define R7_SRCVOLTEN                          (1U << 11)
+#define R7_CSYSPWRUPACK                       (1U << 12)
+#define R7_IM_SLEEP_ENABLE                    (1U << 13)
+#define R7_SRCCLKENO_0                        (1U << 14)
+#define R7_SYSRST                             (1U << 15)
+#define R7_MD_APSRC_ACK                       (1U << 16)
+#define R7_CPU_SYS_TIMER_CLK_SEL              (1U << 17)
+#define R7_SC_AXI_DCM_DIS                     (1U << 18)
+#define R7_FREQH_PAUSE_MAIN                   (1U << 19)
+#define R7_FREQH_PAUSE_MEM                    (1U << 20)
+#define R7_SRCCLKENO_1                        (1U << 21)
+#define R7_WDT_KICK_P                         (1U << 22)
+#define R7_SPM2RC_EVENT_ABORT_ACK             (1U << 23)
+#define R7_WAKEUP_EXT_W_SEL                   (1U << 24)
+#define R7_WAKEUP_EXT_R_SEL                   (1U << 25)
+#define R7_PMIC_IRQ_REQ_EN                    (1U << 26)
+#define R7_FORCE_26M_WAKE                     (1U << 27)
+#define R7_FORCE_APSRC_WAKE                   (1U << 28)
+#define R7_FORCE_INFRA_WAKE                   (1U << 29)
+#define R7_FORCE_VRF18_WAKE                   (1U << 30)
+#define R7_SC_DR_SHORT_QUEUE_PCM              (1U << 31)
+
+/* --- R12 Define --- */
+#define R12_PCM_TIMER                         (1U << 0)
+#define R12_SSPM_WDT_EVENT_B                  (1U << 1)
+#define R12_KP_IRQ_B                          (1U << 2)
+#define R12_APWDT_EVENT_B                     (1U << 3)
+#define R12_APXGPT1_EVENT_B                   (1U << 4)
+#define R12_CONN2AP_SPM_WAKEUP_B              (1U << 5)
+#define R12_EINT_EVENT_B                      (1U << 6)
+#define R12_CONN_WDT_IRQ_B                    (1U << 7)
+#define R12_CCIF0_EVENT_B                     (1U << 8)
+#define R12_LOWBATTERY_IRQ_B                  (1U << 9)
+#define R12_SSPM_SPM_IRQ_B                    (1U << 10)
+#define R12_SCP_SPM_IRQ_B                     (1U << 11)
+#define R12_SCP_WDT_EVENT_B                   (1U << 12)
+#define R12_PCM_WDT_WAKEUP_B                  (1U << 13)
+#define R12_USB_CDSC_B                        (1U << 14)
+#define R12_USB_POWERDWN_B                    (1U << 15)
+#define R12_SYS_TIMER_EVENT_B                 (1U << 16)
+#define R12_EINT_EVENT_SECURE_B               (1U << 17)
+#define R12_CCIF1_EVENT_B                     (1U << 18)
+#define R12_UART0_IRQ_B                       (1U << 19)
+#define R12_AFE_IRQ_MCU_B                     (1U << 20)
+#define R12_THERM_CTRL_EVENT_B                (1U << 21)
+#define R12_SYS_CIRQ_IRQ_B                    (1U << 22)
+#define R12_MD2AP_PEER_EVENT_B                (1U << 23)
+#define R12_CSYSPWREQ_B                       (1U << 24)
+#define R12_MD1_WDT_B                         (1U << 25)
+#define R12_CLDMA_EVENT_B                     (1U << 26)
+#define R12_SEJ_WDT_GPT_B                     (1U << 27)
+#define R12_ALL_SSPM_WAKEUP_B                 (1U << 28)
+#define R12_CPU_IRQ_B                         (1U << 29)
+#define R12_CPU_WFI_AND_B                     (1U << 30)
+#define R12_MCUSYS_IDLE_TO_EMI_ALL_B          (1U << 31)
+
+/* --- R12ext Define --- */
+#define R12EXT_26M_WAKE                       (1U << 0)
+#define R12EXT_26M_SLEEP                      (1U << 1)
+#define R12EXT_INFRA_WAKE                     (1U << 2)
+#define R12EXT_INFRA_SLEEP                    (1U << 3)
+#define R12EXT_APSRC_WAKE                     (1U << 4)
+#define R12EXT_APSRC_SLEEP                    (1U << 5)
+#define R12EXT_VRF18_WAKE                     (1U << 6)
+#define R12EXT_VRF18_SLEEP                    (1U << 7)
+#define R12EXT_DVFS_ALL_STATE                 (1U << 8)
+#define R12EXT_DVFS_LEVEL_STATE0              (1U << 9)
+#define R12EXT_DVFS_LEVEL_STATE1              (1U << 10)
+#define R12EXT_DVFS_LEVEL_STATE2              (1U << 11)
+#define R12EXT_DDREN_WAKE                     (1U << 12)
+#define R12EXT_DDREN_SLEEP                    (1U << 13)
+#define R12EXT_NFC_CLK_BUF_WAKE               (1U << 14)
+#define R12EXT_NFC_CLK_BUF_SLEEP              (1U << 15)
+#define R12EXT_CONN_CLK_BUF_WAKE              (1U << 16)
+#define R12EXT_CONN_CLK_BUF_SLEEP             (1U << 17)
+#define R12EXT_MD_DVFS_ERROR_STATUS           (1U << 18)
+#define R12EXT_DVFS_LEVEL_STATE3              (1U << 19)
+#define R12EXT_DVFS_LEVEL_STATE4              (1U << 20)
+#define R12EXT_DVFS_LEVEL_STATE5              (1U << 21)
+#define R12EXT_DVFS_LEVEL_STATE6              (1U << 22)
+#define R12EXT_DVFS_LEVEL_STATE7              (1U << 23)
+#define R12EXT_DVFS_LEVEL_STATE8              (1U << 24)
+#define R12EXT_DVFS_LEVEL_STATE9              (1U << 25)
+#define R12EXT_DVFS_LEVEL_STATE_G0            (1U << 26)
+#define R12EXT_DVFS_LEVEL_STATE_G1            (1U << 27)
+#define R12EXT_DVFS_LEVEL_STATE_G2            (1U << 28)
+#define R12EXT_DVFS_LEVEL_STATE_G3            (1U << 29)
+#define R12EXT_HYBRID_DDREN_SLEEP             (1U << 30)
+#define R12EXT_HYBRID_DDREN_WAKE              (1U << 31)
+
+/* --- R13 Define --- */
+#define R13_EXT_SRCCLKENI_0                   (1U << 0)
+#define R13_EXT_SRCCLKENI_1                   (1U << 1)
+#define R13_MD1_SRCCLKENA                     (1U << 2)
+#define R13_MD1_APSRC_REQ                     (1U << 3)
+#define R13_CONN_DDR_EN                       (1U << 4)
+#define R13_MD2_SRCCLKENA                     (1U << 5)
+#define R13_SSPM_SRCCLKENA                    (1U << 6)
+#define R13_SSPM_APSRC_REQ                    (1U << 7)
+#define R13_MD_STATE                          (1U << 8)
+#define R13_EMI_CLK_OFF_2_ACK                 (1U << 9)
+#define R13_MM_STATE                          (1U << 10)
+#define R13_SSPM_STATE                        (1U << 11)
+#define R13_MD_DDR_EN                         (1U << 12)
+#define R13_CONN_STATE                        (1U << 13)
+#define R13_CONN_SRCCLKENA                    (1U << 14)
+#define R13_CONN_APSRC_REQ                    (1U << 15)
+#define R13_SLEEP_EVENT_STA                   (1U << 16)
+#define R13_WAKE_EVENT_STA                    (1U << 17)
+#define R13_EMI_IDLE                          (1U << 18)
+#define R13_CSYSPWRUPREQ                      (1U << 19)
+#define R13_PWRAP_SLEEP_ACK                   (1U << 20)
+#define R13_EMI_CLK_OFF_ACK_ALL               (1U << 21)
+#define R13_TOP_MAS_PAU_ACK                   (1U << 22)
+#define R13_SW_DMDRAMCSHU_ACK_ALL             (1U << 23)
+#define R13_RC2SPM_EVENT_ABORT_MASK_OR        (1U << 24)
+#define R13_DR_SHORT_QUEUE_ACK_ALL            (1U << 25)
+#define R13_INFRA_AUX_IDLE                    (1U << 26)
+#define R13_DVFS_ALL_STATE                    (1U << 27)
+#define R13_RC2SPM_EVENT_ABORT_OR             (1U << 28)
+#define R13_DRAMC_SPCMD_APSRC_REQ             (1U << 29)
+#define R13_MD1_VRF18_REQ                     (1U << 30)
+#define R13_C2K_VRF18_REQ                     (1U << 31)
+
+#define is_cpu_pdn(flags)		(!((flags) & SPM_FLAG_DIS_CPU_PDN))
+#define is_infra_pdn(flags)		(!((flags) & SPM_FLAG_DIS_INFRA_PDN))
+#define is_ddrphy_pdn(flags)		(!((flags) & SPM_FLAG_DIS_DDRPHY_PDN))
+
+#define MP0_SPMC_SRAM_DORMANT_EN	(1<<0)
+#define MP1_SPMC_SRAM_DORMANT_EN	(1<<1)
+#define MP2_SPMC_SRAM_DORMANT_EN	(1<<2)
+
+#define EVENT_VEC(event, resume, imme, pc)	\
+	(((pc) << 16) |				\
+	 (!!(imme) << 7) |			\
+	 (!!(resume) << 6) |			\
+	 ((event) & 0x3f))
+
+#define SPM_PROJECT_CODE	0xb16
+#define SPM_REGWR_CFG_KEY	(SPM_PROJECT_CODE << 16)
+
+/**************************************
+ * Config and Parameter
+ **************************************/
+#define POWER_ON_VAL1_DEF		0x00015800
+#define PCM_FSM_STA_DEF			0x00108490
+#define SPM_WAKEUP_EVENT_MASK_DEF	0xF0F92218
+#define PCM_WDT_TIMEOUT			(30 * 32768)	/* 30s */
+#define PCM_TIMER_MAX			(0xffffffff - PCM_WDT_TIMEOUT)
+
+/**************************************
+ * Define and Declare
+ **************************************/
+/* PCM_PWR_IO_EN */
+#define PCM_PWRIO_EN_R0		(1U << 0)
+#define PCM_PWRIO_EN_R7		(1U << 7)
+#define PCM_RF_SYNC_R0		(1U << 16)
+#define PCM_RF_SYNC_R6		(1U << 22)
+#define PCM_RF_SYNC_R7		(1U << 23)
+
+/* SPM_SWINT */
+#define PCM_SW_INT0		(1U << 0)
+#define PCM_SW_INT1		(1U << 1)
+#define PCM_SW_INT2		(1U << 2)
+#define PCM_SW_INT3		(1U << 3)
+#define PCM_SW_INT4		(1U << 4)
+#define PCM_SW_INT5		(1U << 5)
+#define PCM_SW_INT6		(1U << 6)
+#define PCM_SW_INT7		(1U << 7)
+#define PCM_SW_INT8		(1U << 8)
+#define PCM_SW_INT9		(1U << 9)
+#define PCM_SW_INT_ALL		(PCM_SW_INT9 | PCM_SW_INT8 | PCM_SW_INT7 | \
+				 PCM_SW_INT6 | PCM_SW_INT5 | PCM_SW_INT4 | \
+				 PCM_SW_INT3 | PCM_SW_INT2 | PCM_SW_INT1 | \
+				 PCM_SW_INT0)
+/* SPM_IRQ_MASK */
+#define ISRM_TWAM		(1U << 2)
+#define ISRM_PCM_RETURN		(1U << 3)
+#define ISRM_RET_IRQ0		(1U << 8)
+#define ISRM_RET_IRQ1		(1U << 9)
+#define ISRM_RET_IRQ2		(1U << 10)
+#define ISRM_RET_IRQ3		(1U << 11)
+#define ISRM_RET_IRQ4		(1U << 12)
+#define ISRM_RET_IRQ5		(1U << 13)
+#define ISRM_RET_IRQ6		(1U << 14)
+#define ISRM_RET_IRQ7		(1U << 15)
+#define ISRM_RET_IRQ8		(1U << 16)
+#define ISRM_RET_IRQ9		(1U << 17)
+#define ISRM_RET_IRQ_AUX	(ISRM_RET_IRQ9 | ISRM_RET_IRQ8 | \
+				 ISRM_RET_IRQ7 | ISRM_RET_IRQ6 | \
+				 ISRM_RET_IRQ5 | ISRM_RET_IRQ4 | \
+				 ISRM_RET_IRQ3 | ISRM_RET_IRQ2 | \
+				 ISRM_RET_IRQ1)
+#define ISRM_ALL_EXC_TWAM	(ISRM_RET_IRQ_AUX)
+#define ISRM_ALL		(ISRM_ALL_EXC_TWAM | ISRM_TWAM)
+
+/* SPM_IRQ_STA */
+#define ISRS_TWAM		(1U << 2)
+#define ISRS_PCM_RETURN		(1U << 3)
+#define ISRS_SW_INT0		(1U << 4)
+#define ISRC_TWAM		ISRS_TWAM
+#define ISRC_ALL_EXC_TWAM	ISRS_PCM_RETURN
+#define ISRC_ALL		(ISRC_ALL_EXC_TWAM | ISRC_TWAM)
+
+/* SPM_WAKEUP_MISC */
+#define WAKE_MISC_TWAM		(1U << 18)
+#define WAKE_MISC_PCM_TIMER	(1U << 19)
+#define WAKE_MISC_CPU_WAKE	(1U << 20)
+
+enum SPM_WAKE_SRC_LIST {
+	WAKE_SRC_R12_PCM_TIMER = (1U << 0),
+	WAKE_SRC_R12_SSPM_WDT_EVENT_B = (1U << 1),
+	WAKE_SRC_R12_KP_IRQ_B = (1U << 2),
+	WAKE_SRC_R12_APWDT_EVENT_B = (1U << 3),
+	WAKE_SRC_R12_APXGPT1_EVENT_B = (1U << 4),
+	WAKE_SRC_R12_CONN2AP_SPM_WAKEUP_B = (1U << 5),
+	WAKE_SRC_R12_EINT_EVENT_B = (1U << 6),
+	WAKE_SRC_R12_CONN_WDT_IRQ_B = (1U << 7),
+	WAKE_SRC_R12_CCIF0_EVENT_B = (1U << 8),
+	WAKE_SRC_R12_LOWBATTERY_IRQ_B = (1U << 9),
+	WAKE_SRC_R12_SSPM_SPM_IRQ_B = (1U << 10),
+	WAKE_SRC_R12_SCP_SPM_IRQ_B = (1U << 11),
+	WAKE_SRC_R12_SCP_WDT_EVENT_B = (1U << 12),
+	WAKE_SRC_R12_PCM_WDT_WAKEUP_B = (1U << 13),
+	WAKE_SRC_R12_USB_CDSC_B = (1U << 14),
+	WAKE_SRC_R12_USB_POWERDWN_B = (1U << 15),
+	WAKE_SRC_R12_SYS_TIMER_EVENT_B = (1U << 16),
+	WAKE_SRC_R12_EINT_EVENT_SECURE_B = (1U << 17),
+	WAKE_SRC_R12_CCIF1_EVENT_B = (1U << 18),
+	WAKE_SRC_R12_UART0_IRQ_B = (1U << 19),
+	WAKE_SRC_R12_AFE_IRQ_MCU_B = (1U << 20),
+	WAKE_SRC_R12_THERM_CTRL_EVENT_B = (1U << 21),
+	WAKE_SRC_R12_SYS_CIRQ_IRQ_B = (1U << 22),
+	WAKE_SRC_R12_MD2AP_PEER_EVENT_B = (1U << 23),
+	WAKE_SRC_R12_CSYSPWREQ_B = (1U << 24),
+	WAKE_SRC_R12_MD1_WDT_B = (1U << 25),
+	WAKE_SRC_R12_CLDMA_EVENT_B = (1U << 26),
+	WAKE_SRC_R12_SEJ_WDT_GPT_B = (1U << 27),
+	WAKE_SRC_R12_ALL_SSPM_WAKEUP_B = (1U << 28),
+	WAKE_SRC_R12_CPU_IRQ_B = (1U << 29),
+	WAKE_SRC_R12_CPU_WFI_AND_B = (1U << 30),
+};
+
+struct pcm_desc {
+	const char *version;
+	const uint32_t *base;
+	const uint32_t base_dma;
+	const uint32_t size;
+	const uint32_t sess;
+	const uint32_t replace;
+	const uint32_t addr_2nd;
+	const uint32_t reserved;
+
+	uint32_t vec0;
+	uint32_t vec1;
+	uint32_t vec2;
+	uint32_t vec3;
+	uint32_t vec4;
+	uint32_t vec5;
+	uint32_t vec6;
+	uint32_t vec7;
+	uint32_t vec8;
+	uint32_t vec9;
+	uint32_t vec10;
+	uint32_t vec11;
+	uint32_t vec12;
+	uint32_t vec13;
+	uint32_t vec14;
+	uint32_t vec15;
+};
+
+struct pwr_ctrl {
+	uint32_t pcm_flags;
+	uint32_t pcm_flags1;
+	uint32_t timer_val;
+	uint32_t wake_src;
+
+	/* SPM_AP_STANDBY_CON */
+	uint8_t wfi_op;
+	uint8_t mp0_cputop_idle_mask;
+	uint8_t mp1_cputop_idle_mask;
+	uint8_t mcusys_idle_mask;
+	uint8_t mm_mask_b;
+	uint8_t md_ddr_en_0_dbc_en;
+	uint8_t md_ddr_en_1_dbc_en;
+	uint8_t md_mask_b;
+	uint8_t sspm_mask_b;
+	uint8_t scp_mask_b;
+	uint8_t srcclkeni_mask_b;
+	uint8_t md_apsrc_1_sel;
+	uint8_t md_apsrc_0_sel;
+	uint8_t conn_ddr_en_dbc_en;
+	uint8_t conn_mask_b;
+	uint8_t conn_apsrc_sel;
+
+	/* SPM_SRC_REQ */
+	uint8_t spm_apsrc_req;
+	uint8_t spm_f26m_req;
+	uint8_t spm_infra_req;
+	uint8_t spm_vrf18_req;
+	uint8_t spm_ddren_req;
+	uint8_t spm_rsv_src_req;
+	uint8_t spm_ddren_2_req;
+	uint8_t cpu_md_dvfs_sop_force_on;
+
+	/* SPM_SRC_MASK */
+	uint8_t csyspwreq_mask;
+	uint8_t ccif0_md_event_mask_b;
+	uint8_t ccif0_ap_event_mask_b;
+	uint8_t ccif1_md_event_mask_b;
+	uint8_t ccif1_ap_event_mask_b;
+	uint8_t ccif2_md_event_mask_b;
+	uint8_t ccif2_ap_event_mask_b;
+	uint8_t ccif3_md_event_mask_b;
+	uint8_t ccif3_ap_event_mask_b;
+	uint8_t md_srcclkena_0_infra_mask_b;
+	uint8_t md_srcclkena_1_infra_mask_b;
+	uint8_t conn_srcclkena_infra_mask_b;
+	uint8_t ufs_infra_req_mask_b;
+	uint8_t srcclkeni_infra_mask_b;
+	uint8_t md_apsrc_req_0_infra_mask_b;
+	uint8_t md_apsrc_req_1_infra_mask_b;
+	uint8_t conn_apsrcreq_infra_mask_b;
+	uint8_t ufs_srcclkena_mask_b;
+	uint8_t md_vrf18_req_0_mask_b;
+	uint8_t md_vrf18_req_1_mask_b;
+	uint8_t ufs_vrf18_req_mask_b;
+	uint8_t gce_vrf18_req_mask_b;
+	uint8_t conn_infra_req_mask_b;
+	uint8_t gce_apsrc_req_mask_b;
+	uint8_t disp0_apsrc_req_mask_b;
+	uint8_t disp1_apsrc_req_mask_b;
+	uint8_t mfg_req_mask_b;
+	uint8_t vdec_req_mask_b;
+
+	/* SPM_SRC2_MASK */
+	uint8_t md_ddr_en_0_mask_b;
+	uint8_t md_ddr_en_1_mask_b;
+	uint8_t conn_ddr_en_mask_b;
+	uint8_t ddren_sspm_apsrc_req_mask_b;
+	uint8_t ddren_scp_apsrc_req_mask_b;
+	uint8_t disp0_ddren_mask_b;
+	uint8_t disp1_ddren_mask_b;
+	uint8_t gce_ddren_mask_b;
+	uint8_t ddren_emi_self_refresh_ch0_mask_b;
+	uint8_t ddren_emi_self_refresh_ch1_mask_b;
+
+	/* SPM_WAKEUP_EVENT_MASK */
+	uint32_t spm_wakeup_event_mask;
+
+	/* SPM_WAKEUP_EVENT_EXT_MASK */
+	uint32_t spm_wakeup_event_ext_mask;
+
+	/* SPM_SRC3_MASK */
+	uint8_t md_ddr_en_2_0_mask_b;
+	uint8_t md_ddr_en_2_1_mask_b;
+	uint8_t conn_ddr_en_2_mask_b;
+	uint8_t ddren2_sspm_apsrc_req_mask_b;
+	uint8_t ddren2_scp_apsrc_req_mask_b;
+	uint8_t disp0_ddren2_mask_b;
+	uint8_t disp1_ddren2_mask_b;
+	uint8_t gce_ddren2_mask_b;
+	uint8_t ddren2_emi_self_refresh_ch0_mask_b;
+	uint8_t ddren2_emi_self_refresh_ch1_mask_b;
+
+	uint8_t mp0_cpu0_wfi_en;
+	uint8_t mp0_cpu1_wfi_en;
+	uint8_t mp0_cpu2_wfi_en;
+	uint8_t mp0_cpu3_wfi_en;
+
+	uint8_t mp1_cpu0_wfi_en;
+	uint8_t mp1_cpu1_wfi_en;
+	uint8_t mp1_cpu2_wfi_en;
+	uint8_t mp1_cpu3_wfi_en;
+};
+
+struct wake_status {
+	uint32_t assert_pc;
+	uint32_t r12;
+	uint32_t r12_ext;
+	uint32_t raw_sta;
+	uint32_t raw_ext_sta;
+	uint32_t wake_misc;
+	uint32_t timer_out;
+	uint32_t r13;
+	uint32_t r15;
+	uint32_t idle_sta;
+	uint32_t req_sta;
+	uint32_t debug_flag;
+	uint32_t debug_flag1;
+	uint32_t event_reg;
+	uint32_t isr;
+	uint32_t sw_flag;
+	uint32_t sw_flag1;
+	uint32_t log_index;
+};
+
+typedef struct spm_data {
+	unsigned int cmd;
+	union {
+		struct {
+			unsigned int sys_timestamp_l;
+			unsigned int sys_timestamp_h;
+			unsigned int sys_src_clk_l;
+			unsigned int sys_src_clk_h;
+			unsigned int spm_opt;
+		} suspend;
+		struct {
+			unsigned int args1;
+			unsigned int args2;
+			unsigned int args3;
+			unsigned int args4;
+			unsigned int args5;
+			unsigned int args6;
+			unsigned int args7;
+		} args;
+	} u;
+} spm_data_t;
+
+enum {
+	SPM_SUSPEND,
+	SPM_RESUME
+};
+
+extern void spm_disable_pcm_timer(void);
+extern void spm_set_bootaddr(unsigned long bootaddr);
+extern void spm_set_cpu_status(int cpu);
+extern void spm_set_power_control(const struct pwr_ctrl *pwrctrl);
+extern void spm_set_wakeup_event(const struct pwr_ctrl *pwrctrl);
+extern void spm_set_pcm_flags(const struct pwr_ctrl *pwrctrl);
+extern void spm_send_cpu_wakeup_event(void);
+extern void spm_get_wakeup_status(struct wake_status *wakesta);
+extern void spm_clean_after_wakeup(void);
+extern void spm_output_wake_reason(struct wake_status *wakesta,
+				   const char *scenario);
+extern void spm_set_pcm_wdt(int en);
+extern void spm_lock_get(void);
+extern void spm_lock_release(void);
+extern void spm_boot_init(void);
+extern const char *spm_get_firmware_version(void);
+
+#endif /* SPM_H */
diff --git a/plat/mediatek/mt8183/drivers/spm/spm_pmic_wrap.c b/plat/mediatek/mt8183/drivers/spm/spm_pmic_wrap.c
new file mode 100644
index 0000000..ce85272
--- /dev/null
+++ b/plat/mediatek/mt8183/drivers/spm/spm_pmic_wrap.c
@@ -0,0 +1,170 @@
+/*
+ * Copyright (c) 2019, ARM Limited and Contributors. All rights reserved.
+ *
+ * SPDX-License-Identifier: BSD-3-Clause
+ */
+
+#include <common/debug.h>
+#include <lib/mmio.h>
+#include <platform_def.h>
+#include <spm.h>
+#include <spm_pmic_wrap.h>
+#include <lib/libc/string.h>
+
+#define SLEEP_REG_MD_SPM_DVFS_CMD20	(SLEEP_REG_MD_BASE + 0x010)
+#define SLEEP_REG_MD_SPM_DVFS_CMD21	(SLEEP_REG_MD_BASE + 0x014)
+#define SLEEP_REG_MD_SPM_DVFS_CMD22	(SLEEP_REG_MD_BASE + 0x018)
+#define SLEEP_REG_MD_SPM_DVFS_CMD23	(SLEEP_REG_MD_BASE + 0x01C)
+
+/* PMIC_WRAP -> PMIC MT6358 */
+#define VCORE_BASE_UV 50000
+#define VOLT_TO_PMIC_VAL(volt)  (((volt) - VCORE_BASE_UV + 625 - 1) / 625)
+#define PMIC_VAL_TO_VOLT(pmic)  (((pmic) * 625) + VCORE_BASE_UV)
+
+#define DEFAULT_VOLT_VSRAM      (100000)
+#define DEFAULT_VOLT_VCORE      (100000)
+#define NR_PMIC_WRAP_CMD	(NR_IDX_ALL)
+#define MAX_RETRY_COUNT		(100)
+#define SPM_DATA_SHIFT		(16)
+
+#define BUCK_VCORE_ELR0		0x14AA
+#define BUCK_VPROC12_CON0	0x1408
+#define BUCK_VPROC11_CON0	0x1388
+#define TOP_SPI_CON0		0x044C
+#define LDO_VSRAM_PROC12_CON0	0x1B88
+#define LDO_VSRAM_PROC11_CON0	0x1B46
+#define BUCK_VMODEM_ELR0	0x15A6
+
+struct pmic_wrap_cmd {
+	unsigned long cmd_addr;
+	unsigned long cmd_wdata;
+};
+
+struct pmic_wrap_setting {
+	enum pmic_wrap_phase_id phase;
+	struct pmic_wrap_cmd addr[NR_PMIC_WRAP_CMD];
+	struct {
+		struct {
+			unsigned long cmd_addr;
+			unsigned long cmd_wdata;
+		} _[NR_PMIC_WRAP_CMD];
+		const int nr_idx;
+	} set[NR_PMIC_WRAP_PHASE];
+};
+
+static struct pmic_wrap_setting pw = {
+	.phase = NR_PMIC_WRAP_PHASE,
+	.addr = {{0, 0} },
+	.set[PMIC_WRAP_PHASE_ALLINONE] = {
+		._[CMD_0]    = {BUCK_VCORE_ELR0, VOLT_TO_PMIC_VAL(70000),},
+		._[CMD_1]    = {BUCK_VCORE_ELR0, VOLT_TO_PMIC_VAL(80000),},
+		._[CMD_2]    = {BUCK_VPROC12_CON0, 0x3,},
+		._[CMD_3]    = {BUCK_VPROC12_CON0, 0x1,},
+		._[CMD_4]    = {BUCK_VPROC11_CON0, 0x3,},
+		._[CMD_5]    = {BUCK_VPROC11_CON0, 0x1,},
+		._[CMD_6]    = {TOP_SPI_CON0, 0x1,},
+		._[CMD_7]    = {TOP_SPI_CON0, 0x0,},
+		._[CMD_8]    = {BUCK_VPROC12_CON0, 0x0,},
+		._[CMD_9]    = {BUCK_VPROC12_CON0, 0x1,},
+		._[CMD_10]   = {BUCK_VPROC11_CON0, 0x0,},
+		._[CMD_11]   = {BUCK_VPROC11_CON0, 0x1,},
+		._[CMD_12]   = {LDO_VSRAM_PROC12_CON0, 0x0,},
+		._[CMD_13]   = {LDO_VSRAM_PROC12_CON0, 0x1,},
+		._[CMD_14]   = {LDO_VSRAM_PROC11_CON0, 0x0,},
+		._[CMD_15]   = {LDO_VSRAM_PROC11_CON0, 0x1,},
+		._[CMD_20]   = {BUCK_VMODEM_ELR0, VOLT_TO_PMIC_VAL(55000),},
+		._[CMD_21]   = {BUCK_VCORE_ELR0, VOLT_TO_PMIC_VAL(60000),},
+		._[CMD_22]   = {LDO_VSRAM_PROC11_CON0, 0x3,},
+		._[CMD_23]   = {LDO_VSRAM_PROC11_CON0, 0x1,},
+		.nr_idx = NR_IDX_ALL
+	}
+};
+
+void _mt_spm_pmic_table_init(void)
+{
+	struct pmic_wrap_cmd pwrap_cmd_default[NR_PMIC_WRAP_CMD] = {
+		{(uint32_t)SPM_DVFS_CMD0, (uint32_t)SPM_DVFS_CMD0,},
+		{(uint32_t)SPM_DVFS_CMD1, (uint32_t)SPM_DVFS_CMD1,},
+		{(uint32_t)SPM_DVFS_CMD2, (uint32_t)SPM_DVFS_CMD2,},
+		{(uint32_t)SPM_DVFS_CMD3, (uint32_t)SPM_DVFS_CMD3,},
+		{(uint32_t)SPM_DVFS_CMD4, (uint32_t)SPM_DVFS_CMD4,},
+		{(uint32_t)SPM_DVFS_CMD5, (uint32_t)SPM_DVFS_CMD5,},
+		{(uint32_t)SPM_DVFS_CMD6, (uint32_t)SPM_DVFS_CMD6,},
+		{(uint32_t)SPM_DVFS_CMD7, (uint32_t)SPM_DVFS_CMD7,},
+		{(uint32_t)SPM_DVFS_CMD8, (uint32_t)SPM_DVFS_CMD8,},
+		{(uint32_t)SPM_DVFS_CMD9, (uint32_t)SPM_DVFS_CMD9,},
+		{(uint32_t)SPM_DVFS_CMD10, (uint32_t)SPM_DVFS_CMD10,},
+		{(uint32_t)SPM_DVFS_CMD11, (uint32_t)SPM_DVFS_CMD11,},
+		{(uint32_t)SPM_DVFS_CMD12, (uint32_t)SPM_DVFS_CMD12,},
+		{(uint32_t)SPM_DVFS_CMD13, (uint32_t)SPM_DVFS_CMD13,},
+		{(uint32_t)SPM_DVFS_CMD14, (uint32_t)SPM_DVFS_CMD14,},
+		{(uint32_t)SPM_DVFS_CMD15, (uint32_t)SPM_DVFS_CMD15,},
+		{(uint32_t)SLEEP_REG_MD_SPM_DVFS_CMD20,
+		 (uint32_t)SLEEP_REG_MD_SPM_DVFS_CMD20,},
+		{(uint32_t)SLEEP_REG_MD_SPM_DVFS_CMD21,
+		 (uint32_t)SLEEP_REG_MD_SPM_DVFS_CMD21,},
+		{(uint32_t)SLEEP_REG_MD_SPM_DVFS_CMD22,
+		 (uint32_t)SLEEP_REG_MD_SPM_DVFS_CMD22,},
+		{(uint32_t)SLEEP_REG_MD_SPM_DVFS_CMD23,
+		 (uint32_t)SLEEP_REG_MD_SPM_DVFS_CMD23,}
+	};
+
+	memcpy(pw.addr, pwrap_cmd_default, sizeof(pwrap_cmd_default));
+}
+
+void mt_spm_pmic_wrap_set_phase(enum pmic_wrap_phase_id phase)
+{
+	uint32_t idx, addr, data;
+
+	if (phase >= NR_PMIC_WRAP_PHASE)
+		return;
+
+	if (pw.phase == phase)
+		return;
+
+	if (pw.addr[0].cmd_addr == 0)
+		_mt_spm_pmic_table_init();
+
+	pw.phase = phase;
+
+	mmio_write_32(POWERON_CONFIG_EN, SPM_REGWR_CFG_KEY |
+		      BCLK_CG_EN_LSB | MD_BCLK_CG_EN_LSB);
+	for (idx = 0; idx < pw.set[phase].nr_idx; idx++) {
+		addr = pw.set[phase]._[idx].cmd_addr << SPM_DATA_SHIFT;
+		data = pw.set[phase]._[idx].cmd_wdata;
+		mmio_write_32(pw.addr[idx].cmd_addr, addr | data);
+	}
+}
+
+void mt_spm_pmic_wrap_set_cmd(enum pmic_wrap_phase_id phase, uint32_t idx,
+			      uint32_t cmd_wdata)
+{
+	uint32_t addr;
+
+	if (phase >= NR_PMIC_WRAP_PHASE)
+		return;
+
+	if (idx >= pw.set[phase].nr_idx)
+		return;
+
+	pw.set[phase]._[idx].cmd_wdata = cmd_wdata;
+
+	mmio_write_32(POWERON_CONFIG_EN, SPM_REGWR_CFG_KEY |
+		      BCLK_CG_EN_LSB | MD_BCLK_CG_EN_LSB);
+	if (pw.phase == phase) {
+		addr = pw.set[phase]._[idx].cmd_addr << SPM_DATA_SHIFT;
+		mmio_write_32(pw.addr[idx].cmd_addr, addr | cmd_wdata);
+	}
+}
+
+uint64_t mt_spm_pmic_wrap_get_cmd(enum pmic_wrap_phase_id phase, uint32_t idx)
+{
+	if (phase >= NR_PMIC_WRAP_PHASE)
+		return 0;
+
+	if (idx >= pw.set[phase].nr_idx)
+		return 0;
+
+	return pw.set[phase]._[idx].cmd_wdata;
+}
+
diff --git a/plat/mediatek/mt8183/drivers/spm/spm_pmic_wrap.h b/plat/mediatek/mt8183/drivers/spm/spm_pmic_wrap.h
new file mode 100644
index 0000000..194d347
--- /dev/null
+++ b/plat/mediatek/mt8183/drivers/spm/spm_pmic_wrap.h
@@ -0,0 +1,50 @@
+/*
+ * Copyright (c) 2019, ARM Limited and Contributors. All rights reserved.
+ *
+ * SPDX-License-Identifier: BSD-3-Clause
+ */
+
+/****************************************************************
+ * Auto generated by DE, please DO NOT modify this file directly.
+ *****************************************************************/
+
+#ifndef SPM_PMIC_WRAP__H
+#define SPM_PMIC_WRAP__H
+
+enum pmic_wrap_phase_id {
+	PMIC_WRAP_PHASE_ALLINONE,
+	NR_PMIC_WRAP_PHASE
+};
+
+/* IDX mapping */
+enum {
+	CMD_0,        /* 0x0 *//* PMIC_WRAP_PHASE_ALLINONE */
+	CMD_1,        /* 0x1 */
+	CMD_2,        /* 0x2 */
+	CMD_3,        /* 0x3 */
+	CMD_4,        /* 0x4 */
+	CMD_5,        /* 0x5 */
+	CMD_6,        /* 0x6 */
+	CMD_7,        /* 0x7 */
+	CMD_8,        /* 0x8 */
+	CMD_9,        /* 0x9 */
+	CMD_10,       /* 0xA */
+	CMD_11,       /* 0xB */
+	CMD_12,       /* 0xC */
+	CMD_13,       /* 0xD */
+	CMD_14,       /* 0xE */
+	CMD_15,       /* 0xF */
+	CMD_20,       /* 0x14 */
+	CMD_21,       /* 0x15 */
+	CMD_22,       /* 0x16 */
+	CMD_23,       /* 0x17 */
+	NR_IDX_ALL
+};
+
+/* APIs */
+void mt_spm_pmic_wrap_set_phase(enum pmic_wrap_phase_id phase);
+void mt_spm_pmic_wrap_set_cmd(enum pmic_wrap_phase_id phase,
+			      uint32_t idx, uint32_t cmd_wdata);
+uint64_t mt_spm_pmic_wrap_get_cmd(enum pmic_wrap_phase_id phase, uint32_t idx);
+#endif /* SPM_PMIC_WRAP__H */
+
diff --git a/plat/mediatek/mt8183/drivers/spm/spm_suspend.c b/plat/mediatek/mt8183/drivers/spm/spm_suspend.c
new file mode 100644
index 0000000..b9ac19f
--- /dev/null
+++ b/plat/mediatek/mt8183/drivers/spm/spm_suspend.c
@@ -0,0 +1,255 @@
+/*
+ * Copyright (c) 2019, ARM Limited and Contributors. All rights reserved.
+ *
+ * SPDX-License-Identifier: BSD-3-Clause
+ */
+
+#include <arch_helpers.h>
+#include <common/debug.h>
+#include <drivers/delay_timer.h>
+#include <mt_gic_v3.h>
+#include <lib/mmio.h>
+#include <platform_def.h>
+#include <pmic.h>
+#include <spm.h>
+#include <uart.h>
+
+#define SPM_SYSCLK_SETTLE       99
+
+#define WAKE_SRC_FOR_SUSPEND \
+	(WAKE_SRC_R12_PCM_TIMER | \
+	 WAKE_SRC_R12_SSPM_WDT_EVENT_B | \
+	 WAKE_SRC_R12_KP_IRQ_B | \
+	 WAKE_SRC_R12_CONN2AP_SPM_WAKEUP_B | \
+	 WAKE_SRC_R12_EINT_EVENT_B | \
+	 WAKE_SRC_R12_CONN_WDT_IRQ_B | \
+	 WAKE_SRC_R12_CCIF0_EVENT_B | \
+	 WAKE_SRC_R12_SSPM_SPM_IRQ_B | \
+	 WAKE_SRC_R12_SCP_SPM_IRQ_B | \
+	 WAKE_SRC_R12_SCP_WDT_EVENT_B | \
+	 WAKE_SRC_R12_USB_CDSC_B | \
+	 WAKE_SRC_R12_USB_POWERDWN_B | \
+	 WAKE_SRC_R12_SYS_TIMER_EVENT_B | \
+	 WAKE_SRC_R12_EINT_EVENT_SECURE_B | \
+	 WAKE_SRC_R12_CCIF1_EVENT_B | \
+	 WAKE_SRC_R12_MD2AP_PEER_EVENT_B | \
+	 WAKE_SRC_R12_MD1_WDT_B | \
+	 WAKE_SRC_R12_CLDMA_EVENT_B | \
+	 WAKE_SRC_R12_SEJ_WDT_GPT_B)
+
+#define SLP_PCM_FLAGS \
+	(SPM_FLAG_DIS_VCORE_DVS	| SPM_FLAG_DIS_VCORE_DFS | \
+	 SPM_FLAG_DIS_ATF_ABORT | SPM_FLAG_DISABLE_MMSYS_DVFS | \
+	 SPM_FLAG_DIS_INFRA_PDN | SPM_FLAG_SUSPEND_OPTION)
+
+#define SLP_PCM_FLAGS1 \
+	(SPM_FLAG1_DISABLE_MCDSR)
+
+static const struct pwr_ctrl suspend_ctrl = {
+	.wake_src = WAKE_SRC_FOR_SUSPEND,
+	.pcm_flags = SLP_PCM_FLAGS,
+	.pcm_flags1 = SLP_PCM_FLAGS1,
+
+	/* SPM_AP_STANDBY_CON */
+	.wfi_op = 0x1,
+	.mp0_cputop_idle_mask = 0,
+	.mp1_cputop_idle_mask = 0,
+	.mcusys_idle_mask = 0,
+	.mm_mask_b = 0,
+	.md_ddr_en_0_dbc_en = 0x1,
+	.md_ddr_en_1_dbc_en = 0,
+	.md_mask_b = 0x1,
+	.sspm_mask_b = 0x1,
+	.scp_mask_b = 0x1,
+	.srcclkeni_mask_b = 0x1,
+	.md_apsrc_1_sel = 0,
+	.md_apsrc_0_sel = 0,
+	.conn_ddr_en_dbc_en = 0x1,
+	.conn_mask_b = 0x1,
+	.conn_apsrc_sel = 0,
+
+	/* SPM_SRC_REQ */
+	.spm_apsrc_req = 0,
+	.spm_f26m_req = 0,
+	.spm_infra_req = 0,
+	.spm_vrf18_req = 0,
+	.spm_ddren_req = 0,
+	.spm_rsv_src_req = 0,
+	.spm_ddren_2_req = 0,
+	.cpu_md_dvfs_sop_force_on = 0,
+
+	/* SPM_SRC_MASK */
+	.csyspwreq_mask = 0x1,
+	.ccif0_md_event_mask_b = 0x1,
+	.ccif0_ap_event_mask_b = 0x1,
+	.ccif1_md_event_mask_b = 0x1,
+	.ccif1_ap_event_mask_b = 0x1,
+	.ccif2_md_event_mask_b = 0x1,
+	.ccif2_ap_event_mask_b = 0x1,
+	.ccif3_md_event_mask_b = 0x1,
+	.ccif3_ap_event_mask_b = 0x1,
+	.md_srcclkena_0_infra_mask_b = 0x1,
+	.md_srcclkena_1_infra_mask_b = 0,
+	.conn_srcclkena_infra_mask_b = 0,
+	.ufs_infra_req_mask_b = 0,
+	.srcclkeni_infra_mask_b = 0,
+	.md_apsrc_req_0_infra_mask_b = 0x1,
+	.md_apsrc_req_1_infra_mask_b = 0x1,
+	.conn_apsrcreq_infra_mask_b = 0x1,
+	.ufs_srcclkena_mask_b = 0,
+	.md_vrf18_req_0_mask_b = 0,
+	.md_vrf18_req_1_mask_b = 0,
+	.ufs_vrf18_req_mask_b = 0,
+	.gce_vrf18_req_mask_b = 0,
+	.conn_infra_req_mask_b = 0x1,
+	.gce_apsrc_req_mask_b = 0,
+	.disp0_apsrc_req_mask_b = 0,
+	.disp1_apsrc_req_mask_b = 0,
+	.mfg_req_mask_b = 0,
+	.vdec_req_mask_b = 0,
+
+	/* SPM_SRC2_MASK */
+	.md_ddr_en_0_mask_b = 0x1,
+	.md_ddr_en_1_mask_b = 0,
+	.conn_ddr_en_mask_b = 0x1,
+	.ddren_sspm_apsrc_req_mask_b = 0x1,
+	.ddren_scp_apsrc_req_mask_b = 0x1,
+	.disp0_ddren_mask_b = 0x1,
+	.disp1_ddren_mask_b = 0x1,
+	.gce_ddren_mask_b = 0x1,
+	.ddren_emi_self_refresh_ch0_mask_b = 0,
+	.ddren_emi_self_refresh_ch1_mask_b = 0,
+
+	/* SPM_WAKEUP_EVENT_MASK */
+	.spm_wakeup_event_mask = 0xF1782218,
+
+	/* SPM_WAKEUP_EVENT_EXT_MASK */
+	.spm_wakeup_event_ext_mask = 0xFFFFFFFF,
+
+	/* SPM_SRC3_MASK */
+	.md_ddr_en_2_0_mask_b = 0x1,
+	.md_ddr_en_2_1_mask_b = 0,
+	.conn_ddr_en_2_mask_b = 0x1,
+	.ddren2_sspm_apsrc_req_mask_b = 0x1,
+	.ddren2_scp_apsrc_req_mask_b = 0x1,
+	.disp0_ddren2_mask_b = 0,
+	.disp1_ddren2_mask_b = 0,
+	.gce_ddren2_mask_b = 0,
+	.ddren2_emi_self_refresh_ch0_mask_b = 0,
+	.ddren2_emi_self_refresh_ch1_mask_b = 0,
+
+	.mp0_cpu0_wfi_en = 0x1,
+	.mp0_cpu1_wfi_en = 0x1,
+	.mp0_cpu2_wfi_en = 0x1,
+	.mp0_cpu3_wfi_en = 0x1,
+
+	.mp1_cpu0_wfi_en = 0x1,
+	.mp1_cpu1_wfi_en = 0x1,
+	.mp1_cpu2_wfi_en = 0x1,
+	.mp1_cpu3_wfi_en = 0x1
+};
+
+static uint32_t spm_set_sysclk_settle(void)
+{
+	mmio_write_32(SPM_CLK_SETTLE, SPM_SYSCLK_SETTLE);
+	return mmio_read_32(SPM_CLK_SETTLE);
+}
+
+void go_to_sleep_before_wfi(void)
+{
+	int cpu = MPIDR_AFFLVL0_VAL(read_mpidr());
+	uint32_t settle;
+
+	settle = spm_set_sysclk_settle();
+	spm_set_cpu_status(cpu);
+	spm_set_power_control(&suspend_ctrl);
+	spm_set_wakeup_event(&suspend_ctrl);
+	spm_set_pcm_flags(&suspend_ctrl);
+	spm_send_cpu_wakeup_event();
+	spm_set_pcm_wdt(0);
+	spm_disable_pcm_timer();
+
+	if (is_infra_pdn(suspend_ctrl.pcm_flags))
+		mt_uart_save();
+
+	if (!mt_console_uart_cg_status())
+		console_switch_state(CONSOLE_FLAG_BOOT);
+
+	INFO("cpu%d: \"%s\", wakesrc = 0x%x, pcm_con1 = 0x%x\n",
+	     cpu, spm_get_firmware_version(), suspend_ctrl.wake_src,
+	     mmio_read_32(PCM_CON1));
+	INFO("settle = %u, sec = %u, sw_flag = 0x%x 0x%x, src_req = 0x%x\n",
+	     settle, mmio_read_32(PCM_TIMER_VAL) / 32768,
+	     suspend_ctrl.pcm_flags, suspend_ctrl.pcm_flags1,
+	     mmio_read_32(SPM_SRC_REQ));
+
+	if (!mt_console_uart_cg_status())
+		console_switch_state(CONSOLE_FLAG_RUNTIME);
+}
+
+static void go_to_sleep_after_wfi(void)
+{
+	struct wake_status spm_wakesta;
+
+	if (is_infra_pdn(suspend_ctrl.pcm_flags))
+		mt_uart_restore();
+
+	spm_set_pcm_wdt(0);
+	spm_get_wakeup_status(&spm_wakesta);
+	spm_clean_after_wakeup();
+
+	if (!mt_console_uart_cg_status())
+		console_switch_state(CONSOLE_FLAG_BOOT);
+
+	spm_output_wake_reason(&spm_wakesta, "suspend");
+
+	if (!mt_console_uart_cg_status())
+		console_switch_state(CONSOLE_FLAG_RUNTIME);
+}
+
+static void spm_enable_armpll_l(void)
+{
+	/* power on */
+	mmio_setbits_32(ARMPLL_L_PWR_CON0, 0x1);
+
+	/* clear isolation */
+	mmio_clrbits_32(ARMPLL_L_PWR_CON0, 0x2);
+
+	/* enable pll */
+	mmio_setbits_32(ARMPLL_L_CON0, 0x1);
+
+	/* Add 20us delay for turning on PLL */
+	udelay(20);
+}
+
+static void spm_disable_armpll_l(void)
+{
+	/* disable pll */
+	mmio_clrbits_32(ARMPLL_L_CON0, 0x1);
+
+	/* isolation */
+	mmio_setbits_32(ARMPLL_L_PWR_CON0, 0x2);
+
+	/* power off */
+	mmio_clrbits_32(ARMPLL_L_PWR_CON0, 0x1);
+}
+
+void spm_system_suspend(void)
+{
+	spm_disable_armpll_l();
+	bcpu_enable(0);
+	bcpu_sram_enable(0);
+	spm_lock_get();
+	go_to_sleep_before_wfi();
+	spm_lock_release();
+}
+
+void spm_system_suspend_finish(void)
+{
+	spm_lock_get();
+	go_to_sleep_after_wfi();
+	spm_lock_release();
+	spm_enable_armpll_l();
+	bcpu_sram_enable(1);
+	bcpu_enable(1);
+}
diff --git a/plat/mediatek/mt8183/drivers/spm/spm_suspend.h b/plat/mediatek/mt8183/drivers/spm/spm_suspend.h
new file mode 100644
index 0000000..e127c2e
--- /dev/null
+++ b/plat/mediatek/mt8183/drivers/spm/spm_suspend.h
@@ -0,0 +1,13 @@
+/*
+ * Copyright (c) 2019, ARM Limited and Contributors. All rights reserved.
+ *
+ * SPDX-License-Identifier: BSD-3-Clause
+ */
+
+#ifndef __SPM_SUSPEND_H__
+#define __SPM_SUSPEND_H__
+
+void spm_system_suspend(void);
+void spm_system_suspend_finish(void);
+
+#endif /* __SPM_SUSPEND_H__*/
diff --git a/plat/mediatek/mt8183/drivers/spmc/mtspmc_private.h b/plat/mediatek/mt8183/drivers/spmc/mtspmc_private.h
index 613d471..2228e63 100644
--- a/plat/mediatek/mt8183/drivers/spmc/mtspmc_private.h
+++ b/plat/mediatek/mt8183/drivers/spmc/mtspmc_private.h
@@ -136,8 +136,7 @@
 /*
  * MCU configuration registers
  */
-#define MCUCFG_MP0_AXI_CONFIG	((uintptr_t)&mt8183_mcucfg->mp0_axi_config)
-#define MCUCFG_MP1_AXI_CONFIG	((uintptr_t)&mt8183_mcucfg->mp1_axi_config)
+
 /* bit-fields of MCUCFG_MP?_AXI_CONFIG */
 #define MCUCFG_AXI_CONFIG_BROADCASTINNER	(1 << 0)
 #define MCUCFG_AXI_CONFIG_BROADCASTOUTER	(1 << 1)
@@ -146,11 +145,6 @@
 #define MCUCFG_AXI_CONFIG_ACINACTM		(1 << 4)
 #define MCUCFG_AXI_CONFIG_AINACTS		(1 << 5)
 
-/* per_cpu registers for MCUCFG_MP?_AXI_CONFIG */
-static const struct per_cpu_reg MCUCFG_SCUCTRL[] = {
-	[0] = { .cluster_addr = MCUCFG_MP0_AXI_CONFIG },
-	[1] = { .cluster_addr = MCUCFG_MP1_AXI_CONFIG },
-};
 
 #define MCUCFG_MP0_MISC_CONFIG2 ((uintptr_t)&mt8183_mcucfg->mp0_misc_config[2])
 #define MCUCFG_MP0_MISC_CONFIG3 ((uintptr_t)&mt8183_mcucfg->mp0_misc_config[3])
diff --git a/plat/mediatek/mt8183/drivers/sspm/sspm.c b/plat/mediatek/mt8183/drivers/sspm/sspm.c
new file mode 100644
index 0000000..3917638
--- /dev/null
+++ b/plat/mediatek/mt8183/drivers/sspm/sspm.c
@@ -0,0 +1,159 @@
+/*
+ * Copyright (c) 2019, ARM Limited and Contributors. All rights reserved.
+ *
+ * SPDX-License-Identifier: BSD-3-Clause
+ */
+#include <arch_helpers.h>
+#include <common/debug.h>
+#include <drivers/delay_timer.h>
+#include <errno.h>
+#include <lib/mmio.h>
+#include <sspm.h>
+
+static void memcpy_to_sspm(uint32_t dst, uint32_t *src, uint32_t len)
+{
+	while (len--) {
+		mmio_write_32(dst, *src);
+		dst += sizeof(uint32_t);
+		src++;
+	}
+}
+
+static void memcpy_from_sspm(uint32_t *dst, uint32_t src, uint32_t len)
+{
+	while (len--) {
+		*dst = mmio_read_32(src);
+		dst++;
+		src += sizeof(uint32_t);
+	}
+}
+
+int sspm_mbox_read(uint32_t slot, uint32_t *data, uint32_t len)
+{
+	if (slot >= 32)	{
+		ERROR("%s:slot = %d\n", __func__, slot);
+		return -EINVAL;
+	}
+
+	if (data)
+		memcpy_from_sspm(data,
+				 MBOX3_BASE + slot * 4,
+				 len);
+
+	return 0;
+}
+
+int sspm_mbox_write(uint32_t slot, uint32_t *data, uint32_t len)
+{
+	if (slot >= 32) {
+		ERROR("%s:slot = %d\n", __func__, slot);
+		return -EINVAL;
+	}
+
+	if (data)
+		memcpy_to_sspm(MBOX3_BASE + slot * 4,
+			       data,
+			       len);
+
+	return 0;
+}
+
+static int sspm_ipi_check_ack(uint32_t id)
+{
+	int ret = 0;
+
+	if (id == IPI_ID_PLATFORM) {
+		if ((mmio_read_32(MBOX0_BASE + MBOX_IN_IRQ_OFS) & 0x1) == 0x1)
+			ret = -EINPROGRESS;
+	} else if (id == IPI_ID_SUSPEND) {
+		if ((mmio_read_32(MBOX1_BASE + MBOX_IN_IRQ_OFS) & 0x2) == 0x2)
+			ret = -EINPROGRESS;
+	} else {
+		ERROR("%s: id = %d\n", __func__, id);
+		ret = -EINVAL;
+	}
+
+	return ret;
+}
+
+int sspm_ipi_send_non_blocking(uint32_t id, uint32_t *data)
+{
+	int ret = 0;
+
+	ret = sspm_ipi_check_ack(id);
+	if (ret)
+		return ret;
+
+	if (id == IPI_ID_PLATFORM) {
+		memcpy_to_sspm(MBOX0_BASE + PINR_OFFSET_PLATFORM * 4,
+			       data,
+			       PINR_SIZE_PLATFORM);
+		dsb();
+		mmio_write_32(MBOX0_BASE + MBOX_OUT_IRQ_OFS, 0x1);
+	} else if (id == IPI_ID_SUSPEND) {
+		memcpy_to_sspm(MBOX1_BASE + PINR_OFFSET_SUSPEND * 4,
+			       data,
+			       PINR_SIZE_SUSPEND);
+		dsb();
+		mmio_write_32(MBOX1_BASE + MBOX_OUT_IRQ_OFS,
+			      0x2);
+	}
+
+	return 0;
+}
+
+int sspm_ipi_recv_non_blocking(uint32_t id, uint32_t *data, uint32_t len)
+{
+	int ret = 0;
+
+	ret = sspm_ipi_check_ack(id);
+	if (ret == -EINPROGRESS) {
+		if (id == IPI_ID_PLATFORM) {
+			memcpy_from_sspm(data,
+					 MBOX0_BASE + PINR_OFFSET_PLATFORM * 4,
+					 len);
+			dsb();
+			/* clear interrupt bit*/
+			mmio_write_32(MBOX0_BASE + MBOX_IN_IRQ_OFS,
+				      0x1);
+			ret = 0;
+		} else if (id == IPI_ID_SUSPEND) {
+			memcpy_from_sspm(data,
+					 MBOX1_BASE + PINR_OFFSET_SUSPEND * 4,
+					 len);
+			dsb();
+			/* clear interrupt bit*/
+			mmio_write_32(MBOX1_BASE + MBOX_IN_IRQ_OFS,
+				      0x2);
+			ret = 0;
+		}
+	} else if (ret == 0) {
+		ret = -EBUSY;
+	}
+
+	return ret;
+}
+
+int sspm_alive_show(void)
+{
+	uint32_t ipi_data, count;
+	int ret = 0;
+
+	count = 5;
+	ipi_data = 0xdead;
+
+	if (sspm_ipi_send_non_blocking(IPI_ID_PLATFORM, &ipi_data) != 0) {
+		ERROR("sspm init send fail! ret=%d\n", ret);
+		return -1;
+	}
+
+	while (sspm_ipi_recv_non_blocking(IPI_ID_PLATFORM,
+					  &ipi_data,
+					  sizeof(ipi_data))
+					  && count) {
+		mdelay(100);
+		count--;
+	}
+
+	return (ipi_data == 1) ? 0 : -1;
+}
diff --git a/plat/mediatek/mt8183/drivers/sspm/sspm.h b/plat/mediatek/mt8183/drivers/sspm/sspm.h
new file mode 100644
index 0000000..2c2cc10
--- /dev/null
+++ b/plat/mediatek/mt8183/drivers/sspm/sspm.h
@@ -0,0 +1,32 @@
+/*
+ * Copyright (c) 2019, ARM Limited and Contributors. All rights reserved.
+ *
+ * SPDX-License-Identifier: BSD-3-Clause
+ */
+#ifndef __SSPM_H__
+#define __SSPM_H__
+/* These should sync with sspm.bin */
+#define IPI_ID_PLATFORM			0
+#define IPI_ID_SUSPEND			6
+#define PINR_OFFSET_PLATFORM		0
+#define PINR_SIZE_PLATFORM		3
+#define PINR_OFFSET_SUSPEND		2
+#define PINR_SIZE_SUSPEND		8
+
+#define MBOX0_BASE			0x10450000
+#define MBOX1_BASE			0x10460000
+#define MBOX3_BASE			0x10480000
+#define MBOX_OUT_IRQ_OFS		0x1000
+#define MBOX_IN_IRQ_OFS			0x1004
+
+#define SHAREMBOX_OFFSET_MCDI		0
+#define SHAREMBOX_SIZE_MCDI		20
+#define SHAREMBOX_OFFSET_SUSPEND	26
+#define SHAREMBOX_SIZE_SUSPEND		6
+
+int sspm_mbox_read(uint32_t slot, uint32_t *data, uint32_t len);
+int sspm_mbox_write(uint32_t slot, uint32_t *data, uint32_t len);
+int sspm_ipi_send_non_blocking(uint32_t id, uint32_t *data);
+int sspm_ipi_recv_non_blocking(uint32_t slot, uint32_t *data, uint32_t len);
+int sspm_alive_show(void);
+#endif /* __SSPM_H__ */
diff --git a/plat/mediatek/mt8183/drivers/uart/uart.c b/plat/mediatek/mt8183/drivers/uart/uart.c
new file mode 100644
index 0000000..3c6a980
--- /dev/null
+++ b/plat/mediatek/mt8183/drivers/uart/uart.c
@@ -0,0 +1,111 @@
+/*
+ * Copyright (c) 2019, ARM Limited and Contributors. All rights reserved.
+ *
+ * SPDX-License-Identifier: BSD-3-Clause
+ */
+
+#include <lib/mmio.h>
+#include <uart.h>
+
+static struct mt_uart uart_save_addr[DRV_SUPPORT_UART_PORTS];
+
+static const unsigned int uart_base_addr[DRV_SUPPORT_UART_PORTS] = {
+	UART0_BASE,
+	UART1_BASE
+};
+
+void mt_uart_restore(void)
+{
+	int uart_idx = UART_PORT0;
+	struct mt_uart *uart;
+	unsigned long base;
+
+	/* Must NOT print any debug log before UART restore */
+	for (uart_idx = UART_PORT0; uart_idx < HW_SUPPORT_UART_PORTS;
+	     uart_idx++) {
+
+		uart = &uart_save_addr[uart_idx];
+		base = uart->base;
+
+		mmio_write_32(UART_LCR(base), UART_LCR_MODE_B);
+		mmio_write_32(UART_EFR(base), uart->registers.efr);
+		mmio_write_32(UART_LCR(base), uart->registers.lcr);
+		mmio_write_32(UART_FCR(base), uart->registers.fcr);
+
+		/* baudrate */
+		mmio_write_32(UART_HIGHSPEED(base), uart->registers.highspeed);
+		mmio_write_32(UART_FRACDIV_L(base), uart->registers.fracdiv_l);
+		mmio_write_32(UART_FRACDIV_M(base), uart->registers.fracdiv_m);
+		mmio_write_32(UART_LCR(base),
+			      uart->registers.lcr | UART_LCR_DLAB);
+		mmio_write_32(UART_DLL(base), uart->registers.dll);
+		mmio_write_32(UART_DLH(base), uart->registers.dlh);
+		mmio_write_32(UART_LCR(base), uart->registers.lcr);
+		mmio_write_32(UART_SAMPLE_COUNT(base),
+			      uart->registers.sample_count);
+		mmio_write_32(UART_SAMPLE_POINT(base),
+			      uart->registers.sample_point);
+		mmio_write_32(UART_GUARD(base), uart->registers.guard);
+
+		/* flow control */
+		mmio_write_32(UART_ESCAPE_EN(base), uart->registers.escape_en);
+		mmio_write_32(UART_MCR(base), uart->registers.mcr);
+		mmio_write_32(UART_IER(base), uart->registers.ier);
+		mmio_write_32(UART_SCR(base), uart->registers.scr);
+	}
+}
+
+void mt_uart_save(void)
+{
+	int uart_idx = UART_PORT0;
+	struct mt_uart *uart;
+	unsigned long base;
+
+	for (uart_idx = UART_PORT0; uart_idx < HW_SUPPORT_UART_PORTS;
+	     uart_idx++) {
+
+		uart_save_addr[uart_idx].base = uart_base_addr[uart_idx];
+		base = uart_base_addr[uart_idx];
+		uart = &uart_save_addr[uart_idx];
+		uart->registers.lcr = mmio_read_32(UART_LCR(base));
+
+		mmio_write_32(UART_LCR(base), UART_LCR_MODE_B);
+		uart->registers.efr = mmio_read_32(UART_EFR(base));
+		mmio_write_32(UART_LCR(base), uart->registers.lcr);
+		uart->registers.fcr = mmio_read_32(UART_FCR_RD(base));
+
+		/* baudrate */
+		uart->registers.highspeed = mmio_read_32(UART_HIGHSPEED(base));
+		uart->registers.fracdiv_l = mmio_read_32(UART_FRACDIV_L(base));
+		uart->registers.fracdiv_m = mmio_read_32(UART_FRACDIV_M(base));
+		mmio_write_32(UART_LCR(base),
+			      uart->registers.lcr | UART_LCR_DLAB);
+		uart->registers.dll = mmio_read_32(UART_DLL(base));
+		uart->registers.dlh = mmio_read_32(UART_DLH(base));
+		mmio_write_32(UART_LCR(base), uart->registers.lcr);
+		uart->registers.sample_count = mmio_read_32(
+						UART_SAMPLE_COUNT(base));
+		uart->registers.sample_point = mmio_read_32(
+						UART_SAMPLE_POINT(base));
+		uart->registers.guard = mmio_read_32(UART_GUARD(base));
+
+		/* flow control */
+		uart->registers.escape_en = mmio_read_32(UART_ESCAPE_EN(base));
+		uart->registers.mcr = mmio_read_32(UART_MCR(base));
+		uart->registers.ier = mmio_read_32(UART_IER(base));
+		uart->registers.scr = mmio_read_32(UART_SCR(base));
+	}
+}
+
+void mt_console_uart_cg(int on)
+{
+	if (on)
+		mmio_write_32(UART_CLOCK_GATE_CLR, UART0_CLOCK_GATE_BIT);
+	else
+		mmio_write_32(UART_CLOCK_GATE_SET, UART0_CLOCK_GATE_BIT);
+}
+
+int mt_console_uart_cg_status(void)
+{
+	return mmio_read_32(UART_CLOCK_GATE_STA) & UART0_CLOCK_GATE_BIT;
+}
diff --git a/plat/mediatek/mt8183/drivers/uart/uart.h b/plat/mediatek/mt8183/drivers/uart/uart.h
new file mode 100644
index 0000000..be04c35
--- /dev/null
+++ b/plat/mediatek/mt8183/drivers/uart/uart.h
@@ -0,0 +1,100 @@
+/*
+ * Copyright (c) 2019, ARM Limited and Contributors. All rights reserved.
+ *
+ * SPDX-License-Identifier: BSD-3-Clause
+ */
+
+#ifndef __UART_H__
+#define __UART_H__
+
+#include <platform_def.h>
+
+/* UART HW information */
+#define HW_SUPPORT_UART_PORTS	2
+#define DRV_SUPPORT_UART_PORTS	2
+
+/* console UART clock cg */
+#define UART_CLOCK_GATE_SET		(INFRACFG_AO_BASE + 0x80)
+#define UART_CLOCK_GATE_CLR		(INFRACFG_AO_BASE + 0x84)
+#define UART_CLOCK_GATE_STA		(INFRACFG_AO_BASE + 0x90)
+#define UART0_CLOCK_GATE_BIT		(1U<<22)
+#define UART1_CLOCK_GATE_BIT		(1U<<23)
+
+/* UART registers */
+#define UART_RBR(_baseaddr)			(_baseaddr + 0x0)
+#define UART_THR(_baseaddr)			(_baseaddr + 0x0)
+#define UART_IER(_baseaddr)			(_baseaddr + 0x4)
+#define UART_IIR(_baseaddr)			(_baseaddr + 0x8)
+#define UART_FCR(_baseaddr)			(_baseaddr + 0x8)
+#define UART_LCR(_baseaddr)			(_baseaddr + 0xc)
+#define UART_MCR(_baseaddr)			(_baseaddr + 0x10)
+#define UART_LSR(_baseaddr)			(_baseaddr + 0x14)
+#define UART_MSR(_baseaddr)			(_baseaddr + 0x18)
+#define UART_SCR(_baseaddr)			(_baseaddr + 0x1c)
+#define UART_DLL(_baseaddr)			(_baseaddr + 0x0)
+#define UART_DLH(_baseaddr)			(_baseaddr + 0x4)
+#define UART_EFR(_baseaddr)			(_baseaddr + 0x8)
+#define UART_XON1(_baseaddr)			(_baseaddr + 0x10)
+#define UART_XON2(_baseaddr)			(_baseaddr + 0x14)
+#define UART_XOFF1(_baseaddr)			(_baseaddr + 0x18)
+#define UART_XOFF2(_baseaddr)			(_baseaddr + 0x1c)
+#define UART_AUTOBAUD(_baseaddr)		(_baseaddr + 0x20)
+#define UART_HIGHSPEED(_baseaddr)		(_baseaddr + 0x24)
+#define UART_SAMPLE_COUNT(_baseaddr)		(_baseaddr + 0x28)
+#define UART_SAMPLE_POINT(_baseaddr)		(_baseaddr + 0x2c)
+#define UART_AUTOBAUD_REG(_baseaddr)		(_baseaddr + 0x30)
+#define UART_RATE_FIX_REG(_baseaddr)		(_baseaddr + 0x34)
+#define UART_AUTO_BAUDSAMPLE(_baseaddr)		(_baseaddr + 0x38)
+#define UART_GUARD(_baseaddr)			(_baseaddr + 0x3c)
+#define UART_ESCAPE_DAT(_baseaddr)		(_baseaddr + 0x40)
+#define UART_ESCAPE_EN(_baseaddr)		(_baseaddr + 0x44)
+#define UART_SLEEP_EN(_baseaddr)		(_baseaddr + 0x48)
+#define UART_DMA_EN(_baseaddr)			(_baseaddr + 0x4c)
+#define UART_RXTRI_AD(_baseaddr)		(_baseaddr + 0x50)
+#define UART_FRACDIV_L(_baseaddr)		(_baseaddr + 0x54)
+#define UART_FRACDIV_M(_baseaddr)		(_baseaddr + 0x58)
+#define UART_FCR_RD(_baseaddr)			(_baseaddr + 0x5C)
+#define UART_USB_RX_SEL(_baseaddr)		(_baseaddr + 0xB0)
+#define UART_SLEEP_REQ(_baseaddr)		(_baseaddr + 0xB4)
+#define UART_SLEEP_ACK(_baseaddr)		(_baseaddr + 0xB8)
+#define UART_SPM_SEL(_baseaddr)			(_baseaddr + 0xBC)
+#define UART_LCR_DLAB				0x0080
+#define UART_LCR_MODE_B				0x00bf
+
+enum uart_port_ID {
+	UART_PORT0 = 0,
+	UART_PORT1
+};
+
+struct mt_uart_register {
+	unsigned int dll;
+	unsigned int dlh;
+	unsigned int ier;
+	unsigned int lcr;
+	unsigned int mcr;
+	unsigned int fcr;
+	unsigned int lsr;
+	unsigned int scr;
+	unsigned int efr;
+	unsigned int highspeed;
+	unsigned int sample_count;
+	unsigned int sample_point;
+	unsigned int fracdiv_l;
+	unsigned int fracdiv_m;
+	unsigned int escape_en;
+	unsigned int guard;
+	unsigned int rx_sel;
+};
+
+struct mt_uart {
+	unsigned long base;
+	struct mt_uart_register registers;
+};
+
+/* external API */
+void mt_uart_save(void);
+void mt_uart_restore(void);
+void mt_console_uart_cg(int on);
+int mt_console_uart_cg_status(void);
+
+#endif /* __UART_H__ */
diff --git a/plat/mediatek/mt8183/include/mcucfg.h b/plat/mediatek/mt8183/include/mcucfg.h
index 83ee88f..6b03818 100644
--- a/plat/mediatek/mt8183/include/mcucfg.h
+++ b/plat/mediatek/mt8183/include/mcucfg.h
@@ -28,51 +28,141 @@
 	uint32_t mp0_rw_rsvd0;			/* 0x6C */
 	uint32_t mp0_rw_rsvd1;			/* 0x70 */
 	uint32_t mp0_ro_rsvd;			/* 0x74 */
-	uint32_t reserved0_0[98];		/* 0x78 */
-	uint32_t mp1_ca7l_cache_config;		/* 0x200 */
-	uint32_t mp1_miscdbg;			/* 0x204 */
-	uint32_t reserved0_1[9];		/* 0x208 */
-	uint32_t mp1_axi_config;		/* 0x22C */
-	uint32_t mp1_misc_config[10];		/* 0x230 */
-	uint32_t reserved0_2[3];		/* 0x258 */
-	uint32_t mp1_ca7l_misc_config;		/* 0x264 */
-	uint32_t reserved0_3[310];		/* 0x268 */
+	uint32_t reserved0_0;			/* 0x78 */
+	uint32_t mp0_l2_cache_parity1_rdata;	/* 0x7C */
+	uint32_t mp0_l2_cache_parity2_rdata;	/* 0x80 */
+	uint32_t reserved0_1;			/* 0x84 */
+	uint32_t mp0_rgu_dcm_config;		/* 0x88 */
+	uint32_t mp0_ca53_specific_ctrl;	/* 0x8C */
+	uint32_t mp0_esr_case;			/* 0x90 */
+	uint32_t mp0_esr_mask;			/* 0x94 */
+	uint32_t mp0_esr_trig_en;		/* 0x98 */
+	uint32_t reserved_0_2;			/* 0x9C */
+	uint32_t mp0_ses_cg_en;			/* 0xA0 */
+	uint32_t reserved0_3[216];		/* 0xA4 */
+	uint32_t mp_dbg_ctrl;			/* 0x404 */
+	uint32_t reserved0_4[34];		/* 0x408 */
+	uint32_t mp_dfd_ctrl;			/* 0x490 */
+	uint32_t dfd_cnt_l;			/* 0x494 */
+	uint32_t dfd_cnt_h;			/* 0x498 */
+	uint32_t misccfg_ro_rsvd;		/* 0x49C */
+	uint32_t reserved0_5[24];		/* 0x4A0 */
+	uint32_t mp1_rst_status;		/* 0x500 */
+	uint32_t mp1_dbg_ctrl;			/* 0x504 */
+	uint32_t mp1_dbg_flag;			/* 0x508 */
+	uint32_t mp1_ca7l_ir_mon;		/* 0x50C */
+	uint32_t reserved0_6[32];		/* 0x510 */
+	uint32_t mcusys_dbg_mon_sel_a;		/* 0x590 */
+	uint32_t mcucys_dbg_mon;		/* 0x594 */
+	uint32_t misccfg_sec_voi_status0;	/* 0x598 */
+	uint32_t misccfg_sec_vio_status1;	/* 0x59C */
+	uint32_t reserved0_7[18];		/* 0x5A0 */
+	uint32_t gic500_int_mask;		/* 0x5E8 */
+	uint32_t core_rst_en_latch;		/* 0x5EC */
+	uint32_t reserved0_8[3];		/* 0x5F0 */
+	uint32_t dbg_core_ret;			/* 0x5FC */
+	uint32_t mcusys_config_a;		/* 0x600 */
+	uint32_t mcusys_config1_a;		/* 0x604 */
+	uint32_t mcusys_gic_prebase_a;		/* 0x608 */
+	uint32_t mcusys_pinmux;			/* 0x60C */
+	uint32_t sec_range0_start;		/* 0x610 */
+	uint32_t sec_range0_end;		/* 0x614 */
+	uint32_t sec_range_enable;		/* 0x618 */
+	uint32_t l2c_mm_base;			/* 0x61C */
+	uint32_t reserved0_9[8];		/* 0x620 */
+	uint32_t aclken_div;			/* 0x640 */
+	uint32_t pclken_div;			/* 0x644 */
+	uint32_t l2c_sram_ctrl;			/* 0x648 */
+	uint32_t armpll_jit_ctrl;		/* 0x64C */
+	uint32_t cci_addrmap;			/* 0x650 */
+	uint32_t cci_config;			/* 0x654 */
+	uint32_t cci_periphbase;		/* 0x658 */
+	uint32_t cci_nevntcntovfl;		/* 0x65C */
+	uint32_t cci_clk_ctrl;			/* 0x660 */
+	uint32_t cci_acel_s1_ctrl;		/* 0x664 */
+	uint32_t mcusys_bus_fabric_dcm_ctrl;	/* 0x668 */
+	uint32_t mcu_misc_dcm_ctrl;		/* 0x66C */
+	uint32_t xgpt_ctl;			/* 0x670 */
+	uint32_t xgpt_idx;			/* 0x674 */
+	uint32_t reserved0_10[3];		/* 0x678 */
+	uint32_t mcusys_rw_rsvd0;		/* 0x684 */
+	uint32_t mcusys_rw_rsvd1;		/* 0x688 */
+	uint32_t reserved0_11[13];		/* 0x68C */
+	uint32_t gic_500_delsel_ctl;		/* 0x6C0 */
+	uint32_t etb_delsel_ctl;		/* 0x6C4 */
+	uint32_t etb_rst_ctl;			/* 0x6C8 */
+	uint32_t reserved0_12[29];		/* 0x6CC */
 	uint32_t cci_adb400_dcm_config;		/* 0x740 */
 	uint32_t sync_dcm_config;		/* 0x744 */
-	uint32_t reserved0_4[16];		/* 0x748 */
-	uint32_t mp0_cputop_spmc_ctl;		/* 0x788 */
-	uint32_t mp1_cputop_spmc_ctl;		/* 0x78C */
-	uint32_t mp1_cputop_spmc_sram_ctl;	/* 0x790 */
-	uint32_t reserved0_5[23];		/* 0x794 */
+	uint32_t reserved0_13;			/* 0x748 */
+	uint32_t sync_dcm_cluster_config;	/* 0x74C */
+	uint32_t sw_udi;			/* 0x750 */
+	uint32_t reserved0_14;			/* 0x754 */
+	uint32_t gic_sync_dcm;			/* 0x758 */
+	uint32_t big_dbg_pwr_ctrl;		/* 0x75C */
+	uint32_t gic_cpu_periphbase;		/* 0x760 */
+	uint32_t axi_cpu_config;		/* 0x764 */
+	uint32_t reserved0_15[2];		/* 0x768 */
+	uint32_t mcsib_sys_ctrl1;		/* 0x770 */
+	uint32_t mcsib_sys_ctrl2;		/* 0x774 */
+	uint32_t mcsib_sys_ctrl3;		/* 0x778 */
+	uint32_t mcsib_sys_ctrl4;		/* 0x77C */
+	uint32_t mcsib_dbg_ctrl1;		/* 0x780 */
+	uint32_t pwrmcu_apb2to1;		/* 0x784 */
+	uint32_t mp0_spmc;			/* 0x788 */
+	uint32_t reserved0_16;			/* 0x78C */
+	uint32_t mp0_spmc_sram_ctl;		/* 0x790 */
+	uint32_t reserved0_17;			/* 0x794 */
+	uint32_t mp0_sw_rst_wait_cycle;		/* 0x798 */
+	uint32_t reserved0_18;			/* 0x79C */
+	uint32_t mp0_pll_divider_cfg;		/* 0x7A0 */
+	uint32_t reserved0_19;			/* 0x7A4 */
+	uint32_t mp2_pll_divider_cfg;		/* 0x7A8 */
+	uint32_t reserved0_20[5];		/* 0x7AC */
+	uint32_t bus_pll_divider_cfg;		/* 0x7C0 */
+	uint32_t reserved0_21[7];		/* 0x7C4 */
+	uint32_t clusterid_aff1;		/* 0x7E0 */
+	uint32_t clusterid_aff2;		/* 0x7E4 */
+	uint32_t reserved0_22[2];		/* 0x7E8 */
 	uint32_t l2_cfg_mp0;			/* 0x7F0 */
 	uint32_t l2_cfg_mp1;			/* 0x7F4 */
-	uint32_t reserved0_6[1282];		/* 0x7F8 */
+	uint32_t reserved0_23[218];		/* 0x7F8 */
+	uint32_t mscib_dcm_en;			/* 0xB60 */
+	uint32_t reserved0_24[1063];		/* 0xB64 */
 	uint32_t cpusys0_sparkvretcntrl;	/* 0x1C00 */
 	uint32_t cpusys0_sparken;		/* 0x1C04 */
 	uint32_t cpusys0_amuxsel;		/* 0x1C08 */
-	uint32_t reserved0_7[9];		/* 0x1C0C */
+	uint32_t reserved0_25[9];		/* 0x1C0C */
 	uint32_t cpusys0_cpu0_spmc_ctl;		/* 0x1C30 */
 	uint32_t cpusys0_cpu1_spmc_ctl;		/* 0x1C34 */
 	uint32_t cpusys0_cpu2_spmc_ctl;		/* 0x1C38 */
 	uint32_t cpusys0_cpu3_spmc_ctl;		/* 0x1C3C */
-	uint32_t reserved0_8[370];		/* 0x1C40 */
+	uint32_t reserved0_26[8];		/* 0x1C40 */
+	uint32_t mp0_sync_dcm_cgavg_ctrl;	/* 0x1C60 */
+	uint32_t mp0_sync_dcm_cgavg_fact;	/* 0x1C64 */
+	uint32_t mp0_sync_dcm_cgavg_rfact;	/* 0x1C68 */
+	uint32_t mp0_sync_dcm_cgavg;		/* 0x1C6C */
+	uint32_t mp0_l2_parity_clr;		/* 0x1C70 */
+	uint32_t reserved0_27[357];		/* 0x1C74 */
 	uint32_t mp2_cpucfg;			/* 0x2208 */
 	uint32_t mp2_axi_config;		/* 0x220C */
-	uint32_t reserved0_9[36];		/* 0x2210 */
-	uint32_t mp2_cputop_spm_ctl;		/* 0x22A0 */
-	uint32_t mp2_cputop_spm_sta;		/* 0x22A4 */
-	uint32_t reserved0_10[98];		/* 0x22A8 */
-	uint32_t cpusys2_cpu0_spmc_ctl;		/* 0x2430 */
-	uint32_t cpusys2_cpu0_spmc_sta;		/* 0x2434 */
-	uint32_t cpusys2_cpu1_spmc_ctl;		/* 0x2438 */
-	uint32_t cpusys2_cpu1_spmc_sta;		/* 0x243C */
-	uint32_t reserved0_11[176];		/* 0x2440 */
+	uint32_t reserved0_28[25];		/* 0x2210 */
+	uint32_t mp2_sync_dcm;			/* 0x2274 */
+	uint32_t reserved0_29[10];		/* 0x2278 */
+	uint32_t ptp3_cputop_spmc0;		/* 0x22A0 */
+	uint32_t ptp3_cputop_spmc1;		/* 0x22A4 */
+	uint32_t reserved0_30[98];		/* 0x22A8 */
+	uint32_t ptp3_cpu0_spmc0;		/* 0x2430 */
+	uint32_t ptp3_cpu0_spmc1;		/* 0x2434 */
+	uint32_t ptp3_cpu1_spmc0;		/* 0x2438 */
+	uint32_t ptp3_cpu1_spmc1;		/* 0x243C */
+	uint32_t ptp3_cpu2_spmc0;		/* 0x2440 */
+	uint32_t ptp3_cpu2_spmc1;		/* 0x2444 */
+	uint32_t ptp3_cpu3_spmc0;		/* 0x2448 */
+	uint32_t ptp3_cpu3_spmc1;		/* 0x244C */
+	uint32_t ptp3_cpux_spmc;		/* 0x2450 */
+	uint32_t reserved0_31[171];		/* 0x2454 */
 	uint32_t spark2ld0;			/* 0x2700 */
-	uint32_t reserved0_12[1355];		/* 0x2704 */
-	uint32_t cpusys1_cpu0_spmc_ctl;		/* 0x3C30 */
-	uint32_t cpusys1_cpu1_spmc_ctl;		/* 0x3C34 */
-	uint32_t cpusys1_cpu2_spmc_ctl;		/* 0x3C38 */
-	uint32_t cpusys1_cpu3_spmc_ctl;		/* 0x3C3C */
 };
 
 static struct mt8183_mcucfg_regs *const mt8183_mcucfg = (void *)MCUCFG_BASE;
@@ -244,4 +334,235 @@
 	MP1_L2RSTDISABLE = 1 << MP1_L2RSTDISABLE_SHIFT
 };
 
+/* bus pll divider dcm related */
+enum {
+	BUS_PLLDIVIDER_DCM_DBC_CNT_0_SHIFT = 11,
+	BUS_PLLDIV_ARMWFI_DCM_EN_SHIFT = 24,
+	BUS_PLLDIV_ARMWFE_DCM_EN_SHIFT = 25,
+
+	BUS_PLLDIV_DCM = (1 << BUS_PLLDIVIDER_DCM_DBC_CNT_0_SHIFT) |
+			 (1 << BUS_PLLDIV_ARMWFI_DCM_EN_SHIFT) |
+			 (1 << BUS_PLLDIV_ARMWFE_DCM_EN_SHIFT)
+};
+
+/* mp0 pll divider dcm related */
+enum {
+	MP0_PLLDIV_DCM_DBC_CNT_0_SHIFT = 11,
+	MP0_PLLDIV_ARMWFI_DCM_EN_SHIFT = 24,
+	MP0_PLLDIV_ARMWFE_DCM_EN_SHIFT = 25,
+	MP0_PLLDIV_LASTCORE_IDLE_EN_SHIFT = 31,
+	MP0_PLLDIV_DCM = (1 << MP0_PLLDIV_DCM_DBC_CNT_0_SHIFT) |
+			 (1 << MP0_PLLDIV_ARMWFI_DCM_EN_SHIFT) |
+			 (1 << MP0_PLLDIV_ARMWFE_DCM_EN_SHIFT) |
+			 (1u << MP0_PLLDIV_LASTCORE_IDLE_EN_SHIFT)
+};
+
+/* mp2 pll divider dcm related */
+enum {
+	MP2_PLLDIV_DCM_DBC_CNT_0_SHIFT = 11,
+	MP2_PLLDIV_ARMWFI_DCM_EN_SHIFT = 24,
+	MP2_PLLDIV_ARMWFE_DCM_EN_SHIFT = 25,
+	MP2_PLLDIV_LASTCORE_IDLE_EN_SHIFT = 31,
+	MP2_PLLDIV_DCM = (1 << MP2_PLLDIV_DCM_DBC_CNT_0_SHIFT) |
+			 (1 << MP2_PLLDIV_ARMWFI_DCM_EN_SHIFT) |
+			 (1 << MP2_PLLDIV_ARMWFE_DCM_EN_SHIFT) |
+			 (1u << MP2_PLLDIV_LASTCORE_IDLE_EN_SHIFT)
+};
+
+/* mcsib dcm related */
+enum {
+	MCSIB_CACTIVE_SEL_SHIFT = 0,
+	MCSIB_DCM_EN_SHIFT = 16,
+
+	MCSIB_CACTIVE_SEL_MASK = 0xffff << MCSIB_CACTIVE_SEL_SHIFT,
+	MCSIB_CACTIVE_SEL = 0xffff << MCSIB_CACTIVE_SEL_SHIFT,
+
+	MCSIB_DCM_MASK = 0xffffu << MCSIB_DCM_EN_SHIFT,
+	MCSIB_DCM = 0xffffu << MCSIB_DCM_EN_SHIFT,
+};
+
+/* cci adb400 dcm related */
+enum {
+	CCI_M0_ADB400_DCM_EN_SHIFT = 0,
+	CCI_M1_ADB400_DCM_EN_SHIFT = 1,
+	CCI_M2_ADB400_DCM_EN_SHIFT = 2,
+	CCI_S2_ADB400_DCM_EN_SHIFT = 3,
+	CCI_S3_ADB400_DCM_EN_SHIFT = 4,
+	CCI_S4_ADB400_DCM_EN_SHIFT = 5,
+	CCI_S5_ADB400_DCM_EN_SHIFT = 6,
+	ACP_S3_ADB400_DCM_EN_SHIFT = 11,
+
+	CCI_ADB400_DCM_MASK = (1 << CCI_M0_ADB400_DCM_EN_SHIFT) |
+			      (1 << CCI_M1_ADB400_DCM_EN_SHIFT) |
+			      (1 << CCI_M2_ADB400_DCM_EN_SHIFT) |
+			      (1 << CCI_S2_ADB400_DCM_EN_SHIFT) |
+			      (1 << CCI_S4_ADB400_DCM_EN_SHIFT) |
+			      (1 << CCI_S4_ADB400_DCM_EN_SHIFT) |
+			      (1 << CCI_S5_ADB400_DCM_EN_SHIFT) |
+			      (1 << ACP_S3_ADB400_DCM_EN_SHIFT),
+	CCI_ADB400_DCM = (1 << CCI_M0_ADB400_DCM_EN_SHIFT) |
+			 (1 << CCI_M1_ADB400_DCM_EN_SHIFT) |
+			 (1 << CCI_M2_ADB400_DCM_EN_SHIFT) |
+			 (0 << CCI_S2_ADB400_DCM_EN_SHIFT) |
+			 (0 << CCI_S4_ADB400_DCM_EN_SHIFT) |
+			 (0 << CCI_S4_ADB400_DCM_EN_SHIFT) |
+			 (0 << CCI_S5_ADB400_DCM_EN_SHIFT) |
+			 (1 << ACP_S3_ADB400_DCM_EN_SHIFT)
+};
+
+/* sync dcm related */
+enum {
+	CCI_SYNC_DCM_DIV_EN_SHIFT = 0,
+	CCI_SYNC_DCM_UPDATE_TOG_SHIFT = 1,
+	CCI_SYNC_DCM_DIV_SEL_SHIFT = 2,
+	MP0_SYNC_DCM_DIV_EN_SHIFT = 10,
+	MP0_SYNC_DCM_UPDATE_TOG_SHIFT = 11,
+	MP0_SYNC_DCM_DIV_SEL_SHIFT = 12,
+
+	SYNC_DCM_MASK = (1 << CCI_SYNC_DCM_DIV_EN_SHIFT) |
+			(1 << CCI_SYNC_DCM_UPDATE_TOG_SHIFT) |
+			(0x7f << CCI_SYNC_DCM_DIV_SEL_SHIFT) |
+			(1 << MP0_SYNC_DCM_DIV_EN_SHIFT) |
+			(1 << MP0_SYNC_DCM_UPDATE_TOG_SHIFT) |
+			(0x7f << MP0_SYNC_DCM_DIV_SEL_SHIFT),
+	SYNC_DCM = (1 << CCI_SYNC_DCM_DIV_EN_SHIFT) |
+		   (1 << CCI_SYNC_DCM_UPDATE_TOG_SHIFT) |
+		   (0 << CCI_SYNC_DCM_DIV_SEL_SHIFT) |
+		   (1 << MP0_SYNC_DCM_DIV_EN_SHIFT) |
+		   (1 << MP0_SYNC_DCM_UPDATE_TOG_SHIFT) |
+		   (0 << MP0_SYNC_DCM_DIV_SEL_SHIFT)
+};
+
+/* mcu bus dcm related */
+enum {
+	MCU_BUS_DCM_EN_SHIFT = 8,
+	MCU_BUS_DCM = 1 << MCU_BUS_DCM_EN_SHIFT
+};
+
+/* mcusys bus fabric dcm related */
+enum {
+	ACLK_INFRA_DYNAMIC_CG_EN_SHIFT = 0,
+	EMI2_ADB400_S_DCM_CTRL_SHIFT = 1,
+	ACLK_GPU_DYNAMIC_CG_EN_SHIFT = 2,
+	ACLK_PSYS_DYNAMIC_CG_EN_SHIFT = 3,
+	MP0_ADB400_S_DCM_CTRL_SHIFT = 4,
+	MP0_ADB400_M_DCM_CTRL_SHIFT = 5,
+	MP1_ADB400_S_DCM_CTRL_SHIFT = 6,
+	MP1_ADB400_M_DCM_CTRL_SHIFT = 7,
+	EMICLK_EMI_DYNAMIC_CG_EN_SHIFT = 8,
+	INFRACLK_INFRA_DYNAMIC_CG_EN_SHIFT = 9,
+	EMICLK_GPU_DYNAMIC_CG_EN_SHIFT = 10,
+	INFRACLK_PSYS_DYNAMIC_CG_EN_SHIFT = 11,
+	EMICLK_EMI1_DYNAMIC_CG_EN_SHIFT = 12,
+	EMI1_ADB400_S_DCM_CTRL_SHIFT = 16,
+	MP2_ADB400_M_DCM_CTRL_SHIFT = 17,
+	MP0_ICC_AXI_STREAM_ARCH_CG_SHIFT = 18,
+	MP1_ICC_AXI_STREAM_ARCH_CG_SHIFT = 19,
+	MP2_ICC_AXI_STREAM_ARCH_CG_SHIFT = 20,
+	L2_SHARE_ADB400_DCM_CTRL_SHIFT = 21,
+	MP1_AGGRESS_DCM_CTRL_SHIFT = 22,
+	MP0_AGGRESS_DCM_CTRL_SHIFT = 23,
+	MP0_ADB400_ACP_S_DCM_CTRL_SHIFT = 24,
+	MP0_ADB400_ACP_M_DCM_CTRL_SHIFT = 25,
+	MP1_ADB400_ACP_S_DCM_CTRL_SHIFT = 26,
+	MP1_ADB400_ACP_M_DCM_CTRL_SHIFT = 27,
+	MP3_ADB400_M_DCM_CTRL_SHIFT = 28,
+	MP3_ICC_AXI_STREAM_ARCH_CG_SHIFT = 29,
+
+	MCUSYS_BUS_FABRIC_DCM_MASK = (1 << ACLK_INFRA_DYNAMIC_CG_EN_SHIFT) |
+				     (1 << EMI2_ADB400_S_DCM_CTRL_SHIFT) |
+				     (1 << ACLK_GPU_DYNAMIC_CG_EN_SHIFT) |
+				     (1 << ACLK_PSYS_DYNAMIC_CG_EN_SHIFT) |
+				     (1 << MP0_ADB400_S_DCM_CTRL_SHIFT) |
+				     (1 << MP0_ADB400_M_DCM_CTRL_SHIFT) |
+				     (1 << MP1_ADB400_S_DCM_CTRL_SHIFT) |
+				     (1 << MP1_ADB400_M_DCM_CTRL_SHIFT) |
+				     (1 << EMICLK_EMI_DYNAMIC_CG_EN_SHIFT) |
+				     (1 << INFRACLK_INFRA_DYNAMIC_CG_EN_SHIFT) |
+				     (1 << EMICLK_GPU_DYNAMIC_CG_EN_SHIFT) |
+				     (1 << INFRACLK_PSYS_DYNAMIC_CG_EN_SHIFT) |
+				     (1 << EMICLK_EMI1_DYNAMIC_CG_EN_SHIFT) |
+				     (1 << EMI1_ADB400_S_DCM_CTRL_SHIFT) |
+				     (1 << MP2_ADB400_M_DCM_CTRL_SHIFT) |
+				     (1 << MP0_ICC_AXI_STREAM_ARCH_CG_SHIFT) |
+				     (1 << MP1_ICC_AXI_STREAM_ARCH_CG_SHIFT) |
+				     (1 << MP2_ICC_AXI_STREAM_ARCH_CG_SHIFT) |
+				     (1 << L2_SHARE_ADB400_DCM_CTRL_SHIFT) |
+				     (1 << MP1_AGGRESS_DCM_CTRL_SHIFT) |
+				     (1 << MP0_AGGRESS_DCM_CTRL_SHIFT) |
+				     (1 << MP0_ADB400_ACP_S_DCM_CTRL_SHIFT) |
+				     (1 << MP0_ADB400_ACP_M_DCM_CTRL_SHIFT) |
+				     (1 << MP1_ADB400_ACP_S_DCM_CTRL_SHIFT) |
+				     (1 << MP1_ADB400_ACP_M_DCM_CTRL_SHIFT) |
+				     (1 << MP3_ADB400_M_DCM_CTRL_SHIFT) |
+				     (1 << MP3_ICC_AXI_STREAM_ARCH_CG_SHIFT),
+
+	MCUSYS_BUS_FABRIC_DCM = (1 << ACLK_INFRA_DYNAMIC_CG_EN_SHIFT) |
+				(1 << EMI2_ADB400_S_DCM_CTRL_SHIFT) |
+				(1 << ACLK_GPU_DYNAMIC_CG_EN_SHIFT) |
+				(1 << ACLK_PSYS_DYNAMIC_CG_EN_SHIFT) |
+				(0 << MP0_ADB400_S_DCM_CTRL_SHIFT) |
+				(0 << MP0_ADB400_M_DCM_CTRL_SHIFT) |
+				(1 << MP1_ADB400_S_DCM_CTRL_SHIFT) |
+				(1 << MP1_ADB400_M_DCM_CTRL_SHIFT) |
+				(1 << EMICLK_EMI_DYNAMIC_CG_EN_SHIFT) |
+				(1 << INFRACLK_INFRA_DYNAMIC_CG_EN_SHIFT) |
+				(1 << EMICLK_GPU_DYNAMIC_CG_EN_SHIFT) |
+				(1 << INFRACLK_PSYS_DYNAMIC_CG_EN_SHIFT) |
+				(1 << EMICLK_EMI1_DYNAMIC_CG_EN_SHIFT) |
+				(1 << EMI1_ADB400_S_DCM_CTRL_SHIFT) |
+				(0 << MP2_ADB400_M_DCM_CTRL_SHIFT) |
+				(1 << MP0_ICC_AXI_STREAM_ARCH_CG_SHIFT) |
+				(1 << MP1_ICC_AXI_STREAM_ARCH_CG_SHIFT) |
+				(1 << MP2_ICC_AXI_STREAM_ARCH_CG_SHIFT) |
+				(1 << L2_SHARE_ADB400_DCM_CTRL_SHIFT) |
+				(1 << MP1_AGGRESS_DCM_CTRL_SHIFT) |
+				(1 << MP0_AGGRESS_DCM_CTRL_SHIFT) |
+				(1 << MP0_ADB400_ACP_S_DCM_CTRL_SHIFT) |
+				(1 << MP0_ADB400_ACP_M_DCM_CTRL_SHIFT) |
+				(1 << MP1_ADB400_ACP_S_DCM_CTRL_SHIFT) |
+				(1 << MP1_ADB400_ACP_M_DCM_CTRL_SHIFT) |
+				(1 << MP3_ADB400_M_DCM_CTRL_SHIFT) |
+				(1 << MP3_ICC_AXI_STREAM_ARCH_CG_SHIFT)
+};
+
+/* l2c_sram dcm related */
+enum {
+	L2C_SRAM_DCM_EN_SHIFT = 0,
+	L2C_SRAM_DCM = 1 << L2C_SRAM_DCM_EN_SHIFT
+};
+
+/* mcu misc dcm related */
+enum {
+	MP0_CNTVALUEB_DCM_EN_SHIFT = 0,
+	MP_CNTVALUEB_DCM_EN = 8,
+
+	CNTVALUEB_DCM = (1 << MP0_CNTVALUEB_DCM_EN_SHIFT) |
+			(1 << MP_CNTVALUEB_DCM_EN)
+};
+
+/* sync dcm cluster config related */
+enum {
+	MP0_SYNC_DCM_STALL_WR_EN_SHIFT = 7,
+	MCUSYS_MAX_ACCESS_LATENCY_SHIFT = 24,
+
+	MCU0_SYNC_DCM_STALL_WR_EN = 1 << MP0_SYNC_DCM_STALL_WR_EN_SHIFT,
+
+	MCUSYS_MAX_ACCESS_LATENCY_MASK = 0xf << MCUSYS_MAX_ACCESS_LATENCY_SHIFT,
+	MCUSYS_MAX_ACCESS_LATENCY = 0x5 << MCUSYS_MAX_ACCESS_LATENCY_SHIFT
+};
+
+/* cpusys rgu dcm related */
+enum {
+	CPUSYS_RGU_DCM_CONFIG_SHIFT = 0,
+
+	CPUSYS_RGU_DCM_CINFIG = 1 << CPUSYS_RGU_DCM_CONFIG_SHIFT
+};
+
+/* mp2 sync dcm related */
+enum {
+	MP2_DCM_EN_SHIFT = 0,
+
+	MP2_DCM_EN = 1 << MP2_DCM_EN_SHIFT
+};
 #endif  /* MT8183_MCUCFG_H */
diff --git a/plat/mediatek/mt8183/include/plat_debug.h b/plat/mediatek/mt8183/include/plat_debug.h
index e51a6ea..c9d73cc 100644
--- a/plat/mediatek/mt8183/include/plat_debug.h
+++ b/plat/mediatek/mt8183/include/plat_debug.h
@@ -24,8 +24,6 @@
 #define BIT_CA15M_L2PARITY_EN		(1 << 1)
 #define BIT_CA15M_LASTPC_DIS		(1 << 8)
 
-#define MP1_CPUTOP_PWR_CON		0x10006218
-
 #define MCU_ALL_PWR_ON_CTRL		0x0c530b58
 #define PLAT_MTK_CIRCULAR_BUFFER_UNLOCK	0xefab4133
 #define PLAT_MTK_CIRCULAR_BUFFER_LOCK	0xefab4134
diff --git a/plat/mediatek/mt8183/include/platform_def.h b/plat/mediatek/mt8183/include/platform_def.h
index f802ac2..766e766 100644
--- a/plat/mediatek/mt8183/include/platform_def.h
+++ b/plat/mediatek/mt8183/include/platform_def.h
@@ -41,6 +41,7 @@
 #define APMIXEDSYS         (IO_PHYS + 0xC000)
 #define ARMPLL_LL_CON0     (APMIXEDSYS + 0x200)
 #define ARMPLL_L_CON0      (APMIXEDSYS + 0x210)
+#define ARMPLL_L_PWR_CON0  (APMIXEDSYS + 0x21c)
 #define MAINPLL_CON0       (APMIXEDSYS + 0x220)
 #define CCIPLL_CON0        (APMIXEDSYS + 0x290)
 
@@ -74,6 +75,7 @@
 #define MT_L2_WRITE_ACCESS_RATE  (MCUCFG_BASE + 0x604)
 #define MP0_CA7L_CACHE_CONFIG    (MCUCFG_BASE + 0x7f0)
 #define MP1_CA7L_CACHE_CONFIG    (MCUCFG_BASE + 0x7f4)
+#define EMI_WFIFO                (MCUCFG_BASE + 0x0b5c)
 
 /*******************************************************************************
  * GIC related constants
@@ -87,6 +89,7 @@
  * UART related constants
  ******************************************************************************/
 #define UART0_BASE    (IO_PHYS + 0x01002000)
+#define UART1_BASE    (IO_PHYS + 0x01003000)
 
 #define UART_BAUDRATE 115200
 #define UART_CLOCK    26000000
diff --git a/plat/mediatek/mt8183/include/spm.h b/plat/mediatek/mt8183/include/spm.h
deleted file mode 100644
index 208d760..0000000
--- a/plat/mediatek/mt8183/include/spm.h
+++ /dev/null
@@ -1,1715 +0,0 @@
-/*
- * Copyright (c) 2019, MediaTek Inc. All rights reserved.
- *
- * SPDX-License-Identifier: BSD-3-Clause
- */
-
-#ifndef SPM_H
-#define SPM_H
-
-#define POWERON_CONFIG_EN		(SPM_BASE + 0x000)
-#define SPM_POWER_ON_VAL0		(SPM_BASE + 0x004)
-#define SPM_POWER_ON_VAL1		(SPM_BASE + 0x008)
-#define SPM_CLK_CON			(SPM_BASE + 0x00C)
-#define SPM_CLK_SETTLE			(SPM_BASE + 0x010)
-#define SPM_AP_STANDBY_CON		(SPM_BASE + 0x014)
-#define PCM_CON0			(SPM_BASE + 0x018)
-#define PCM_CON1			(SPM_BASE + 0x01C)
-#define PCM_IM_PTR			(SPM_BASE + 0x020)
-#define PCM_IM_LEN			(SPM_BASE + 0x024)
-#define PCM_REG_DATA_INI		(SPM_BASE + 0x028)
-#define PCM_PWR_IO_EN			(SPM_BASE + 0x02C)
-#define PCM_TIMER_VAL			(SPM_BASE + 0x030)
-#define PCM_WDT_VAL			(SPM_BASE + 0x034)
-#define PCM_IM_HOST_RW_PTR		(SPM_BASE + 0x038)
-#define PCM_IM_HOST_RW_DAT		(SPM_BASE + 0x03C)
-#define PCM_EVENT_VECTOR0		(SPM_BASE + 0x040)
-#define PCM_EVENT_VECTOR1		(SPM_BASE + 0x044)
-#define PCM_EVENT_VECTOR2		(SPM_BASE + 0x048)
-#define PCM_EVENT_VECTOR3		(SPM_BASE + 0x04C)
-#define PCM_EVENT_VECTOR4		(SPM_BASE + 0x050)
-#define PCM_EVENT_VECTOR5		(SPM_BASE + 0x054)
-#define PCM_EVENT_VECTOR6		(SPM_BASE + 0x058)
-#define PCM_EVENT_VECTOR7		(SPM_BASE + 0x05C)
-#define PCM_EVENT_VECTOR8		(SPM_BASE + 0x060)
-#define PCM_EVENT_VECTOR9		(SPM_BASE + 0x064)
-#define PCM_EVENT_VECTOR10		(SPM_BASE + 0x068)
-#define PCM_EVENT_VECTOR11		(SPM_BASE + 0x06C)
-#define PCM_EVENT_VECTOR12		(SPM_BASE + 0x070)
-#define PCM_EVENT_VECTOR13		(SPM_BASE + 0x074)
-#define PCM_EVENT_VECTOR14		(SPM_BASE + 0x078)
-#define PCM_EVENT_VECTOR15		(SPM_BASE + 0x07C)
-#define PCM_EVENT_VECTOR_EN		(SPM_BASE + 0x080)
-#define SPM_SWINT			(SPM_BASE + 0x08C)
-#define SPM_SWINT_SET			(SPM_BASE + 0x090)
-#define SPM_SWINT_CLR			(SPM_BASE + 0x094)
-#define SPM_SCP_MAILBOX			(SPM_BASE + 0x098)
-#define SPM_SCP_IRQ			(SPM_BASE + 0x09C)
-#define SPM_TWAM_CON			(SPM_BASE + 0x0A0)
-#define SPM_TWAM_WINDOW_LEN		(SPM_BASE + 0x0A4)
-#define SPM_TWAM_IDLE_SEL		(SPM_BASE + 0x0A8)
-#define SPM_CPU_WAKEUP_EVENT		(SPM_BASE + 0x0B0)
-#define SPM_IRQ_MASK			(SPM_BASE + 0x0B4)
-#define SPM_SRC_REQ			(SPM_BASE + 0x0B8)
-#define SPM_SRC_MASK			(SPM_BASE + 0x0BC)
-#define SPM_SRC2_MASK			(SPM_BASE + 0x0C0)
-#define SPM_WAKEUP_EVENT_MASK		(SPM_BASE + 0x0C4)
-#define SPM_WAKEUP_EVENT_EXT_MASK	(SPM_BASE + 0x0C8)
-#define SCP_CLK_CON			(SPM_BASE + 0x0D0)
-#define PCM_DEBUG_CON			(SPM_BASE + 0x0D4)
-#define PCM_REG0_DATA			(SPM_BASE + 0x100)
-#define PCM_REG1_DATA			(SPM_BASE + 0x104)
-#define PCM_REG2_DATA			(SPM_BASE + 0x108)
-#define PCM_REG3_DATA			(SPM_BASE + 0x10C)
-#define PCM_REG4_DATA			(SPM_BASE + 0x110)
-#define PCM_REG5_DATA			(SPM_BASE + 0x114)
-#define PCM_REG6_DATA			(SPM_BASE + 0x118)
-#define PCM_REG7_DATA			(SPM_BASE + 0x11C)
-#define PCM_REG8_DATA			(SPM_BASE + 0x120)
-#define PCM_REG9_DATA			(SPM_BASE + 0x124)
-#define PCM_REG10_DATA			(SPM_BASE + 0x128)
-#define PCM_REG11_DATA			(SPM_BASE + 0x12C)
-#define PCM_REG12_DATA			(SPM_BASE + 0x130)
-#define PCM_REG13_DATA			(SPM_BASE + 0x134)
-#define PCM_REG14_DATA			(SPM_BASE + 0x138)
-#define PCM_REG15_DATA			(SPM_BASE + 0x13C)
-#define PCM_REG12_MASK_B_STA		(SPM_BASE + 0x140)
-#define PCM_REG12_EXT_DATA		(SPM_BASE + 0x144)
-#define PCM_REG12_EXT_MASK_B_STA	(SPM_BASE + 0x148)
-#define PCM_EVENT_REG_STA		(SPM_BASE + 0x14C)
-#define PCM_TIMER_OUT			(SPM_BASE + 0x150)
-#define PCM_WDT_OUT			(SPM_BASE + 0x154)
-#define SPM_IRQ_STA			(SPM_BASE + 0x158)
-#define SPM_WAKEUP_STA			(SPM_BASE + 0x15C)
-#define SPM_WAKEUP_EXT_STA		(SPM_BASE + 0x160)
-#define SPM_WAKEUP_MISC			(SPM_BASE + 0x164)
-#define BUS_PROTECT_RDY			(SPM_BASE + 0x168)
-#define BUS_PROTECT2_RDY		(SPM_BASE + 0x16C)
-#define SUBSYS_IDLE_STA			(SPM_BASE + 0x170)
-#define CPU_IDLE_STA			(SPM_BASE + 0x174)
-#define PCM_FSM_STA			(SPM_BASE + 0x178)
-#define PWR_STATUS			(SPM_BASE + 0x180)
-#define PWR_STATUS_2ND			(SPM_BASE + 0x184)
-#define CPU_PWR_STATUS			(SPM_BASE + 0x188)
-#define CPU_PWR_STATUS_2ND		(SPM_BASE + 0x18C)
-#define PCM_WDT_LATCH_0			(SPM_BASE + 0x190)
-#define PCM_WDT_LATCH_1			(SPM_BASE + 0x194)
-#define PCM_WDT_LATCH_2			(SPM_BASE + 0x198)
-#define DRAMC_DBG_LATCH			(SPM_BASE + 0x19C)
-#define SPM_TWAM_LAST_STA0		(SPM_BASE + 0x1A0)
-#define SPM_TWAM_LAST_STA1		(SPM_BASE + 0x1A4)
-#define SPM_TWAM_LAST_STA2		(SPM_BASE + 0x1A8)
-#define SPM_TWAM_LAST_STA3		(SPM_BASE + 0x1AC)
-#define SPM_TWAM_CURR_STA0		(SPM_BASE + 0x1B0)
-#define SPM_TWAM_CURR_STA1		(SPM_BASE + 0x1B4)
-#define SPM_TWAM_CURR_STA2		(SPM_BASE + 0x1B8)
-#define SPM_TWAM_CURR_STA3		(SPM_BASE + 0x1BC)
-#define SPM_TWAM_TIMER_OUT		(SPM_BASE + 0x1C0)
-#define PCM_WDT_LATCH_3			(SPM_BASE + 0x1C4)
-#define SPM_SRC_RDY_STA			(SPM_BASE + 0x1D0)
-#define MISC_STA			(SPM_BASE + 0x1D4)
-#define MCU_PWR_CON			(SPM_BASE + 0x200)
-#define MP0_CPUTOP_PWR_CON		(SPM_BASE + 0x204)
-#define MP0_CPU0_PWR_CON		(SPM_BASE + 0x208)
-#define MP0_CPU1_PWR_CON		(SPM_BASE + 0x20C)
-#define MP0_CPU2_PWR_CON		(SPM_BASE + 0x210)
-#define MP0_CPU3_PWR_CON		(SPM_BASE + 0x214)
-#define MP1_CPUTOP_PWR_CON		(SPM_BASE + 0x218)
-#define MP1_CPU0_PWR_CON		(SPM_BASE + 0x21C)
-#define MP1_CPU1_PWR_CON		(SPM_BASE + 0x220)
-#define MP1_CPU2_PWR_CON		(SPM_BASE + 0x224)
-#define MP1_CPU3_PWR_CON		(SPM_BASE + 0x228)
-#define MP0_CPUTOP_L2_PDN		(SPM_BASE + 0x240)
-#define MP0_CPUTOP_L2_SLEEP_B		(SPM_BASE + 0x244)
-#define MP0_CPU0_L1_PDN			(SPM_BASE + 0x248)
-#define MP0_CPU1_L1_PDN			(SPM_BASE + 0x24C)
-#define MP0_CPU2_L1_PDN			(SPM_BASE + 0x250)
-#define MP0_CPU3_L1_PDN			(SPM_BASE + 0x254)
-#define MP1_CPUTOP_L2_PDN		(SPM_BASE + 0x258)
-#define MP1_CPUTOP_L2_SLEEP_B		(SPM_BASE + 0x25C)
-#define MP1_CPU0_L1_PDN			(SPM_BASE + 0x260)
-#define MP1_CPU1_L1_PDN			(SPM_BASE + 0x264)
-#define MP1_CPU2_L1_PDN			(SPM_BASE + 0x268)
-#define MP1_CPU3_L1_PDN			(SPM_BASE + 0x26C)
-#define CPU_EXT_BUCK_ISO		(SPM_BASE + 0x290)
-#define DUMMY1_PWR_CON			(SPM_BASE + 0x2B0)
-#define BYPASS_SPMC			(SPM_BASE + 0x2B4)
-#define SPMC_DORMANT_ENABLE		(SPM_BASE + 0x2B8)
-#define ARMPLL_CLK_CON			(SPM_BASE + 0x2BC)
-#define SPMC_IN_RET			(SPM_BASE + 0x2C0)
-#define VDE_PWR_CON			(SPM_BASE + 0x300)
-#define VEN_PWR_CON			(SPM_BASE + 0x304)
-#define ISP_PWR_CON			(SPM_BASE + 0x308)
-#define DIS_PWR_CON			(SPM_BASE + 0x30C)
-#define MJC_PWR_CON			(SPM_BASE + 0x310)
-#define AUDIO_PWR_CON			(SPM_BASE + 0x314)
-#define IFR_PWR_CON			(SPM_BASE + 0x318)
-#define DPY_PWR_CON			(SPM_BASE + 0x31C)
-#define MD1_PWR_CON			(SPM_BASE + 0x320)
-#define MD2_PWR_CON			(SPM_BASE + 0x324)
-#define C2K_PWR_CON			(SPM_BASE + 0x328)
-#define CONN_PWR_CON			(SPM_BASE + 0x32C)
-#define VCOREPDN_PWR_CON		(SPM_BASE + 0x330)
-#define MFG_ASYNC_PWR_CON		(SPM_BASE + 0x334)
-#define MFG_PWR_CON			(SPM_BASE + 0x338)
-#define MFG_CORE0_PWR_CON		(SPM_BASE + 0x33C)
-#define MFG_CORE1_PWR_CON		(SPM_BASE + 0x340)
-#define CAM_PWR_CON			(SPM_BASE + 0x344)
-#define SYSRAM_CON			(SPM_BASE + 0x350)
-#define SYSROM_CON			(SPM_BASE + 0x354)
-#define SCP_SRAM_CON			(SPM_BASE + 0x358)
-#define GCPU_SRAM_CON			(SPM_BASE + 0x35C)
-#define MDSYS_INTF_INFRA_PWR_CON	(SPM_BASE + 0x360)
-#define MDSYS_INTF_MD1_PWR_CON		(SPM_BASE + 0x364)
-#define MDSYS_INTF_C2K_PWR_CON		(SPM_BASE + 0x368)
-#define BSI_TOP_SRAM_CON		(SPM_BASE + 0x370)
-#define DVFSP_SRAM_CON			(SPM_BASE + 0x374)
-#define MD_EXT_BUCK_ISO			(SPM_BASE + 0x390)
-#define DUMMY2_PWR_CON			(SPM_BASE + 0x3B0)
-#define MD1_OUTPUT_PISO_S_EN_IZ		(SPM_BASE + 0x3B4)
-#define SPM_DVFS_CON			(SPM_BASE + 0x400)
-#define SPM_MDBSI_CON			(SPM_BASE + 0x404)
-#define SPM_MAS_PAUSE_MASK_B		(SPM_BASE + 0x408)
-#define SPM_MAS_PAUSE2_MASK_B		(SPM_BASE + 0x40C)
-#define SPM_BSI_GEN			(SPM_BASE + 0x410)
-#define SPM_BSI_EN_SR			(SPM_BASE + 0x414)
-#define SPM_BSI_CLK_SR			(SPM_BASE + 0x418)
-#define SPM_BSI_D0_SR			(SPM_BASE + 0x41C)
-#define SPM_BSI_D1_SR			(SPM_BASE + 0x420)
-#define SPM_BSI_D2_SR			(SPM_BASE + 0x424)
-#define SPM_AP_SEMA			(SPM_BASE + 0x428)
-#define SPM_SPM_SEMA			(SPM_BASE + 0x42C)
-#define AP2MD_CROSS_TRIGGER		(SPM_BASE + 0x430)
-#define AP_MDSRC_REQ			(SPM_BASE + 0x434)
-#define SPM2MD_DVFS_CON			(SPM_BASE + 0x438)
-#define MD2SPM_DVFS_CON			(SPM_BASE + 0x43C)
-#define DRAMC_DPY_CLK_SW_CON_RSV	(SPM_BASE + 0x440)
-#define DPY_LP_CON			(SPM_BASE + 0x444)
-#define CPU_DVFS_REQ			(SPM_BASE + 0x448)
-#define SPM_PLL_CON			(SPM_BASE + 0x44C)
-#define SPM_EMI_BW_MODE			(SPM_BASE + 0x450)
-#define AP2MD_PEER_WAKEUP		(SPM_BASE + 0x454)
-#define ULPOSC_CON			(SPM_BASE + 0x458)
-#define DRAMC_DPY_CLK_SW_CON_SEL	(SPM_BASE + 0x460)
-#define DRAMC_DPY_CLK_SW_CON		(SPM_BASE + 0x464)
-#define DRAMC_DPY_CLK_SW_CON_SEL2	(SPM_BASE + 0x470)
-#define DRAMC_DPY_CLK_SW_CON2		(SPM_BASE + 0x474)
-#define SPM_SEMA_M0			(SPM_BASE + 0x480)
-#define SPM_SEMA_M1			(SPM_BASE + 0x484)
-#define SPM_SEMA_M2			(SPM_BASE + 0x488)
-#define SPM_SEMA_M3			(SPM_BASE + 0x48C)
-#define SPM_SEMA_M4			(SPM_BASE + 0x490)
-#define SPM_SEMA_M5			(SPM_BASE + 0x494)
-#define SPM_SEMA_M6			(SPM_BASE + 0x498)
-#define SPM_SEMA_M7			(SPM_BASE + 0x49C)
-#define SPM_SEMA_M8			(SPM_BASE + 0x4A0)
-#define SPM_SEMA_M9			(SPM_BASE + 0x4A4)
-#define SRAM_DREQ_ACK			(SPM_BASE + 0x4AC)
-#define SRAM_DREQ_CON			(SPM_BASE + 0x4B0)
-#define SRAM_DREQ_CON_SET		(SPM_BASE + 0x4B4)
-#define SRAM_DREQ_CON_CLR		(SPM_BASE + 0x4B8)
-#define MP0_CPU0_IRQ_MASK		(SPM_BASE + 0x500)
-#define MP0_CPU1_IRQ_MASK		(SPM_BASE + 0x504)
-#define MP0_CPU2_IRQ_MASK		(SPM_BASE + 0x508)
-#define MP0_CPU3_IRQ_MASK		(SPM_BASE + 0x50C)
-#define MP1_CPU0_IRQ_MASK		(SPM_BASE + 0x510)
-#define MP1_CPU1_IRQ_MASK		(SPM_BASE + 0x514)
-#define MP1_CPU2_IRQ_MASK		(SPM_BASE + 0x518)
-#define MP1_CPU3_IRQ_MASK		(SPM_BASE + 0x51C)
-#define MP0_CPU0_WFI_EN			(SPM_BASE + 0x530)
-#define MP0_CPU1_WFI_EN			(SPM_BASE + 0x534)
-#define MP0_CPU2_WFI_EN			(SPM_BASE + 0x538)
-#define MP0_CPU3_WFI_EN			(SPM_BASE + 0x53C)
-#define MP1_CPU0_WFI_EN			(SPM_BASE + 0x540)
-#define MP1_CPU1_WFI_EN			(SPM_BASE + 0x544)
-#define MP1_CPU2_WFI_EN			(SPM_BASE + 0x548)
-#define MP1_CPU3_WFI_EN			(SPM_BASE + 0x54C)
-#define CPU_PTPOD2_CON			(SPM_BASE + 0x560)
-#define ROOT_CPUTOP_ADDR		(SPM_BASE + 0x570)
-#define ROOT_CORE_ADDR			(SPM_BASE + 0x574)
-#define CPU_SPARE_CON			(SPM_BASE + 0x580)
-#define CPU_SPARE_CON_SET		(SPM_BASE + 0x584)
-#define CPU_SPARE_CON_CLR		(SPM_BASE + 0x588)
-#define SPM_SW_FLAG			(SPM_BASE + 0x600)
-#define SPM_SW_DEBUG			(SPM_BASE + 0x604)
-#define SPM_SW_RSV_0			(SPM_BASE + 0x608)
-#define SPM_SW_RSV_1			(SPM_BASE + 0x60C)
-#define SPM_SW_RSV_2			(SPM_BASE + 0x610)
-#define SPM_SW_RSV_3			(SPM_BASE + 0x614)
-#define SPM_SW_RSV_4			(SPM_BASE + 0x618)
-#define SPM_SW_RSV_5			(SPM_BASE + 0x61C)
-#define SPM_RSV_CON			(SPM_BASE + 0x620)
-#define SPM_RSV_STA			(SPM_BASE + 0x624)
-#define SPM_PASR_DPD_0			(SPM_BASE + 0x630)
-#define SPM_PASR_DPD_1			(SPM_BASE + 0x634)
-#define SPM_PASR_DPD_2			(SPM_BASE + 0x638)
-#define SPM_PASR_DPD_3			(SPM_BASE + 0x63C)
-#define SPM_SPARE_CON			(SPM_BASE + 0x640)
-#define SPM_SPARE_CON_SET		(SPM_BASE + 0x644)
-#define SPM_SPARE_CON_CLR		(SPM_BASE + 0x648)
-#define SPM_SW_RSV_6			(SPM_BASE + 0x64C)
-#define SPM_SW_RSV_7			(SPM_BASE + 0x650)
-#define SPM_SW_RSV_8			(SPM_BASE + 0x654)
-#define SPM_SW_RSV_9			(SPM_BASE + 0x658)
-#define SPM_SW_RSV_10			(SPM_BASE + 0x65C)
-#define SPM_SW_RSV_11			(SPM_BASE + 0x660)
-#define SPM_SW_RSV_12			(SPM_BASE + 0x664)
-#define SPM_SW_RSV_13			(SPM_BASE + 0x668)
-#define SPM_SW_RSV_14			(SPM_BASE + 0x66C)
-#define SPM_SW_RSV_15			(SPM_BASE + 0x670)
-#define SPM_SW_RSV_16			(SPM_BASE + 0x674)
-#define SPM_SW_RSV_17			(SPM_BASE + 0x678)
-#define SPM_SW_RSV_18			(SPM_BASE + 0x67C)
-#define SPM_SW_RSV_19			(SPM_BASE + 0x680)
-#define SW_CRTL_EVENT			(SPM_BASE + 0x690)
-
-
-#define MP1_CPU3_PWR_STA_MASK	(1U << 19)
-#define MP1_CPU2_PWR_STA_MASK	(1U << 18)
-#define MP1_CPU1_PWR_STA_MASK	(1U << 17)
-#define MP1_CPU0_PWR_STA_MASK	(1U << 16)
-#define MP1_CPUTOP_PWR_STA_MASK	(1U << 15)
-#define MCU_PWR_STA_MASK	(1U << 14)
-#define MP0_CPU3_PWR_STA_MASK	(1U << 12)
-#define MP0_CPU2_PWR_STA_MASK	(1U << 11)
-#define MP0_CPU1_PWR_STA_MASK	(1U << 10)
-#define MP0_CPU0_PWR_STA_MASK	(1U << 9)
-#define MP0_CPUTOP_PWR_STA_MASK	(1U << 8)
-
-
-#define MP1_CPU3_STANDBYWFI	(1U << 17)
-#define MP1_CPU2_STANDBYWFI	(1U << 16)
-#define MP1_CPU1_STANDBYWFI	(1U << 15)
-#define MP1_CPU0_STANDBYWFI	(1U << 14)
-#define MP0_CPU3_STANDBYWFI	(1U << 13)
-#define MP0_CPU2_STANDBYWFI	(1U << 12)
-#define MP0_CPU1_STANDBYWFI	(1U << 11)
-#define MP0_CPU0_STANDBYWFI	(1U << 10)
-
-#define MP0_SPMC_SRAM_DORMANT_EN	(1<<0)
-#define MP1_SPMC_SRAM_DORMANT_EN	(1<<1)
-#define MP2_SPMC_SRAM_DORMANT_EN	(1<<2)
-
-/* POWERON_CONFIG_EN (0x10006000+0x000) */
-#define BCLK_CG_EN_LSB                      (1U << 0)       /* 1b */
-#define PROJECT_CODE_LSB                    (1U << 16)      /* 16b */
-
-/* SPM_POWER_ON_VAL0 (0x10006000+0x004) */
-#define POWER_ON_VAL0_LSB                   (1U << 0)       /* 32b */
-
-/* SPM_POWER_ON_VAL1 (0x10006000+0x008) */
-#define POWER_ON_VAL1_LSB                   (1U << 0)       /* 32b */
-
-/* SPM_CLK_CON (0x10006000+0x00C) */
-#define SYSCLK0_EN_CTRL_LSB                 (1U << 0)       /* 2b */
-#define SYSCLK1_EN_CTRL_LSB                 (1U << 2)       /* 2b */
-#define SYS_SETTLE_SEL_LSB                  (1U << 4)       /* 1b */
-#define SPM_LOCK_INFRA_DCM_LSB              (1U << 5)       /* 1b */
-#define EXT_SRCCLKEN_MASK_LSB               (1U << 6)       /* 3b */
-#define CXO32K_REMOVE_EN_MD1_LSB            (1U << 9)       /* 1b */
-#define CXO32K_REMOVE_EN_MD2_LSB            (1U << 10)      /* 1b */
-#define CLKSQ0_SEL_CTRL_LSB                 (1U << 11)      /* 1b */
-#define CLKSQ1_SEL_CTRL_LSB                 (1U << 12)      /* 1b */
-#define SRCLKEN0_EN_LSB                     (1U << 13)      /* 1b */
-#define SRCLKEN1_EN_LSB                     (1U << 14)      /* 1b */
-#define SCP_DCM_EN_LSB                      (1U << 15)      /* 1b */
-#define SYSCLK0_SRC_MASK_B_LSB              (1U << 16)      /* 7b */
-#define SYSCLK1_SRC_MASK_B_LSB              (1U << 23)      /* 7b */
-
-/* SPM_CLK_SETTLE (0x10006000+0x010) */
-#define SYSCLK_SETTLE_LSB                   (1U << 0)       /* 28b */
-
-/* SPM_AP_STANDBY_CON (0x10006000+0x014) */
-#define WFI_OP_LSB                          (1U << 0)       /* 1b */
-#define MP0_CPUTOP_IDLE_MASK_LSB            (1U << 1)       /* 1b */
-#define MP1_CPUTOP_IDLE_MASK_LSB            (1U << 2)       /* 1b */
-#define MCUSYS_IDLE_MASK_LSB                (1U << 4)       /* 1b */
-#define MM_MASK_B_LSB                       (1U << 16)      /* 2b */
-#define MD_DDR_EN_DBC_EN_LSB                (1U << 18)      /* 1b */
-#define MD_MASK_B_LSB                       (1U << 19)      /* 2b */
-#define SCP_MASK_B_LSB                      (1U << 21)      /* 1b */
-#define LTE_MASK_B_LSB                      (1U << 22)      /* 1b */
-#define SRCCLKENI_MASK_B_LSB                (1U << 23)      /* 1b */
-#define MD_APSRC_1_SEL_LSB                  (1U << 24)      /* 1b */
-#define MD_APSRC_0_SEL_LSB                  (1U << 25)      /* 1b */
-#define CONN_MASK_B_LSB                     (1U << 26)      /* 1b */
-#define CONN_APSRC_SEL_LSB                  (1U << 27)      /* 1b */
-
-/* PCM_CON0 (0x10006000+0x018) */
-#define PCM_KICK_L_LSB                      (1U << 0)       /* 1b */
-#define IM_KICK_L_LSB                       (1U << 1)       /* 1b */
-#define PCM_CK_EN_LSB                       (1U << 2)       /* 1b */
-#define EN_IM_SLEEP_DVS_LSB                 (1U << 3)       /* 1b */
-#define IM_AUTO_PDN_EN_LSB                  (1U << 4)       /* 1b */
-#define PCM_SW_RESET_LSB                    (1U << 15)      /* 1b */
-#define PROJECT_CODE_LSB                    (1U << 16)      /* 16b */
-
-/* PCM_CON1 (0x10006000+0x01C) */
-#define IM_SLAVE_LSB                        (1U << 0)       /* 1b */
-#define IM_SLEEP_LSB                        (1U << 1)       /* 1b */
-#define MIF_APBEN_LSB                       (1U << 3)       /* 1b */
-#define IM_PDN_LSB                          (1U << 4)       /* 1b */
-#define PCM_TIMER_EN_LSB                    (1U << 5)       /* 1b */
-#define IM_NONRP_EN_LSB                     (1U << 6)       /* 1b */
-#define DIS_MIF_PROT_LSB                    (1U << 7)       /* 1b */
-#define PCM_WDT_EN_LSB                      (1U << 8)       /* 1b */
-#define PCM_WDT_WAKE_MODE_LSB               (1U << 9)       /* 1b */
-#define SPM_SRAM_SLEEP_B_LSB                (1U << 10)      /* 1b */
-#define SPM_SRAM_ISOINT_B_LSB               (1U << 11)      /* 1b */
-#define EVENT_LOCK_EN_LSB                   (1U << 12)      /* 1b */
-#define SRCCLKEN_FAST_RESP_LSB              (1U << 13)      /* 1b */
-#define SCP_APB_INTERNAL_EN_LSB             (1U << 14)      /* 1b */
-#define PROJECT_CODE_LSB                    (1U << 16)      /* 16b */
-
-/* PCM_IM_PTR (0x10006000+0x020) */
-#define PCM_IM_PTR_LSB                      (1U << 0)       /* 32b */
-
-/* PCM_IM_LEN (0x10006000+0x024) */
-#define PCM_IM_LEN_LSB                      (1U << 0)       /* 13b */
-
-/* PCM_REG_DATA_INI (0x10006000+0x028) */
-#define PCM_REG_DATA_INI_LSB                (1U << 0)       /* 32b */
-
-/* PCM_PWR_IO_EN (0x10006000+0x02C) */
-#define PCM_PWR_IO_EN_LSB                   (1U << 0)       /* 8b */
-#define PCM_RF_SYNC_EN_LSB                  (1U << 16)      /* 8b */
-
-/* PCM_TIMER_VAL (0x10006000+0x030) */
-#define PCM_TIMER_VAL_LSB                   (1U << 0)       /* 32b */
-
-/* PCM_WDT_VAL (0x10006000+0x034) */
-#define PCM_WDT_VAL_LSB                     (1U << 0)       /* 32b */
-
-/* PCM_IM_HOST_RW_PTR (0x10006000+0x038) */
-#define PCM_IM_HOST_RW_PTR_LSB              (1U << 0)       /* 12b */
-#define PCM_IM_HOST_W_EN_LSB                (1U << 30)      /* 1b */
-#define PCM_IM_HOST_EN_LSB                  (1U << 31)      /* 1b */
-
-/* PCM_IM_HOST_RW_DAT (0x10006000+0x03C) */
-#define PCM_IM_HOST_RW_DAT_LSB              (1U << 0)       /* 32b */
-
-/* PCM_EVENT_VECTOR0 (0x10006000+0x040) */
-#define PCM_EVENT_VECTOR_0_LSB              (1U << 0)       /* 6b */
-#define PCM_EVENT_RESUME_0_LSB              (1U << 6)       /* 1b */
-#define PCM_EVENT_IMMEDIA_0_LSB             (1U << 7)       /* 1b */
-#define PCM_EVENT_VECTPC_0_LSB              (1U << 16)      /* 11b */
-
-/* PCM_EVENT_VECTOR1 (0x10006000+0x044) */
-#define PCM_EVENT_VECTOR_1_LSB              (1U << 0)       /* 6b */
-#define PCM_EVENT_RESUME_1_LSB              (1U << 6)       /* 1b */
-#define PCM_EVENT_IMMEDIA_1_LSB             (1U << 7)       /* 1b */
-#define PCM_EVENT_VECTPC_1_LSB              (1U << 16)      /* 11b */
-
-/* PCM_EVENT_VECTOR2 (0x10006000+0x048) */
-#define PCM_EVENT_VECTOR_2_LSB              (1U << 0)       /* 6b */
-#define PCM_EVENT_RESUME_2_LSB              (1U << 6)       /* 1b */
-#define PCM_EVENT_IMMEDIA_2_LSB             (1U << 7)       /* 1b */
-#define PCM_EVENT_VECTPC_2_LSB              (1U << 16)      /* 11b */
-
-/* PCM_EVENT_VECTOR3 (0x10006000+0x04C) */
-#define PCM_EVENT_VECTOR_3_LSB              (1U << 0)       /* 6b */
-#define PCM_EVENT_RESUME_3_LSB              (1U << 6)       /* 1b */
-#define PCM_EVENT_IMMEDIA_3_LSB             (1U << 7)       /* 1b */
-#define PCM_EVENT_VECTPC_3_LSB              (1U << 16)      /* 11b */
-
-/* PCM_EVENT_VECTOR4 (0x10006000+0x050) */
-#define PCM_EVENT_VECTOR_4_LSB              (1U << 0)       /* 6b */
-#define PCM_EVENT_RESUME_4_LSB              (1U << 6)       /* 1b */
-#define PCM_EVENT_IMMEDIA_4_LSB             (1U << 7)       /* 1b */
-#define PCM_EVENT_VECTPC_4_LSB              (1U << 16)      /* 11b */
-
-/* PCM_EVENT_VECTOR5 (0x10006000+0x054) */
-#define PCM_EVENT_VECTOR_5_LSB              (1U << 0)       /* 6b */
-#define PCM_EVENT_RESUME_5_LSB              (1U << 6)       /* 1b */
-#define PCM_EVENT_IMMEDIA_5_LSB             (1U << 7)       /* 1b */
-#define PCM_EVENT_VECTPC_5_LSB              (1U << 16)      /* 11b */
-
-/* PCM_EVENT_VECTOR6 (0x10006000+0x058) */
-#define PCM_EVENT_VECTOR_6_LSB              (1U << 0)       /* 6b */
-#define PCM_EVENT_RESUME_6_LSB              (1U << 6)       /* 1b */
-#define PCM_EVENT_IMMEDIA_6_LSB             (1U << 7)       /* 1b */
-#define PCM_EVENT_VECTPC_6_LSB              (1U << 16)      /* 11b */
-
-/* PCM_EVENT_VECTOR7 (0x10006000+0x05C) */
-#define PCM_EVENT_VECTOR_7_LSB              (1U << 0)       /* 6b */
-#define PCM_EVENT_RESUME_7_LSB              (1U << 6)       /* 1b */
-#define PCM_EVENT_IMMEDIA_7_LSB             (1U << 7)       /* 1b */
-#define PCM_EVENT_VECTPC_7_LSB              (1U << 16)      /* 11b */
-
-/* PCM_EVENT_VECTOR8 (0x10006000+0x060) */
-#define PCM_EVENT_VECTOR_8_LSB              (1U << 0)       /* 6b */
-#define PCM_EVENT_RESUME_8_LSB              (1U << 6)       /* 1b */
-#define PCM_EVENT_IMMEDIA_8_LSB             (1U << 7)       /* 1b */
-#define PCM_EVENT_VECTPC_8_LSB              (1U << 16)      /* 11b */
-
-/* PCM_EVENT_VECTOR9 (0x10006000+0x064) */
-#define PCM_EVENT_VECTOR_9_LSB              (1U << 0)       /* 6b */
-#define PCM_EVENT_RESUME_9_LSB              (1U << 6)       /* 1b */
-#define PCM_EVENT_IMMEDIA_9_LSB             (1U << 7)       /* 1b */
-#define PCM_EVENT_VECTPC_9_LSB              (1U << 16)      /* 11b */
-
-/* PCM_EVENT_VECTOR10 (0x10006000+0x068) */
-#define PCM_EVENT_VECTOR_10_LSB             (1U << 0)       /* 6b */
-#define PCM_EVENT_RESUME_10_LSB             (1U << 6)       /* 1b */
-#define PCM_EVENT_IMMEDIA_10_LSB            (1U << 7)       /* 1b */
-#define PCM_EVENT_VECTPC_10_LSB             (1U << 16)      /* 11b */
-
-/* PCM_EVENT_VECTOR11 (0x10006000+0x06C) */
-#define PCM_EVENT_VECTOR_11_LSB             (1U << 0)       /* 6b */
-#define PCM_EVENT_RESUME_11_LSB             (1U << 6)       /* 1b */
-#define PCM_EVENT_IMMEDIA_11_LSB            (1U << 7)       /* 1b */
-#define PCM_EVENT_VECTPC_11_LSB             (1U << 16)      /* 11b */
-
-/* PCM_EVENT_VECTOR12 (0x10006000+0x070) */
-#define PCM_EVENT_VECTOR_12_LSB             (1U << 0)       /* 6b */
-#define PCM_EVENT_RESUME_12_LSB             (1U << 6)       /* 1b */
-#define PCM_EVENT_IMMEDIA_12_LSB            (1U << 7)       /* 1b */
-#define PCM_EVENT_VECTPC_12_LSB             (1U << 16)      /* 11b */
-
-/* PCM_EVENT_VECTOR13 (0x10006000+0x074) */
-#define PCM_EVENT_VECTOR_13_LSB             (1U << 0)       /* 6b */
-#define PCM_EVENT_RESUME_13_LSB             (1U << 6)       /* 1b */
-#define PCM_EVENT_IMMEDIA_13_LSB            (1U << 7)       /* 1b */
-#define PCM_EVENT_VECTPC_13_LSB             (1U << 16)      /* 11b */
-
-/* PCM_EVENT_VECTOR14 (0x10006000+0x078) */
-#define PCM_EVENT_VECTOR_14_LSB             (1U << 0)       /* 6b */
-#define PCM_EVENT_RESUME_14_LSB             (1U << 6)       /* 1b */
-#define PCM_EVENT_IMMEDIA_14_LSB            (1U << 7)       /* 1b */
-#define PCM_EVENT_VECTPC_14_LSB             (1U << 16)      /* 11b */
-
-/* PCM_EVENT_VECTOR15 (0x10006000+0x07C) */
-#define PCM_EVENT_VECTOR_15_LSB             (1U << 0)       /* 6b */
-#define PCM_EVENT_RESUME_15_LSB             (1U << 6)       /* 1b */
-#define PCM_EVENT_IMMEDIA_15_LSB            (1U << 7)       /* 1b */
-#define PCM_EVENT_VECTPC_15_LSB             (1U << 16)      /* 11b */
-
-/* PCM_EVENT_VECTOR_EN (0x10006000+0x080) */
-#define PCM_EVENT_VECTOR_EN_LSB             (1U << 0)       /* 16b */
-
-/* SPM_SWINT (0x10006000+0x08C) */
-#define SPM_SWINT_LSB                       (1U << 0)       /* 10b */
-
-/* SPM_SWINT_SET (0x10006000+0x090) */
-#define SPM_SWINT_SET_LSB                   (1U << 0)       /* 10b */
-
-/* SPM_SWINT_CLR (0x10006000+0x094) */
-#define SPM_SWINT_CLR_LSB                   (1U << 0)       /* 10b */
-
-/* SPM_SCP_MAILBOX (0x10006000+0x098) */
-#define SPM_SCP_MAILBOX_LSB                 (1U << 0)       /* 32b */
-
-/* SPM_SCP_IRQ (0x10006000+0x09C) */
-#define SPM_SCP_IRQ_LSB                     (1U << 0)       /* 1b */
-#define SPM_SCP_IRQ_SEL_LSB                 (1U << 4)       /* 1b */
-
-/* SPM_TWAM_CON (0x10006000+0x0A0) */
-#define TWAM_ENABLE_LSB                     (1U << 0)       /* 1b */
-#define TWAM_SPEED_MODE_ENABLE_LSB          (1U << 1)       /* 1b */
-#define TWAM_SW_RST_LSB                     (1U << 2)       /* 1b */
-#define TWAM_MON_TYPE0_LSB                  (1U << 4)       /* 2b */
-#define TWAM_MON_TYPE1_LSB                  (1U << 6)       /* 2b */
-#define TWAM_MON_TYPE2_LSB                  (1U << 8)       /* 2b */
-#define TWAM_MON_TYPE3_LSB                  (1U << 10)      /* 2b */
-#define TWAM_SIGNAL_SEL0_LSB                (1U << 12)      /* 5b */
-#define TWAM_SIGNAL_SEL1_LSB                (1U << 17)      /* 5b */
-#define TWAM_SIGNAL_SEL2_LSB                (1U << 22)      /* 5b */
-#define TWAM_SIGNAL_SEL3_LSB                (1U << 27)      /* 5b */
-
-/* SPM_TWAM_WINDOW_LEN (0x10006000+0x0A4) */
-#define TWAM_WINDOW_LEN_LSB                 (1U << 0)       /* 32b */
-
-/* SPM_TWAM_IDLE_SEL (0x10006000+0x0A8) */
-#define TWAM_IDLE_SEL_LSB                   (1U << 0)       /* 5b */
-
-/* SPM_CPU_WAKEUP_EVENT (0x10006000+0x0B0) */
-#define SPM_CPU_WAKEUP_EVENT_LSB            (1U << 0)       /* 1b */
-
-/* SPM_IRQ_MASK (0x10006000+0x0B4) */
-#define SPM_TWAM_IRQ_MASK_LSB               (1U << 2)       /* 1b */
-#define PCM_IRQ_ROOT_MASK_LSB               (1U << 3)       /* 1b */
-#define SPM_IRQ_MASK_LSB                    (1U << 8)       /* 10b */
-
-/* SPM_SRC_REQ (0x10006000+0x0B8) */
-#define SPM_APSRC_REQ_LSB                   (1U << 0)       /* 1b */
-#define SPM_F26M_REQ_LSB                    (1U << 1)       /* 1b */
-#define SPM_LTE_REQ_LSB                     (1U << 2)       /* 1b */
-#define SPM_INFRA_REQ_LSB                   (1U << 3)       /* 1b */
-#define SPM_VRF18_REQ_LSB                   (1U << 4)       /* 1b */
-#define SPM_DVFS_REQ_LSB                    (1U << 5)       /* 1b */
-#define SPM_DVFS_FORCE_DOWN_LSB             (1U << 6)       /* 1b */
-#define SPM_DDREN_REQ_LSB                   (1U << 7)       /* 1b */
-#define SPM_RSV_SRC_REQ_LSB                 (1U << 8)       /* 3b */
-#define CPU_MD_DVFS_SOP_FORCE_ON_LSB        (1U << 16)      /* 1b */
-
-/* SPM_SRC_MASK (0x10006000+0x0BC) */
-#define CSYSPWREQ_MASK_LSB                  (1U << 0)       /* 1b */
-#define CCIF0_MD_EVENT_MASK_B_LSB           (1U << 1)       /* 1b */
-#define CCIF0_AP_EVENT_MASK_B_LSB           (1U << 2)       /* 1b */
-#define CCIF1_MD_EVENT_MASK_B_LSB           (1U << 3)       /* 1b */
-#define CCIF1_AP_EVENT_MASK_B_LSB           (1U << 4)       /* 1b */
-#define CCIFMD_MD1_EVENT_MASK_B_LSB         (1U << 5)       /* 1b */
-#define CCIFMD_MD2_EVENT_MASK_B_LSB         (1U << 6)       /* 1b */
-#define DSI0_VSYNC_MASK_B_LSB               (1U << 7)       /* 1b */
-#define DSI1_VSYNC_MASK_B_LSB               (1U << 8)       /* 1b */
-#define DPI_VSYNC_MASK_B_LSB                (1U << 9)       /* 1b */
-#define ISP0_VSYNC_MASK_B_LSB               (1U << 10)      /* 1b */
-#define ISP1_VSYNC_MASK_B_LSB               (1U << 11)      /* 1b */
-#define MD_SRCCLKENA_0_INFRA_MASK_B_LSB     (1U << 12)      /* 1b */
-#define MD_SRCCLKENA_1_INFRA_MASK_B_LSB     (1U << 13)      /* 1b */
-#define CONN_SRCCLKENA_INFRA_MASK_B_LSB     (1U << 14)      /* 1b */
-#define MD32_SRCCLKENA_INFRA_MASK_B_LSB     (1U << 15)      /* 1b */
-#define SRCCLKENI_INFRA_MASK_B_LSB          (1U << 16)      /* 1b */
-#define MD_APSRC_REQ_0_INFRA_MASK_B_LSB     (1U << 17)      /* 1b */
-#define MD_APSRC_REQ_1_INFRA_MASK_B_LSB     (1U << 18)      /* 1b */
-#define CONN_APSRCREQ_INFRA_MASK_B_LSB      (1U << 19)      /* 1b */
-#define MD32_APSRCREQ_INFRA_MASK_B_LSB      (1U << 20)      /* 1b */
-#define MD_DDR_EN_0_MASK_B_LSB              (1U << 21)      /* 1b */
-#define MD_DDR_EN_1_MASK_B_LSB              (1U << 22)      /* 1b */
-#define MD_VRF18_REQ_0_MASK_B_LSB           (1U << 23)      /* 1b */
-#define MD_VRF18_REQ_1_MASK_B_LSB           (1U << 24)      /* 1b */
-#define MD1_DVFS_REQ_MASK_LSB               (1U << 25)      /* 2b */
-#define CPU_DVFS_REQ_MASK_LSB               (1U << 27)      /* 1b */
-#define EMI_BW_DVFS_REQ_MASK_LSB            (1U << 28)      /* 1b */
-#define MD_SRCCLKENA_0_DVFS_REQ_MASK_B_LSB  (1U << 29)      /* 1b */
-#define MD_SRCCLKENA_1_DVFS_REQ_MASK_B_LSB  (1U << 30)      /* 1b */
-#define CONN_SRCCLKENA_DVFS_REQ_MASK_B_LSB  (1U << 31)      /* 1b */
-
-/* SPM_SRC2_MASK (0x10006000+0x0C0) */
-#define DVFS_HALT_MASK_B_LSB                (1U << 0)       /* 5b */
-#define VDEC_REQ_MASK_B_LSB                 (1U << 6)       /* 1b */
-#define GCE_REQ_MASK_B_LSB                  (1U << 7)       /* 1b */
-#define CPU_MD_DVFS_REQ_MERGE_MASK_B_LSB    (1U << 8)       /* 1b */
-#define MD_DDR_EN_DVFS_HALT_MASK_B_LSB      (1U << 9)       /* 2b */
-#define DSI0_VSYNC_DVFS_HALT_MASK_B_LSB     (1U << 11)      /* 1b */
-#define DSI1_VSYNC_DVFS_HALT_MASK_B_LSB     (1U << 12)      /* 1b */
-#define DPI_VSYNC_DVFS_HALT_MASK_B_LSB      (1U << 13)      /* 1b */
-#define ISP0_VSYNC_DVFS_HALT_MASK_B_LSB     (1U << 14)      /* 1b */
-#define ISP1_VSYNC_DVFS_HALT_MASK_B_LSB     (1U << 15)      /* 1b */
-#define CONN_DDR_EN_MASK_B_LSB              (1U << 16)      /* 1b */
-#define DISP_REQ_MASK_B_LSB                 (1U << 17)      /* 1b */
-#define DISP1_REQ_MASK_B_LSB                (1U << 18)      /* 1b */
-#define MFG_REQ_MASK_B_LSB                  (1U << 19)      /* 1b */
-#define C2K_PS_RCCIF_WAKE_MASK_B_LSB        (1U << 20)      /* 1b */
-#define C2K_L1_RCCIF_WAKE_MASK_B_LSB        (1U << 21)      /* 1b */
-#define PS_C2K_RCCIF_WAKE_MASK_B_LSB        (1U << 22)      /* 1b */
-#define L1_C2K_RCCIF_WAKE_MASK_B_LSB        (1U << 23)      /* 1b */
-#define SDIO_ON_DVFS_REQ_MASK_B_LSB         (1U << 24)      /* 1b */
-#define EMI_BOOST_DVFS_REQ_MASK_B_LSB       (1U << 25)      /* 1b */
-#define CPU_MD_EMI_DVFS_REQ_PROT_DIS_LSB    (1U << 26)      /* 1b */
-#define DRAMC_SPCMD_APSRC_REQ_MASK_B_LSB    (1U << 27)      /* 1b */
-
-/* SPM_WAKEUP_EVENT_MASK (0x10006000+0x0C4) */
-#define SPM_WAKEUP_EVENT_MASK_LSB           (1U << 0)       /* 32b */
-
-/* SPM_WAKEUP_EVENT_EXT_MASK (0x10006000+0x0C8) */
-#define SPM_WAKEUP_EVENT_EXT_MASK_LSB       (1U << 0)       /* 32b */
-
-/* SCP_CLK_CON (0x10006000+0x0D0) */
-#define SCP_26M_CK_SEL_LSB                  (1U << 0)       /* 1b */
-
-/* PCM_DEBUG_CON (0x10006000+0x0D4) */
-#define PCM_DEBUG_OUT_ENABLE_LSB            (1U << 0)       /* 1b */
-
-/* PCM_REG0_DATA (0x10006000+0x100) */
-#define PCM_REG0_DATA_LSB                   (1U << 0)       /* 32b */
-
-/* PCM_REG1_DATA (0x10006000+0x104) */
-#define PCM_REG1_DATA_LSB                   (1U << 0)       /* 32b */
-
-/* PCM_REG2_DATA (0x10006000+0x108) */
-#define PCM_REG2_DATA_LSB                   (1U << 0)       /* 32b */
-
-/* PCM_REG3_DATA (0x10006000+0x10C) */
-#define PCM_REG3_DATA_LSB                   (1U << 0)       /* 32b */
-
-/* PCM_REG4_DATA (0x10006000+0x110) */
-#define PCM_REG4_DATA_LSB                   (1U << 0)       /* 32b */
-
-/* PCM_REG5_DATA (0x10006000+0x114) */
-#define PCM_REG5_DATA_LSB                   (1U << 0)       /* 32b */
-
-/* PCM_REG6_DATA (0x10006000+0x118) */
-#define PCM_REG6_DATA_LSB                   (1U << 0)       /* 32b */
-
-/* PCM_REG7_DATA (0x10006000+0x11C) */
-#define PCM_REG7_DATA_LSB                   (1U << 0)       /* 32b */
-
-/* PCM_REG8_DATA (0x10006000+0x120) */
-#define PCM_REG8_DATA_LSB                   (1U << 0)       /* 32b */
-
-/* PCM_REG9_DATA (0x10006000+0x124) */
-#define PCM_REG9_DATA_LSB                   (1U << 0)       /* 32b */
-
-/* PCM_REG10_DATA (0x10006000+0x128) */
-#define PCM_REG10_DATA_LSB                  (1U << 0)       /* 32b */
-
-/* PCM_REG11_DATA (0x10006000+0x12C) */
-#define PCM_REG11_DATA_LSB                  (1U << 0)       /* 32b */
-
-/* PCM_REG12_DATA (0x10006000+0x130) */
-#define PCM_REG12_DATA_LSB                  (1U << 0)       /* 32b */
-
-/* PCM_REG13_DATA (0x10006000+0x134) */
-#define PCM_REG13_DATA_LSB                  (1U << 0)       /* 32b */
-
-/* PCM_REG14_DATA (0x10006000+0x138) */
-#define PCM_REG14_DATA_LSB                  (1U << 0)       /* 32b */
-
-/* PCM_REG15_DATA (0x10006000+0x13C) */
-#define PCM_REG15_DATA_LSB                  (1U << 0)       /* 32b */
-
-/* PCM_REG12_MASK_B_STA (0x10006000+0x140) */
-#define PCM_REG12_MASK_B_STA_LSB            (1U << 0)       /* 32b */
-
-/* PCM_REG12_EXT_DATA (0x10006000+0x144) */
-#define PCM_REG12_EXT_DATA_LSB              (1U << 0)       /* 32b */
-
-/* PCM_REG12_EXT_MASK_B_STA (0x10006000+0x148) */
-#define PCM_REG12_EXT_MASK_B_STA_LSB        (1U << 0)       /* 32b */
-
-/* PCM_EVENT_REG_STA (0x10006000+0x14C) */
-#define PCM_EVENT_REG_STA_LSB               (1U << 0)       /* 32b */
-
-/* PCM_TIMER_OUT (0x10006000+0x150) */
-#define PCM_TIMER_OUT_LSB                   (1U << 0)       /* 32b */
-
-/* PCM_WDT_OUT (0x10006000+0x154) */
-#define PCM_WDT_OUT_LSB                     (1U << 0)       /* 32b */
-
-/* SPM_IRQ_STA (0x10006000+0x158) */
-#define TWAM_IRQ_LSB                        (1U << 2)       /* 1b */
-#define PCM_IRQ_LSB                         (1U << 3)       /* 1b */
-#define SPM_IRQ_SWINT_LSB                   (1U << 4)       /* 10b */
-
-/* SPM_WAKEUP_STA (0x10006000+0x15C) */
-#define SPM_WAKEUP_EVENT_STA_LSB            (1U << 0)       /* 32b */
-
-/* SPM_WAKEUP_EXT_STA (0x10006000+0x160) */
-#define SPM_WAKEUP_EVENT_EXT_STA_LSB        (1U << 0)       /* 32b */
-
-/* SPM_WAKEUP_MISC (0x10006000+0x164) */
-#define SPM_WAKEUP_EVENT_MISC_LSB           (1U << 0)       /* 30b */
-#define SPM_PWRAP_IRQ_ACK_LSB               (1U << 30)      /* 1b */
-#define SPM_PWRAP_IRQ_LSB                   (1U << 31)      /* 1b */
-
-/* BUS_PROTECT_RDY (0x10006000+0x168) */
-#define BUS_PROTECT_RDY_LSB                 (1U << 0)       /* 32b */
-
-/* BUS_PROTECT2_RDY (0x10006000+0x16C) */
-#define BUS_PROTECT2_RDY_LSB                (1U << 0)       /* 32b */
-
-/* SUBSYS_IDLE_STA (0x10006000+0x170) */
-#define SUBSYS_IDLE_STA_LSB                 (1U << 0)       /* 32b */
-
-/* CPU_IDLE_STA (0x10006000+0x174) */
-#define MP0_CPU0_STANDBYWFI_AFTER_SEL_LSB   (1U << 0)       /* 1b */
-#define MP0_CPU1_STANDBYWFI_AFTER_SEL_LSB   (1U << 1)       /* 1b */
-#define MP0_CPU2_STANDBYWFI_AFTER_SEL_LSB   (1U << 2)       /* 1b */
-#define MP0_CPU3_STANDBYWFI_AFTER_SEL_LSB   (1U << 3)       /* 1b */
-#define MP1_CPU0_STANDBYWFI_AFTER_SEL_LSB   (1U << 4)       /* 1b */
-#define MP1_CPU1_STANDBYWFI_AFTER_SEL_LSB   (1U << 5)       /* 1b */
-#define MP1_CPU2_STANDBYWFI_AFTER_SEL_LSB   (1U << 6)       /* 1b */
-#define MP1_CPU3_STANDBYWFI_AFTER_SEL_LSB   (1U << 7)       /* 1b */
-#define MP0_CPU0_STANDBYWFI_LSB             (1U << 10)      /* 1b */
-#define MP0_CPU1_STANDBYWFI_LSB             (1U << 11)      /* 1b */
-#define MP0_CPU2_STANDBYWFI_LSB             (1U << 12)      /* 1b */
-#define MP0_CPU3_STANDBYWFI_LSB             (1U << 13)      /* 1b */
-#define MP1_CPU0_STANDBYWFI_LSB             (1U << 14)      /* 1b */
-#define MP1_CPU1_STANDBYWFI_LSB             (1U << 15)      /* 1b */
-#define MP1_CPU2_STANDBYWFI_LSB             (1U << 16)      /* 1b */
-#define MP1_CPU3_STANDBYWFI_LSB             (1U << 17)      /* 1b */
-#define MP0_CPUTOP_IDLE_LSB                 (1U << 20)      /* 1b */
-#define MP1_CPUTOP_IDLE_LSB                 (1U << 21)      /* 1b */
-#define MCU_BIU_IDLE_LSB                    (1U << 22)      /* 1b */
-#define MCUSYS_IDLE_LSB                     (1U << 23)      /* 1b */
-
-/* PCM_FSM_STA (0x10006000+0x178) */
-#define EXEC_INST_OP_LSB                    (1U << 0)       /* 4b */
-#define PC_STATE_LSB                        (1U << 4)       /* 3b */
-#define IM_STATE_LSB                        (1U << 7)       /* 3b */
-#define MASTER_STATE_LSB                    (1U << 10)      /* 5b */
-#define EVENT_FSM_LSB                       (1U << 15)      /* 3b */
-#define PCM_CLK_SEL_STA_LSB                 (1U << 18)      /* 3b */
-#define PCM_KICK_LSB                        (1U << 21)      /* 1b */
-#define IM_KICK_LSB                         (1U << 22)      /* 1b */
-#define EXT_SRCCLKEN_STA_LSB                (1U << 23)      /* 2b */
-#define EXT_SRCVOLTEN_STA_LSB               (1U << 25)      /* 1b */
-
-/* PWR_STATUS (0x10006000+0x180) */
-#define PWR_STATUS_LSB                      (1U << 0)       /* 32b */
-
-/* PWR_STATUS_2ND (0x10006000+0x184) */
-#define PWR_STATUS_2ND_LSB                  (1U << 0)       /* 32b */
-
-/* CPU_PWR_STATUS (0x10006000+0x188) */
-#define CPU_PWR_STATUS_LSB                  (1U << 0)       /* 32b */
-
-/* CPU_PWR_STATUS_2ND (0x10006000+0x18C) */
-#define CPU_PWR_STATUS_2ND_LSB              (1U << 0)       /* 32b */
-
-/* PCM_WDT_LATCH_0 (0x10006000+0x190) */
-#define PCM_WDT_LATCH_0_LSB                 (1U << 0)       /* 32b */
-
-/* PCM_WDT_LATCH_1 (0x10006000+0x194) */
-#define PCM_WDT_LATCH_1_LSB                 (1U << 0)       /* 32b */
-
-/* PCM_WDT_LATCH_2 (0x10006000+0x198) */
-#define PCM_WDT_LATCH_2_LSB                 (1U << 0)       /* 32b */
-
-/* DRAMC_DBG_LATCH (0x10006000+0x19C) */
-#define DRAMC_DEBUG_LATCH_STATUS_LSB        (1U << 0)       /* 32b */
-
-/* SPM_TWAM_LAST_STA0 (0x10006000+0x1A0) */
-#define SPM_TWAM_LAST_STA0_LSB              (1U << 0)       /* 32b */
-
-/* SPM_TWAM_LAST_STA1 (0x10006000+0x1A4) */
-#define SPM_TWAM_LAST_STA1_LSB              (1U << 0)       /* 32b */
-
-/* SPM_TWAM_LAST_STA2 (0x10006000+0x1A8) */
-#define SPM_TWAM_LAST_STA2_LSB              (1U << 0)       /* 32b */
-
-/* SPM_TWAM_LAST_STA3 (0x10006000+0x1AC) */
-#define SPM_TWAM_LAST_STA3_LSB              (1U << 0)       /* 32b */
-
-/* SPM_TWAM_CURR_STA0 (0x10006000+0x1B0) */
-#define SPM_TWAM_CURR_STA0_LSB              (1U << 0)       /* 32b */
-
-/* SPM_TWAM_CURR_STA1 (0x10006000+0x1B4) */
-#define SPM_TWAM_CURR_STA1_LSB              (1U << 0)       /* 32b */
-
-/* SPM_TWAM_CURR_STA2 (0x10006000+0x1B8) */
-#define SPM_TWAM_CURR_STA2_LSB              (1U << 0)       /* 32b */
-
-/* SPM_TWAM_CURR_STA3 (0x10006000+0x1BC) */
-#define SPM_TWAM_CURR_STA3_LSB              (1U << 0)       /* 32b */
-
-/* SPM_TWAM_TIMER_OUT (0x10006000+0x1C0) */
-#define SPM_TWAM_TIMER_OUT_LSB              (1U << 0)       /* 32b */
-
-/* PCM_WDT_LATCH_3 (0x10006000+0x1C4) */
-#define PCM_WDT_LATCH_3_LSB                 (1U << 0)       /* 32b */
-
-/* SPM_SRC_RDY_STA (0x10006000+0x1D0) */
-#define SPM_INFRA_SRC_ACK_LSB               (1U << 0)       /* 1b */
-#define SPM_VRF18_SRC_ACK_LSB               (1U << 1)       /* 1b */
-
-/* MISC_STA (0x10006000+0x1D4) */
-#define MM_DVFS_HALT_AF_MASK_LSB            (1U << 0)       /* 5b */
-
-/* MCU_PWR_CON (0x10006000+0x200) */
-#define MCU_PWR_RST_B_LSB                   (1U << 0)       /* 1b */
-#define MCU_PWR_ISO_LSB                     (1U << 1)       /* 1b */
-#define MCU_PWR_ON_LSB                      (1U << 2)       /* 1b */
-#define MCU_PWR_ON_2ND_LSB                  (1U << 3)       /* 1b */
-#define MCU_PWR_CLK_DIS_LSB                 (1U << 4)       /* 1b */
-#define MCU_SRAM_CKISO_LSB                  (1U << 5)       /* 1b */
-#define MCU_SRAM_ISOINT_B_LSB               (1U << 6)       /* 1b */
-#define MCU_SRAM_PD_SLPB_CLAMP_LSB          (1U << 7)       /* 1b */
-#define MCU_SRAM_PDN_LSB                    (1U << 8)       /* 1b */
-#define MCU_SRAM_SLEEP_B_LSB                (1U << 12)      /* 1b */
-#define SC_MCU_SRAM_PDN_ACK_LSB             (1U << 24)      /* 1b */
-#define SC_MCU_SRAM_SLEEP_B_ACK_LSB         (1U << 28)      /* 1b */
-
-/* MP0_CPUTOP_PWR_CON (0x10006000+0x204) */
-#define MP0_CPUTOP_PWR_RST_B_LSB            (1U << 0)       /* 1b */
-#define MP0_CPUTOP_PWR_ISO_LSB              (1U << 1)       /* 1b */
-#define MP0_CPUTOP_PWR_ON_LSB               (1U << 2)       /* 1b */
-#define MP0_CPUTOP_PWR_ON_2ND_LSB           (1U << 3)       /* 1b */
-#define MP0_CPUTOP_PWR_CLK_DIS_LSB          (1U << 4)       /* 1b */
-#define MP0_CPUTOP_SRAM_CKISO_LSB           (1U << 5)       /* 1b */
-#define MP0_CPUTOP_SRAM_ISOINT_B_LSB        (1U << 6)       /* 1b */
-#define MP0_CPUTOP_SRAM_PD_SLPB_CLAMP_LSB   (1U << 7)       /* 1b */
-#define MP0_CPUTOP_SRAM_PDN_LSB             (1U << 8)       /* 1b */
-#define MP0_CPUTOP_SRAM_SLEEP_B_LSB         (1U << 12)      /* 1b */
-#define SC_MP0_CPUTOP_SRAM_PDN_ACK_LSB      (1U << 24)      /* 1b */
-#define SC_MP0_CPUTOP_SRAM_SLEEP_B_ACK_LSB  (1U << 28)      /* 1b */
-
-/* MP0_CPU0_PWR_CON (0x10006000+0x208) */
-#define MP0_CPU0_PWR_RST_B_LSB              (1U << 0)       /* 1b */
-#define MP0_CPU0_PWR_ISO_LSB                (1U << 1)       /* 1b */
-#define MP0_CPU0_PWR_ON_LSB                 (1U << 2)       /* 1b */
-#define MP0_CPU0_PWR_ON_2ND_LSB             (1U << 3)       /* 1b */
-#define MP0_CPU0_PWR_CLK_DIS_LSB            (1U << 4)       /* 1b */
-#define MP0_CPU0_SRAM_CKISO_LSB             (1U << 5)       /* 1b */
-#define MP0_CPU0_SRAM_ISOINT_B_LSB          (1U << 6)       /* 1b */
-#define MP0_CPU0_SRAM_PD_SLPB_CLAMP_LSB     (1U << 7)       /* 1b */
-#define MP0_CPU0_SRAM_PDN_LSB               (1U << 8)       /* 1b */
-#define MP0_CPU0_SRAM_SLEEP_B_LSB           (1U << 12)      /* 1b */
-#define SC_MP0_CPU0_SRAM_PDN_ACK_LSB        (1U << 24)      /* 1b */
-#define SC_MP0_CPU0_SRAM_SLEEP_B_ACK_LSB    (1U << 28)      /* 1b */
-
-/* MP0_CPU1_PWR_CON (0x10006000+0x20C) */
-#define MP0_CPU1_PWR_RST_B_LSB              (1U << 0)       /* 1b */
-#define MP0_CPU1_PWR_ISO_LSB                (1U << 1)       /* 1b */
-#define MP0_CPU1_PWR_ON_LSB                 (1U << 2)       /* 1b */
-#define MP0_CPU1_PWR_ON_2ND_LSB             (1U << 3)       /* 1b */
-#define MP0_CPU1_PWR_CLK_DIS_LSB            (1U << 4)       /* 1b */
-#define MP0_CPU1_SRAM_CKISO_LSB             (1U << 5)       /* 1b */
-#define MP0_CPU1_SRAM_ISOINT_B_LSB          (1U << 6)       /* 1b */
-#define MP0_CPU1_SRAM_PD_SLPB_CLAMP_LSB     (1U << 7)       /* 1b */
-#define MP0_CPU1_SRAM_PDN_LSB               (1U << 8)       /* 1b */
-#define MP0_CPU1_SRAM_SLEEP_B_LSB           (1U << 12)      /* 1b */
-#define SC_MP0_CPU1_SRAM_PDN_ACK_LSB        (1U << 24)      /* 1b */
-#define SC_MP0_CPU1_SRAM_SLEEP_B_ACK_LSB    (1U << 28)      /* 1b */
-
-/* MP0_CPU2_PWR_CON (0x10006000+0x210) */
-#define MP0_CPU2_PWR_RST_B_LSB              (1U << 0)       /* 1b */
-#define MP0_CPU2_PWR_ISO_LSB                (1U << 1)       /* 1b */
-#define MP0_CPU2_PWR_ON_LSB                 (1U << 2)       /* 1b */
-#define MP0_CPU2_PWR_ON_2ND_LSB             (1U << 3)       /* 1b */
-#define MP0_CPU2_PWR_CLK_DIS_LSB            (1U << 4)       /* 1b */
-#define MP0_CPU2_SRAM_CKISO_LSB             (1U << 5)       /* 1b */
-#define MP0_CPU2_SRAM_ISOINT_B_LSB          (1U << 6)       /* 1b */
-#define MP0_CPU2_SRAM_PD_SLPB_CLAMP_LSB     (1U << 7)       /* 1b */
-#define MP0_CPU2_SRAM_PDN_LSB               (1U << 8)       /* 1b */
-#define MP0_CPU2_SRAM_SLEEP_B_LSB           (1U << 12)      /* 1b */
-#define SC_MP0_CPU2_SRAM_PDN_ACK_LSB        (1U << 24)      /* 1b */
-#define SC_MP0_CPU2_SRAM_SLEEP_B_ACK_LSB    (1U << 28)      /* 1b */
-
-/* MP0_CPU3_PWR_CON (0x10006000+0x214) */
-#define MP0_CPU3_PWR_RST_B_LSB              (1U << 0)       /* 1b */
-#define MP0_CPU3_PWR_ISO_LSB                (1U << 1)       /* 1b */
-#define MP0_CPU3_PWR_ON_LSB                 (1U << 2)       /* 1b */
-#define MP0_CPU3_PWR_ON_2ND_LSB             (1U << 3)       /* 1b */
-#define MP0_CPU3_PWR_CLK_DIS_LSB            (1U << 4)       /* 1b */
-#define MP0_CPU3_SRAM_CKISO_LSB             (1U << 5)       /* 1b */
-#define MP0_CPU3_SRAM_ISOINT_B_LSB          (1U << 6)       /* 1b */
-#define MP0_CPU3_SRAM_PD_SLPB_CLAMP_LSB     (1U << 7)       /* 1b */
-#define MP0_CPU3_SRAM_PDN_LSB               (1U << 8)       /* 1b */
-#define MP0_CPU3_SRAM_SLEEP_B_LSB           (1U << 12)      /* 1b */
-#define SC_MP0_CPU3_SRAM_PDN_ACK_LSB        (1U << 24)      /* 1b */
-#define SC_MP0_CPU3_SRAM_SLEEP_B_ACK_LSB    (1U << 28)      /* 1b */
-
-/* MP1_CPUTOP_PWR_CON (0x10006000+0x218) */
-#define MP1_CPUTOP_PWR_RST_B_LSB            (1U << 0)       /* 1b */
-#define MP1_CPUTOP_PWR_ISO_LSB              (1U << 1)       /* 1b */
-#define MP1_CPUTOP_PWR_ON_LSB               (1U << 2)       /* 1b */
-#define MP1_CPUTOP_PWR_ON_2ND_LSB           (1U << 3)       /* 1b */
-#define MP1_CPUTOP_PWR_CLK_DIS_LSB          (1U << 4)       /* 1b */
-#define MP1_CPUTOP_SRAM_CKISO_LSB           (1U << 5)       /* 1b */
-#define MP1_CPUTOP_SRAM_ISOINT_B_LSB        (1U << 6)       /* 1b */
-#define MP1_CPUTOP_SRAM_PD_SLPB_CLAMP_LSB   (1U << 7)       /* 1b */
-#define MP1_CPUTOP_SRAM_PDN_LSB             (1U << 8)       /* 1b */
-#define MP1_CPUTOP_SRAM_SLEEP_B_LSB         (1U << 12)      /* 1b */
-#define SC_MP1_CPUTOP_SRAM_PDN_ACK_LSB      (1U << 24)      /* 1b */
-#define SC_MP1_CPUTOP_SRAM_SLEEP_B_ACK_LSB  (1U << 28)      /* 1b */
-
-/* MP1_CPU0_PWR_CON (0x10006000+0x21C) */
-#define MP1_CPU0_PWR_RST_B_LSB              (1U << 0)       /* 1b */
-#define MP1_CPU0_PWR_ISO_LSB                (1U << 1)       /* 1b */
-#define MP1_CPU0_PWR_ON_LSB                 (1U << 2)       /* 1b */
-#define MP1_CPU0_PWR_ON_2ND_LSB             (1U << 3)       /* 1b */
-#define MP1_CPU0_PWR_CLK_DIS_LSB            (1U << 4)       /* 1b */
-#define MP1_CPU0_SRAM_CKISO_LSB             (1U << 5)       /* 1b */
-#define MP1_CPU0_SRAM_ISOINT_B_LSB          (1U << 6)       /* 1b */
-#define MP1_CPU0_SRAM_PD_SLPB_CLAMP_LSB     (1U << 7)       /* 1b */
-#define MP1_CPU0_SRAM_PDN_LSB               (1U << 8)       /* 1b */
-#define MP1_CPU0_SRAM_SLEEP_B_LSB           (1U << 12)      /* 1b */
-#define SC_MP1_CPU0_SRAM_PDN_ACK_LSB        (1U << 24)      /* 1b */
-#define SC_MP1_CPU0_SRAM_SLEEP_B_ACK_LSB    (1U << 28)      /* 1b */
-
-/* MP1_CPU1_PWR_CON (0x10006000+0x220) */
-#define MP1_CPU1_PWR_RST_B_LSB              (1U << 0)       /* 1b */
-#define MP1_CPU1_PWR_ISO_LSB                (1U << 1)       /* 1b */
-#define MP1_CPU1_PWR_ON_LSB                 (1U << 2)       /* 1b */
-#define MP1_CPU1_PWR_ON_2ND_LSB             (1U << 3)       /* 1b */
-#define MP1_CPU1_PWR_CLK_DIS_LSB            (1U << 4)       /* 1b */
-#define MP1_CPU1_SRAM_CKISO_LSB             (1U << 5)       /* 1b */
-#define MP1_CPU1_SRAM_ISOINT_B_LSB          (1U << 6)       /* 1b */
-#define MP1_CPU1_SRAM_PD_SLPB_CLAMP_LSB     (1U << 7)       /* 1b */
-#define MP1_CPU1_SRAM_PDN_LSB               (1U << 8)       /* 1b */
-#define MP1_CPU1_SRAM_SLEEP_B_LSB           (1U << 12)      /* 1b */
-#define SC_MP1_CPU1_SRAM_PDN_ACK_LSB        (1U << 24)      /* 1b */
-#define SC_MP1_CPU1_SRAM_SLEEP_B_ACK_LSB    (1U << 28)      /* 1b */
-
-/* MP1_CPU2_PWR_CON (0x10006000+0x224) */
-#define MP1_CPU2_PWR_RST_B_LSB              (1U << 0)       /* 1b */
-#define MP1_CPU2_PWR_ISO_LSB                (1U << 1)       /* 1b */
-#define MP1_CPU2_PWR_ON_LSB                 (1U << 2)       /* 1b */
-#define MP1_CPU2_PWR_ON_2ND_LSB             (1U << 3)       /* 1b */
-#define MP1_CPU2_PWR_CLK_DIS_LSB            (1U << 4)       /* 1b */
-#define MP1_CPU2_SRAM_CKISO_LSB             (1U << 5)       /* 1b */
-#define MP1_CPU2_SRAM_ISOINT_B_LSB          (1U << 6)       /* 1b */
-#define MP1_CPU2_SRAM_PD_SLPB_CLAMP_LSB     (1U << 7)       /* 1b */
-#define MP1_CPU2_SRAM_PDN_LSB               (1U << 8)       /* 1b */
-#define MP1_CPU2_SRAM_SLEEP_B_LSB           (1U << 12)      /* 1b */
-#define SC_MP1_CPU2_SRAM_PDN_ACK_LSB        (1U << 24)      /* 1b */
-#define SC_MP1_CPU2_SRAM_SLEEP_B_ACK_LSB    (1U << 28)      /* 1b */
-
-/* MP1_CPU3_PWR_CON (0x10006000+0x228) */
-#define MP1_CPU3_PWR_RST_B_LSB              (1U << 0)       /* 1b */
-#define MP1_CPU3_PWR_ISO_LSB                (1U << 1)       /* 1b */
-#define MP1_CPU3_PWR_ON_LSB                 (1U << 2)       /* 1b */
-#define MP1_CPU3_PWR_ON_2ND_LSB             (1U << 3)       /* 1b */
-#define MP1_CPU3_PWR_CLK_DIS_LSB            (1U << 4)       /* 1b */
-#define MP1_CPU3_SRAM_CKISO_LSB             (1U << 5)       /* 1b */
-#define MP1_CPU3_SRAM_ISOINT_B_LSB          (1U << 6)       /* 1b */
-#define MP1_CPU3_SRAM_PD_SLPB_CLAMP_LSB     (1U << 7)       /* 1b */
-#define MP1_CPU3_SRAM_PDN_LSB               (1U << 8)       /* 1b */
-#define MP1_CPU3_SRAM_SLEEP_B_LSB           (1U << 12)      /* 1b */
-#define SC_MP1_CPU3_SRAM_PDN_ACK_LSB        (1U << 24)      /* 1b */
-#define SC_MP1_CPU3_SRAM_SLEEP_B_ACK_LSB    (1U << 28)      /* 1b */
-
-/* MP0_CPUTOP_L2_PDN (0x10006000+0x240) */
-#define MP0_CPUTOP_L2_SRAM_PDN_LSB          (1U << 0)       /* 1b */
-#define MP0_CPUTOP_L2_SRAM_PDN_ACK_LSB      (1U << 8)       /* 1b */
-
-/* MP0_CPUTOP_L2_SLEEP_B (0x10006000+0x244) */
-#define MP0_CPUTOP_L2_SRAM_SLEEP_B_LSB      (1U << 0)       /* 1b */
-#define MP0_CPUTOP_L2_SRAM_SLEEP_B_ACK_LSB  (1U << 8)       /* 1b */
-
-/* MP0_CPU0_L1_PDN (0x10006000+0x248) */
-#define MP0_CPU0_L1_PDN_LSB                 (1U << 0)       /* 1b */
-#define MP0_CPU0_L1_PDN_ACK_LSB             (1U << 8)       /* 1b */
-
-/* MP0_CPU1_L1_PDN (0x10006000+0x24C) */
-#define MP0_CPU1_L1_PDN_LSB                 (1U << 0)       /* 1b */
-#define MP0_CPU1_L1_PDN_ACK_LSB             (1U << 8)       /* 1b */
-
-/* MP0_CPU2_L1_PDN (0x10006000+0x250) */
-#define MP0_CPU2_L1_PDN_LSB                 (1U << 0)       /* 1b */
-#define MP0_CPU2_L1_PDN_ACK_LSB             (1U << 8)       /* 1b */
-
-/* MP0_CPU3_L1_PDN (0x10006000+0x254) */
-#define MP0_CPU3_L1_PDN_LSB                 (1U << 0)       /* 1b */
-#define MP0_CPU3_L1_PDN_ACK_LSB             (1U << 8)       /* 1b */
-
-/* MP1_CPUTOP_L2_PDN (0x10006000+0x258) */
-#define MP1_CPUTOP_L2_SRAM_PDN_LSB          (1U << 0)       /* 1b */
-#define MP1_CPUTOP_L2_SRAM_PDN_ACK_LSB      (1U << 8)       /* 1b */
-
-/* MP1_CPUTOP_L2_SLEEP_B (0x10006000+0x25C) */
-#define MP1_CPUTOP_L2_SRAM_SLEEP_B_LSB      (1U << 0)       /* 1b */
-#define MP1_CPUTOP_L2_SRAM_SLEEP_B_ACK_LSB  (1U << 8)       /* 1b */
-
-/* MP1_CPU0_L1_PDN (0x10006000+0x260) */
-#define MP1_CPU0_L1_PDN_LSB                 (1U << 0)       /* 1b */
-#define MP1_CPU0_L1_PDN_ACK_LSB             (1U << 8)       /* 1b */
-
-/* MP1_CPU1_L1_PDN (0x10006000+0x264) */
-#define MP1_CPU1_L1_PDN_LSB                 (1U << 0)       /* 1b */
-#define MP1_CPU1_L1_PDN_ACK_LSB             (1U << 8)       /* 1b */
-
-/* MP1_CPU2_L1_PDN (0x10006000+0x268) */
-#define MP1_CPU2_L1_PDN_LSB                 (1U << 0)       /* 1b */
-#define MP1_CPU2_L1_PDN_ACK_LSB             (1U << 8)       /* 1b */
-
-/* MP1_CPU3_L1_PDN (0x10006000+0x26C) */
-#define MP1_CPU3_L1_PDN_LSB                 (1U << 0)       /* 1b */
-#define MP1_CPU3_L1_PDN_ACK_LSB             (1U << 8)       /* 1b */
-
-/* CPU_EXT_BUCK_ISO (0x10006000+0x290) */
-#define MP0_EXT_BUCK_ISO_LSB                (1U << 0)       /* 1b */
-#define MP1_EXT_BUCK_ISO_LSB                (1U << 1)       /* 1b */
-
-/* DUMMY1_PWR_CON (0x10006000+0x2B0) */
-#define DUMMY1_PWR_RST_B_LSB                (1U << 0)       /* 1b */
-#define DUMMY1_PWR_ISO_LSB                  (1U << 1)       /* 1b */
-#define DUMMY1_PWR_ON_LSB                   (1U << 2)       /* 1b */
-#define DUMMY1_PWR_ON_2ND_LSB               (1U << 3)       /* 1b */
-#define DUMMY1_PWR_CLK_DIS_LSB              (1U << 4)       /* 1b */
-
-/* BYPASS_SPMC (0x10006000+0x2B4) */
-#define BYPASS_CPU_SPMC_MODE_LSB            (1U << 0)       /* 1b */
-
-/* SPMC_DORMANT_ENABLE (0x10006000+0x2B8) */
-#define MP0_SPMC_SRAM_DORMANT_EN_LSB        (1U << 0)       /* 1b */
-#define MP1_SPMC_SRAM_DORMANT_EN_LSB        (1U << 1)       /* 1b */
-
-/* ARMPLL_CLK_CON (0x10006000+0x2BC) */
-#define MUXSEL_SC_CCIPLL_LSB                (1U << 0)       /* 1b */
-#define MUXSEL_SC_ARMPLL1_LSB               (1U << 1)       /* 1b */
-#define MUXSEL_SC_ARMPLL2_LSB               (1U << 2)       /* 1b */
-#define REG_SC_ARM_CLK_OFF_LSB              (1U << 8)       /* 4b */
-#define REG_SC_ARMPLL_OFF_LSB               (1U << 12)      /* 4b */
-#define REG_SC_ARMPLLOUT_OFF_LSB            (1U << 16)      /* 4b */
-#define REG_SC_FHC_PAUSE_LSB                (1U << 20)      /* 4b */
-#define REG_SC_ARMPLL_S_OFF_LSB             (1U << 24)      /* 4b */
-
-/* SPMC_IN_RET (0x10006000+0x2C0) */
-#define SPMC_STATUS_LSB                     (1U << 0)       /* 8b */
-
-/* VDE_PWR_CON (0x10006000+0x300) */
-#define VDE_PWR_RST_B_LSB                   (1U << 0)       /* 1b */
-#define VDE_PWR_ISO_LSB                     (1U << 1)       /* 1b */
-#define VDE_PWR_ON_LSB                      (1U << 2)       /* 1b */
-#define VDE_PWR_ON_2ND_LSB                  (1U << 3)       /* 1b */
-#define VDE_PWR_CLK_DIS_LSB                 (1U << 4)       /* 1b */
-#define VDE_SRAM_PDN_LSB                    (1U << 8)       /* 4b */
-#define VDE_SRAM_PDN_ACK_LSB                (1U << 12)      /* 4b */
-
-/* VEN_PWR_CON (0x10006000+0x304) */
-#define VEN_PWR_RST_B_LSB                   (1U << 0)       /* 1b */
-#define VEN_PWR_ISO_LSB                     (1U << 1)       /* 1b */
-#define VEN_PWR_ON_LSB                      (1U << 2)       /* 1b */
-#define VEN_PWR_ON_2ND_LSB                  (1U << 3)       /* 1b */
-#define VEN_PWR_CLK_DIS_LSB                 (1U << 4)       /* 1b */
-#define VEN_SRAM_PDN_LSB                    (1U << 8)       /* 4b */
-#define VEN_SRAM_PDN_ACK_LSB                (1U << 12)      /* 4b */
-
-/* ISP_PWR_CON (0x10006000+0x308) */
-#define ISP_PWR_RST_B_LSB                   (1U << 0)       /* 1b */
-#define ISP_PWR_ISO_LSB                     (1U << 1)       /* 1b */
-#define ISP_PWR_ON_LSB                      (1U << 2)       /* 1b */
-#define ISP_PWR_ON_2ND_LSB                  (1U << 3)       /* 1b */
-#define ISP_PWR_CLK_DIS_LSB                 (1U << 4)       /* 1b */
-#define ISP_SRAM_PDN_LSB                    (1U << 8)       /* 4b */
-#define ISP_SRAM_PDN_ACK_LSB                (1U << 12)      /* 4b */
-
-/* DIS_PWR_CON (0x10006000+0x30C) */
-#define DIS_PWR_RST_B_LSB                   (1U << 0)       /* 1b */
-#define DIS_PWR_ISO_LSB                     (1U << 1)       /* 1b */
-#define DIS_PWR_ON_LSB                      (1U << 2)       /* 1b */
-#define DIS_PWR_ON_2ND_LSB                  (1U << 3)       /* 1b */
-#define DIS_PWR_CLK_DIS_LSB                 (1U << 4)       /* 1b */
-#define DIS_SRAM_PDN_LSB                    (1U << 8)       /* 4b */
-#define DIS_SRAM_PDN_ACK_LSB                (1U << 12)      /* 4b */
-
-/* MJC_PWR_CON (0x10006000+0x310) */
-#define MJC_PWR_RST_B_LSB                   (1U << 0)       /* 1b */
-#define MJC_PWR_ISO_LSB                     (1U << 1)       /* 1b */
-#define MJC_PWR_ON_LSB                      (1U << 2)       /* 1b */
-#define MJC_PWR_ON_2ND_LSB                  (1U << 3)       /* 1b */
-#define MJC_PWR_CLK_DIS_LSB                 (1U << 4)       /* 1b */
-#define MJC_SRAM_PDN_LSB                    (1U << 8)       /* 4b */
-#define MJC_SRAM_PDN_ACK_LSB                (1U << 12)      /* 4b */
-
-/* AUDIO_PWR_CON (0x10006000+0x314) */
-#define AUD_PWR_RST_B_LSB                   (1U << 0)       /* 1b */
-#define AUD_PWR_ISO_LSB                     (1U << 1)       /* 1b */
-#define AUD_PWR_ON_LSB                      (1U << 2)       /* 1b */
-#define AUD_PWR_ON_2ND_LSB                  (1U << 3)       /* 1b */
-#define AUD_PWR_CLK_DIS_LSB                 (1U << 4)       /* 1b */
-#define AUD_SRAM_PDN_LSB                    (1U << 8)       /* 4b */
-#define AUD_SRAM_PDN_ACK_LSB                (1U << 12)      /* 4b */
-
-/* IFR_PWR_CON (0x10006000+0x318) */
-#define IFR_PWR_RST_B_LSB                   (1U << 0)       /* 1b */
-#define IFR_PWR_ISO_LSB                     (1U << 1)       /* 1b */
-#define IFR_PWR_ON_LSB                      (1U << 2)       /* 1b */
-#define IFR_PWR_ON_2ND_LSB                  (1U << 3)       /* 1b */
-#define IFR_PWR_CLK_DIS_LSB                 (1U << 4)       /* 1b */
-#define IFR_SRAM_PDN_LSB                    (1U << 8)       /* 4b */
-#define IFR_SRAM_PDN_ACK_LSB                (1U << 12)      /* 4b */
-
-/* DPY_PWR_CON (0x10006000+0x31C) */
-#define DPY_PWR_RST_B_LSB                   (1U << 0)       /* 1b */
-#define DPY_PWR_ISO_LSB                     (1U << 1)       /* 1b */
-#define DPY_PWR_ON_LSB                      (1U << 2)       /* 1b */
-#define DPY_PWR_ON_2ND_LSB                  (1U << 3)       /* 1b */
-#define DPY_PWR_CLK_DIS_LSB                 (1U << 4)       /* 1b */
-#define DPY_SRAM_PDN_LSB                    (1U << 8)       /* 4b */
-#define DPY_SRAM_PDN_ACK_LSB                (1U << 12)      /* 4b */
-
-/* MD1_PWR_CON (0x10006000+0x320) */
-#define MD1_PWR_RST_B_LSB                   (1U << 0)       /* 1b */
-#define MD1_PWR_ISO_LSB                     (1U << 1)       /* 1b */
-#define MD1_PWR_ON_LSB                      (1U << 2)       /* 1b */
-#define MD1_PWR_ON_2ND_LSB                  (1U << 3)       /* 1b */
-#define MD1_PWR_CLK_DIS_LSB                 (1U << 4)       /* 1b */
-#define MD1_SRAM_PDN_LSB                    (1U << 8)       /* 1b */
-
-/* MD2_PWR_CON (0x10006000+0x324) */
-#define MD2_PWR_RST_B_LSB                   (1U << 0)       /* 1b */
-#define MD2_PWR_ISO_LSB                     (1U << 1)       /* 1b */
-#define MD2_PWR_ON_LSB                      (1U << 2)       /* 1b */
-#define MD2_PWR_ON_2ND_LSB                  (1U << 3)       /* 1b */
-#define MD2_PWR_CLK_DIS_LSB                 (1U << 4)       /* 1b */
-#define MD2_SRAM_PDN_LSB                    (1U << 8)       /* 1b */
-
-/* C2K_PWR_CON (0x10006000+0x328) */
-#define C2K_PWR_RST_B_LSB                   (1U << 0)       /* 1b */
-#define C2K_PWR_ISO_LSB                     (1U << 1)       /* 1b */
-#define C2K_PWR_ON_LSB                      (1U << 2)       /* 1b */
-#define C2K_PWR_ON_2ND_LSB                  (1U << 3)       /* 1b */
-#define C2K_PWR_CLK_DIS_LSB                 (1U << 4)       /* 1b */
-
-/* CONN_PWR_CON (0x10006000+0x32C) */
-#define CONN_PWR_RST_B_LSB                  (1U << 0)       /* 1b */
-#define CONN_PWR_ISO_LSB                    (1U << 1)       /* 1b */
-#define CONN_PWR_ON_LSB                     (1U << 2)       /* 1b */
-#define CONN_PWR_ON_2ND_LSB                 (1U << 3)       /* 1b */
-#define CONN_PWR_CLK_DIS_LSB                (1U << 4)       /* 1b */
-#define CONN_SRAM_PDN_LSB                   (1U << 8)       /* 1b */
-#define CONN_SRAM_PDN_ACK_LSB               (1U << 12)      /* 1b */
-
-/* VCOREPDN_PWR_CON (0x10006000+0x330) */
-#define VCOREPDN_PWR_RST_B_LSB              (1U << 0)       /* 1b */
-#define VCOREPDN_PWR_ISO_LSB                (1U << 1)       /* 1b */
-#define VCOREPDN_PWR_ON_LSB                 (1U << 2)       /* 1b */
-#define VCOREPDN_PWR_ON_2ND_LSB             (1U << 3)       /* 1b */
-#define VCOREPDN_PWR_CLK_DIS_LSB            (1U << 4)       /* 1b */
-
-/* MFG_ASYNC_PWR_CON (0x10006000+0x334) */
-#define MFG_ASYNC_PWR_RST_B_LSB             (1U << 0)       /* 1b */
-#define MFG_ASYNC_PWR_ISO_LSB               (1U << 1)       /* 1b */
-#define MFG_ASYNC_PWR_ON_LSB                (1U << 2)       /* 1b */
-#define MFG_ASYNC_PWR_ON_2ND_LSB            (1U << 3)       /* 1b */
-#define MFG_ASYNC_PWR_CLK_DIS_LSB           (1U << 4)       /* 1b */
-#define MFG_ASYNC_SRAM_PDN_LSB              (1U << 8)       /* 4b */
-#define MFG_ASYNC_SRAM_PDN_ACK_LSB          (1U << 12)      /* 4b */
-
-/* MFG_PWR_CON (0x10006000+0x338) */
-#define MFG_PWR_RST_B_LSB                   (1U << 0)       /* 1b */
-#define MFG_PWR_ISO_LSB                     (1U << 1)       /* 1b */
-#define MFG_PWR_ON_LSB                      (1U << 2)       /* 1b */
-#define MFG_PWR_ON_2ND_LSB                  (1U << 3)       /* 1b */
-#define MFG_PWR_CLK_DIS_LSB                 (1U << 4)       /* 1b */
-#define MFG_SRAM_PDN_LSB                    (1U << 8)       /* 6b */
-#define MFG_SRAM_PDN_ACK_LSB                (1U << 16)      /* 6b */
-
-/* MFG_CORE0_PWR_CON (0x10006000+0x33C) */
-#define MFG_CORE0_PWR_RST_B_LSB             (1U << 0)       /* 1b */
-#define MFG_CORE0_PWR_ISO_LSB               (1U << 1)       /* 1b */
-#define MFG_CORE0_PWR_ON_LSB                (1U << 2)       /* 1b */
-#define MFG_CORE0_ON_2ND_LSB                (1U << 3)       /* 1b */
-#define MFG_CORE0_CLK_DIS_LSB               (1U << 4)       /* 1b */
-#define MFG_CORE0_SRAM_PDN_LSB              (1U << 5)       /* 1b */
-#define MFG_CORE0_SRAM_PDN_ACK_LSB          (1U << 6)       /* 1b */
-
-/* MFG_CORE1_PWR_CON (0x10006000+0x340) */
-#define MFG_CORE1_PWR_RST_B_LSB             (1U << 0)       /* 1b */
-#define MFG_CORE1_PWR_ISO_LSB               (1U << 1)       /* 1b */
-#define MFG_CORE1_PWR_ON_LSB                (1U << 2)       /* 1b */
-#define MFG_CORE1_ON_2ND_LSB                (1U << 3)       /* 1b */
-#define MFG_CORE1_CLK_DIS_LSB               (1U << 4)       /* 1b */
-#define MFG_CORE1_SRAM_PDN_LSB              (1U << 5)       /* 1b */
-#define MFG_CORE1_SRAM_PDN_ACK_LSB          (1U << 6)       /* 1b */
-
-/* CAM_PWR_CON (0x10006000+0x344) */
-#define CAM_PWR_RST_B_LSB                   (1U << 0)       /* 1b */
-#define CAM_PWR_ISO_LSB                     (1U << 1)       /* 1b */
-#define CAM_PWR_ON_LSB                      (1U << 2)       /* 1b */
-#define CAM_PWR_ON_2ND_LSB                  (1U << 3)       /* 1b */
-#define CAM_PWR_CLK_DIS_LSB                 (1U << 4)       /* 1b */
-#define CAM_SRAM_PDN_LSB                    (1U << 8)       /* 4b */
-#define CAM_SRAM_PDN_ACK_LSB                (1U << 12)      /* 4b */
-
-/* SYSRAM_CON (0x10006000+0x350) */
-#define IFR_SRAMROM_SRAM_PDN_LSB            (1U << 0)       /* 8b */
-#define IFR_SRAMROM_SRAM_CKISO_LSB          (1U << 8)       /* 8b */
-#define IFR_SRAMROM_SRAM_SLEEP_B_LSB        (1U << 16)      /* 8b */
-#define IFR_SRAMROM_SRAM_ISOINT_B_LSB       (1U << 24)      /* 8b */
-
-/* SYSROM_CON (0x10006000+0x354) */
-#define IFR_SRAMROM_ROM_PDN_LSB             (1U << 0)       /* 6b */
-
-/* SCP_SRAM_CON (0x10006000+0x358) */
-#define SCP_SRAM_PDN_LSB                    (1U << 0)       /* 1b */
-#define SCP_SRAM_SLEEP_B_LSB                (1U << 4)       /* 1b */
-#define SCP_SRAM_ISOINT_B_LSB               (1U << 8)       /* 1b */
-
-/* GCPU_SRAM_CON (0x10006000+0x35C) */
-#define GCPU_SRAM_PDN_LSB                   (1U << 0)       /* 4b */
-#define GCPU_SRAM_CKISO_LSB                 (1U << 4)       /* 4b */
-#define GCPU_SRAM_SLEEP_B_LSB               (1U << 8)       /* 4b */
-#define GCPU_SRAM_ISOINT_B_LSB              (1U << 12)      /* 4b */
-
-/* MDSYS_INTF_INFRA_PWR_CON (0x10006000+0x360) */
-#define MDSYS_INTF_INFRA_PWR_RST_B_LSB      (1U << 0)       /* 1b */
-#define MDSYS_INTF_INFRA_PWR_ISO_LSB        (1U << 1)       /* 1b */
-#define MDSYS_INTF_INFRA_PWR_ON_LSB         (1U << 2)       /* 1b */
-#define MDSYS_INTF_INFRA_PWR_ON_2ND_LSB     (1U << 3)       /* 1b */
-#define MDSYS_INTF_INFRA_PWR_CLK_DIS_LSB    (1U << 4)       /* 1b */
-
-/* MDSYS_INTF_MD1_PWR_CON (0x10006000+0x364) */
-#define MDSYS_INTF_MD1_PWR_RST_B_LSB        (1U << 0)       /* 1b */
-#define MDSYS_INTF_MD1_PWR_ISO_LSB          (1U << 1)       /* 1b */
-#define MDSYS_INTF_MD1_PWR_ON_LSB           (1U << 2)       /* 1b */
-#define MDSYS_INTF_MD1_PWR_ON_2ND_LSB       (1U << 3)       /* 1b */
-#define MDSYS_INTF_MD1_PWR_CLK_DIS_LSB      (1U << 4)       /* 1b */
-
-/* MDSYS_INTF_C2K_PWR_CON (0x10006000+0x368) */
-#define MDSYS_INTF_C2K_PWR_RST_B_LSB        (1U << 0)       /* 1b */
-#define MDSYS_INTF_C2K_PWR_ISO_LSB          (1U << 1)       /* 1b */
-#define MDSYS_INTF_C2K_PWR_ON_LSB           (1U << 2)       /* 1b */
-#define MDSYS_INTF_C2K_PWR_ON_2ND_LSB       (1U << 3)       /* 1b */
-#define MDSYS_INTF_C2K_PWR_CLK_DIS_LSB      (1U << 4)       /* 1b */
-
-/* BSI_TOP_SRAM_CON (0x10006000+0x370) */
-#define BSI_TOP_SRAM_PDN_LSB                (1U << 0)       /* 7b */
-#define BSI_TOP_SRAM_DSLP_LSB               (1U << 7)       /* 7b */
-#define BSI_TOP_SRAM_SLEEP_B_LSB            (1U << 14)      /* 7b */
-#define BSI_TOP_SRAM_ISOINT_B_LSB           (1U << 21)      /* 7b */
-#define BSI_TOP_SRAM_ISO_EN_LSB             (1U << 28)      /* 2b */
-
-/* DVFSP_SRAM_CON (0x10006000+0x374) */
-#define DVFSP_SRAM_PDN_LSB                  (1U << 0)       /* 2b */
-#define DVFSP_SRAM_SLEEP_B_LSB              (1U << 4)       /* 2b */
-#define DVFSP_SRAM_ISOINT_B_LSB             (1U << 8)       /* 2b */
-
-/* MD_EXT_BUCK_ISO (0x10006000+0x390) */
-#define MD_EXT_BUCK_ISO_LSB                 (1U << 0)       /* 1b */
-
-/* DUMMY2_PWR_CON (0x10006000+0x3B0) */
-#define DUMMY2_PWR_RST_B_LSB                (1U << 0)       /* 1b */
-#define DUMMY2_PWR_ISO_LSB                  (1U << 1)       /* 1b */
-#define DUMMY2_PWR_ON_LSB                   (1U << 2)       /* 1b */
-#define DUMMY2_PWR_ON_2ND_LSB               (1U << 3)       /* 1b */
-#define DUMMY2_PWR_CLK_DIS_LSB              (1U << 4)       /* 1b */
-#define DUMMY2_SRAM_PDN_LSB                 (1U << 8)       /* 4b */
-#define DUMMY2_SRAM_PDN_ACK_LSB             (1U << 12)      /* 4b */
-
-/* MD1_OUTPUT_PISO_S_EN_IZ (0x10006000+0x3B4) */
-#define MD1_OUTPUT_PISO_S_EN_IZ_LSB         (1U << 0)       /* 1b */
-
-/* SPM_DVFS_CON (0x10006000+0x400) */
-#define SPM_DVFS_CON_LSB                    (1U << 0)       /* 4b */
-#define SPM_DVFS_ACK_LSB                    (1U << 30)      /* 2b */
-
-/* SPM_MDBSI_CON (0x10006000+0x404) */
-#define SPM_MDBSI_CON_LSB                   (1U << 0)       /* 3b */
-
-/* SPM_MAS_PAUSE_MASK_B (0x10006000+0x408) */
-#define SPM_MAS_PAUSE_MASK_B_LSB            (1U << 0)       /* 32b */
-
-/* SPM_MAS_PAUSE2_MASK_B (0x10006000+0x40C) */
-#define SPM_MAS_PAUSE2_MASK_B_LSB           (1U << 0)       /* 32b */
-
-/* SPM_BSI_GEN (0x10006000+0x410) */
-#define SPM_BSI_START_LSB                   (1U << 0)       /* 1b */
-
-/* SPM_BSI_EN_SR (0x10006000+0x414) */
-#define SPM_BSI_EN_SR_LSB                   (1U << 0)       /* 32b */
-
-/* SPM_BSI_CLK_SR (0x10006000+0x418) */
-#define SPM_BSI_CLK_SR_LSB                  (1U << 0)       /* 32b */
-
-/* SPM_BSI_D0_SR (0x10006000+0x41C) */
-#define SPM_BSI_D0_SR_LSB                   (1U << 0)       /* 32b */
-
-/* SPM_BSI_D1_SR (0x10006000+0x420) */
-#define SPM_BSI_D1_SR_LSB                   (1U << 0)       /* 32b */
-
-/* SPM_BSI_D2_SR (0x10006000+0x424) */
-#define SPM_BSI_D2_SR_LSB                   (1U << 0)       /* 32b */
-
-/* SPM_AP_SEMA (0x10006000+0x428) */
-#define SPM_AP_SEMA_LSB                     (1U << 0)       /* 1b */
-
-/* SPM_SPM_SEMA (0x10006000+0x42C) */
-#define SPM_SPM_SEMA_LSB                    (1U << 0)       /* 1b */
-
-/* AP2MD_CROSS_TRIGGER (0x10006000+0x430) */
-#define AP2MD_CROSS_TRIGGER_REQ_LSB         (1U << 0)       /* 1b */
-#define AP2MD_CROSS_TRIGGER_ACK_LSB         (1U << 1)       /* 1b */
-
-/* AP_MDSRC_REQ (0x10006000+0x434) */
-#define AP_MD1SRC_REQ_LSB                   (1U << 0)       /* 1b */
-#define AP_MD2SRC_REQ_LSB                   (1U << 1)       /* 1b */
-#define AP_MD1SRC_ACK_LSB                   (1U << 4)       /* 1b */
-#define AP_MD2SRC_ACK_LSB                   (1U << 5)       /* 1b */
-
-/* SPM2MD_DVFS_CON (0x10006000+0x438) */
-#define SPM2MD_DVFS_CON_LSB                 (1U << 0)       /* 16b */
-
-/* MD2SPM_DVFS_CON (0x10006000+0x43C) */
-#define MD2SPM_DVFS_CON_LSB                 (1U << 0)       /* 16b */
-
-/* DRAMC_DPY_CLK_SW_CON_RSV (0x10006000+0x440) */
-#define SPM2DRAMC_SHUFFLE_START_LSB         (1U << 0)       /* 1b */
-#define SPM2DRAMC_SHUFFLE_SWITCH_LSB        (1U << 1)       /* 1b */
-#define SPM2DPY_DIV2_SYNC_LSB               (1U << 2)       /* 1b */
-#define SPM2DPY_1PLL_SWITCH_LSB             (1U << 3)       /* 1b */
-#define SPM2DPY_TEST_CK_MUX_LSB             (1U << 4)       /* 1b */
-#define SPM2DPY_ASYNC_MODE_LSB              (1U << 5)       /* 1b */
-#define SPM2TOP_ASYNC_MODE_LSB              (1U << 6)       /* 1b */
-
-/* DPY_LP_CON (0x10006000+0x444) */
-#define SC_DDRPHY_LP_SIGNALS_LSB            (1U << 0)       /* 3b */
-
-/* CPU_DVFS_REQ (0x10006000+0x448) */
-#define CPU_DVFS_REQ_LSB                    (1U << 0)       /* 16b */
-#define DVFS_HALT_LSB                       (1U << 16)      /* 1b */
-#define MD_DVFS_ERROR_STATUS_LSB            (1U << 17)      /* 1b */
-
-/* SPM_PLL_CON (0x10006000+0x44C) */
-#define SC_MPLLOUT_OFF_LSB                  (1U << 0)       /* 1b */
-#define SC_UNIPLLOUT_OFF_LSB                (1U << 1)       /* 1b */
-#define SC_MPLL_OFF_LSB                     (1U << 4)       /* 1b */
-#define SC_UNIPLL_OFF_LSB                   (1U << 5)       /* 1b */
-#define SC_MPLL_S_OFF_LSB                   (1U << 8)       /* 1b */
-#define SC_UNIPLL_S_OFF_LSB                 (1U << 9)       /* 1b */
-#define SC_SMI_CK_OFF_LSB                   (1U << 16)      /* 1b */
-#define SC_MD32K_CK_OFF_LSB                 (1U << 17)      /* 1b */
-
-/* SPM_EMI_BW_MODE (0x10006000+0x450) */
-#define EMI_BW_MODE_LSB                     (1U << 0)       /* 1b */
-#define EMI_BOOST_MODE_LSB                  (1U << 1)       /* 1b */
-
-/* AP2MD_PEER_WAKEUP (0x10006000+0x454) */
-#define AP2MD_PEER_WAKEUP_LSB               (1U << 0)       /* 1b */
-
-/* ULPOSC_CON (0x10006000+0x458) */
-#define ULPOSC_EN_LSB                       (1U << 0)       /* 1b */
-#define ULPOSC_RST_LSB                      (1U << 1)       /* 1b */
-#define ULPOSC_CG_EN_LSB                    (1U << 2)       /* 1b */
-
-/* DRAMC_DPY_CLK_SW_CON_SEL (0x10006000+0x460) */
-#define SW_DR_GATE_RETRY_EN_SEL_LSB         (1U << 0)       /* 2b */
-#define SW_EMI_CLK_OFF_SEL_LSB              (1U << 2)       /* 2b */
-#define SW_DPY_MODE_SW_SEL_LSB              (1U << 4)       /* 2b */
-#define SW_DMSUS_OFF_SEL_LSB                (1U << 6)       /* 2b */
-#define SW_MEM_CK_OFF_SEL_LSB               (1U << 8)       /* 2b */
-#define SW_DPY_2ND_DLL_EN_SEL_LSB           (1U << 10)      /* 2b */
-#define SW_DPY_DLL_EN_SEL_LSB               (1U << 12)      /* 2b */
-#define SW_DPY_DLL_CK_EN_SEL_LSB            (1U << 14)      /* 2b */
-#define SW_DPY_VREF_EN_SEL_LSB              (1U << 16)      /* 2b */
-#define SW_PHYPLL_EN_SEL_LSB                (1U << 18)      /* 2b */
-#define SW_DDRPHY_FB_CK_EN_SEL_LSB          (1U << 20)      /* 2b */
-#define SEPERATE_PHY_PWR_SEL_LSB            (1U << 23)      /* 1b */
-#define SW_DMDRAMCSHU_ACK_SEL_LSB           (1U << 24)      /* 2b */
-#define SW_EMI_CLK_OFF_ACK_SEL_LSB          (1U << 26)      /* 2b */
-#define SW_DR_SHORT_QUEUE_ACK_SEL_LSB       (1U << 28)      /* 2b */
-#define SW_DRAMC_DFS_STA_SEL_LSB            (1U << 30)      /* 2b */
-
-/* DRAMC_DPY_CLK_SW_CON (0x10006000+0x464) */
-#define SW_DR_GATE_RETRY_EN_LSB             (1U << 0)       /* 2b */
-#define SW_EMI_CLK_OFF_LSB                  (1U << 2)       /* 2b */
-#define SW_DPY_MODE_SW_LSB                  (1U << 4)       /* 2b */
-#define SW_DMSUS_OFF_LSB                    (1U << 6)       /* 2b */
-#define SW_MEM_CK_OFF_LSB                   (1U << 8)       /* 2b */
-#define SW_DPY_2ND_DLL_EN_LSB               (1U << 10)      /* 2b */
-#define SW_DPY_DLL_EN_LSB                   (1U << 12)      /* 2b */
-#define SW_DPY_DLL_CK_EN_LSB                (1U << 14)      /* 2b */
-#define SW_DPY_VREF_EN_LSB                  (1U << 16)      /* 2b */
-#define SW_PHYPLL_EN_LSB                    (1U << 18)      /* 2b */
-#define SW_DDRPHY_FB_CK_EN_LSB              (1U << 20)      /* 2b */
-#define SC_DR_SHU_EN_ACK_LSB                (1U << 24)      /* 2b */
-#define EMI_CLK_OFF_ACK_LSB                 (1U << 26)      /* 2b */
-#define SC_DR_SHORT_QUEUE_ACK_LSB           (1U << 28)      /* 2b */
-#define SC_DRAMC_DFS_STA_LSB                (1U << 30)      /* 2b */
-
-/* DRAMC_DPY_CLK_SW_CON_SEL2 (0x10006000+0x470) */
-#define SW_PHYPLL_SHU_EN_SEL_LSB            (1U << 0)       /* 1b */
-#define SW_PHYPLL2_SHU_EN_SEL_LSB           (1U << 1)       /* 1b */
-#define SW_PHYPLL_MODE_SW_SEL_LSB           (1U << 2)       /* 1b */
-#define SW_PHYPLL2_MODE_SW_SEL_LSB          (1U << 3)       /* 1b */
-#define SW_DR_SHORT_QUEUE_SEL_LSB           (1U << 4)       /* 1b */
-#define SW_DR_SHU_EN_SEL_LSB                (1U << 5)       /* 1b */
-#define SW_DR_SHU_LEVEL_SEL_LSB             (1U << 6)       /* 1b */
-
-/* DRAMC_DPY_CLK_SW_CON2 (0x10006000+0x474) */
-#define SW_PHYPLL_SHU_EN_LSB                (1U << 0)       /* 1b */
-#define SW_PHYPLL2_SHU_EN_LSB               (1U << 1)       /* 1b */
-#define SW_PHYPLL_MODE_SW_LSB               (1U << 2)       /* 1b */
-#define SW_PHYPLL2_MODE_SW_LSB              (1U << 3)       /* 1b */
-#define SW_DR_SHORT_QUEUE_LSB               (1U << 4)       /* 1b */
-#define SW_DR_SHU_EN_LSB                    (1U << 5)       /* 1b */
-#define SW_DR_SHU_LEVEL_LSB                 (1U << 6)       /* 2b */
-#define SPM2MM_ULTRAREQ_LSB                 (1U << 8)       /* 1b */
-#define SPM2MD_ULTRAREQ_LSB                 (1U << 9)       /* 1b */
-#define SPM2MM_ULTRAACK_D2T_LSB             (1U << 30)      /* 1b */
-#define SPM2MD_ULTRAACK_D2T_LSB             (1U << 31)      /* 1b */
-
-/* SPM_SEMA_M0 (0x10006000+0x480) */
-#define SPM_SEMA_M0_LSB                     (1U << 0)       /* 8b */
-
-/* SPM_SEMA_M1 (0x10006000+0x484) */
-#define SPM_SEMA_M1_LSB                     (1U << 0)       /* 8b */
-
-/* SPM_SEMA_M2 (0x10006000+0x488) */
-#define SPM_SEMA_M2_LSB                     (1U << 0)       /* 8b */
-
-/* SPM_SEMA_M3 (0x10006000+0x48C) */
-#define SPM_SEMA_M3_LSB                     (1U << 0)       /* 8b */
-
-/* SPM_SEMA_M4 (0x10006000+0x490) */
-#define SPM_SEMA_M4_LSB                     (1U << 0)       /* 8b */
-
-/* SPM_SEMA_M5 (0x10006000+0x494) */
-#define SPM_SEMA_M5_LSB                     (1U << 0)       /* 8b */
-
-/* SPM_SEMA_M6 (0x10006000+0x498) */
-#define SPM_SEMA_M6_LSB                     (1U << 0)       /* 8b */
-
-/* SPM_SEMA_M7 (0x10006000+0x49C) */
-#define SPM_SEMA_M7_LSB                     (1U << 0)       /* 8b */
-
-/* SPM_SEMA_M8 (0x10006000+0x4A0) */
-#define SPM_SEMA_M8_LSB                     (1U << 0)       /* 8b */
-
-/* SPM_SEMA_M9 (0x10006000+0x4A4) */
-#define SPM_SEMA_M9_LSB                     (1U << 0)       /* 8b */
-
-/* SRAM_DREQ_ACK (0x10006000+0x4AC) */
-#define SRAM_DREQ_ACK_LSB                   (1U << 0)       /* 16b */
-
-/* SRAM_DREQ_CON (0x10006000+0x4B0) */
-#define SRAM_DREQ_CON_LSB                   (1U << 0)       /* 16b */
-
-/* SRAM_DREQ_CON_SET (0x10006000+0x4B4) */
-#define SRAM_DREQ_CON_SET_LSB               (1U << 0)       /* 16b */
-
-/* SRAM_DREQ_CON_CLR (0x10006000+0x4B8) */
-#define SRAM_DREQ_CON_CLR_LSB               (1U << 0)       /* 16b */
-
-/* MP0_CPU0_IRQ_MASK (0x10006000+0x500) */
-#define MP0_CPU0_IRQ_MASK_LSB               (1U << 0)       /* 1b */
-#define MP0_CPU0_AUX_LSB                    (1U << 8)       /* 11b */
-
-/* MP0_CPU1_IRQ_MASK (0x10006000+0x504) */
-#define MP0_CPU1_IRQ_MASK_LSB               (1U << 0)       /* 1b */
-#define MP0_CPU1_AUX_LSB                    (1U << 8)       /* 11b */
-
-/* MP0_CPU2_IRQ_MASK (0x10006000+0x508) */
-#define MP0_CPU2_IRQ_MASK_LSB               (1U << 0)       /* 1b */
-#define MP0_CPU2_AUX_LSB                    (1U << 8)       /* 11b */
-
-/* MP0_CPU3_IRQ_MASK (0x10006000+0x50C) */
-#define MP0_CPU3_IRQ_MASK_LSB               (1U << 0)       /* 1b */
-#define MP0_CPU3_AUX_LSB                    (1U << 8)       /* 11b */
-
-/* MP1_CPU0_IRQ_MASK (0x10006000+0x510) */
-#define MP1_CPU0_IRQ_MASK_LSB               (1U << 0)       /* 1b */
-#define MP1_CPU0_AUX_LSB                    (1U << 8)       /* 11b */
-
-/* MP1_CPU1_IRQ_MASK (0x10006000+0x514) */
-#define MP1_CPU1_IRQ_MASK_LSB               (1U << 0)       /* 1b */
-#define MP1_CPU1_AUX_LSB                    (1U << 8)       /* 11b */
-
-/* MP1_CPU2_IRQ_MASK (0x10006000+0x518) */
-#define MP1_CPU2_IRQ_MASK_LSB               (1U << 0)       /* 1b */
-#define MP1_CPU2_AUX_LSB                    (1U << 8)       /* 11b */
-
-/* MP1_CPU3_IRQ_MASK (0x10006000+0x51C) */
-#define MP1_CPU3_IRQ_MASK_LSB               (1U << 0)       /* 1b */
-#define MP1_CPU3_AUX_LSB                    (1U << 8)       /* 11b */
-
-/* MP0_CPU0_WFI_EN (0x10006000+0x530) */
-#define MP0_CPU0_WFI_EN_LSB                 (1U << 0)       /* 1b */
-
-/* MP0_CPU1_WFI_EN (0x10006000+0x534) */
-#define MP0_CPU1_WFI_EN_LSB                 (1U << 0)       /* 1b */
-
-/* MP0_CPU2_WFI_EN (0x10006000+0x538) */
-#define MP0_CPU2_WFI_EN_LSB                 (1U << 0)       /* 1b */
-
-/* MP0_CPU3_WFI_EN (0x10006000+0x53C) */
-#define MP0_CPU3_WFI_EN_LSB                 (1U << 0)       /* 1b */
-
-/* MP1_CPU0_WFI_EN (0x10006000+0x540) */
-#define MP1_CPU0_WFI_EN_LSB                 (1U << 0)       /* 1b */
-
-/* MP1_CPU1_WFI_EN (0x10006000+0x544) */
-#define MP1_CPU1_WFI_EN_LSB                 (1U << 0)       /* 1b */
-
-/* MP1_CPU2_WFI_EN (0x10006000+0x548) */
-#define MP1_CPU2_WFI_EN_LSB                 (1U << 0)       /* 1b */
-
-/* MP1_CPU3_WFI_EN (0x10006000+0x54C) */
-#define MP1_CPU3_WFI_EN_LSB                 (1U << 0)       /* 1b */
-
-/* CPU_PTPOD2_CON (0x10006000+0x560) */
-#define MP0_PTPOD2_FBB_EN_LSB               (1U << 0)       /* 1b */
-#define MP1_PTPOD2_FBB_EN_LSB               (1U << 1)       /* 1b */
-#define MP0_PTPOD2_SPARK_EN_LSB             (1U << 2)       /* 1b */
-#define MP1_PTPOD2_SPARK_EN_LSB             (1U << 3)       /* 1b */
-#define MP0_PTPOD2_FBB_ACK_LSB              (1U << 4)       /* 1b */
-#define MP1_PTPOD2_FBB_ACK_LSB              (1U << 5)       /* 1b */
-
-/* ROOT_CPUTOP_ADDR (0x10006000+0x570) */
-#define ROOT_CPUTOP_ADDR_LSB                (1U << 0)       /* 32b */
-
-/* ROOT_CORE_ADDR (0x10006000+0x574) */
-#define ROOT_CORE_ADDR_LSB                  (1U << 0)       /* 32b */
-
-/* CPU_SPARE_CON (0x10006000+0x580) */
-#define CPU_SPARE_CON_LSB                   (1U << 0)       /* 32b */
-
-/* CPU_SPARE_CON_SET (0x10006000+0x584) */
-#define CPU_SPARE_CON_SET_LSB               (1U << 0)       /* 32b */
-
-/* CPU_SPARE_CON_CLR (0x10006000+0x588) */
-#define CPU_SPARE_CON_CLR_LSB               (1U << 0)       /* 32b */
-
-/* SPM_SW_FLAG (0x10006000+0x600) */
-#define SPM_SW_FLAG_LSB                     (1U << 0)       /* 32b */
-
-/* SPM_SW_DEBUG (0x10006000+0x604) */
-#define SPM_SW_DEBUG_LSB                    (1U << 0)       /* 32b */
-
-/* SPM_SW_RSV_0 (0x10006000+0x608) */
-#define SPM_SW_RSV_0_LSB                    (1U << 0)       /* 32b */
-
-/* SPM_SW_RSV_1 (0x10006000+0x60C) */
-#define SPM_SW_RSV_1_LSB                    (1U << 0)       /* 32b */
-
-/* SPM_SW_RSV_2 (0x10006000+0x610) */
-#define SPM_SW_RSV_2_LSB                    (1U << 0)       /* 32b */
-
-/* SPM_SW_RSV_3 (0x10006000+0x614) */
-#define SPM_SW_RSV_3_LSB                    (1U << 0)       /* 32b */
-
-/* SPM_SW_RSV_4 (0x10006000+0x618) */
-#define SPM_SW_RSV_4_LSB                    (1U << 0)       /* 32b */
-
-/* SPM_SW_RSV_5 (0x10006000+0x61C) */
-#define SPM_SW_RSV_5_LSB                    (1U << 0)       /* 32b */
-
-/* SPM_RSV_CON (0x10006000+0x620) */
-#define SPM_RSV_CON_LSB                     (1U << 0)       /* 16b */
-
-/* SPM_RSV_STA (0x10006000+0x624) */
-#define SPM_RSV_STA_LSB                     (1U << 0)       /* 16b */
-
-/* SPM_PASR_DPD_0 (0x10006000+0x630) */
-#define SPM_PASR_DPD_0_LSB                  (1U << 0)       /* 32b */
-
-/* SPM_PASR_DPD_1 (0x10006000+0x634) */
-#define SPM_PASR_DPD_1_LSB                  (1U << 0)       /* 32b */
-
-/* SPM_PASR_DPD_2 (0x10006000+0x638) */
-#define SPM_PASR_DPD_2_LSB                  (1U << 0)       /* 32b */
-
-/* SPM_PASR_DPD_3 (0x10006000+0x63C) */
-#define SPM_PASR_DPD_3_LSB                  (1U << 0)       /* 32b */
-
-/* SPM_SPARE_CON (0x10006000+0x640) */
-#define SPM_SPARE_CON_LSB                   (1U << 0)       /* 32b */
-
-/* SPM_SPARE_CON_SET (0x10006000+0x644) */
-#define SPM_SPARE_CON_SET_LSB               (1U << 0)       /* 32b */
-
-/* SPM_SPARE_CON_CLR (0x10006000+0x648) */
-#define SPM_SPARE_CON_CLR_LSB               (1U << 0)       /* 32b */
-
-/* SPM_SW_RSV_6 (0x10006000+0x64C) */
-#define SPM_SW_RSV_6_LSB                    (1U << 0)       /* 32b */
-
-/* SPM_SW_RSV_7 (0x10006000+0x650) */
-#define SPM_SW_RSV_7_LSB                    (1U << 0)       /* 32b */
-
-/* SPM_SW_RSV_8 (0x10006000+0x654) */
-#define SPM_SW_RSV_8_LSB                    (1U << 0)       /* 32b */
-
-/* SPM_SW_RSV_9 (0x10006000+0x658) */
-#define SPM_SW_RSV_9_LSB                    (1U << 0)       /* 32b */
-
-/* SPM_SW_RSV_10 (0x10006000+0x65C) */
-#define SPM_SW_RSV_10_LSB                   (1U << 0)       /* 32b */
-
-/* SPM_SW_RSV_11 (0x10006000+0x660) */
-#define SPM_SW_RSV_11_LSB                   (1U << 0)       /* 32b */
-
-/* SPM_SW_RSV_12 (0x10006000+0x664) */
-#define SPM_SW_RSV_12_LSB                   (1U << 0)       /* 32b */
-
-/* SPM_SW_RSV_13 (0x10006000+0x668) */
-#define SPM_SW_RSV_13_LSB                   (1U << 0)       /* 32b */
-
-/* SPM_SW_RSV_14 (0x10006000+0x66C) */
-#define SPM_SW_RSV_14_LSB                   (1U << 0)       /* 32b */
-
-/* SPM_SW_RSV_15 (0x10006000+0x670) */
-#define SPM_SW_RSV_15_LSB                   (1U << 0)       /* 32b */
-
-/* SPM_SW_RSV_16 (0x10006000+0x674) */
-#define SPM_SW_RSV_16_LSB                   (1U << 0)       /* 32b */
-
-/* SPM_SW_RSV_17 (0x10006000+0x678) */
-#define SPM_SW_RSV_17_LSB                   (1U << 0)       /* 32b */
-
-/* SPM_SW_RSV_18 (0x10006000+0x67C) */
-#define SPM_SW_RSV_18_LSB                   (1U << 0)       /* 32b */
-
-/* SPM_SW_RSV_19 (0x10006000+0x680) */
-#define SPM_SW_RSV_19_LSB                   (1U << 0)       /* 32b */
-
-/* SW_CRTL_EVENT (0x10006000+0x690) */
-#define SW_CRTL_EVENT_ON_LSB                (1U << 0)       /* 1b */
-
-#define SPM_PROJECT_CODE	0xb16
-
-#define SPM_REGWR_EN		(1U << 0)
-#define SPM_REGWR_CFG_KEY	(SPM_PROJECT_CODE << 16)
-
-#define SPM_CPU_PDN_DIS		(1U << 0)
-#define SPM_INFRA_PDN_DIS	(1U << 1)
-#define SPM_DDRPHY_PDN_DIS	(1U << 2)
-#define SPM_DUALVCORE_PDN_DIS	(1U << 3)
-#define SPM_PASR_DIS		(1U << 4)
-#define SPM_DPD_DIS		(1U << 5)
-#define SPM_SODI_DIS		(1U << 6)
-#define SPM_MEMPLL_RESET	(1U << 7)
-#define SPM_MAINPLL_PDN_DIS	(1U << 8)
-#define SPM_CPU_DVS_DIS		(1U << 9)
-#define SPM_CPU_DORMANT		(1U << 10)
-#define SPM_EXT_VSEL_GPIO103	(1U << 11)
-#define SPM_DDR_HIGH_SPEED	(1U << 12)
-#define SPM_OPT			(1U << 13)
-
-#define POWER_ON_VAL1_DEF	0x15820
-#define PCM_FSM_STA_DEF		0x48490
-#define PCM_END_FSM_STA_DEF	0x08490
-#define PCM_END_FSM_STA_MASK	0x3fff0
-#define PCM_HANDSHAKE_SEND1	0xbeefbeef
-
-#define PCM_WDT_TIMEOUT		(30 * 32768)
-#define PCM_TIMER_MAX		(0xffffffff - PCM_WDT_TIMEOUT)
-
-#define CON0_PCM_KICK		(1U << 0)
-#define CON0_IM_KICK		(1U << 1)
-#define CON0_IM_SLEEP_DVS	(1U << 3)
-#define CON0_PCM_SW_RESET	(1U << 15)
-#define CON0_CFG_KEY		(SPM_PROJECT_CODE << 16)
-
-#define CON1_IM_SLAVE		(1U << 0)
-#define CON1_MIF_APBEN		(1U << 3)
-#define CON1_PCM_TIMER_EN	(1U << 5)
-#define CON1_IM_NONRP_EN	(1U << 6)
-#define CON1_PCM_WDT_EN		(1U << 8)
-#define CON1_PCM_WDT_WAKE_MODE	(1U << 9)
-#define CON1_SPM_SRAM_SLP_B	(1U << 10)
-#define CON1_SPM_SRAM_ISO_B	(1U << 11)
-#define CON1_EVENT_LOCK_EN	(1U << 12)
-#define CON1_CFG_KEY		(SPM_PROJECT_CODE << 16)
-
-#define PCM_PWRIO_EN_R0		(1U << 0)
-#define PCM_PWRIO_EN_R7		(1U << 7)
-#define PCM_RF_SYNC_R0		(1U << 16)
-#define PCM_RF_SYNC_R2		(1U << 18)
-#define PCM_RF_SYNC_R6		(1U << 22)
-#define PCM_RF_SYNC_R7		(1U << 23)
-
-#define CC_SYSCLK0_EN_0		(1U << 0)
-#define CC_SYSCLK0_EN_1		(1U << 1)
-#define CC_SYSCLK1_EN_0		(1U << 2)
-#define CC_SYSCLK1_EN_1		(1U << 3)
-#define CC_SYSSETTLE_SEL	(1U << 4)
-#define CC_LOCK_INFRA_DCM	(1U << 5)
-#define CC_SRCLKENA_MASK_0	(1U << 6)
-#define CC_CXO32K_RM_EN_MD1	(1U << 9)
-#define CC_CXO32K_RM_EN_MD2	(1U << 10)
-#define CC_CLKSQ1_SEL		(1U << 12)
-#define CC_DISABLE_DORM_PWR	(1U << 14)
-#define CC_MD32_DCM_EN		(1U << 18)
-
-#define WFI_OP_AND		1
-#define WFI_OP_OR		0
-
-#define WAKE_MISC_PCM_TIMER	(1U << 19)
-#define WAKE_MISC_CPU_WAKE	(1U << 20)
-
-/* define WAKE_SRC_XXX */
-#define WAKE_SRC_SPM_MERGE	(1 << 0)
-#define WAKE_SRC_KP		(1 << 2)
-#define WAKE_SRC_WDT		(1 << 3)
-#define WAKE_SRC_GPT		(1 << 4)
-#define WAKE_SRC_EINT		(1 << 6)
-#define WAKE_SRC_LOW_BAT	(1 << 9)
-#define WAKE_SRC_MD32		(1 << 10)
-#define WAKE_SRC_USB_CD		(1 << 14)
-#define WAKE_SRC_USB_PDN	(1 << 15)
-#define WAKE_SRC_AFE		(1 << 20)
-#define WAKE_SRC_THERM		(1 << 21)
-#define WAKE_SRC_SYSPWREQ	(1 << 24)
-#define WAKE_SRC_SEJ		(1 << 27)
-#define WAKE_SRC_ALL_MD32	(1 << 28)
-#define WAKE_SRC_CPU_IRQ	(1 << 29)
-
-#define spm_read(addr)		mmio_read_32(addr)
-#define spm_write(addr, val)	mmio_write_32(addr, val)
-
-#endif /* SPM_H */
diff --git a/plat/mediatek/mt8183/include/sspm_reg.h b/plat/mediatek/mt8183/include/sspm_reg.h
new file mode 100644
index 0000000..3f1ac86
--- /dev/null
+++ b/plat/mediatek/mt8183/include/sspm_reg.h
@@ -0,0 +1,41 @@
+/*
+ * Copyright (c) 2019, ARM Limited and Contributors. All rights reserved.
+ *
+ * SPDX-License-Identifier: BSD-3-Clause
+ */
+
+#ifndef __SSPM_REG_H__
+#define __SSPM_REG_H__
+
+#include "platform_def.h"
+
+#define SSPM_CFGREG_RSV_RW_REG0        (SSPM_CFGREG_BASE + 0x0100)
+#define SSPM_CFGREG_ACAO_INT_SET       (SSPM_CFGREG_BASE + 0x00D8)
+#define SSPM_CFGREG_ACAO_INT_CLR       (SSPM_CFGREG_BASE + 0x00DC)
+#define SSPM_CFGREG_ACAO_WAKEUP_EN     (SSPM_CFGREG_BASE + 0x0204)
+
+#define STANDBYWFI_EN(n)               (1 << (n +  8))
+#define GIC_IRQOUT_EN(n)               (1 << (n +  0))
+
+#define NF_MCDI_MBOX                            19
+#define MCDI_MBOX_CLUSTER_0_CAN_POWER_OFF       0
+#define MCDI_MBOX_CLUSTER_1_CAN_POWER_OFF       1
+#define MCDI_MBOX_BUCK_POWER_OFF_MASK           2
+#define MCDI_MBOX_CLUSTER_0_ATF_ACTION_DONE     3
+#define MCDI_MBOX_CLUSTER_1_ATF_ACTION_DONE     4
+#define MCDI_MBOX_BOOTADDR                      5
+#define MCDI_MBOX_PAUSE_ACTION                  6
+#define MCDI_MBOX_AVAIL_CPU_MASK                7
+#define MCDI_MBOX_CPU_CLUSTER_PWR_STAT          8
+#define MCDI_MBOX_ACTION_STAT                   9
+#define MCDI_MBOX_CLUSTER_0_CNT                 10
+#define MCDI_MBOX_CLUSTER_1_CNT                 11
+#define MCDI_MBOX_CPU_ISOLATION_MASK            12
+#define MCDI_MBOX_PAUSE_ACK                     13
+#define MCDI_MBOX_PENDING_ON_EVENT              14
+#define MCDI_MBOX_PROF_CMD                      15
+#define MCDI_MBOX_DRCC_CALI_DONE                16
+#define MCDI_MBOX_HP_CMD                        17
+#define MCDI_MBOX_HP_ACK                        18
+
+#endif /* __SSPM_REG_H__ */
diff --git a/plat/mediatek/mt8183/plat_debug.c b/plat/mediatek/mt8183/plat_debug.c
index 51816db..2f0b67d 100644
--- a/plat/mediatek/mt8183/plat_debug.c
+++ b/plat/mediatek/mt8183/plat_debug.c
@@ -9,6 +9,7 @@
 #include <lib/mmio.h>
 #include <plat_debug.h>
 #include <platform_def.h>
+#include <spm.h>
 
 void circular_buffer_setup(void)
 {
diff --git a/plat/mediatek/mt8183/plat_pm.c b/plat/mediatek/mt8183/plat_pm.c
index 83c8d4c..555b389 100644
--- a/plat/mediatek/mt8183/plat_pm.c
+++ b/plat/mediatek/mt8183/plat_pm.c
@@ -16,6 +16,7 @@
 #include <platform_def.h>
 #include <scu.h>
 #include <mt_gic_v3.h>
+#include <mtk_mcdi.h>
 #include <mtk_plat_common.h>
 #include <mtgpio.h>
 #include <mtspmc.h>
@@ -25,9 +26,103 @@
 #include <plat_private.h>
 #include <power_tracer.h>
 #include <pmic.h>
+#include <spm.h>
+#include <spm_suspend.h>
+#include <sspm.h>
 #include <rtc.h>
 
-#define MTK_LOCAL_STATE_OFF     2
+/* Local power state for power domains in Run state. */
+#define MTK_LOCAL_STATE_RUN	0
+/* Local power state for retention. */
+#define MTK_LOCAL_STATE_RET	1
+/* Local power state for OFF/power-down. */
+#define MTK_LOCAL_STATE_OFF	2
+
+#if PSCI_EXTENDED_STATE_ID
+/*
+ * Macros used to parse state information from State-ID if it is using the
+ * recommended encoding for State-ID.
+ */
+#define MTK_LOCAL_PSTATE_WIDTH		4
+#define MTK_LOCAL_PSTATE_MASK		((1 << MTK_LOCAL_PSTATE_WIDTH) - 1)
+
+/* Macros to construct the composite power state */
+
+/* Make composite power state parameter till power level 0 */
+
+#define mtk_make_pwrstate_lvl0(lvl0_state, pwr_lvl, type) \
+	(((lvl0_state) << PSTATE_ID_SHIFT) | ((type) << PSTATE_TYPE_SHIFT))
+
+#else /* !PSCI_EXTENDED_STATE_ID */
+
+#define mtk_make_pwrstate_lvl0(lvl0_state, pwr_lvl, type) \
+		(((lvl0_state) << PSTATE_ID_SHIFT) | \
+		((pwr_lvl) << PSTATE_PWR_LVL_SHIFT) | \
+		((type) << PSTATE_TYPE_SHIFT))
+
+#endif /* PSCI_EXTENDED_STATE_ID */
+
+/* Make composite power state parameter till power level 1 */
+#define mtk_make_pwrstate_lvl1(lvl1_state, lvl0_state, pwr_lvl, type) \
+		(((lvl1_state) << MTK_LOCAL_PSTATE_WIDTH) | \
+		mtk_make_pwrstate_lvl0(lvl0_state, pwr_lvl, type))
+
+/* Make composite power state parameter till power level 2 */
+#define mtk_make_pwrstate_lvl2( \
+		lvl2_state, lvl1_state, lvl0_state, pwr_lvl, type) \
+		(((lvl2_state) << (MTK_LOCAL_PSTATE_WIDTH * 2)) | \
+		mtk_make_pwrstate_lvl1(lvl1_state, lvl0_state, pwr_lvl, type))
+
+#define MTK_PWR_LVL0	0
+#define MTK_PWR_LVL1	1
+#define MTK_PWR_LVL2	2
+
+/* Macros to read the MTK power domain state */
+#define MTK_CORE_PWR_STATE(state)	(state)->pwr_domain_state[MTK_PWR_LVL0]
+#define MTK_CLUSTER_PWR_STATE(state)	(state)->pwr_domain_state[MTK_PWR_LVL1]
+#define MTK_SYSTEM_PWR_STATE(state)	((PLAT_MAX_PWR_LVL > MTK_PWR_LVL1) ? \
+			(state)->pwr_domain_state[MTK_PWR_LVL2] : 0)
+
+#if PSCI_EXTENDED_STATE_ID
+/*
+ *  The table storing the valid idle power states. Ensure that the
+ *  array entries are populated in ascending order of state-id to
+ *  enable us to use binary search during power state validation.
+ *  The table must be terminated by a NULL entry.
+ */
+const unsigned int mtk_pm_idle_states[] = {
+	/* State-id - 0x001 */
+	mtk_make_pwrstate_lvl2(MTK_LOCAL_STATE_RUN, MTK_LOCAL_STATE_RUN,
+		MTK_LOCAL_STATE_RET, MTK_PWR_LVL0, PSTATE_TYPE_STANDBY),
+	/* State-id - 0x002 */
+	mtk_make_pwrstate_lvl2(MTK_LOCAL_STATE_RUN, MTK_LOCAL_STATE_RUN,
+		MTK_LOCAL_STATE_OFF, MTK_PWR_LVL0, PSTATE_TYPE_POWERDOWN),
+	/* State-id - 0x022 */
+	mtk_make_pwrstate_lvl2(MTK_LOCAL_STATE_RUN, MTK_LOCAL_STATE_OFF,
+		MTK_LOCAL_STATE_OFF, MTK_PWR_LVL1, PSTATE_TYPE_POWERDOWN),
+#if PLAT_MAX_PWR_LVL > MTK_PWR_LVL1
+	/* State-id - 0x222 */
+	mtk_make_pwrstate_lvl2(MTK_LOCAL_STATE_OFF, MTK_LOCAL_STATE_OFF,
+		MTK_LOCAL_STATE_OFF, MTK_PWR_LVL2, PSTATE_TYPE_POWERDOWN),
+#endif
+	0,
+};
+#endif
+
+#define CPU_IDX(cluster, cpu)		((cluster << 2) + cpu)
+#define ON	true
+#define OFF	false
+
+/* Pause MCDI when CPU hotplug */
+static bool HP_SSPM_PAUSE;
+/* CPU Hotplug by SSPM */
+static bool HP_SSPM_CTRL = true;
+/* Turn off cluster when CPU hotplug off */
+static bool HP_CLUSTER_OFF = true;
+/* Turn off cluster when CPU MCDI off */
+static bool MCDI_C2 = true;
+/* Enable MCDI */
+static bool MCDI_SSPM = true;
 
 static uintptr_t secure_entrypoint;
 
@@ -38,30 +133,171 @@
 	dsb();
 }
 
+static bool clst_single_pwr(int cluster, int cpu)
+{
+	uint32_t cpu_mask[2] = {0x00001e00, 0x000f0000};
+	uint32_t cpu_pwr_bit[] = {9, 10, 11, 12, 16, 17, 18, 19};
+	int my_idx = (cluster << 2) + cpu;
+	uint32_t pwr_stat = mmio_read_32(0x10006180);
+
+	return !(pwr_stat & (cpu_mask[cluster] & ~BIT(cpu_pwr_bit[my_idx])));
+}
+
+static bool clst_single_on(int cluster, int cpu)
+{
+	uint32_t cpu_mask[2] = {0x0f, 0xf0};
+	int my_idx = (cluster << 2) + cpu;
+	uint32_t on_stat = mcdi_avail_cpu_mask_read();
+
+	return !(on_stat & (cpu_mask[cluster] & ~BIT(my_idx)));
+}
+
+static void plat_cluster_pwrdwn_common(uint64_t mpidr, int cluster)
+{
+	if (cluster > 0)
+		mt_gic_sync_dcm_enable();
+
+	/* Disable coherency */
+	plat_mtk_cci_disable();
+	disable_scu(mpidr);
+}
+
+static void plat_cluster_pwron_common(uint64_t mpidr, int cluster)
+{
+	if (cluster > 0) {
+		l2c_parity_check_setup();
+		circular_buffer_setup();
+		mp1_L2_desel_config();
+		mt_gic_sync_dcm_disable();
+	}
+
+	/* Enable coherency */
+	enable_scu(mpidr);
+	plat_mtk_cci_enable();
+	/* Enable big core dcm */
+	plat_dcm_restore_cluster_on(mpidr);
+	/* Enable rgu dcm */
+	plat_dcm_rgu_enable();
+}
+
+static void plat_cpu_standby(plat_local_state_t cpu_state)
+{
+	unsigned int scr;
+
+	scr = read_scr_el3();
+	write_scr_el3(scr | SCR_IRQ_BIT | SCR_FIQ_BIT);
+
+	isb();
+	dsb();
+	wfi();
+
+	write_scr_el3(scr);
+}
+
+static void mcdi_ctrl_before_hotplug_on(int cluster, int cpu)
+{
+	if (!HP_SSPM_CTRL && HP_SSPM_PAUSE && MCDI_SSPM) {
+		mcdi_pause_clr(cluster, CPU_IDX(cluster, cpu), OFF);
+		mcdi_pause_set(cluster, CPU_IDX(cluster, cpu), ON);
+	}
+}
+
+static void mcdi_ctrl_before_hotplug_off(int cluster, int cpu, bool cluster_off)
+{
+	if (!HP_SSPM_CTRL && HP_SSPM_PAUSE && MCDI_SSPM)
+		mcdi_pause_set(cluster_off ? cluster : -1,
+				CPU_IDX(cluster, cpu), OFF);
+}
+
+static void mcdi_ctrl_cluster_cpu_off(int cluster, int cpu, bool cluster_off)
+{
+	if (MCDI_SSPM) {
+		sspm_set_bootaddr(secure_entrypoint);
+
+		sspm_standbywfi_irq_enable(CPU_IDX(cluster, cpu));
+
+		if (cluster_off)
+			sspm_cluster_pwr_off_notify(cluster);
+		else
+			sspm_cluster_pwr_on_notify(cluster);
+	}
+}
+
+static void mcdi_ctrl_suspend(void)
+{
+	if (MCDI_SSPM)
+		mcdi_pause();
+}
+
+static void mcdi_ctrl_resume(void)
+{
+	if (MCDI_SSPM)
+		mcdi_unpause();
+}
+
+static void hotplug_ctrl_cluster_on(int cluster, int cpu)
+{
+	if (HP_SSPM_CTRL && MCDI_SSPM) {
+		mcdi_hotplug_clr(cluster, CPU_IDX(cluster, cpu), OFF);
+		mcdi_hotplug_set(cluster, -1, ON);
+		mcdi_hotplug_wait_ack(cluster, -1, ON);
+	} else {
+		/* power on cluster */
+		if (!spm_get_cluster_powerstate(cluster))
+			spm_poweron_cluster(cluster);
+	}
+}
+
+static void hotplug_ctrl_cpu_on(int cluster, int cpu)
+{
+	if (HP_SSPM_CTRL && MCDI_SSPM)
+		mcdi_hotplug_set(cluster, CPU_IDX(cluster, cpu), ON);
+	else
+		spm_poweron_cpu(cluster, cpu);
+}
+
+static void hotplug_ctrl_cpu_on_finish(int cluster, int cpu)
+{
+	spm_disable_cpu_auto_off(cluster, cpu);
+
+	if (HP_SSPM_CTRL && MCDI_SSPM)
+		mcdi_hotplug_clr(cluster, CPU_IDX(cluster, cpu), ON);
+	else if (HP_SSPM_PAUSE && MCDI_SSPM)
+		mcdi_pause_clr(cluster, CPU_IDX(cluster, cpu), ON);
+
+	mcdi_avail_cpu_mask_set(BIT(CPU_IDX(cluster, cpu)));
+}
+
+static void hotplug_ctrl_cluster_cpu_off(int cluster, int cpu, bool cluster_off)
+{
+	mcdi_avail_cpu_mask_clr(BIT(CPU_IDX(cluster, cpu)));
+
+	if (HP_SSPM_CTRL && MCDI_SSPM) {
+		mcdi_hotplug_set(cluster_off ? cluster : -1,
+				CPU_IDX(cluster, cpu), OFF);
+	} else {
+		spm_enable_cpu_auto_off(cluster, cpu);
+
+		if (cluster_off)
+			spm_enable_cluster_auto_off(cluster);
+
+		spm_set_cpu_power_off(cluster, cpu);
+	}
+}
+
 static int plat_mtk_power_domain_on(unsigned long mpidr)
 {
 	int cpu = MPIDR_AFFLVL0_VAL(mpidr);
 	int cluster = MPIDR_AFFLVL1_VAL(mpidr);
 
-	INFO("%s():%d: mpidr: %lx, c.c: %d.%d\n",
-		__func__, __LINE__, mpidr, cluster, cpu);
-
-	/* power on cluster */
-	if (!spm_get_cluster_powerstate(cluster)) {
-		spm_poweron_cluster(cluster);
-		if (cluster == 1) {
-			l2c_parity_check_setup();
-			circular_buffer_setup();
-			mp1_L2_desel_config();
-			mt_gic_sync_dcm_disable();
-		}
-	}
+	mcdi_ctrl_before_hotplug_on(cluster, cpu);
+	hotplug_ctrl_cluster_on(cluster, cpu);
 
 	/* init cpu reset arch as AARCH64 */
 	mcucfg_init_archstate(cluster, cpu, 1);
 	mcucfg_set_bootaddr(cluster, cpu, secure_entrypoint);
 
-	spm_poweron_cpu(cluster, cpu);
+	hotplug_ctrl_cpu_on(cluster, cpu);
 
 	return PSCI_E_SUCCESS;
 }
@@ -71,23 +307,18 @@
 	uint64_t mpidr = read_mpidr();
 	int cpu = MPIDR_AFFLVL0_VAL(mpidr);
 	int cluster = MPIDR_AFFLVL1_VAL(mpidr);
+	const plat_local_state_t *pds = state->pwr_domain_state;
+	bool afflvl1 = (pds[MPIDR_AFFLVL1] == MTK_LOCAL_STATE_OFF);
+	bool cluster_off = (HP_CLUSTER_OFF && afflvl1 &&
+					clst_single_on(cluster, cpu));
 
-	INFO("%s():%d: c.c: %d.%d\n", __func__, __LINE__, cluster, cpu);
-
-	/* Prevent interrupts from spuriously waking up this cpu */
 	mt_gic_cpuif_disable();
 
-	spm_enable_cpu_auto_off(cluster, cpu);
+	if (cluster_off)
+		plat_cluster_pwrdwn_common(mpidr, cluster);
 
-	if (state->pwr_domain_state[MPIDR_AFFLVL1] == MTK_LOCAL_STATE_OFF) {
-		if (cluster == 1)
-			mt_gic_sync_dcm_enable();
-
-		plat_mtk_cci_disable();
-		spm_enable_cluster_auto_off(cluster);
-	}
-
-	spm_set_cpu_power_off(cluster, cpu);
+	mcdi_ctrl_before_hotplug_off(cluster, cpu, cluster_off);
+	hotplug_ctrl_cluster_cpu_off(cluster, cpu, cluster_off);
 }
 
 static void plat_mtk_power_domain_on_finish(const psci_power_state_t *state)
@@ -95,29 +326,170 @@
 	uint64_t mpidr = read_mpidr();
 	int cpu = MPIDR_AFFLVL0_VAL(mpidr);
 	int cluster = MPIDR_AFFLVL1_VAL(mpidr);
+	const plat_local_state_t *pds = state->pwr_domain_state;
+	bool afflvl1 = (pds[MPIDR_AFFLVL1] == MTK_LOCAL_STATE_OFF);
 
-	INFO("%s():%d: c.c: %d.%d\n", __func__, __LINE__, cluster, cpu);
+	if (afflvl1)
+		plat_cluster_pwron_common(mpidr, cluster);
 
-	assert(state->pwr_domain_state[MPIDR_AFFLVL0] == MTK_LOCAL_STATE_OFF);
-
-	if (state->pwr_domain_state[MPIDR_AFFLVL1] == MTK_LOCAL_STATE_OFF) {
-		enable_scu(mpidr);
-
-		/* Enable coherency if this cluster was off */
-		plat_mtk_cci_enable();
-		/* Enable big core dcm if this cluster was on */
-		plat_dcm_restore_cluster_on(mpidr);
-		/* Enable rgu dcm if this cluster was off */
-		plat_dcm_rgu_enable();
-	}
-
-	spm_disable_cpu_auto_off(cluster, cpu);
-
-	/* Enable the gic cpu interface */
 	mt_gic_pcpu_init();
 	mt_gic_cpuif_enable();
+
+	hotplug_ctrl_cpu_on_finish(cluster, cpu);
 }
 
+static void plat_mtk_power_domain_suspend(const psci_power_state_t *state)
+{
+	uint64_t mpidr = read_mpidr();
+	int cpu = MPIDR_AFFLVL0_VAL(mpidr);
+	int cluster = MPIDR_AFFLVL1_VAL(mpidr);
+	const plat_local_state_t *pds = state->pwr_domain_state;
+	bool afflvl1 = (pds[MPIDR_AFFLVL1] == MTK_LOCAL_STATE_OFF);
+	bool afflvl2 = (pds[MPIDR_AFFLVL2] == MTK_LOCAL_STATE_OFF);
+	bool cluster_off = MCDI_C2 && afflvl1 && clst_single_pwr(cluster, cpu);
+
+	/* init cpu reset arch as AARCH64 */
+	mcucfg_init_archstate(cluster, cpu, 1);
+	mcucfg_set_bootaddr(cluster, cpu, secure_entrypoint);
+
+	mt_gic_cpuif_disable();
+	mt_gic_irq_save();
+	plat_dcm_mcsi_a_backup();
+
+	if (cluster_off || afflvl2)
+		plat_cluster_pwrdwn_common(mpidr, cluster);
+
+	if (afflvl2) {
+		spm_data_t spm_d = { .cmd = SPM_SUSPEND };
+		uint32_t *d = (uint32_t *)&spm_d;
+		uint32_t l = sizeof(spm_d) / sizeof(uint32_t);
+
+		mcdi_ctrl_suspend();
+
+		spm_set_bootaddr(secure_entrypoint);
+
+		if (MCDI_SSPM)
+			sspm_ipi_send_non_blocking(IPI_ID_SUSPEND, d);
+
+		spm_system_suspend();
+
+		if (MCDI_SSPM)
+			while (sspm_ipi_recv_non_blocking(IPI_ID_SUSPEND, d, l))
+				;
+	} else {
+		mcdi_ctrl_cluster_cpu_off(cluster, cpu, cluster_off);
+	}
+}
+
+static void plat_mtk_power_domain_suspend_finish(const psci_power_state_t *state)
+{
+	uint64_t mpidr = read_mpidr();
+	int cluster = MPIDR_AFFLVL1_VAL(mpidr);
+	const plat_local_state_t *pds = state->pwr_domain_state;
+	bool afflvl2 = (pds[MPIDR_AFFLVL2] == MTK_LOCAL_STATE_OFF);
+
+	if (afflvl2) {
+		spm_data_t spm_d = { .cmd = SPM_RESUME };
+		uint32_t *d = (uint32_t *)&spm_d;
+		uint32_t l = sizeof(spm_d) / sizeof(uint32_t);
+
+		mt_gic_init();
+		mt_gic_irq_restore();
+		mmio_write_32(EMI_WFIFO, 0xf);
+
+		if (MCDI_SSPM)
+			sspm_ipi_send_non_blocking(IPI_ID_SUSPEND, d);
+
+		spm_system_suspend_finish();
+
+		if (MCDI_SSPM)
+			while (sspm_ipi_recv_non_blocking(IPI_ID_SUSPEND, d, l))
+				;
+
+		mcdi_ctrl_resume();
+	}
+
+	plat_cluster_pwron_common(mpidr, cluster);
+
+	plat_dcm_mcsi_a_restore();
+}
+
+#if PSCI_EXTENDED_STATE_ID
+
+static int plat_mtk_validate_power_state(unsigned int power_state,
+				psci_power_state_t *req_state)
+{
+	unsigned int state_id;
+	int i;
+
+	assert(req_state);
+
+	if (!MCDI_SSPM)
+		return PSCI_E_INVALID_PARAMS;
+
+	/*
+	 *  Currently we are using a linear search for finding the matching
+	 *  entry in the idle power state array. This can be made a binary
+	 *  search if the number of entries justify the additional complexity.
+	 */
+	for (i = 0; !!mtk_pm_idle_states[i]; i++) {
+		if (power_state == mtk_pm_idle_states[i])
+			break;
+	}
+
+	/* Return error if entry not found in the idle state array */
+	if (!mtk_pm_idle_states[i])
+		return PSCI_E_INVALID_PARAMS;
+
+	i = 0;
+	state_id = psci_get_pstate_id(power_state);
+
+	/* Parse the State ID and populate the state info parameter */
+	while (state_id) {
+		req_state->pwr_domain_state[i++] = state_id &
+						MTK_LOCAL_PSTATE_MASK;
+		state_id >>= MTK_LOCAL_PSTATE_WIDTH;
+	}
+
+	return PSCI_E_SUCCESS;
+}
+
+#else /* if !PSCI_EXTENDED_STATE_ID */
+
+static int plat_mtk_validate_power_state(unsigned int power_state,
+					psci_power_state_t *req_state)
+{
+	int pstate = psci_get_pstate_type(power_state);
+	int pwr_lvl = psci_get_pstate_pwrlvl(power_state);
+	int i;
+
+	assert(req_state);
+
+	if (pwr_lvl > PLAT_MAX_PWR_LVL)
+		return PSCI_E_INVALID_PARAMS;
+
+	/* Sanity check the requested state */
+	if (pstate == PSTATE_TYPE_STANDBY) {
+		/*
+		 * It's possible to enter standby only on power level 0
+		 * Ignore any other power level.
+		 */
+		if (pwr_lvl != 0)
+			return PSCI_E_INVALID_PARAMS;
+
+		req_state->pwr_domain_state[MTK_PWR_LVL0] = MTK_LOCAL_STATE_RET;
+	} else if (!MCDI_SSPM) {
+		return PSCI_E_INVALID_PARAMS;
+	} else {
+		for (i = 0; i <= pwr_lvl; i++)
+			req_state->pwr_domain_state[i] = MTK_LOCAL_STATE_OFF;
+	}
+
+	return PSCI_E_SUCCESS;
+}
+
+#endif /* PSCI_EXTENDED_STATE_ID */
+
 /*******************************************************************************
  * MTK handlers to shutdown/reboot the system
  ******************************************************************************/
@@ -147,21 +519,29 @@
 	panic();
 }
 
+static void plat_mtk_get_sys_suspend_power_state(psci_power_state_t *req_state)
+{
+	assert(PLAT_MAX_PWR_LVL >= 2);
+
+	for (int i = MPIDR_AFFLVL0; i <= PLAT_MAX_PWR_LVL; i++)
+		req_state->pwr_domain_state[i] = MTK_LOCAL_STATE_OFF;
+}
+
 /*******************************************************************************
  * MTK_platform handler called when an affinity instance is about to be turned
  * on. The level and mpidr determine the affinity instance.
  ******************************************************************************/
 static const plat_psci_ops_t plat_plat_pm_ops = {
-	.cpu_standby			= NULL,
+	.cpu_standby			= plat_cpu_standby,
 	.pwr_domain_on			= plat_mtk_power_domain_on,
 	.pwr_domain_on_finish		= plat_mtk_power_domain_on_finish,
 	.pwr_domain_off			= plat_mtk_power_domain_off,
-	.pwr_domain_suspend		= NULL,
-	.pwr_domain_suspend_finish	= NULL,
+	.pwr_domain_suspend		= plat_mtk_power_domain_suspend,
+	.pwr_domain_suspend_finish	= plat_mtk_power_domain_suspend_finish,
 	.system_off			= plat_mtk_system_off,
 	.system_reset			= plat_mtk_system_reset,
-	.validate_power_state		= NULL,
-	.get_sys_suspend_power_state	= NULL,
+	.validate_power_state		= plat_mtk_validate_power_state,
+	.get_sys_suspend_power_state	= plat_mtk_get_sys_suspend_power_state,
 };
 
 int plat_setup_psci_ops(uintptr_t sec_entrypoint,
@@ -169,5 +549,11 @@
 {
 	*psci_ops = &plat_plat_pm_ops;
 	secure_entrypoint = sec_entrypoint;
+
+	if (!check_mcdi_ctl_stat()) {
+		HP_SSPM_CTRL = false;
+		MCDI_SSPM = false;
+	}
+
 	return 0;
 }
diff --git a/plat/mediatek/mt8183/platform.mk b/plat/mediatek/mt8183/platform.mk
index 09fd133..efa7e9e 100644
--- a/plat/mediatek/mt8183/platform.mk
+++ b/plat/mediatek/mt8183/platform.mk
@@ -9,10 +9,14 @@
 
 PLAT_INCLUDES := -I${MTK_PLAT}/common/                            \
                  -I${MTK_PLAT_SOC}/drivers/                       \
+                 -I${MTK_PLAT_SOC}/drivers/mcdi/                  \
                  -I${MTK_PLAT_SOC}/drivers/spmc/                  \
                  -I${MTK_PLAT_SOC}/drivers/gpio/                  \
                  -I${MTK_PLAT_SOC}/drivers/pmic/                  \
+                 -I${MTK_PLAT_SOC}/drivers/spm/                   \
+                 -I${MTK_PLAT_SOC}/drivers/sspm/                  \
                  -I${MTK_PLAT_SOC}/drivers/rtc/                   \
+                 -I${MTK_PLAT_SOC}/drivers/uart/                  \
                  -I${MTK_PLAT_SOC}/include/
 
 PLAT_BL_COMMON_SOURCES := lib/xlat_tables/aarch64/xlat_tables.c       \
@@ -45,15 +49,21 @@
                    ${MTK_PLAT_SOC}/drivers/mcsi/mcsi.c                   \
                    ${MTK_PLAT_SOC}/drivers/pmic/pmic.c                   \
                    ${MTK_PLAT_SOC}/drivers/rtc/rtc.c                     \
+                   ${MTK_PLAT_SOC}/drivers/mcdi/mtk_mcdi.c               \
                    ${MTK_PLAT_SOC}/drivers/spmc/mtspmc.c                 \
+                   ${MTK_PLAT_SOC}/drivers/spm/spm.c                     \
+                   ${MTK_PLAT_SOC}/drivers/spm/spm_pmic_wrap.c           \
+                   ${MTK_PLAT_SOC}/drivers/spm/spm_suspend.c             \
                    ${MTK_PLAT_SOC}/drivers/gpio/mtgpio.c                 \
+                   ${MTK_PLAT_SOC}/drivers/uart/uart.c                   \
                    ${MTK_PLAT_SOC}/plat_pm.c                             \
                    ${MTK_PLAT_SOC}/plat_topology.c                       \
                    ${MTK_PLAT_SOC}/plat_mt_gic.c                         \
                    ${MTK_PLAT_SOC}/plat_dcm.c                            \
                    ${MTK_PLAT_SOC}/bl31_plat_setup.c                     \
                    ${MTK_PLAT_SOC}/plat_debug.c                          \
-                   ${MTK_PLAT_SOC}/scu.c
+                   ${MTK_PLAT_SOC}/scu.c                                 \
+                   ${MTK_PLAT_SOC}/drivers/sspm/sspm.c
 
 # Enable workarounds for selected Cortex-A53 erratas.
 ERRATA_A53_826319 := 0