Merge "docs: marvell: Add information about CZ.NIC Armada 3720 Secure Firmware" into integration
diff --git a/Makefile b/Makefile
index b6c8b21..d424508 100644
--- a/Makefile
+++ b/Makefile
@@ -245,6 +245,13 @@
 # Determine if FEAT_RNG is supported
 ENABLE_FEAT_RNG		=	$(if $(findstring rng,${arch-features}),1,0)
 
+# Determine if FEAT_SB is supported
+ENABLE_FEAT_SB		=	$(if $(findstring sb,${arch-features}),1,0)
+
+ifeq "8.5" "$(word 1, $(sort 8.5 $(ARM_ARCH_MAJOR).$(ARM_ARCH_MINOR)))"
+ENABLE_FEAT_SB		= 	1
+endif
+
 ifneq ($(findstring armclang,$(notdir $(CC))),)
 TF_CFLAGS_aarch32	=	-target arm-arm-none-eabi $(march32-directive)
 TF_CFLAGS_aarch64	=	-target aarch64-arm-none-eabi $(march64-directive)
@@ -945,6 +952,7 @@
         COT_DESC_IN_DTB \
         USE_SP804_TIMER \
         ENABLE_FEAT_RNG \
+        ENABLE_FEAT_SB \
 )))
 
 $(eval $(call assert_numerics,\
@@ -1038,6 +1046,7 @@
         COT_DESC_IN_DTB \
         USE_SP804_TIMER \
         ENABLE_FEAT_RNG \
+        ENABLE_FEAT_SB \
 )))
 
 ifeq (${SANITIZE_UB},trap)
@@ -1298,8 +1307,6 @@
 fwu_fip: ${BUILD_PLAT}/${FWU_FIP_NAME}
 
 ${FIPTOOL}: FORCE
-	@${ECHO_BLANK_LINE}
-	@echo "Building $@"
 ifdef UNIX_MK
 	${Q}${MAKE} CPPFLAGS="-DVERSION='\"${VERSION_STRING}\"'" FIPTOOL=${FIPTOOL} --no-print-directory -C ${FIPTOOLPATH}
 else
@@ -1307,7 +1314,6 @@
 # to pass the gnumake flags to nmake.
 	${Q}set MAKEFLAGS= && ${MSVC_NMAKE} /nologo /f ${FIPTOOLPATH}/Makefile.msvc FIPTOOLPATH=$(subst /,\,$(FIPTOOLPATH)) FIPTOOL=$(subst /,\,$(FIPTOOL))
 endif
-	@${ECHO_BLANK_LINE}
 
 sptool: ${SPTOOL}
 ${SPTOOL}: FORCE
diff --git a/docs/about/maintainers.rst b/docs/about/maintainers.rst
index 0b3f782..30b2ab2 100644
--- a/docs/about/maintainers.rst
+++ b/docs/about/maintainers.rst
@@ -142,6 +142,15 @@
 :|F|: include/drivers/ufs.h
 :|F|: include/drivers/synopsys/dw_mmc.h
 
+JTAG DCC console driver
+^^^^^^^^^^^^^^^^^^^^^^^
+:M: Michal Simek <michal.simek@xilinx.com>
+:G: `michalsimek`_
+:M: Venkatesh Yadav Abbarapu <venkatesh.abbarapu@xilinx.com>
+:G: `venkatesh`_
+:F: drivers/arm/dcc/
+:F: include/drivers/arm/dcc.h
+
 Power State Coordination Interface (PSCI)
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 :|M|: Javier Almansa Sobrino <Javier.AlmansaSobrino@arm.com>
diff --git a/docs/getting_started/prerequisites.rst b/docs/getting_started/prerequisites.rst
index 91ecdf3..e2c527e 100644
--- a/docs/getting_started/prerequisites.rst
+++ b/docs/getting_started/prerequisites.rst
@@ -60,7 +60,7 @@
 
 The following libraries are required for Trusted Board Boot support:
 
-- mbed TLS == 2.24.0 (tag: ``mbedtls-2.24.0``)
+- mbed TLS == 2.26.0 (tag: ``mbedtls-2.26.0``)
 
 These tools are optional:
 
diff --git a/docs/plat/marvell/armada/build.rst b/docs/plat/marvell/armada/build.rst
index c2566c2..c74ff7a 100644
--- a/docs/plat/marvell/armada/build.rst
+++ b/docs/plat/marvell/armada/build.rst
@@ -26,7 +26,7 @@
 
        *u-boot.bin* should be used and not *u-boot-spl.bin*
 
-Set MSS/SCP image path (mandatory only for A7K/8K/CN913x)
+Set MSS/SCP image path (mandatory only for A7K/8K/CN913x when MSS_SUPPORT=1)
 
     .. code:: shell
 
diff --git a/docs/plat/xilinx-versal.rst b/docs/plat/xilinx-versal.rst
index 57a363b..3d4c4a4 100644
--- a/docs/plat/xilinx-versal.rst
+++ b/docs/plat/xilinx-versal.rst
@@ -19,6 +19,11 @@
 make RESET_TO_BL31=1 CROSS_COMPILE=aarch64-none-elf- PLAT=versal VERSAL_PLATFORM=versal_virt bl31
 ```
 
+To build TF-A for JTAG DCC console
+```bash
+make RESET_TO_BL31=1 CROSS_COMPILE=aarch64-none-elf- PLAT=versal bl31 VERSAL_CONSOLE=dcc
+```
+
 Xilinx Versal platform specific build options
 ---------------------------------------------
 
diff --git a/docs/plat/xilinx-zynqmp.rst b/docs/plat/xilinx-zynqmp.rst
index 5db4488..79c2535 100644
--- a/docs/plat/xilinx-zynqmp.rst
+++ b/docs/plat/xilinx-zynqmp.rst
@@ -22,6 +22,12 @@
 
     make CROSS_COMPILE=aarch64-none-elf- PLAT=zynqmp SPD=tspd bl31 bl32
 
+To build TF-A for JTAG DCC console:
+
+.. code:: bash
+
+    make CROSS_COMPILE=aarch64-none-elf- PLAT=zynqmp RESET_TO_BL31=1 bl31 ZYNQMP_CONSOLE=dcc
+
 ZynqMP platform specific build options
 --------------------------------------
 
diff --git a/drivers/arm/dcc/dcc_console.c b/drivers/arm/dcc/dcc_console.c
new file mode 100644
index 0000000..0b7e541
--- /dev/null
+++ b/drivers/arm/dcc/dcc_console.c
@@ -0,0 +1,152 @@
+/*
+ * Copyright (c) 2015-2021, Xilinx Inc.
+ * Written by Michal Simek.
+ *
+ * SPDX-License-Identifier: BSD-3-Clause
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *
+ * Redistributions of source code must retain the above copyright notice, this
+ * list of conditions and the following disclaimer.
+ *
+ * Redistributions in binary form must reproduce the above copyright notice,
+ * this list of conditions and the following disclaimer in the documentation
+ * and/or other materials provided with the distribution.
+ *
+ * Neither the name of ARM nor the names of its contributors may be used
+ * to endorse or promote products derived from this software without specific
+ * prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
+ * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
+ * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
+ * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
+ * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ */
+
+#include <errno.h>
+#include <stddef.h>
+#include <arch_helpers.h>
+#include <drivers/arm/dcc.h>
+#include <drivers/console.h>
+#include <drivers/delay_timer.h>
+#include <lib/mmio.h>
+
+/* DCC Status Bits */
+#define DCC_STATUS_RX		BIT(30)
+#define DCC_STATUS_TX		BIT(29)
+#define TIMEOUT_COUNT_US	U(0x10624)
+
+struct dcc_console {
+	struct console console;
+};
+
+static inline uint32_t __dcc_getstatus(void)
+{
+	return read_mdccsr_el0();
+}
+
+static inline char __dcc_getchar(void)
+{
+	char c;
+
+	c = read_dbgdtrrx_el0();
+
+	return c;
+}
+
+static inline void __dcc_putchar(char c)
+{
+	/*
+	 * The typecast is to make absolutely certain that 'c' is
+	 * zero-extended.
+	 */
+	write_dbgdtrtx_el0((unsigned char)c);
+}
+
+static int32_t dcc_status_timeout(uint32_t mask)
+{
+	const unsigned int timeout_count = TIMEOUT_COUNT_US;
+	uint64_t timeout;
+	unsigned int status;
+
+	timeout = timeout_init_us(timeout_count);
+
+	do {
+		status = (__dcc_getstatus() & mask);
+		if (timeout_elapsed(timeout)) {
+			return -ETIMEDOUT;
+		}
+	} while ((status != 0U));
+
+	return 0;
+}
+
+static int32_t dcc_console_putc(int32_t ch, struct console *console)
+{
+	unsigned int status;
+
+	status = dcc_status_timeout(DCC_STATUS_TX);
+	if (status != 0U) {
+		return status;
+	}
+	__dcc_putchar(ch);
+
+	return ch;
+}
+
+static int32_t dcc_console_getc(struct console *console)
+{
+	unsigned int status;
+
+	status = dcc_status_timeout(DCC_STATUS_RX);
+	if (status != 0U) {
+		return status;
+	}
+
+	return __dcc_getchar();
+}
+
+int32_t dcc_console_init(unsigned long base_addr, uint32_t uart_clk,
+		      uint32_t baud_rate)
+{
+	return 0; /* No init needed */
+}
+
+/**
+ * dcc_console_flush() - Function to force a write of all buffered data
+ *		          that hasn't been output.
+ * @console		Console struct
+ *
+ */
+static void dcc_console_flush(struct console *console)
+{
+	unsigned int status;
+
+	status = dcc_status_timeout(DCC_STATUS_TX);
+	if (status != 0U) {
+		return;
+	}
+}
+
+static struct dcc_console dcc_console = {
+	.console = {
+		.flags = CONSOLE_FLAG_BOOT |
+			CONSOLE_FLAG_RUNTIME,
+		.putc = dcc_console_putc,
+		.getc = dcc_console_getc,
+		.flush = dcc_console_flush,
+	},
+};
+
+int console_dcc_register(void)
+{
+	return console_register(&dcc_console.console);
+}
diff --git a/drivers/brcm/mdio/mdio.c b/drivers/brcm/mdio/mdio.c
new file mode 100644
index 0000000..1cf9d66
--- /dev/null
+++ b/drivers/brcm/mdio/mdio.c
@@ -0,0 +1,87 @@
+/*
+ * Copyright (c) 2016 - 2021, Broadcom
+ *
+ * SPDX-License-Identifier: BSD-3-Clause
+ */
+#include <string.h>
+
+#include <platform_def.h>
+
+#include <common/debug.h>
+#include <drivers/delay_timer.h>
+#include <lib/mmio.h>
+#include <mdio.h>
+
+static int mdio_op_status(uint32_t result)
+{
+	uint32_t timeout = 1000000U; /* loop for 1s */
+	uint32_t val;
+
+	do {
+		val = mmio_read_32(CMIC_MIIM_STAT);
+		if ((val & MDIO_STAT_DONE) == result) {
+			return 0;
+		}
+
+		udelay(1U);
+	} while (timeout-- != 0U);
+	return -1;
+}
+
+static int mdio_op(uint16_t busid, uint16_t phyid, uint32_t reg,
+	       uint16_t val, uint8_t op)
+{
+	uint32_t param;
+	int ret;
+
+	mmio_write_32(CMIC_MIIM_CTRL, 0U);
+	ret = mdio_op_status(0U);
+	if (ret != 0) {
+		goto err;
+	}
+
+	param = 0U;
+	param |= 1U << MDIO_PARAM_INTERNAL_SEL;
+	param |= (busid & MDIO_PARAM_BUSID_MASK) << MDIO_PARAM_BUSID;
+	param |= (phyid & MDIO_PARAM_PHYID_MASK) << MDIO_PARAM_PHYID;
+	param |= (val & MDIO_PARAM_DATA_MASK) << MDIO_PARAM_DATA;
+
+	mmio_write_32(CMIC_MIIM_PARAM, param);
+
+	mmio_write_32(CMIC_MIIM_ADDRESS, reg);
+
+	mmio_write_32(CMIC_MIIM_CTRL, op);
+
+	ret = mdio_op_status(1U);
+	if (ret != 0) {
+		goto err;
+	}
+
+	if (op == MDIO_CTRL_READ_OP) {
+		ret = mmio_read_32(CMIC_MIIM_READ_DATA) & MDIO_READ_DATA_MASK;
+	}
+err:
+	return ret;
+}
+
+int mdio_write(uint16_t busid, uint16_t phyid, uint32_t reg, uint16_t val)
+{
+	int ret;
+
+	ret = mdio_op(busid, phyid, reg, val, MDIO_CTRL_WRITE_OP);
+	if (ret == -1) {
+		INFO("MDIO write fail\n");
+	}
+	return ret;
+}
+
+int mdio_read(uint16_t busid, uint16_t phyid, uint32_t reg)
+{
+	int ret;
+
+	ret = mdio_op(busid, phyid, reg, 0U, MDIO_CTRL_READ_OP);
+	if (ret == -1) {
+		INFO("MDIO read fail\n");
+	}
+	return ret;
+}
diff --git a/drivers/marvell/comphy/phy-comphy-cp110.c b/drivers/marvell/comphy/phy-comphy-cp110.c
index d1c26f8..c8ba9b8 100644
--- a/drivers/marvell/comphy/phy-comphy-cp110.c
+++ b/drivers/marvell/comphy/phy-comphy-cp110.c
@@ -61,6 +61,11 @@
 					SAR_RST_PCIE1_CLOCK_CONFIG_CP1_OFFSET)
 #define SAR_STATUS_0_REG			200
 #define DFX_FROM_COMPHY_ADDR(x)			((x & ~0xffffff) + DFX_BASE)
+/* Common Phy training  */
+#define COMPHY_TRX_TRAIN_COMPHY_OFFS		0x1000
+#define COMPHY_TRX_TRAIN_RX_TRAIN_ENABLE	0x1
+#define COMPHY_TRX_RELATIVE_ADDR(comphy_index)	(comphy_train_base + \
+			(comphy_index) * COMPHY_TRX_TRAIN_COMPHY_OFFS)
 
 /* The same Units Soft Reset Config register are accessed in all PCIe ports
  * initialization, so a spin lock is defined in case when more than 1 CPUs
@@ -829,7 +834,8 @@
 
 static int mvebu_cp110_comphy_xfi_power_on(uint64_t comphy_base,
 					   uint8_t comphy_index,
-					   uint32_t comphy_mode)
+					   uint32_t comphy_mode,
+					   uint64_t comphy_train_base)
 {
 	uintptr_t hpipe_addr, sd_ip_addr, comphy_addr, addr;
 	uint32_t mask, data, speed = COMPHY_GET_SPEED(comphy_mode);
@@ -837,7 +843,6 @@
 	uint8_t ap_nr, cp_nr;
 
 	debug_enter();
-
 	mvebu_cp110_get_ap_and_cp_nr(&ap_nr, &cp_nr, comphy_base);
 
 	if (rx_trainng_done[ap_nr][cp_nr][comphy_index]) {
@@ -1234,6 +1239,14 @@
 	data |= 0x1 << SD_EXTERNAL_CONFIG1_RF_RESET_IN_OFFSET;
 	reg_set(sd_ip_addr + SD_EXTERNAL_CONFIG1_REG, data, mask);
 
+	/* Force rx training on 10G port */
+	data = mmio_read_32(COMPHY_TRX_RELATIVE_ADDR(comphy_index));
+	data |= COMPHY_TRX_TRAIN_RX_TRAIN_ENABLE;
+	mmio_write_32(COMPHY_TRX_RELATIVE_ADDR(comphy_index), data);
+	mdelay(200);
+	data &= ~COMPHY_TRX_TRAIN_RX_TRAIN_ENABLE;
+	mmio_write_32(COMPHY_TRX_RELATIVE_ADDR(comphy_index), data);
+
 	debug_exit();
 
 	return ret;
@@ -2284,7 +2297,6 @@
 					  uint32_t comphy_mode)
 {
 	uint32_t mask, data;
-	uint8_t ap_nr, cp_nr;
 	uintptr_t comphy_addr = comphy_addr =
 				COMPHY_ADDR(comphy_base, comphy_index);
 
@@ -2301,10 +2313,16 @@
 	reg_set(comphy_addr + COMMON_PHY_CFG1_REG, data, mask);
 	debug_exit();
 
-	/* Start AP Firmware */
-	mvebu_cp110_get_ap_and_cp_nr(&ap_nr, &cp_nr, comphy_base);
-	mg_start_ap_fw(cp_nr, comphy_index);
+#if MSS_SUPPORT
+	do {
+		uint8_t ap_nr, cp_nr;
 
+		/* start ap fw */
+		mvebu_cp110_get_ap_and_cp_nr(&ap_nr, &cp_nr, comphy_base);
+		mg_start_ap_fw(cp_nr, comphy_index);
+
+	} while (0);
+#endif
 	return 0;
 }
 
@@ -2343,8 +2361,10 @@
 	return 0;
 }
 
-int mvebu_cp110_comphy_power_on(uint64_t comphy_base, uint8_t comphy_index,
-				uint64_t comphy_mode)
+int mvebu_cp110_comphy_power_on(uint64_t comphy_base,
+				uint8_t comphy_index,
+				uint64_t comphy_mode,
+				uint64_t comphy_train_base)
 {
 	int mode = COMPHY_GET_MODE(comphy_mode);
 	int err = 0;
@@ -2368,7 +2388,8 @@
 	case (COMPHY_SFI_MODE):
 		err = mvebu_cp110_comphy_xfi_power_on(comphy_base,
 						      comphy_index,
-						      comphy_mode);
+						      comphy_mode,
+						      comphy_train_base);
 		break;
 	case (COMPHY_PCIE_MODE):
 		err = mvebu_cp110_comphy_pcie_power_on(comphy_base,
diff --git a/drivers/marvell/comphy/phy-comphy-cp110.h b/drivers/marvell/comphy/phy-comphy-cp110.h
index b4a2102..0be6c26 100644
--- a/drivers/marvell/comphy/phy-comphy-cp110.h
+++ b/drivers/marvell/comphy/phy-comphy-cp110.h
@@ -89,8 +89,9 @@
 				     uint8_t comphy_index);
 int mvebu_cp110_comphy_power_off(uint64_t comphy_base,
 				 uint8_t comphy_index, uint64_t comphy_mode);
-int mvebu_cp110_comphy_power_on(uint64_t comphy_base,
-				uint8_t comphy_index, uint64_t comphy_mode);
+int mvebu_cp110_comphy_power_on(uint64_t comphy_base, uint8_t comphy_index,
+				uint64_t comphy_mode,
+				uint64_t comphy_train_base);
 int mvebu_cp110_comphy_xfi_rx_training(uint64_t comphy_base,
 				       uint8_t comphy_index);
 int mvebu_cp110_comphy_digital_reset(uint64_t comphy_base, uint8_t comphy_index,
diff --git a/drivers/marvell/ddr_phy_access.c b/drivers/marvell/ddr_phy_access.c
new file mode 100644
index 0000000..352d1ef
--- /dev/null
+++ b/drivers/marvell/ddr_phy_access.c
@@ -0,0 +1,58 @@
+/*
+ * Copyright (C) 2021 Marvell International Ltd.
+ *
+ * SPDX-License-Identifier:     BSD-3-Clause
+ * https://spdx.org/licenses
+ */
+
+#include "ddr_phy_access.h"
+#include <lib/mmio.h>
+#include <drivers/marvell/ccu.h>
+#include <errno.h>
+
+#define DDR_PHY_END_ADDRESS	0x100000
+
+#ifdef DDR_PHY_DEBUG
+#define debug_printf(...) printf(__VA_ARGS__)
+#else
+#define debug_printf(...)
+#endif
+
+
+/*
+ * This routine writes 'data' to specified 'address' offset,
+ * with optional debug print support
+ */
+int snps_fw_write(uintptr_t offset, uint16_t data)
+{
+	debug_printf("In %s\n", __func__);
+
+	if (offset < DDR_PHY_END_ADDRESS) {
+		mmio_write_16(DDR_PHY_BASE_ADDR + (2 * offset), data);
+		return 0;
+	}
+	debug_printf("%s: illegal offset value: 0x%x\n", __func__, offset);
+	return -EINVAL;
+}
+
+int snps_fw_read(uintptr_t offset, uint16_t *read)
+{
+	debug_printf("In %s\n", __func__);
+
+	if (offset < DDR_PHY_END_ADDRESS) {
+		*read = mmio_read_16(DDR_PHY_BASE_ADDR + (2 * offset));
+		return 0;
+	}
+	debug_printf("%s: illegal offset value: 0x%x\n", __func__, offset);
+	return -EINVAL;
+}
+
+int mvebu_ddr_phy_write(uintptr_t offset, uint16_t data)
+{
+	return snps_fw_write(offset, data);
+}
+
+int mvebu_ddr_phy_read(uintptr_t offset, uint16_t *read)
+{
+	return snps_fw_read(offset, read);
+}
diff --git a/drivers/marvell/ddr_phy_access.h b/drivers/marvell/ddr_phy_access.h
new file mode 100644
index 0000000..5f9a668
--- /dev/null
+++ b/drivers/marvell/ddr_phy_access.h
@@ -0,0 +1,15 @@
+/*
+ * Copyright (C) 2021 Marvell International Ltd.
+ *
+ * SPDX-License-Identifier:     BSD-3-Clause
+ * https://spdx.org/licenses
+ */
+
+#include <plat_marvell.h>
+
+#define DEVICE_BASE		0xF0000000
+#define DDR_PHY_OFFSET		0x1000000
+#define DDR_PHY_BASE_ADDR	(DEVICE_BASE + DDR_PHY_OFFSET)
+
+int mvebu_ddr_phy_write(uintptr_t offset, uint16_t data);
+int mvebu_ddr_phy_read(uintptr_t offset, uint16_t *read);
diff --git a/drivers/marvell/mochi/cp110_setup.c b/drivers/marvell/mochi/cp110_setup.c
index 906df66..f12da0e 100644
--- a/drivers/marvell/mochi/cp110_setup.c
+++ b/drivers/marvell/mochi/cp110_setup.c
@@ -14,6 +14,7 @@
 #include <drivers/marvell/mochi/cp110_setup.h>
 #include <drivers/rambus/trng_ip_76.h>
 
+#include <efuse_def.h>
 #include <plat_marvell.h>
 
 /*
@@ -110,6 +111,8 @@
  * TRNG Configuration
  ******************************************************************************/
 #define MVEBU_TRNG_BASE					(0x760000)
+#define MVEBU_EFUSE_TRNG_ENABLE_EFUSE_WORD		MVEBU_AP_LDX_220_189_EFUSE_OFFS
+#define MVEBU_EFUSE_TRNG_ENABLE_BIT_OFFSET		13	/* LD0[202] */
 
 enum axi_attr {
 	AXI_ADUNIT_ATTR = 0,
@@ -389,6 +392,22 @@
 {
 	static bool done;
 	int ret;
+	uint32_t reg_val, efuse;
+
+	/* Set access to LD0 */
+	reg_val = mmio_read_32(MVEBU_AP_EFUSE_SRV_CTRL_REG);
+	reg_val &= ~EFUSE_SRV_CTRL_LD_SELECT_MASK;
+	mmio_write_32(MVEBU_AP_EFUSE_SRV_CTRL_REG, reg_val);
+
+	/* Obtain the AP LD0 bit defining TRNG presence */
+	efuse = mmio_read_32(MVEBU_EFUSE_TRNG_ENABLE_EFUSE_WORD);
+	efuse >>= MVEBU_EFUSE_TRNG_ENABLE_BIT_OFFSET;
+	efuse &= 1;
+
+	if (efuse == 0) {
+		VERBOSE("TRNG is not present, skipping");
+		return;
+	}
 
 	if (!done) {
 		ret = eip76_rng_probe(base + MVEBU_TRNG_BASE);
diff --git a/drivers/marvell/secure_dfx_access/armada_thermal.c b/drivers/marvell/secure_dfx_access/armada_thermal.c
new file mode 100644
index 0000000..4f7191b
--- /dev/null
+++ b/drivers/marvell/secure_dfx_access/armada_thermal.c
@@ -0,0 +1,253 @@
+/*
+ * Copyright (C) 2019 Marvell International Ltd.
+ *
+ * SPDX-License-Identifier:     BSD-3-Clause
+ * https://spdx.org/licenses
+ */
+#include <common/debug.h>
+#include <drivers/delay_timer.h>
+#include <errno.h>
+#include <lib/mmio.h>
+#include <mvebu.h>
+#include <stdbool.h>
+#include "dfx.h"
+
+/* #define DEBUG_DFX */
+#ifdef DEBUG_DFX
+#define debug(format...) NOTICE(format)
+#else
+#define debug(format, arg...)
+#endif
+
+#define TSEN_CTRL0			0xf06f8084
+ #define TSEN_CTRL0_START		BIT(0)
+ #define TSEN_CTRL0_RESET		BIT(1)
+ #define TSEN_CTRL0_ENABLE		BIT(2)
+ #define TSEN_CTRL0_AVG_BYPASS		BIT(6)
+ #define TSEN_CTRL0_CHAN_SHIFT		13
+ #define TSEN_CTRL0_CHAN_MASK		0xF
+ #define TSEN_CTRL0_OSR_SHIFT		24
+ #define TSEN_CTRL0_OSR_MAX		0x3
+ #define TSEN_CTRL0_MODE_SHIFT		30
+ #define TSEN_CTRL0_MODE_EXTERNAL	0x2U
+ #define TSEN_CTRL0_MODE_MASK		0x3U
+
+#define TSEN_CTRL1			0xf06f8088
+ #define TSEN_CTRL1_INT_EN		BIT(25)
+ #define TSEN_CTRL1_HYST_SHIFT		19
+ #define TSEN_CTRL1_HYST_MASK		(0x3 << TSEN_CTRL1_HYST_SHIFT)
+ #define TSEN_CTRL1_THRESH_SHIFT	3
+ #define TSEN_CTRL1_THRESH_MASK		(0x3ff << TSEN_CTRL1_THRESH_SHIFT)
+
+#define TSEN_STATUS			0xf06f808c
+ #define TSEN_STATUS_VALID_OFFSET	16
+ #define TSEN_STATUS_VALID_MASK		(0x1 << TSEN_STATUS_VALID_OFFSET)
+ #define TSEN_STATUS_TEMP_OUT_OFFSET	0
+ #define TSEN_STATUS_TEMP_OUT_MASK	(0x3FF << TSEN_STATUS_TEMP_OUT_OFFSET)
+
+#define DFX_SERVER_IRQ_SUM_MASK_REG	0xf06f8104
+ #define DFX_SERVER_IRQ_EN		BIT(1)
+
+#define DFX_IRQ_CAUSE_REG		0xf06f8108
+
+#define DFX_IRQ_MASK_REG		0xf06f810c
+ #define DFX_IRQ_TSEN_OVERHEAT_OFFSET	BIT(22)
+
+#define THERMAL_SEN_OUTPUT_MSB		512
+#define THERMAL_SEN_OUTPUT_COMP		1024
+
+#define COEF_M 423
+#define COEF_B -150000LL
+
+static void armada_ap806_thermal_read(u_register_t *temp)
+{
+	uint32_t reg;
+
+	reg = mmio_read_32(TSEN_STATUS);
+
+	reg = ((reg & TSEN_STATUS_TEMP_OUT_MASK) >>
+	      TSEN_STATUS_TEMP_OUT_OFFSET);
+
+	/*
+	 * TSEN output format is signed as a 2s complement number
+	 * ranging from-512 to +511. when MSB is set, need to
+	 * calculate the complement number
+	 */
+	if (reg >= THERMAL_SEN_OUTPUT_MSB)
+		reg -= THERMAL_SEN_OUTPUT_COMP;
+
+	*temp = ((COEF_M * ((signed int)reg)) - COEF_B);
+}
+
+static void armada_ap806_thermal_irq(void)
+{
+	/* Dummy read, register ROC */
+	mmio_read_32(DFX_IRQ_CAUSE_REG);
+}
+
+static void armada_ap806_thermal_overheat_irq_init(void)
+{
+	uint32_t reg;
+
+	/* Clear DFX temperature IRQ cause */
+	reg = mmio_read_32(DFX_IRQ_CAUSE_REG);
+
+	/* Enable DFX Temperature IRQ */
+	reg = mmio_read_32(DFX_IRQ_MASK_REG);
+	reg |= DFX_IRQ_TSEN_OVERHEAT_OFFSET;
+	mmio_write_32(DFX_IRQ_MASK_REG, reg);
+
+	/* Enable DFX server IRQ */
+	reg = mmio_read_32(DFX_SERVER_IRQ_SUM_MASK_REG);
+	reg |= DFX_SERVER_IRQ_EN;
+	mmio_write_32(DFX_SERVER_IRQ_SUM_MASK_REG, reg);
+
+	/* Enable overheat interrupt */
+	reg = mmio_read_32(TSEN_CTRL1);
+	reg |= TSEN_CTRL1_INT_EN;
+	mmio_write_32(TSEN_CTRL1, reg);
+}
+
+static unsigned int armada_mc_to_reg_temp(unsigned int temp_mc)
+{
+	unsigned int sample;
+
+	sample = (temp_mc + COEF_B) / COEF_M;
+
+	return sample & 0x3ff;
+}
+
+/*
+ * The documentation states:
+ * high/low watermark = threshold +/- 0.4761 * 2^(hysteresis + 2)
+ * which is the mathematical derivation for:
+ * 0x0 <=> 1.9°C, 0x1 <=> 3.8°C, 0x2 <=> 7.6°C, 0x3 <=> 15.2°C
+ */
+static unsigned int hyst_levels_mc[] = {1900, 3800, 7600, 15200};
+
+static unsigned int armada_mc_to_reg_hyst(int hyst_mc)
+{
+	int i;
+
+	/*
+	 * We will always take the smallest possible hysteresis to avoid risking
+	 * the hardware integrity by enlarging the threshold by +8°C in the
+	 * worst case.
+	 */
+	for (i = ARRAY_SIZE(hyst_levels_mc) - 1; i > 0; i--)
+		if (hyst_mc >= hyst_levels_mc[i])
+			break;
+
+	return i;
+}
+
+static void armada_ap806_thermal_threshold(int thresh_mc, int hyst_mc)
+{
+	uint32_t ctrl1;
+	unsigned int threshold = armada_mc_to_reg_temp(thresh_mc);
+	unsigned int hysteresis = armada_mc_to_reg_hyst(hyst_mc);
+
+	ctrl1 = mmio_read_32(TSEN_CTRL1);
+	/* Set Threshold */
+	if (thresh_mc >= 0) {
+		ctrl1 &= ~(TSEN_CTRL1_THRESH_MASK);
+		ctrl1 |= threshold << TSEN_CTRL1_THRESH_SHIFT;
+	}
+
+	/* Set Hysteresis */
+	if (hyst_mc >= 0) {
+		ctrl1 &= ~(TSEN_CTRL1_HYST_MASK);
+		ctrl1 |= hysteresis << TSEN_CTRL1_HYST_SHIFT;
+	}
+
+	mmio_write_32(TSEN_CTRL1, ctrl1);
+}
+
+static void armada_select_channel(int channel)
+{
+	uint32_t ctrl0;
+
+	/* Stop the measurements */
+	ctrl0 = mmio_read_32(TSEN_CTRL0);
+	ctrl0 &= ~TSEN_CTRL0_START;
+	mmio_write_32(TSEN_CTRL0, ctrl0);
+
+	/* Reset the mode, internal sensor will be automatically selected */
+	ctrl0 &= ~(TSEN_CTRL0_MODE_MASK << TSEN_CTRL0_MODE_SHIFT);
+
+	/* Other channels are external and should be selected accordingly */
+	if (channel) {
+		/* Change the mode to external */
+		ctrl0 |= TSEN_CTRL0_MODE_EXTERNAL <<
+			 TSEN_CTRL0_MODE_SHIFT;
+		/* Select the sensor */
+		ctrl0 &= ~(TSEN_CTRL0_CHAN_MASK << TSEN_CTRL0_CHAN_SHIFT);
+		ctrl0 |= (channel - 1) << TSEN_CTRL0_CHAN_SHIFT;
+	}
+
+	/* Actually set the mode/channel */
+	mmio_write_32(TSEN_CTRL0, ctrl0);
+
+	/* Re-start the measurements */
+	ctrl0 |= TSEN_CTRL0_START;
+	mmio_write_32(TSEN_CTRL0, ctrl0);
+}
+
+static void armada_ap806_thermal_init(void)
+{
+	uint32_t reg;
+
+	reg = mmio_read_32(TSEN_CTRL0);
+	reg &= ~TSEN_CTRL0_RESET;
+	reg |= TSEN_CTRL0_START | TSEN_CTRL0_ENABLE;
+
+	/* Sample every ~2ms */
+	reg |= TSEN_CTRL0_OSR_MAX << TSEN_CTRL0_OSR_SHIFT;
+
+	/* Enable average (2 samples by default) */
+	reg &= ~TSEN_CTRL0_AVG_BYPASS;
+
+	mmio_write_32(TSEN_CTRL0, reg);
+
+	debug("thermal: Initialization done\n");
+}
+
+static void armada_is_valid(u_register_t *read)
+{
+	*read = (mmio_read_32(TSEN_STATUS) & TSEN_STATUS_VALID_MASK);
+}
+
+int mvebu_dfx_thermal_handle(u_register_t func, u_register_t *read,
+			     u_register_t x2, u_register_t x3)
+{
+	debug_enter();
+
+	switch (func) {
+	case MV_SIP_DFX_THERMAL_INIT:
+		armada_ap806_thermal_init();
+		break;
+	case MV_SIP_DFX_THERMAL_READ:
+		armada_ap806_thermal_read(read);
+		break;
+	case MV_SIP_DFX_THERMAL_IRQ:
+		armada_ap806_thermal_irq();
+		break;
+	case MV_SIP_DFX_THERMAL_THRESH:
+		armada_ap806_thermal_threshold(x2, x3);
+		armada_ap806_thermal_overheat_irq_init();
+		break;
+	case MV_SIP_DFX_THERMAL_IS_VALID:
+		armada_is_valid(read);
+		break;
+	case MV_SIP_DFX_THERMAL_SEL_CHANNEL:
+		armada_select_channel(x2);
+		break;
+	default:
+		ERROR("unsupported dfx func\n");
+		return -EINVAL;
+	}
+
+	debug_exit();
+
+	return 0;
+}
diff --git a/drivers/marvell/secure_dfx_access/dfx.h b/drivers/marvell/secure_dfx_access/dfx.h
new file mode 100644
index 0000000..88c4de8
--- /dev/null
+++ b/drivers/marvell/secure_dfx_access/dfx.h
@@ -0,0 +1,22 @@
+/*
+ * Copyright (C) 2019 Marvell International Ltd.
+ *
+ * SPDX-License-Identifier:     BSD-3-Clause
+ * https://spdx.org/licenses
+ */
+
+/* DFX sub-FID */
+#define MV_SIP_DFX_THERMAL_INIT		1
+#define MV_SIP_DFX_THERMAL_READ		2
+#define MV_SIP_DFX_THERMAL_IS_VALID	3
+#define MV_SIP_DFX_THERMAL_IRQ		4
+#define MV_SIP_DFX_THERMAL_THRESH	5
+#define MV_SIP_DFX_THERMAL_SEL_CHANNEL	6
+
+#define MV_SIP_DFX_SREAD		20
+#define MV_SIP_DFX_SWRITE		21
+
+int mvebu_dfx_thermal_handle(u_register_t func, u_register_t *read,
+			     u_register_t x2, u_register_t x3);
+int mvebu_dfx_misc_handle(u_register_t func, u_register_t *read,
+			  u_register_t addr, u_register_t val);
diff --git a/drivers/marvell/secure_dfx_access/misc_dfx.c b/drivers/marvell/secure_dfx_access/misc_dfx.c
new file mode 100644
index 0000000..189105f
--- /dev/null
+++ b/drivers/marvell/secure_dfx_access/misc_dfx.c
@@ -0,0 +1,123 @@
+/*
+ * Copyright (C) 2021 Marvell International Ltd.
+ *
+ * SPDX-License-Identifier:     BSD-3-Clause
+ * https://spdx.org/licenses
+ */
+
+#include <common/debug.h>
+#include <lib/mmio.h>
+#include "dfx.h"
+#include <mvebu_def.h>
+#include <mvebu.h>
+#include <errno.h>
+
+/* #define DEBUG_DFX */
+#ifdef DEBUG_DFX
+#define debug(format...) NOTICE(format)
+#else
+#define debug(format, arg...)
+#endif
+
+#define SAR_BASE			(MVEBU_REGS_BASE + 0x6F8200)
+#define SAR_SIZE			0x4
+#define AP_DEV_ID_STATUS_REG		(MVEBU_REGS_BASE + 0x6F8240)
+#define JTAG_DEV_ID_STATUS_REG		(MVEBU_REGS_BASE + 0x6F8244)
+#define EFUSE_CTRL			(MVEBU_REGS_BASE + 0x6F8008)
+#define EFUSE_LD_BASE			(MVEBU_REGS_BASE + 0x6F8F00)
+#define EFUSE_LD_SIZE			0x1C
+#define EFUSE_HD_BASE			(MVEBU_REGS_BASE + 0x6F9000)
+#define EFUSE_HD_SIZE			0x3F8
+
+/* AP806 CPU DFS register mapping*/
+#define AP806_CA72MP2_0_PLL_CR_0_BASE		(MVEBU_REGS_BASE + 0x6F8278)
+#define AP806_CA72MP2_0_PLL_CR_1_BASE		(MVEBU_REGS_BASE + 0x6F8280)
+#define AP806_CA72MP2_0_PLL_CR_2_BASE		(MVEBU_REGS_BASE + 0x6F8284)
+#define AP806_CA72MP2_0_PLL_SR_BASE		(MVEBU_REGS_BASE + 0x6F8C94)
+
+/* AP807 CPU DFS register mapping */
+#define AP807_DEVICE_GENERAL_CR_10_BASE		(MVEBU_REGS_BASE + 0x6F8278)
+#define AP807_DEVICE_GENERAL_CR_11_BASE		(MVEBU_REGS_BASE + 0x6F827C)
+#define AP807_DEVICE_GENERAL_STATUS_6_BASE	(MVEBU_REGS_BASE + 0x6F8C98)
+
+#ifdef MVEBU_SOC_AP807
+ #define CLUSTER_OFFSET		0x8
+ #define CLK_DIVIDER_REG	AP807_DEVICE_GENERAL_CR_10_BASE
+ #define CLK_FORCE_REG		AP807_DEVICE_GENERAL_CR_11_BASE
+ #define CLK_RATIO_REG		AP807_DEVICE_GENERAL_CR_11_BASE
+ #define CLK_RATIO_STATE_REG	AP807_DEVICE_GENERAL_STATUS_6_BASE
+#else
+ #define CLUSTER_OFFSET		0x14
+ #define CLK_DIVIDER_REG		AP806_CA72MP2_0_PLL_CR_0_BASE
+ #define CLK_FORCE_REG		AP806_CA72MP2_0_PLL_CR_1_BASE
+ #define CLK_RATIO_REG		AP806_CA72MP2_0_PLL_CR_2_BASE
+ #define CLK_RATIO_STATE_REG	AP806_CA72MP2_0_PLL_SR_BASE
+#endif /* MVEBU_SOC_AP807 */
+
+static _Bool is_valid(u_register_t addr)
+{
+	switch (addr) {
+	case AP_DEV_ID_STATUS_REG:
+	case JTAG_DEV_ID_STATUS_REG:
+	case SAR_BASE ... (SAR_BASE + SAR_SIZE):
+	case EFUSE_LD_BASE ... (EFUSE_LD_BASE + EFUSE_LD_SIZE):
+	case EFUSE_HD_BASE ... (EFUSE_HD_BASE + EFUSE_HD_SIZE):
+	case EFUSE_CTRL:
+	/* cpu-clk related registers */
+	case CLK_DIVIDER_REG:
+	case CLK_DIVIDER_REG + CLUSTER_OFFSET:
+	case CLK_FORCE_REG:
+	case CLK_FORCE_REG + CLUSTER_OFFSET:
+#ifndef MVEBU_SOC_AP807
+	case CLK_RATIO_REG:
+	case CLK_RATIO_REG + CLUSTER_OFFSET:
+#endif
+	case CLK_RATIO_STATE_REG:
+	case CLK_RATIO_STATE_REG + CLUSTER_OFFSET:
+		return true;
+	default:
+		return false;
+	}
+}
+
+static int armada_dfx_sread(u_register_t *read, u_register_t addr)
+{
+	if (!is_valid(addr))
+		return -EINVAL;
+
+	*read = mmio_read_32(addr);
+
+	return 0;
+}
+
+static int armada_dfx_swrite(u_register_t addr, u_register_t val)
+{
+	if (!is_valid(addr))
+		return -EINVAL;
+
+	mmio_write_32(addr, val);
+
+	return 0;
+}
+
+int mvebu_dfx_misc_handle(u_register_t func, u_register_t *read,
+			  u_register_t addr, u_register_t val)
+{
+	debug_enter();
+
+	debug("func %ld, addr 0x%lx, val 0x%lx\n", func, addr, val);
+
+	switch (func) {
+	case MV_SIP_DFX_SREAD:
+		return armada_dfx_sread(read, addr);
+	case MV_SIP_DFX_SWRITE:
+		return armada_dfx_swrite(addr, val);
+	default:
+		ERROR("unsupported dfx misc sub-func\n");
+		return -EINVAL;
+	}
+
+	debug_exit();
+
+	return 0;
+}
diff --git a/drivers/mmc/mmc.c b/drivers/mmc/mmc.c
index 3ea17fb..e288d47 100644
--- a/drivers/mmc/mmc.c
+++ b/drivers/mmc/mmc.c
@@ -1,5 +1,5 @@
 /*
- * Copyright (c) 2018-2019, ARM Limited and Contributors. All rights reserved.
+ * Copyright (c) 2018-2021, ARM Limited and Contributors. All rights reserved.
  *
  * SPDX-License-Identifier: BSD-3-Clause
  */
@@ -27,7 +27,7 @@
 static struct mmc_csd_emmc mmc_csd;
 static unsigned char mmc_ext_csd[512] __aligned(16);
 static unsigned int mmc_flags;
-static struct mmc_device_info mmc_dev_info;
+static struct mmc_device_info *mmc_dev_info;
 static unsigned int rca;
 static unsigned int scr[2]__aligned(16) = { 0 };
 
@@ -195,7 +195,7 @@
 	int ret;
 	unsigned int width = bus_width;
 
-	if (mmc_dev_info.mmc_dev_type != MMC_IS_EMMC) {
+	if (mmc_dev_info->mmc_dev_type != MMC_IS_EMMC) {
 		if (width == MMC_BUS_WIDTH_8) {
 			WARN("Wrong bus config for SD-card, force to 4\n");
 			width = MMC_BUS_WIDTH_4;
@@ -226,9 +226,9 @@
 	int ret = 0;
 	struct mmc_csd_sd_v2 *csd_sd_v2;
 
-	switch (mmc_dev_info.mmc_dev_type) {
+	switch (mmc_dev_info->mmc_dev_type) {
 	case MMC_IS_EMMC:
-		mmc_dev_info.block_size = MMC_BLOCK_SIZE;
+		mmc_dev_info->block_size = MMC_BLOCK_SIZE;
 
 		ret = ops->prepare(0, (uintptr_t)&mmc_ext_csd,
 				   sizeof(mmc_ext_csd));
@@ -260,8 +260,8 @@
 			    (mmc_ext_csd[CMD_EXTCSD_SEC_CNT + 2] << 16) |
 			    (mmc_ext_csd[CMD_EXTCSD_SEC_CNT + 3] << 24);
 
-		mmc_dev_info.device_size = (unsigned long long)nb_blocks *
-			mmc_dev_info.block_size;
+		mmc_dev_info->device_size = (unsigned long long)nb_blocks *
+			mmc_dev_info->block_size;
 
 		break;
 
@@ -270,29 +270,29 @@
 		 * Use the same mmc_csd struct, as required fields here
 		 * (READ_BL_LEN, C_SIZE, CSIZE_MULT) are common with eMMC.
 		 */
-		mmc_dev_info.block_size = BIT_32(mmc_csd.read_bl_len);
+		mmc_dev_info->block_size = BIT_32(mmc_csd.read_bl_len);
 
 		c_size = ((unsigned long long)mmc_csd.c_size_high << 2U) |
 			 (unsigned long long)mmc_csd.c_size_low;
 		assert(c_size != 0xFFFU);
 
-		mmc_dev_info.device_size = (c_size + 1U) *
+		mmc_dev_info->device_size = (c_size + 1U) *
 					    BIT_64(mmc_csd.c_size_mult + 2U) *
-					    mmc_dev_info.block_size;
+					    mmc_dev_info->block_size;
 
 		break;
 
 	case MMC_IS_SD_HC:
 		assert(mmc_csd.csd_structure == 1U);
 
-		mmc_dev_info.block_size = MMC_BLOCK_SIZE;
+		mmc_dev_info->block_size = MMC_BLOCK_SIZE;
 
 		/* Need to use mmc_csd_sd_v2 struct */
 		csd_sd_v2 = (struct mmc_csd_sd_v2 *)&mmc_csd;
 		c_size = ((unsigned long long)csd_sd_v2->c_size_high << 16) |
 			 (unsigned long long)csd_sd_v2->c_size_low;
 
-		mmc_dev_info.device_size = (c_size + 1U) << MULT_BY_512K_SHIFT;
+		mmc_dev_info->device_size = (c_size + 1U) << MULT_BY_512K_SHIFT;
 
 		break;
 
@@ -310,19 +310,19 @@
 
 	assert(speed_idx > 0U);
 
-	if (mmc_dev_info.mmc_dev_type == MMC_IS_EMMC) {
-		mmc_dev_info.max_bus_freq = tran_speed_base[speed_idx];
+	if (mmc_dev_info->mmc_dev_type == MMC_IS_EMMC) {
+		mmc_dev_info->max_bus_freq = tran_speed_base[speed_idx];
 	} else {
-		mmc_dev_info.max_bus_freq = sd_tran_speed_base[speed_idx];
+		mmc_dev_info->max_bus_freq = sd_tran_speed_base[speed_idx];
 	}
 
 	freq_unit = mmc_csd.tran_speed & CSD_TRAN_SPEED_UNIT_MASK;
 	while (freq_unit != 0U) {
-		mmc_dev_info.max_bus_freq *= 10U;
+		mmc_dev_info->max_bus_freq *= 10U;
 		--freq_unit;
 	}
 
-	mmc_dev_info.max_bus_freq *= 10000U;
+	mmc_dev_info->max_bus_freq *= 10000U;
 
 	return 0;
 }
@@ -343,7 +343,7 @@
 
 		/* ACMD41: SD_SEND_OP_COND */
 		ret = mmc_send_cmd(MMC_ACMD(41), OCR_HCS |
-			mmc_dev_info.ocr_voltage, MMC_RESPONSE_R3,
+			mmc_dev_info->ocr_voltage, MMC_RESPONSE_R3,
 			&resp_data[0]);
 		if (ret != 0) {
 			return ret;
@@ -353,9 +353,9 @@
 			mmc_ocr_value = resp_data[0];
 
 			if ((mmc_ocr_value & OCR_HCS) != 0U) {
-				mmc_dev_info.mmc_dev_type = MMC_IS_SD_HC;
+				mmc_dev_info->mmc_dev_type = MMC_IS_SD_HC;
 			} else {
-				mmc_dev_info.mmc_dev_type = MMC_IS_SD;
+				mmc_dev_info->mmc_dev_type = MMC_IS_SD;
 			}
 
 			return 0;
@@ -392,7 +392,7 @@
 	ret = mmc_reset_to_idle();
 	if (ret != 0) {
 		return ret;
-	};
+	}
 
 	for (n = 0; n < SEND_OP_COND_MAX_RETRIES; n++) {
 		ret = mmc_send_cmd(MMC_CMD(1), OCR_SECTOR_MODE |
@@ -427,7 +427,7 @@
 		return ret;
 	}
 
-	if (mmc_dev_info.mmc_dev_type == MMC_IS_EMMC) {
+	if (mmc_dev_info->mmc_dev_type == MMC_IS_EMMC) {
 		ret = mmc_send_op_cond();
 	} else {
 		/* CMD8: Send Interface Condition Command */
@@ -449,7 +449,7 @@
 	}
 
 	/* CMD3: Set Relative Address */
-	if (mmc_dev_info.mmc_dev_type == MMC_IS_EMMC) {
+	if (mmc_dev_info->mmc_dev_type == MMC_IS_EMMC) {
 		rca = MMC_FIX_RCA;
 		ret = mmc_send_cmd(MMC_CMD(3), rca << RCA_SHIFT_OFFSET,
 				   MMC_RESPONSE_R1, NULL);
@@ -530,7 +530,7 @@
 	}
 
 	if (((mmc_ocr_value & OCR_ACCESS_MODE_MASK) == OCR_BYTE_MODE) &&
-	    (mmc_dev_info.mmc_dev_type != MMC_IS_SD_HC)) {
+	    (mmc_dev_info->mmc_dev_type != MMC_IS_SD_HC)) {
 		cmd_arg = lba * MMC_BLOCK_SIZE;
 	} else {
 		cmd_arg = lba;
@@ -731,7 +731,7 @@
 
 	ops = ops_ptr;
 	mmc_flags = flags;
-	memcpy(&mmc_dev_info, device_info, sizeof(struct mmc_device_info));
+	mmc_dev_info = device_info;
 
 	return mmc_enumerate(clk, width);
 }
diff --git a/fdts/tc0.dts b/fdts/tc0.dts
index 2d7611c..382860d 100644
--- a/fdts/tc0.dts
+++ b/fdts/tc0.dts
@@ -1,5 +1,5 @@
 /*
- * Copyright (c) 2020, Arm Limited. All rights reserved.
+ * Copyright (c) 2020-2021, Arm Limited. All rights reserved.
  *
  * SPDX-License-Identifier: BSD-3-Clause
  */
@@ -236,7 +236,7 @@
 		ranges;
 		interrupt-controller;
 		reg = <0x0 0x30000000 0 0x10000>, /* GICD */
-		      <0x0 0x30140000 0 0x200000>; /* GICR */
+		      <0x0 0x30080000 0 0x200000>; /* GICR */
 		interrupts = <0x1 0x9 0x4>;
 	};
 
diff --git a/include/arch/aarch32/asm_macros.S b/include/arch/aarch32/asm_macros.S
index f75da0c..483f9fe 100644
--- a/include/arch/aarch32/asm_macros.S
+++ b/include/arch/aarch32/asm_macros.S
@@ -107,12 +107,12 @@
 
 #else
 	/*
-	 * Macro for mitigating against speculative execution beyond ERET.
-	 * If possible use Speculation Barrier instruction defined in ARMv8.5
+	 * Macro for mitigating against speculative execution beyond ERET. Uses the
+	 * speculation barrier instruction introduced by FEAT_SB, if it's enabled.
 	 */
 	.macro exception_return
 	eret
-#if ARM_ARCH_AT_LEAST(8, 5)
+#if ENABLE_FEAT_SB
 	sb
 #else
 	dsb	nsh
diff --git a/include/arch/aarch64/arch_helpers.h b/include/arch/aarch64/arch_helpers.h
index 8c3400a..a41b325 100644
--- a/include/arch/aarch64/arch_helpers.h
+++ b/include/arch/aarch64/arch_helpers.h
@@ -260,6 +260,9 @@
 DEFINE_SYSREG_RW_FUNCS(elr_el1)
 DEFINE_SYSREG_RW_FUNCS(elr_el2)
 DEFINE_SYSREG_RW_FUNCS(elr_el3)
+DEFINE_SYSREG_RW_FUNCS(mdccsr_el0)
+DEFINE_SYSREG_RW_FUNCS(dbgdtrrx_el0)
+DEFINE_SYSREG_RW_FUNCS(dbgdtrtx_el0)
 
 DEFINE_SYSOP_FUNC(wfi)
 DEFINE_SYSOP_FUNC(wfe)
diff --git a/include/arch/aarch64/asm_macros.S b/include/arch/aarch64/asm_macros.S
index cbb9f0b..464c05b 100644
--- a/include/arch/aarch64/asm_macros.S
+++ b/include/arch/aarch64/asm_macros.S
@@ -219,12 +219,12 @@
 	.endm
 
 	/*
-	 * Macro for mitigating against speculative execution beyond ERET.
-	 * If possible use Speculation Barrier instruction defined in ARMv8.5
+	 * Macro for mitigating against speculative execution beyond ERET. Uses the
+	 * speculation barrier instruction introduced by FEAT_SB, if it's enabled.
 	 */
 	.macro exception_return
 	eret
-#if ARM_ARCH_AT_LEAST(8, 5)
+#if ENABLE_FEAT_SB
 	sb
 #else
 	dsb	nsh
diff --git a/include/drivers/arm/css/scmi.h b/include/drivers/arm/css/scmi.h
index e8a2863..adce7a6 100644
--- a/include/drivers/arm/css/scmi.h
+++ b/include/drivers/arm/css/scmi.h
@@ -1,5 +1,5 @@
 /*
- * Copyright (c) 2017-2020, ARM Limited and Contributors. All rights reserved.
+ * Copyright (c) 2017-2021, ARM Limited and Contributors. All rights reserved.
  *
  * SPDX-License-Identifier: BSD-3-Clause
  */
@@ -16,7 +16,7 @@
 
 /* Supported SCMI Protocol Versions */
 #define SCMI_AP_CORE_PROTO_VER			MAKE_SCMI_VERSION(1, 0)
-#define SCMI_PWR_DMN_PROTO_VER			MAKE_SCMI_VERSION(1, 0)
+#define SCMI_PWR_DMN_PROTO_VER			MAKE_SCMI_VERSION(2, 0)
 #define SCMI_SYS_PWR_PROTO_VER			MAKE_SCMI_VERSION(1, 0)
 
 #define GET_SCMI_MAJOR_VER(ver)			(((ver) >> 16) & 0xffff)
diff --git a/include/drivers/arm/dcc.h b/include/drivers/arm/dcc.h
new file mode 100644
index 0000000..1f1fd03
--- /dev/null
+++ b/include/drivers/arm/dcc.h
@@ -0,0 +1,19 @@
+/*
+ * Copyright (c) 2021,  Xilinx Inc.
+ *
+ * SPDX-License-Identifier: BSD-3-Clause
+ */
+
+#ifndef DCC_H
+#define DCC_H
+
+#include <stdint.h>
+#include <drivers/console.h>
+
+/*
+ * Initialize a new dcc console instance and register it with the console
+ * framework.
+ */
+int console_dcc_register(void);
+
+#endif /* DCC */
diff --git a/include/drivers/brcm/mdio/mdio.h b/include/drivers/brcm/mdio/mdio.h
new file mode 100644
index 0000000..b27c7b3
--- /dev/null
+++ b/include/drivers/brcm/mdio/mdio.h
@@ -0,0 +1,31 @@
+/*
+ * Copyright (c) 2016 - 2021, Broadcom
+ *
+ * SPDX-License-Identifier: BSD-3-Clause
+ */
+
+#ifndef MDIO_H
+#define MDIO_H
+
+#define CMIC_MIIM_PARAM		(PLAT_CMIC_MIIM_BASE + 0x23cU)
+#define MDIO_PARAM_MIIM_CYCLE	29U
+#define MDIO_PARAM_INTERNAL_SEL	25U
+#define MDIO_PARAM_BUSID	22U
+#define MDIO_PARAM_BUSID_MASK	0x7U
+#define MDIO_PARAM_C45_SEL	21U
+#define MDIO_PARAM_PHYID	16U
+#define MDIO_PARAM_PHYID_MASK	0x1FU
+#define MDIO_PARAM_DATA		0U
+#define MDIO_PARAM_DATA_MASK	0xFFFFU
+#define CMIC_MIIM_READ_DATA	(PLAT_CMIC_MIIM_BASE + 0x240U)
+#define MDIO_READ_DATA_MASK	0xffffU
+#define CMIC_MIIM_ADDRESS	(PLAT_CMIC_MIIM_BASE + 0x244U)
+#define CMIC_MIIM_CTRL		(PLAT_CMIC_MIIM_BASE + 0x248U)
+#define MDIO_CTRL_WRITE_OP	0x1U
+#define MDIO_CTRL_READ_OP	0x2U
+#define CMIC_MIIM_STAT		(PLAT_CMIC_MIIM_BASE + 0x24cU)
+#define MDIO_STAT_DONE		1U
+
+int mdio_write(uint16_t busid, uint16_t phyid, uint32_t reg, uint16_t val);
+int mdio_read(uint16_t busid, uint16_t phyid, uint32_t reg);
+#endif /* MDIO_H */
diff --git a/include/drivers/brcm/usbh_xhci_regs.h b/include/drivers/brcm/usbh_xhci_regs.h
new file mode 100644
index 0000000..93dec7b
--- /dev/null
+++ b/include/drivers/brcm/usbh_xhci_regs.h
@@ -0,0 +1,4809 @@
+/*
+ * Copyright (c) 2017 - 2021, Broadcom
+ *
+ * SPDX-License-Identifier: BSD-3-Clause
+ */
+
+
+#ifndef USBH_XHCI_REGS_H
+#define USBH_XHCI_REGS_H
+
+#include <lib/mmio.h>
+#include <platform_def.h>
+
+#define XHCI_LEN (8096U)
+
+#define XHC_CPLIVER_OFFSET			0x000U
+#define XHC_SPARAMS1_OFFSET			0x004U
+#define XHC_SPARAMS2_OFFSET			0x008U
+#define XHC_SPARAMS3_OFFSET			0x00cU
+#define XHC_CPARAMS1_OFFSET			0x010U
+#define XHC_DBOFF_OFFSET			0x014U
+#define XHC_RTOFF_OFFSET			0x018U
+#define XHC_CPARAMS2_OFFSET			0x01cU
+#define XHC_USBCMD_OFFSET			0x020U
+#define XHC_USBSTS_OFFSET			0x024U
+#define XHC_PAGESIZE_OFFSET			0x028U
+#define XHC_DNCTRL_OFFSET			0x034U
+#define XHC_CRCRL_OFFSET			0x038U
+#define XHC_CRCRH_OFFSET			0x03cU
+#define XHC_DCBAAPL_OFFSET			0x050U
+#define XHC_DCBAAPH_OFFSET			0x054U
+#define XHC_CONFIG_OFFSET			0x058U
+#define XHC_PORTSC1_OFFSET			0x420U
+#define XHC_PORTPM1_OFFSET			0x424U
+#define XHC_PORTLC1_OFFSET			0x428U
+#define XHC_PORTSC2_OFFSET			0x430U
+#define XHC_PORTPM2_OFFSET			0x434U
+#define XHC_PORTLC2_OFFSET			0x43cU
+#define XHC_PORTSC3_OFFSET			0x440U
+#define XHC_PORTPM3_OFFSET			0x444U
+#define XHC_PORTLI3_OFFSET			0x44cU
+#define XHC_MFINDEX_OFFSET			0x4a0U
+#define XHC_IMAN0_OFFSET			0x4c0U
+#define XHC_IMOD0_OFFSET			0x4c4U
+#define XHC_ERSTSZ0_OFFSET			0x4c8U
+#define XHC_ERSTBAL0_OFFSET			0x4d0U
+#define XHC_ERSTBAH0_OFFSET			0x4d4U
+#define XHC_ERDPL0_OFFSET			0x4d8U
+#define XHC_ERDPH0_OFFSET			0x4dcU
+#define XHC_IMAN1_OFFSET			0x4e0U
+#define XHC_IMOD1_OFFSET			0x4e4U
+#define XHC_ERSTSZ1_OFFSET			0x4e8U
+#define XHC_ERSTBAL1_OFFSET			0x4f0U
+#define XHC_ERSTBAH1_OFFSET			0x4f4U
+#define XHC_ERDPL1_OFFSET			0x4f8U
+#define XHC_ERDPH1_OFFSET			0x4fcU
+#define XHC_DBLCMD_OFFSET			0x8c0U
+#define XHC_DBLDVX1_OFFSET			0x8c4U
+#define XHC_DBLDVX2_OFFSET			0x8c8U
+#define XHC_DBLDVX3_OFFSET			0x8ccU
+#define XHC_DBLDVX4_OFFSET			0x8d0U
+#define XHC_DBLDVX5_OFFSET			0x8d4U
+#define XHC_DBLDVX6_OFFSET			0x8d8U
+#define XHC_DBLDVX7_OFFSET			0x8dcU
+#define XHC_DBLDVX8_OFFSET			0x8e0U
+#define XHC_DBLDVX9_OFFSET			0x8e4U
+#define XHC_DBLDVX10_OFFSET			0x8e8U
+#define XHC_DBLDVX11_OFFSET			0x8ecU
+#define XHC_DBLDVX12_OFFSET			0x8f0U
+#define XHC_DBLDVX13_OFFSET			0x8f4U
+#define XHC_DBLDVX14_OFFSET			0x8f8U
+#define XHC_DBLDVX15_OFFSET			0x8fcU
+#define XHC_DBLDVX16_OFFSET			0x900U
+#define XHC_ECHSPT3_OFFSET			0x940U
+#define XHC_PNSTR3_OFFSET			0x944U
+#define XHC_PSUM3_OFFSET			0x948U
+#define XHC_PTSLTYP3_OFFSET			0x94cU
+#define XHC_ECHSPT2_OFFSET			0x950U
+#define XHC_PNSTR2_OFFSET			0x954U
+#define XHC_PSUM2_OFFSET			0x958U
+#define XHC_PTSLTYP2_OFFSET			0x95cU
+#define XHC_ECHRSVP_OFFSET			0x960U
+#define XHC_ECHRSVI_OFFSET			0x968U
+#define XHC_ECHRSVM_OFFSET			0xae8U
+#define XHC_ECHRSVD_OFFSET			0xaf8U
+#define XHC_ECHRSVO_OFFSET			0xb38U
+#define XHC_ECHCTT_OFFSET			0xbf0U
+#define XHC_CTTMTS0_OFFSET			0xbf8U
+#define XHC_CTTMTS1_OFFSET			0xbfcU
+#define XHC_ECHBIU_OFFSET			0xc00U
+#define XHC_BIUSPC_OFFSET			0xc04U
+#define XHC_AXIWRA_OFFSET			0xc08U
+#define XHC_AXIRDA_OFFSET			0xc0cU
+#define XHC_AXILPM_OFFSET			0xc10U
+#define XHC_AXIQOS_OFFSET			0xc14U
+#define XHC_ECHCSR_OFFSET			0xc20U
+#define XHC_CSRSPC_OFFSET			0xc24U
+#define XHC_ECHAIU_OFFSET			0xc30U
+#define XHC_AIUDMA_OFFSET			0xc34U
+#define XHC_AIUFLA_OFFSET			0xc38U
+#define XHC_AIUCFG_OFFSET			0xc3cU
+#define XHC_ECHFSC_OFFSET			0xc40U
+#define XHC_FSCPOC_OFFSET			0xc54U
+#define XHC_FSCGOC_OFFSET			0xc58U
+#define XHC_FSCNOC_OFFSET			0xc5cU
+#define XHC_FSCAIC_OFFSET			0xc60U
+#define XHC_FSCPIC_OFFSET			0xc64U
+#define XHC_FSCGIC_OFFSET			0xc68U
+#define XHC_FSCNIC_OFFSET			0xc6cU
+#define XHC_ECHPRT_OFFSET			0xc70U
+#define XHC_PRTHSC_OFFSET			0xc78U
+#define XHC_PRTHSR_OFFSET			0xc7cU
+#define XHC_ECHRHS_OFFSET			0xc80U
+#define XHC_RHSDES_OFFSET			0xc84U
+#define XHC_RHSHSC0_OFFSET			0xc90U
+#define XHC_RHSHSR0_OFFSET			0xc94U
+#define XHC_RHSHSC1_OFFSET			0xc98U
+#define XHC_RHSHSR1_OFFSET			0xc9cU
+#define XHC_RHSHSC2_OFFSET			0xca0U
+#define XHC_RHSHSR2_OFFSET			0xca4U
+#define XHC_RHSHSC3_OFFSET			0xca8U
+#define XHC_RHSHSR3_OFFSET			0xcacU
+#define XHC_ECHSSP_OFFSET			0xcb0U
+#define XHC_SSPVER_OFFSET			0xcb4U
+#define XHC_SSPMGN_OFFSET			0xcb8U
+#define XHC_ECHFSC2_OFFSET			0xcc0U
+#define XHC_FSC2POC_OFFSET			0xcd4U
+#define XHC_FSC2GOC_OFFSET			0xcd8U
+#define XHC_FSC2NOC_OFFSET			0xcdcU
+#define XHC_FSC2AIC_OFFSET			0xce0U
+#define XHC_FSC2PIC_OFFSET			0xce4U
+#define XHC_FSC2GIC_OFFSET			0xce8U
+#define XHC_FSC2NIC_OFFSET			0xcecU
+#define XHC_ECHPRT2_OFFSET			0xcf0U
+#define XHC_PRT2HSC_OFFSET			0xcf8U
+#define XHC_PRT2HSR_OFFSET			0xcfcU
+#define XHC_ECHRH2_OFFSET			0xd00U
+#define XHC_RH2DES_OFFSET			0xd04U
+#define XHC_RH2HSC0_OFFSET			0xd10U
+#define XHC_RH2HSR0_OFFSET			0xd14U
+#define XHC_RH2HSC1_OFFSET			0xd18U
+#define XHC_RH2HSR1_OFFSET			0xd1cU
+#define XHC_RH2HSC2_OFFSET			0xd20U
+#define XHC_RH2HSR2_OFFSET			0xd24U
+#define XHC_RH2HSC3_OFFSET			0xd28U
+#define XHC_RH2HSR3_OFFSET			0xd2cU
+#define XHC_ECHU2P_OFFSET			0xd30U
+#define XHC_U2PVER_OFFSET			0xd34U
+#define XHC_U2PMGN_OFFSET			0xd38U
+#define XHC_ECHRSV2_OFFSET			0xd40U
+#define XHC_ECHIRA_OFFSET			0xf90U
+#define XHC_IRAADR_OFFSET			0xf98U
+#define XHC_IRADAT_OFFSET			0xf9cU
+#define XHC_ECHHST_OFFSET			0xfa0U
+#define XHC_HSTDBG_OFFSET			0xfa4U
+#define XHC_HSTNPL_OFFSET			0xfa8U
+#define XHC_HSTNPH_OFFSET			0xfacU
+#define XHC_ECHRBV_OFFSET			0xfb0U
+#define XHC_RBVPDT_OFFSET			0xfb4U
+#define XHC_RBVMGN_OFFSET			0xfbcU
+
+#define XHC_CPLIVER_BASE			0x000U
+#define XHC_CPLIVER__IVH_L			31U
+#define XHC_CPLIVER__IVH_R			24U
+#define XHC_CPLIVER__IVH_WIDTH			8U
+#define XHC_CPLIVER__IVH_RESETVALUE		0x01U
+#define XHC_CPLIVER__IVL_L			23U
+#define XHC_CPLIVER__IVL_R			16U
+#define XHC_CPLIVER__IVL_WIDTH			8U
+#define XHC_CPLIVER__IVL_RESETVALUE		0x10U
+#define XHC_CPLIVER__reserved_L			15U
+#define XHC_CPLIVER__reserved_R			8U
+#define XHC_CPLIVER__reserved_WIDTH		8U
+#define XHC_CPLIVER__reserved_RESETVALUE	0x00U
+#define XHC_CPLIVER__CPL_L			7U
+#define XHC_CPLIVER__CPL_R			0U
+#define XHC_CPLIVER__CPL_WIDTH			8U
+#define XHC_CPLIVER__CPL_RESETVALUE		0x00U
+#define XHC_CPLIVER_WIDTH			32U
+#define XHC_CPLIVER__WIDTH			32U
+#define XHC_CPLIVER_ALL_L			31U
+#define XHC_CPLIVER_ALL_R			0U
+#define XHC_CPLIVER__ALL_L			31U
+#define XHC_CPLIVER__ALL_R			0U
+#define XHC_CPLIVER_DATAMASK			0xffffffffU
+#define XHC_CPLIVER_RDWRMASK			0x00000000U
+#define XHC_CPLIVER_RESETVALUE			0x01100000U
+
+#define XHC_SPARAMS1_OFFSET			0x004U
+#define XHC_SPARAMS1_BASE			0x004U
+#define XHC_SPARAMS1__NPTS_L			31U
+#define XHC_SPARAMS1__NPTS_R			24U
+#define XHC_SPARAMS1__NPTS_WIDTH		8U
+#define XHC_SPARAMS1__NPTS_RESETVALUE		0x00U
+#define XHC_SPARAMS1__reserved_L		23U
+#define XHC_SPARAMS1__reserved_R		19U
+#define XHC_SPARAMS1__reserved_WIDTH		5U
+#define XHC_SPARAMS1__reserved_RESETVALUE	0x0U
+#define XHC_SPARAMS1__MITS_L			18U
+#define XHC_SPARAMS1__MITS_R			8U
+#define XHC_SPARAMS1__MITS_WIDTH		11U
+#define XHC_SPARAMS1__MITS_RESETVALUE		0x1U
+#define XHC_SPARAMS1__MSLS_L			7U
+#define XHC_SPARAMS1__MSLS_R			0U
+#define XHC_SPARAMS1__MSLS_WIDTH		8U
+#define XHC_SPARAMS1__MSLS_RESETVALUE		0x00U
+#define XHC_SPARAMS1_WIDTH			32U
+#define XHC_SPARAMS1__WIDTH			32U
+#define XHC_SPARAMS1_ALL_L			31U
+#define XHC_SPARAMS1_ALL_R			0U
+#define XHC_SPARAMS1__ALL_L			31U
+#define XHC_SPARAMS1__ALL_R			0U
+#define XHC_SPARAMS1_DATAMASK			0xffffffffU
+#define XHC_SPARAMS1_RDWRMASK			0x00000000U
+#define XHC_SPARAMS1_RESETVALUE			0x00000100U
+
+#define XHC_SPARAMS2_OFFSET			0x008U
+#define XHC_SPARAMS2_BASE			0x008U
+#define XHC_SPARAMS2__MSPBSL_L			31U
+#define XHC_SPARAMS2__MSPBSL_R			27U
+#define XHC_SPARAMS2__MSPBSL_WIDTH		5U
+#define XHC_SPARAMS2__MSPBSL_RESETVALUE		0x0U
+#define XHC_SPARAMS2__SPR			26U
+#define XHC_SPARAMS2__SPR_L			26U
+#define XHC_SPARAMS2__SPR_R			26U
+#define XHC_SPARAMS2__SPR_WIDTH			1U
+#define XHC_SPARAMS2__SPR_RESETVALUE		0x1U
+#define XHC_SPARAMS2__MSPBSH_L			25U
+#define XHC_SPARAMS2__MSPBSH_R			21U
+#define XHC_SPARAMS2__MSPBSH_WIDTH		5U
+#define XHC_SPARAMS2__MSPBSH_RESETVALUE		0x0U
+#define XHC_SPARAMS2__reserved_L		20U
+#define XHC_SPARAMS2__reserved_R		8U
+#define XHC_SPARAMS2__reserved_WIDTH		13U
+#define XHC_SPARAMS2__reserved_RESETVALUE	0x0U
+#define XHC_SPARAMS2__MERST_L			7U
+#define XHC_SPARAMS2__MERST_R			4U
+#define XHC_SPARAMS2__MERST_WIDTH		4U
+#define XHC_SPARAMS2__MERST_RESETVALUE		0x0U
+#define XHC_SPARAMS2__IST_L			3U
+#define XHC_SPARAMS2__IST_R			0U
+#define XHC_SPARAMS2__IST_WIDTH			4U
+#define XHC_SPARAMS2__IST_RESETVALUE		0x0U
+#define XHC_SPARAMS2_WIDTH			32U
+#define XHC_SPARAMS2__WIDTH			32U
+#define XHC_SPARAMS2_ALL_L			31U
+#define XHC_SPARAMS2_ALL_R			0U
+#define XHC_SPARAMS2__ALL_L			31U
+#define XHC_SPARAMS2__ALL_R			0U
+#define XHC_SPARAMS2_DATAMASK			0xffffffffU
+#define XHC_SPARAMS2_RDWRMASK			0x00000000U
+#define XHC_SPARAMS2_RESETVALUE			0x04000000U
+
+#define XHC_SPARAMS3_OFFSET			0x00cU
+#define XHC_SPARAMS3_BASE			0x00cU
+#define XHC_SPARAMS3__U2L_L			31U
+#define XHC_SPARAMS3__U2L_R			16U
+#define XHC_SPARAMS3__U2L_WIDTH			16U
+#define XHC_SPARAMS3__U2L_RESETVALUE		0x0000U
+#define XHC_SPARAMS3__reserved_L		15U
+#define XHC_SPARAMS3__reserved_R		8U
+#define XHC_SPARAMS3__reserved_WIDTH		8U
+#define XHC_SPARAMS3__reserved_RESETVALUE	0x00U
+#define XHC_SPARAMS3__U1L_L			7U
+#define XHC_SPARAMS3__U1L_R			0U
+#define XHC_SPARAMS3__U1L_WIDTH			8U
+#define XHC_SPARAMS3__U1L_RESETVALUE		0x00U
+#define XHC_SPARAMS3_WIDTH			32U
+#define XHC_SPARAMS3__WIDTH			32U
+#define XHC_SPARAMS3_ALL_L			31U
+#define XHC_SPARAMS3_ALL_R			0U
+#define XHC_SPARAMS3__ALL_L			31U
+#define XHC_SPARAMS3__ALL_R			0U
+#define XHC_SPARAMS3_DATAMASK			0xffffffffU
+#define XHC_SPARAMS3_RDWRMASK			0x00000000U
+#define XHC_SPARAMS3_RESETVALUE			0x00000000U
+
+#define XHC_CPARAMS1_OFFSET			0x010U
+#define XHC_CPARAMS1_BASE			0x010U
+#define XHC_CPARAMS1__XECP_L			31U
+#define XHC_CPARAMS1__XECP_R			16U
+#define XHC_CPARAMS1__XECP_WIDTH		16U
+#define XHC_CPARAMS1__XECP_RESETVALUE		0x0000U
+#define XHC_CPARAMS1__MPSA_L			15U
+#define XHC_CPARAMS1__MPSA_R			12U
+#define XHC_CPARAMS1__MPSA_WIDTH		4U
+#define XHC_CPARAMS1__MPSA_RESETVALUE		0x0U
+#define XHC_CPARAMS1__CFC			11U
+#define XHC_CPARAMS1__CFC_L			11U
+#define XHC_CPARAMS1__CFC_R			11U
+#define XHC_CPARAMS1__CFC_WIDTH			1U
+#define XHC_CPARAMS1__CFC_RESETVALUE		0x0U
+#define XHC_CPARAMS1__SEC			10U
+#define XHC_CPARAMS1__SEC_L			10U
+#define XHC_CPARAMS1__SEC_R			10U
+#define XHC_CPARAMS1__SEC_WIDTH			1U
+#define XHC_CPARAMS1__SEC_RESETVALUE		0x0U
+#define XHC_CPARAMS1__SPC			9U
+#define XHC_CPARAMS1__SPC_L			9U
+#define XHC_CPARAMS1__SPC_R			9U
+#define XHC_CPARAMS1__SPC_WIDTH			1U
+#define XHC_CPARAMS1__SPC_RESETVALUE		0x0U
+#define XHC_CPARAMS1__PAE			8U
+#define XHC_CPARAMS1__PAE_L			8U
+#define XHC_CPARAMS1__PAE_R			8U
+#define XHC_CPARAMS1__PAE_WIDTH			1U
+#define XHC_CPARAMS1__PAE_RESETVALUE		0x1U
+#define XHC_CPARAMS1__NSS			7U
+#define XHC_CPARAMS1__NSS_L			7U
+#define XHC_CPARAMS1__NSS_R			7U
+#define XHC_CPARAMS1__NSS_WIDTH			1U
+#define XHC_CPARAMS1__NSS_RESETVALUE		0x0U
+#define XHC_CPARAMS1__LTC			6U
+#define XHC_CPARAMS1__LTC_L			6U
+#define XHC_CPARAMS1__LTC_R			6U
+#define XHC_CPARAMS1__LTC_WIDTH			1U
+#define XHC_CPARAMS1__LTC_RESETVALUE		0x1U
+#define XHC_CPARAMS1__LRC			5U
+#define XHC_CPARAMS1__LRC_L			5U
+#define XHC_CPARAMS1__LRC_R			5U
+#define XHC_CPARAMS1__LRC_WIDTH			1U
+#define XHC_CPARAMS1__LRC_RESETVALUE		0x0U
+#define XHC_CPARAMS1__PIND			4U
+#define XHC_CPARAMS1__PIND_L			4U
+#define XHC_CPARAMS1__PIND_R			4U
+#define XHC_CPARAMS1__PIND_WIDTH		1U
+#define XHC_CPARAMS1__PIND_RESETVALUE		0x0U
+
+#define XHC_CPARAMS1__PPC_L			3U
+#define XHC_CPARAMS1__PPC_R			3U
+#define XHC_CPARAMS1__PPC_WIDTH			1U
+#define XHC_CPARAMS1__PPC_RESETVALUE		0x0U
+#define XHC_CPARAMS1__CSZ			2U
+#define XHC_CPARAMS1__CSZ_L			2U
+#define XHC_CPARAMS1__CSZ_R			2U
+#define XHC_CPARAMS1__CSZ_WIDTH			1U
+#define XHC_CPARAMS1__CSZ_RESETVALUE		0x1U
+#define XHC_CPARAMS1__BNC			1U
+#define XHC_CPARAMS1__BNC_L			1U
+#define XHC_CPARAMS1__BNC_R			1U
+#define XHC_CPARAMS1__BNC_WIDTH			1U
+#define XHC_CPARAMS1__BNC_RESETVALUE		0x0U
+#define XHC_CPARAMS1__AC64			0U
+#define XHC_CPARAMS1__AC64_L			0U
+#define XHC_CPARAMS1__AC64_R			0U
+#define XHC_CPARAMS1__AC64_WIDTH		1U
+#define XHC_CPARAMS1__AC64_RESETVALUE		0x0U
+#define XHC_CPARAMS1_WIDTH			32U
+#define XHC_CPARAMS1__WIDTH			32U
+#define XHC_CPARAMS1_ALL_L			31U
+#define XHC_CPARAMS1_ALL_R			0U
+#define XHC_CPARAMS1__ALL_L			31U
+#define XHC_CPARAMS1__ALL_R			0U
+#define XHC_CPARAMS1_DATAMASK			0xffffffffU
+#define XHC_CPARAMS1_RDWRMASK			0x00000000U
+#define XHC_CPARAMS1_RESETVALUE			0x00000144U
+
+#define XHC_DBOFF_OFFSET			0x014U
+#define XHC_DBOFF_BASE				0x014U
+#define XHC_DBOFF__DBO_L			15U
+#define XHC_DBOFF__DBO_R			2U
+#define XHC_DBOFF__DBO_WIDTH			14U
+#define XHC_DBOFF__DBO_RESETVALUE		0x0U
+#define XHC_DBOFF__reserved_L			1U
+#define XHC_DBOFF__reserved_R			0U
+#define XHC_DBOFF__reserved_WIDTH		2U
+#define XHC_DBOFF__reserved_RESETVALUE		0x0U
+#define XHC_DBOFF__RESERVED_L			31U
+#define XHC_DBOFF__RESERVED_R			16U
+#define XHC_DBOFF_WIDTH				16U
+#define XHC_DBOFF__WIDTH			16U
+#define XHC_DBOFF_ALL_L				15U
+#define XHC_DBOFF_ALL_R				0U
+#define XHC_DBOFF__ALL_L			15U
+#define XHC_DBOFF__ALL_R			0U
+#define XHC_DBOFF_DATAMASK			0x0000ffffU
+#define XHC_DBOFF_RDWRMASK			0xffff0000U
+#define XHC_DBOFF_RESETVALUE			0x0000U
+
+#define XHC_RTOFF_OFFSET			0x018U
+#define XHC_RTOFF_BASE				0x018U
+#define XHC_RTOFF__RTO_L			15U
+#define XHC_RTOFF__RTO_R			5U
+#define XHC_RTOFF__RTO_WIDTH			11U
+#define XHC_RTOFF__RTO_RESETVALUE		0x0U
+#define XHC_RTOFF__reserved_L			4U
+#define XHC_RTOFF__reserved_R			0U
+#define XHC_RTOFF__reserved_WIDTH		5U
+#define XHC_RTOFF__reserved_RESETVALUE		0x0U
+#define XHC_RTOFF__RESERVED_L			31U
+#define XHC_RTOFF__RESERVED_R			16U
+#define XHC_RTOFF_WIDTH				16U
+#define XHC_RTOFF__WIDTH			16U
+#define XHC_RTOFF_ALL_L				15U
+#define XHC_RTOFF_ALL_R				0U
+#define XHC_RTOFF__ALL_L			15U
+#define XHC_RTOFF__ALL_R			0U
+#define XHC_RTOFF_DATAMASK			0x0000ffffU
+#define XHC_RTOFF_RDWRMASK			0xffff0000U
+#define XHC_RTOFF_RESETVALUE			0x0000U
+
+#define XHC_CPARAMS2_OFFSET			0x01cU
+#define XHC_CPARAMS2_BASE			0x01cU
+#define XHC_CPARAMS2__reserved_L		31U
+#define XHC_CPARAMS2__reserved_R		6U
+#define XHC_CPARAMS2__reserved_WIDTH		26U
+#define XHC_CPARAMS2__reserved_RESETVALUE	0x0U
+#define XHC_CPARAMS2__CIC			5U
+#define XHC_CPARAMS2__CIC_L			5U
+#define XHC_CPARAMS2__CIC_R			5U
+#define XHC_CPARAMS2__CIC_WIDTH			1U
+#define XHC_CPARAMS2__CIC_RESETVALUE		0x0U
+#define XHC_CPARAMS2__LEC			4U
+#define XHC_CPARAMS2__LEC_L			4U
+#define XHC_CPARAMS2__LEC_R			4U
+#define XHC_CPARAMS2__LEC_WIDTH			1U
+#define XHC_CPARAMS2__LEC_RESETVALUE		0x0U
+#define XHC_CPARAMS2__CTC			3U
+#define XHC_CPARAMS2__CTC_L			3U
+#define XHC_CPARAMS2__CTC_R			3U
+#define XHC_CPARAMS2__CTC_WIDTH			1U
+#define XHC_CPARAMS2__CTC_RESETVALUE		0x0U
+#define XHC_CPARAMS2__FSC			2U
+#define XHC_CPARAMS2__FSC_L			2U
+#define XHC_CPARAMS2__FSC_R			2U
+#define XHC_CPARAMS2__FSC_WIDTH			1U
+#define XHC_CPARAMS2__FSC_RESETVALUE		0x0U
+#define XHC_CPARAMS2__CMC			1U
+#define XHC_CPARAMS2__CMC_L			1U
+#define XHC_CPARAMS2__CMC_R			1U
+#define XHC_CPARAMS2__CMC_WIDTH			1U
+#define XHC_CPARAMS2__CMC_RESETVALUE		0x0U
+#define XHC_CPARAMS2__U3C			0U
+#define XHC_CPARAMS2__U3C_L			0U
+#define XHC_CPARAMS2__U3C_R			0U
+#define XHC_CPARAMS2__U3C_WIDTH			1U
+#define XHC_CPARAMS2__U3C_RESETVALUE		0x0U
+#define XHC_CPARAMS2_WIDTH			32U
+#define XHC_CPARAMS2__WIDTH			32U
+#define XHC_CPARAMS2_ALL_L			31U
+#define XHC_CPARAMS2_ALL_R			0U
+#define XHC_CPARAMS2__ALL_L			31U
+#define XHC_CPARAMS2__ALL_R			0U
+#define XHC_CPARAMS2_DATAMASK			0xffffffffU
+#define XHC_CPARAMS2_RDWRMASK			0x00000000U
+#define XHC_CPARAMS2_RESETVALUE			0x00000000U
+
+#define XHC_USBCMD_OFFSET			0x020U
+#define XHC_USBCMD_BASE				0x020U
+#define XHC_USBCMD__CME				13U
+#define XHC_USBCMD__CME_L			13U
+#define XHC_USBCMD__CME_R			13U
+#define XHC_USBCMD__CME_WIDTH			1U
+#define XHC_USBCMD__CME_RESETVALUE		0x0U
+#define XHC_USBCMD__SPE				12U
+#define XHC_USBCMD__SPE_L			12U
+#define XHC_USBCMD__SPE_R			12U
+#define XHC_USBCMD__SPE_WIDTH			1U
+#define XHC_USBCMD__SPE_RESETVALUE		0x0U
+#define XHC_USBCMD__EU3S			11U
+#define XHC_USBCMD__EU3S_L			11U
+#define XHC_USBCMD__EU3S_R			11U
+#define XHC_USBCMD__EU3S_WIDTH			1U
+#define XHC_USBCMD__EU3S_RESETVALUE		0x0U
+#define XHC_USBCMD__EWE				10U
+#define XHC_USBCMD__EWE_L			10U
+#define XHC_USBCMD__EWE_R			10U
+#define XHC_USBCMD__EWE_WIDTH			1U
+#define XHC_USBCMD__EWE_RESETVALUE		0x0U
+#define XHC_USBCMD__CRS				9U
+#define XHC_USBCMD__CRS_L			9U
+#define XHC_USBCMD__CRS_R			9U
+#define XHC_USBCMD__CRS_WIDTH			1U
+#define XHC_USBCMD__CRS_RESETVALUE		0x0U
+#define XHC_USBCMD__CSS				8U
+#define XHC_USBCMD__CSS_L			8U
+#define XHC_USBCMD__CSS_R			8U
+#define XHC_USBCMD__CSS_WIDTH			1U
+#define XHC_USBCMD__CSS_RESETVALUE		0x0U
+#define XHC_USBCMD__LRST			7U
+#define XHC_USBCMD__LRST_L			7U
+#define XHC_USBCMD__LRST_R			7U
+#define XHC_USBCMD__LRST_WIDTH			1U
+#define XHC_USBCMD__LRST_RESETVALUE		0x0U
+#define XHC_USBCMD__reserved_L			6U
+#define XHC_USBCMD__reserved_R			4U
+#define XHC_USBCMD__reserved_WIDTH		3U
+#define XHC_USBCMD__reserved_RESETVALUE		0x0U
+#define XHC_USBCMD__HSEE			3U
+#define XHC_USBCMD__HSEE_L			3U
+#define XHC_USBCMD__HSEE_R			3U
+#define XHC_USBCMD__HSEE_WIDTH			1U
+#define XHC_USBCMD__HSEE_RESETVALUE		0x0U
+#define XHC_USBCMD__INTE			2U
+#define XHC_USBCMD__INTE_L			2U
+#define XHC_USBCMD__INTE_R			2U
+#define XHC_USBCMD__INTE_WIDTH			1U
+#define XHC_USBCMD__INTE_RESETVALUE		0x0U
+#define XHC_USBCMD__RST				1U
+#define XHC_USBCMD__RST_L			1U
+#define XHC_USBCMD__RST_R			1U
+#define XHC_USBCMD__RST_WIDTH			1U
+#define XHC_USBCMD__RST_RESETVALUE		0x0U
+#define XHC_USBCMD__RS				0U
+#define XHC_USBCMD__RS_L			0U
+#define XHC_USBCMD__RS_R			0U
+#define XHC_USBCMD__RS_WIDTH			1U
+#define XHC_USBCMD__RS_RESETVALUE		0x0U
+#define XHC_USBCMD__RESERVED_L			31U
+#define XHC_USBCMD__RESERVED_R			14U
+#define XHC_USBCMD_WIDTH			14U
+#define XHC_USBCMD__WIDTH			14U
+#define XHC_USBCMD_ALL_L			13U
+#define XHC_USBCMD_ALL_R			0U
+#define XHC_USBCMD__ALL_L			13U
+#define XHC_USBCMD__ALL_R			0U
+#define XHC_USBCMD_DATAMASK			0x00003fffU
+#define XHC_USBCMD_RDWRMASK			0xffffc000U
+#define XHC_USBCMD_RESETVALUE			0x0000U
+
+#define XHC_USBSTS_OFFSET			0x024U
+#define XHC_USBSTS_BASE				0x024U
+#define XHC_USBSTS__CE				12U
+#define XHC_USBSTS__CE_L			12U
+#define XHC_USBSTS__CE_R			12U
+#define XHC_USBSTS__CE_WIDTH			1U
+#define XHC_USBSTS__CE_RESETVALUE		0x0U
+#define XHC_USBSTS__CNR				11U
+#define XHC_USBSTS__CNR_L			11U
+#define XHC_USBSTS__CNR_R			11U
+#define XHC_USBSTS__CNR_WIDTH			1U
+#define XHC_USBSTS__CNR_RESETVALUE		0x1U
+
+#define XHC_USBSTS__SRE				10U
+#define XHC_USBSTS__SRE_L			10U
+#define XHC_USBSTS__SRE_R			10U
+#define XHC_USBSTS__SRE_WIDTH			1U
+#define XHC_USBSTS__SRE_RESETVALUE		0x0U
+#define XHC_USBSTS__RSS				9U
+#define XHC_USBSTS__RSS_L			9U
+#define XHC_USBSTS__RSS_R			9U
+#define XHC_USBSTS__RSS_WIDTH			1U
+#define XHC_USBSTS__RSS_RESETVALUE		0x0U
+#define XHC_USBSTS__SSS				8U
+#define XHC_USBSTS__SSS_L			8U
+#define XHC_USBSTS__SSS_R			8U
+#define XHC_USBSTS__SSS_WIDTH			1U
+#define XHC_USBSTS__SSS_RESETVALUE		0x0U
+#define XHC_USBSTS__PCD				4U
+#define XHC_USBSTS__PCD_L			4U
+#define XHC_USBSTS__PCD_R			4U
+#define XHC_USBSTS__PCD_WIDTH			1U
+#define XHC_USBSTS__PCD_RESETVALUE		0x0U
+#define XHC_USBSTS__EINT			3U
+#define XHC_USBSTS__EINT_L			3U
+#define XHC_USBSTS__EINT_R			3U
+#define XHC_USBSTS__EINT_WIDTH			1U
+#define XHC_USBSTS__EINT_RESETVALUE		0x0U
+#define XHC_USBSTS__HSE				2U
+#define XHC_USBSTS__HSE_L			2U
+#define XHC_USBSTS__HSE_R			2U
+#define XHC_USBSTS__HSE_WIDTH			1U
+#define XHC_USBSTS__HSE_RESETVALUE		0x0U
+#define XHC_USBSTS__reserved			1U
+#define XHC_USBSTS__reserved_L			1U
+#define XHC_USBSTS__reserved_R			1U
+#define XHC_USBSTS__reserved_WIDTH		1U
+#define XHC_USBSTS__reserved_RESETVALUE		0x0U
+
+#define XHC_USBSTS__CH_L			0U
+#define XHC_USBSTS__CH_R			0U
+#define XHC_USBSTS__CH_WIDTH			1U
+#define XHC_USBSTS__CH_RESETVALUE		0x1U
+#define XHC_USBSTS__RESERVED_L			31U
+#define XHC_USBSTS__RESERVED_R			13U
+#define XHC_USBSTS_WIDTH			13U
+#define XHC_USBSTS__WIDTH			13U
+#define XHC_USBSTS_ALL_L			12U
+#define XHC_USBSTS_ALL_R			0U
+#define XHC_USBSTS__ALL_L			12U
+#define XHC_USBSTS__ALL_R			0U
+#define XHC_USBSTS_DATAMASK			0x00001f1fU
+#define XHC_USBSTS_RDWRMASK			0xffffe0e0U
+#define XHC_USBSTS_RESETVALUE			0x0801U
+
+#define XHC_PAGESIZE_OFFSET			0x028U
+#define XHC_PAGESIZE_BASE			0x028U
+#define XHC_PAGESIZE__reserved_L		31U
+#define XHC_PAGESIZE__reserved_R		16U
+#define XHC_PAGESIZE__reserved_WIDTH		16U
+#define XHC_PAGESIZE__reserved_RESETVALUE	0x0000U
+#define XHC_PAGESIZE__PS_L			15U
+#define XHC_PAGESIZE__PS_R			0U
+#define XHC_PAGESIZE__PS_WIDTH			16U
+#define XHC_PAGESIZE__PS_RESETVALUE		0x0000U
+#define XHC_PAGESIZE_WIDTH			32U
+#define XHC_PAGESIZE__WIDTH			32U
+#define XHC_PAGESIZE_ALL_L			31U
+#define XHC_PAGESIZE_ALL_R			0U
+#define XHC_PAGESIZE__ALL_L			31U
+#define XHC_PAGESIZE__ALL_R			0U
+#define XHC_PAGESIZE_DATAMASK			0xffffffffU
+#define XHC_PAGESIZE_RDWRMASK			0x00000000U
+#define XHC_PAGESIZE_RESETVALUE			0x00000000U
+
+#define XHC_DNCTRL_OFFSET			0x034U
+#define XHC_DNCTRL_BASE				0x034U
+#define XHC_DNCTRL__reserved_L			31U
+#define XHC_DNCTRL__reserved_R			16U
+#define XHC_DNCTRL__reserved_WIDTH		16U
+#define XHC_DNCTRL__reserved_RESETVALUE		0x0000U
+#define XHC_DNCTRL__DNE_L			15U
+#define XHC_DNCTRL__DNE_R			0U
+#define XHC_DNCTRL__DNE_WIDTH			16U
+#define XHC_DNCTRL__DNE_RESETVALUE		0x0000U
+#define XHC_DNCTRL_WIDTH			32U
+#define XHC_DNCTRL__WIDTH			32U
+#define XHC_DNCTRL_ALL_L			31U
+#define XHC_DNCTRL_ALL_R			0U
+#define XHC_DNCTRL__ALL_L			31U
+#define XHC_DNCTRL__ALL_R			0U
+#define XHC_DNCTRL_DATAMASK			0xffffffffU
+#define XHC_DNCTRL_RDWRMASK			0x00000000U
+#define XHC_DNCTRL_RESETVALUE			0x00000000U
+
+#define XHC_CRCRL_OFFSET			0x038U
+#define XHC_CRCRL_BASE				0x038U
+#define XHC_CRCRL__CRPL_L			31U
+#define XHC_CRCRL__CRPL_R			6U
+#define XHC_CRCRL__CRPL_WIDTH			26U
+#define XHC_CRCRL__CRPL_RESETVALUE		0x0U
+#define XHC_CRCRL__reserved_L			5U
+#define XHC_CRCRL__reserved_R			4U
+#define XHC_CRCRL__reserved_WIDTH		2U
+#define XHC_CRCRL__reserved_RESETVALUE		0x0U
+#define XHC_CRCRL__CRR				3U
+#define XHC_CRCRL__CRR_L			3U
+#define XHC_CRCRL__CRR_R			3U
+#define XHC_CRCRL__CRR_WIDTH			1U
+#define XHC_CRCRL__CRR_RESETVALUE		0x0U
+#define XHC_CRCRL__CA				2U
+#define XHC_CRCRL__CA_L				2U
+#define XHC_CRCRL__CA_R				2U
+#define XHC_CRCRL__CA_WIDTH			1U
+#define XHC_CRCRL__CA_RESETVALUE		0x0U
+#define XHC_CRCRL__CS				1U
+#define XHC_CRCRL__CS_L				1U
+#define XHC_CRCRL__CS_R				1U
+#define XHC_CRCRL__CS_WIDTH			1U
+#define XHC_CRCRL__CS_RESETVALUE		0x0U
+#define XHC_CRCRL__RCS				0U
+#define XHC_CRCRL__RCS_L			0U
+#define XHC_CRCRL__RCS_R			0U
+#define XHC_CRCRL__RCS_WIDTH			1U
+#define XHC_CRCRL__RCS_RESETVALUE		0x0U
+#define XHC_CRCRL_WIDTH				32U
+#define XHC_CRCRL__WIDTH			32U
+#define XHC_CRCRL_ALL_L				31U
+#define XHC_CRCRL_ALL_R				0U
+#define XHC_CRCRL__ALL_L			31U
+#define XHC_CRCRL__ALL_R			0U
+#define XHC_CRCRL_DATAMASK			0xffffffffU
+#define XHC_CRCRL_RDWRMASK			0x00000000U
+#define XHC_CRCRL_RESETVALUE			0x00000000U
+
+#define XHC_CRCRH_OFFSET			0x03cU
+#define XHC_CRCRH_BASE				0x03cU
+#define XHC_CRCRH__CRPH_L			31U
+#define XHC_CRCRH__CRPH_R			0U
+#define XHC_CRCRH__CRPH_WIDTH			32U
+#define XHC_CRCRH__CRPH_RESETVALUE		0x00000000U
+#define XHC_CRCRH_WIDTH				32U
+#define XHC_CRCRH__WIDTH			32U
+#define XHC_CRCRH_ALL_L				31U
+#define XHC_CRCRH_ALL_R				0U
+#define XHC_CRCRH__ALL_L			31U
+#define XHC_CRCRH__ALL_R			0U
+#define XHC_CRCRH_DATAMASK			0xffffffffU
+#define XHC_CRCRH_RDWRMASK			0x00000000U
+#define XHC_CRCRH_RESETVALUE			0x00000000U
+
+#define XHC_DCBAAPL_OFFSET			0x050U
+#define XHC_DCBAAPL_BASE			0x050U
+#define XHC_DCBAAPL__DCAL_L			31U
+#define XHC_DCBAAPL__DCAL_R			6U
+#define XHC_DCBAAPL__DCAL_WIDTH			26U
+#define XHC_DCBAAPL__DCAL_RESETVALUE		0x0U
+
+#define XHC_DCBAAPL__reserved_L			5U
+#define XHC_DCBAAPL__reserved_R			0U
+#define XHC_DCBAAPL__reserved_WIDTH		6U
+#define XHC_DCBAAPL__reserved_RESETVALUE	0x0U
+#define XHC_DCBAAPL_WIDTH			32U
+#define XHC_DCBAAPL__WIDTH			32U
+#define XHC_DCBAAPL_ALL_L			31U
+#define XHC_DCBAAPL_ALL_R			0U
+#define XHC_DCBAAPL__ALL_L			31U
+#define XHC_DCBAAPL__ALL_R			0U
+#define XHC_DCBAAPL_DATAMASK			0xffffffffU
+#define XHC_DCBAAPL_RDWRMASK			0x00000000U
+#define XHC_DCBAAPL_RESETVALUE			0x00000000U
+
+#define XHC_DCBAAPH_OFFSET			0x054U
+#define XHC_DCBAAPH_BASE			0x054U
+#define XHC_DCBAAPH__DCAH_L			31U
+#define XHC_DCBAAPH__DCAH_R			0U
+#define XHC_DCBAAPH__DCAH_WIDTH			32U
+#define XHC_DCBAAPH__DCAH_RESETVALUE		0x00000000U
+#define XHC_DCBAAPH_WIDTH			32U
+#define XHC_DCBAAPH__WIDTH			32U
+#define XHC_DCBAAPH_ALL_L			31U
+#define XHC_DCBAAPH_ALL_R			0U
+#define XHC_DCBAAPH__ALL_L			31U
+#define XHC_DCBAAPH__ALL_R			0U
+#define XHC_DCBAAPH_DATAMASK			0xffffffffU
+#define XHC_DCBAAPH_RDWRMASK			0x00000000U
+#define XHC_DCBAAPH_RESETVALUE			0x00000000U
+
+#define XHC_CONFIG_OFFSET			0x058U
+#define XHC_CONFIG_BASE				0x058U
+#define XHC_CONFIG__reserved_L			31U
+#define XHC_CONFIG__reserved_R			10U
+#define XHC_CONFIG__reserved_WIDTH		22U
+#define XHC_CONFIG__reserved_RESETVALUE		0x0U
+#define XHC_CONFIG__CIE				9U
+#define XHC_CONFIG__CIE_L			9U
+#define XHC_CONFIG__CIE_R			9U
+#define XHC_CONFIG__CIE_WIDTH			1U
+#define XHC_CONFIG__CIE_RESETVALUE		0x0U
+#define XHC_CONFIG__U3E				8U
+#define XHC_CONFIG__U3E_L			8U
+#define XHC_CONFIG__U3E_R			8U
+#define XHC_CONFIG__U3E_WIDTH			1U
+#define XHC_CONFIG__U3E_RESETVALUE		0x0U
+#define XHC_CONFIG__MSE_L			7U
+#define XHC_CONFIG__MSE_R			0U
+#define XHC_CONFIG__MSE_WIDTH			8U
+#define XHC_CONFIG__MSE_RESETVALUE		0x00U
+#define XHC_CONFIG_WIDTH			32U
+#define XHC_CONFIG__WIDTH			32U
+#define XHC_CONFIG_ALL_L			31U
+#define XHC_CONFIG_ALL_R			0U
+#define XHC_CONFIG__ALL_L			31U
+#define XHC_CONFIG__ALL_R			0U
+#define XHC_CONFIG_DATAMASK			0xffffffffU
+#define XHC_CONFIG_RDWRMASK			0x00000000U
+#define XHC_CONFIG_RESETVALUE			0x00000000U
+
+#define XHC_PORTSC1_OFFSET			0x420U
+#define XHC_PORTSC1_BASE			0x420U
+
+#define XHC_PORTSC1__WPR_L			31U
+#define XHC_PORTSC1__WPR_R			31U
+#define XHC_PORTSC1__WPR_WIDTH			1U
+#define XHC_PORTSC1__WPR_RESETVALUE		0x0U
+
+#define XHC_PORTSC1__DNR_L			30U
+#define XHC_PORTSC1__DNR_R			30U
+#define XHC_PORTSC1__DNR_WIDTH			1U
+#define XHC_PORTSC1__DNR_RESETVALUE		0x0U
+
+#define XHC_PORTSC1__WOE_L			27U
+#define XHC_PORTSC1__WOE_R			27U
+#define XHC_PORTSC1__WOE_WIDTH			1U
+#define XHC_PORTSC1__WOE_RESETVALUE		0x0U
+
+#define XHC_PORTSC1__WDE_L			26U
+#define XHC_PORTSC1__WDE_R			26U
+#define XHC_PORTSC1__WDE_WIDTH			1U
+#define XHC_PORTSC1__WDE_RESETVALUE		0x0U
+
+#define XHC_PORTSC1__WCE_L			25U
+#define XHC_PORTSC1__WCE_R			25U
+#define XHC_PORTSC1__WCE_WIDTH			1U
+#define XHC_PORTSC1__WCE_RESETVALUE		0x0U
+
+#define XHC_PORTSC1__CAS_L			24U
+#define XHC_PORTSC1__CAS_R			24U
+#define XHC_PORTSC1__CAS_WIDTH			1U
+#define XHC_PORTSC1__CAS_RESETVALUE		0x0U
+
+#define XHC_PORTSC1__CEC_L			23U
+#define XHC_PORTSC1__CEC_R			23U
+#define XHC_PORTSC1__CEC_WIDTH			1U
+#define XHC_PORTSC1__CEC_RESETVALUE		0x0U
+
+#define XHC_PORTSC1__PLC_L			22U
+#define XHC_PORTSC1__PLC_R			22U
+#define XHC_PORTSC1__PLC_WIDTH			1U
+#define XHC_PORTSC1__PLC_RESETVALUE		0x0U
+
+#define XHC_PORTSC1__PRC_L			21U
+#define XHC_PORTSC1__PRC_R			21U
+#define XHC_PORTSC1__PRC_WIDTH			1U
+#define XHC_PORTSC1__PRC_RESETVALUE		0x0U
+
+#define XHC_PORTSC1__OCC_L			20U
+#define XHC_PORTSC1__OCC_R			20U
+#define XHC_PORTSC1__OCC_WIDTH			1U
+#define XHC_PORTSC1__OCC_RESETVALUE		0x0U
+
+#define XHC_PORTSC1__WRC_L			19U
+#define XHC_PORTSC1__WRC_R			19U
+#define XHC_PORTSC1__WRC_WIDTH			1U
+#define XHC_PORTSC1__WRC_RESETVALUE		0x0U
+
+#define XHC_PORTSC1__PEC_L			18U
+#define XHC_PORTSC1__PEC_R			18U
+#define XHC_PORTSC1__PEC_WIDTH			1U
+#define XHC_PORTSC1__PEC_RESETVALUE		0x0U
+
+#define XHC_PORTSC1__CSC_L			17U
+#define XHC_PORTSC1__CSC_R			17U
+#define XHC_PORTSC1__CSC_WIDTH			1U
+#define XHC_PORTSC1__CSC_RESETVALUE		0x0U
+
+#define XHC_PORTSC1__LWS_L			16U
+#define XHC_PORTSC1__LWS_R			16U
+#define XHC_PORTSC1__LWS_WIDTH			1U
+#define XHC_PORTSC1__LWS_RESETVALUE		0x0U
+#define XHC_PORTSC1__PIC_L			15U
+#define XHC_PORTSC1__PIC_R			14U
+#define XHC_PORTSC1__PIC_WIDTH			2U
+#define XHC_PORTSC1__PIC_RESETVALUE		0x0U
+#define XHC_PORTSC1__PS_L			13U
+#define XHC_PORTSC1__PS_R			10U
+#define XHC_PORTSC1__PS_WIDTH			4U
+#define XHC_PORTSC1__PS_RESETVALUE		0x0U
+
+#define XHC_PORTSC1__PP_L			9U
+#define XHC_PORTSC1__PP_R			9U
+#define XHC_PORTSC1__PP_WIDTH			1U
+#define XHC_PORTSC1__PP_RESETVALUE		0x0U
+#define XHC_PORTSC1__PLS_L			8U
+#define XHC_PORTSC1__PLS_R			5U
+#define XHC_PORTSC1__PLS_WIDTH			4U
+#define XHC_PORTSC1__PLS_RESETVALUE		0x5U
+
+#define XHC_PORTSC1__PRST_L			4U
+#define XHC_PORTSC1__PRST_R			4U
+#define XHC_PORTSC1__PRST_WIDTH			1U
+#define XHC_PORTSC1__PRST_RESETVALUE		0x0U
+
+#define XHC_PORTSC1__OCA_L			3U
+#define XHC_PORTSC1__OCA_R			3U
+#define XHC_PORTSC1__OCA_WIDTH			1U
+#define XHC_PORTSC1__OCA_RESETVALUE		0x0U
+#define XHC_PORTSC1__reserved			2U
+#define XHC_PORTSC1__reserved_L			2U
+#define XHC_PORTSC1__reserved_R			2U
+#define XHC_PORTSC1__reserved_WIDTH		1U
+#define XHC_PORTSC1__reserved_RESETVALUE	0x0U
+
+#define XHC_PORTSC1__PED_L			1U
+#define XHC_PORTSC1__PED_R			1U
+#define XHC_PORTSC1__PED_WIDTH			1U
+#define XHC_PORTSC1__PED_RESETVALUE		0x0U
+
+#define XHC_PORTSC1__CCS_L			0U
+#define XHC_PORTSC1__CCS_R			0U
+#define XHC_PORTSC1__CCS_WIDTH			1U
+#define XHC_PORTSC1__CCS_RESETVALUE		0x0U
+#define XHC_PORTSC1__RESERVED_L			29U
+#define XHC_PORTSC1__RESERVED_R			28U
+#define XHC_PORTSC1_WIDTH			32U
+#define XHC_PORTSC1__WIDTH			32U
+#define XHC_PORTSC1_ALL_L			31U
+#define XHC_PORTSC1_ALL_R			0U
+#define XHC_PORTSC1__ALL_L			31U
+#define XHC_PORTSC1__ALL_R			0U
+#define XHC_PORTSC1_DATAMASK			0xcfffffffU
+#define XHC_PORTSC1_RDWRMASK			0x30000000U
+#define XHC_PORTSC1_RESETVALUE			0x000000a0U
+
+#define XHC_PORTPM1_OFFSET			0x424U
+#define XHC_PORTPM1_BASE			0x424U
+#define XHC_PORTPM1__reserved_L			31U
+#define XHC_PORTPM1__reserved_R			17U
+#define XHC_PORTPM1__reserved_WIDTH		15U
+#define XHC_PORTPM1__reserved_RESETVALUE	0x0U
+#define XHC_PORTPM1__FLA			16U
+#define XHC_PORTPM1__FLA_L			16U
+#define XHC_PORTPM1__FLA_R			16U
+#define XHC_PORTPM1__FLA_WIDTH			1U
+#define XHC_PORTPM1__FLA_RESETVALUE		0x0U
+#define XHC_PORTPM1__U2T_L			15U
+#define XHC_PORTPM1__U2T_R			8U
+#define XHC_PORTPM1__U2T_WIDTH			8U
+#define XHC_PORTPM1__U2T_RESETVALUE		0x00U
+#define XHC_PORTPM1__U1T_L			7U
+#define XHC_PORTPM1__U1T_R			0U
+#define XHC_PORTPM1__U1T_WIDTH			8U
+#define XHC_PORTPM1__U1T_RESETVALUE		0x00U
+#define XHC_PORTPM1_WIDTH			32U
+#define XHC_PORTPM1__WIDTH			32U
+#define XHC_PORTPM1_ALL_L			31U
+#define XHC_PORTPM1_ALL_R			0U
+#define XHC_PORTPM1__ALL_L			31U
+#define XHC_PORTPM1__ALL_R			0U
+#define XHC_PORTPM1_DATAMASK			0xffffffffU
+#define XHC_PORTPM1_RDWRMASK			0x00000000U
+#define XHC_PORTPM1_RESETVALUE			0x00000000U
+
+#define XHC_PORTLC1_OFFSET			0x428U
+#define XHC_PORTLC1_BASE			0x428U
+#define XHC_PORTLC1__reserved_L			31U
+#define XHC_PORTLC1__reserved_R			0U
+#define XHC_PORTLC1__reserved_WIDTH		32U
+#define XHC_PORTLC1__reserved_RESETVALUE	0x00000000U
+#define XHC_PORTLC1_WIDTH			32U
+#define XHC_PORTLC1__WIDTH			32U
+#define XHC_PORTLC1_ALL_L			31U
+#define XHC_PORTLC1_ALL_R			0U
+#define XHC_PORTLC1__ALL_L			31U
+#define XHC_PORTLC1__ALL_R			0U
+#define XHC_PORTLC1_DATAMASK			0xffffffffU
+#define XHC_PORTLC1_RDWRMASK			0x00000000U
+#define XHC_PORTLC1_RESETVALUE			0x00000000U
+
+#define XHC_PORTSC2_OFFSET			0x430U
+#define XHC_PORTSC2_BASE			0x430U
+#define XHC_PORTSC2__WPR			31U
+#define XHC_PORTSC2__WPR_L			31U
+#define XHC_PORTSC2__WPR_R			31U
+#define XHC_PORTSC2__WPR_WIDTH			1U
+#define XHC_PORTSC2__WPR_RESETVALUE		0x0U
+#define XHC_PORTSC2__DNR			30U
+#define XHC_PORTSC2__DNR_L			30U
+#define XHC_PORTSC2__DNR_R			30U
+#define XHC_PORTSC2__DNR_WIDTH			1U
+#define XHC_PORTSC2__DNR_RESETVALUE		0x0U
+#define XHC_PORTSC2__WOE			27U
+#define XHC_PORTSC2__WOE_L			27U
+#define XHC_PORTSC2__WOE_R			27U
+#define XHC_PORTSC2__WOE_WIDTH			1U
+#define XHC_PORTSC2__WOE_RESETVALUE		0x0U
+#define XHC_PORTSC2__WDE			26U
+#define XHC_PORTSC2__WDE_L			26U
+#define XHC_PORTSC2__WDE_R			26U
+#define XHC_PORTSC2__WDE_WIDTH			1U
+#define XHC_PORTSC2__WDE_RESETVALUE		0x0U
+#define XHC_PORTSC2__WCE			25U
+#define XHC_PORTSC2__WCE_L			25U
+#define XHC_PORTSC2__WCE_R			25U
+#define XHC_PORTSC2__WCE_WIDTH			1U
+#define XHC_PORTSC2__WCE_RESETVALUE		0x0U
+#define XHC_PORTSC2__CAS			24U
+#define XHC_PORTSC2__CAS_L			24U
+#define XHC_PORTSC2__CAS_R			24U
+#define XHC_PORTSC2__CAS_WIDTH			1U
+#define XHC_PORTSC2__CAS_RESETVALUE		0x0U
+#define XHC_PORTSC2__CEC			23U
+#define XHC_PORTSC2__CEC_L			23U
+#define XHC_PORTSC2__CEC_R			23U
+#define XHC_PORTSC2__CEC_WIDTH			1U
+#define XHC_PORTSC2__CEC_RESETVALUE		0x0U
+#define XHC_PORTSC2__PLC			22U
+#define XHC_PORTSC2__PLC_L			22U
+#define XHC_PORTSC2__PLC_R			22U
+#define XHC_PORTSC2__PLC_WIDTH			1U
+#define XHC_PORTSC2__PLC_RESETVALUE		0x0U
+#define XHC_PORTSC2__PRC			21U
+#define XHC_PORTSC2__PRC_L			21U
+#define XHC_PORTSC2__PRC_R			21U
+#define XHC_PORTSC2__PRC_WIDTH			1U
+#define XHC_PORTSC2__PRC_RESETVALUE		0x0U
+#define XHC_PORTSC2__OCC			20U
+#define XHC_PORTSC2__OCC_L			20U
+#define XHC_PORTSC2__OCC_R			20U
+#define XHC_PORTSC2__OCC_WIDTH			1U
+#define XHC_PORTSC2__OCC_RESETVALUE		0x0U
+#define XHC_PORTSC2__WRC			19U
+#define XHC_PORTSC2__WRC_L			19U
+#define XHC_PORTSC2__WRC_R			19U
+#define XHC_PORTSC2__WRC_WIDTH			1U
+#define XHC_PORTSC2__WRC_RESETVALUE		0x0U
+#define XHC_PORTSC2__PEC			18U
+#define XHC_PORTSC2__PEC_L			18U
+#define XHC_PORTSC2__PEC_R			18U
+#define XHC_PORTSC2__PEC_WIDTH			1U
+#define XHC_PORTSC2__PEC_RESETVALUE		0x0U
+#define XHC_PORTSC2__CSC			17U
+#define XHC_PORTSC2__CSC_L			17U
+#define XHC_PORTSC2__CSC_R			17U
+#define XHC_PORTSC2__CSC_WIDTH			1U
+#define XHC_PORTSC2__CSC_RESETVALUE		0x0U
+#define XHC_PORTSC2__LWS			16U
+#define XHC_PORTSC2__LWS_L			16U
+#define XHC_PORTSC2__LWS_R			16U
+#define XHC_PORTSC2__LWS_WIDTH			1U
+#define XHC_PORTSC2__LWS_RESETVALUE		0x0U
+#define XHC_PORTSC2__PIC_L			15U
+#define XHC_PORTSC2__PIC_R			14U
+#define XHC_PORTSC2__PIC_WIDTH			2U
+#define XHC_PORTSC2__PIC_RESETVALUE		0x0U
+#define XHC_PORTSC2__PS_L			13U
+#define XHC_PORTSC2__PS_R			10U
+#define XHC_PORTSC2__PS_WIDTH			4U
+#define XHC_PORTSC2__PS_RESETVALUE		0x0U
+#define XHC_PORTSC2__PP				9U
+#define XHC_PORTSC2__PP_L			9U
+#define XHC_PORTSC2__PP_R			9U
+#define XHC_PORTSC2__PP_WIDTH			1U
+#define XHC_PORTSC2__PP_RESETVALUE		0x0U
+#define XHC_PORTSC2__PLS_L			8U
+#define XHC_PORTSC2__PLS_R			5U
+#define XHC_PORTSC2__PLS_WIDTH			4U
+#define XHC_PORTSC2__PLS_RESETVALUE		0x5U
+
+#define XHC_PORTSC2__PRST_L			4U
+#define XHC_PORTSC2__PRST_R			4U
+#define XHC_PORTSC2__PRST_WIDTH			1U
+#define XHC_PORTSC2__PRST_RESETVALUE		0x0U
+#define XHC_PORTSC2__OCA			3U
+#define XHC_PORTSC2__OCA_L			3U
+#define XHC_PORTSC2__OCA_R			3U
+#define XHC_PORTSC2__OCA_WIDTH			1U
+#define XHC_PORTSC2__OCA_RESETVALUE		0x0U
+#define XHC_PORTSC2__reserved			2U
+#define XHC_PORTSC2__reserved_L			2U
+#define XHC_PORTSC2__reserved_R			2U
+#define XHC_PORTSC2__reserved_WIDTH		1U
+#define XHC_PORTSC2__reserved_RESETVALUE	0x0U
+#define XHC_PORTSC2__PED			1U
+#define XHC_PORTSC2__PED_L			1U
+#define XHC_PORTSC2__PED_R			1U
+#define XHC_PORTSC2__PED_WIDTH			1U
+#define XHC_PORTSC2__PED_RESETVALUE		0x0U
+#define XHC_PORTSC2__CCS			0U
+#define XHC_PORTSC2__CCS_L			0U
+#define XHC_PORTSC2__CCS_R			0U
+#define XHC_PORTSC2__CCS_WIDTH			1U
+#define XHC_PORTSC2__CCS_RESETVALUE		0x0U
+#define XHC_PORTSC2__RESERVED_L			29U
+#define XHC_PORTSC2__RESERVED_R			28U
+#define XHC_PORTSC2_WIDTH			32U
+#define XHC_PORTSC2__WIDTH			32U
+#define XHC_PORTSC2_ALL_L			31U
+#define XHC_PORTSC2_ALL_R			0U
+#define XHC_PORTSC2__ALL_L			31U
+#define XHC_PORTSC2__ALL_R			0U
+#define XHC_PORTSC2_DATAMASK			0xcfffffffU
+#define XHC_PORTSC2_RDWRMASK			0x30000000U
+#define XHC_PORTSC2_RESETVALUE			0x000000a0U
+
+#define XHC_PORTPM2_OFFSET			0x434U
+#define XHC_PORTPM2_BASE			0x434U
+#define XHC_PORTPM2__PTC_L			31U
+#define XHC_PORTPM2__PTC_R			28U
+#define XHC_PORTPM2__PTC_WIDTH			4U
+#define XHC_PORTPM2__PTC_RESETVALUE		0x0U
+#define XHC_PORTPM2__reserved_L			27U
+#define XHC_PORTPM2__reserved_R			17U
+#define XHC_PORTPM2__reserved_WIDTH		11U
+#define XHC_PORTPM2__reserved_RESETVALUE	0x0U
+#define XHC_PORTPM2__HLE			16U
+#define XHC_PORTPM2__HLE_L			16U
+#define XHC_PORTPM2__HLE_R			16U
+#define XHC_PORTPM2__HLE_WIDTH			1U
+#define XHC_PORTPM2__HLE_RESETVALUE		0x0U
+#define XHC_PORTPM2__L1DS_L			15U
+#define XHC_PORTPM2__L1DS_R			8U
+#define XHC_PORTPM2__L1DS_WIDTH			8U
+#define XHC_PORTPM2__L1DS_RESETVALUE		0x00U
+#define XHC_PORTPM2__BESL_L			7U
+#define XHC_PORTPM2__BESL_R			4U
+#define XHC_PORTPM2__BESL_WIDTH			4U
+#define XHC_PORTPM2__BESL_RESETVALUE		0x0U
+#define XHC_PORTPM2__RWE			3U
+#define XHC_PORTPM2__RWE_L			3U
+#define XHC_PORTPM2__RWE_R			3U
+#define XHC_PORTPM2__RWE_WIDTH			1U
+#define XHC_PORTPM2__RWE_RESETVALUE		0x0U
+#define XHC_PORTPM2__L1S_L			2U
+#define XHC_PORTPM2__L1S_R			0U
+#define XHC_PORTPM2__L1S_WIDTH			3U
+#define XHC_PORTPM2__L1S_RESETVALUE		0x0U
+#define XHC_PORTPM2_WIDTH			32U
+#define XHC_PORTPM2__WIDTH			32U
+#define XHC_PORTPM2_ALL_L			31U
+#define XHC_PORTPM2_ALL_R			0U
+#define XHC_PORTPM2__ALL_L			31U
+#define XHC_PORTPM2__ALL_R			0U
+#define XHC_PORTPM2_DATAMASK			0xffffffffU
+#define XHC_PORTPM2_RDWRMASK			0x00000000U
+#define XHC_PORTPM2_RESETVALUE			0x00000000U
+
+#define XHC_PORTLC2_OFFSET			0x43cU
+#define XHC_PORTLC2_BASE			0x43cU
+#define XHC_PORTLC2__reserved_L			31U
+#define XHC_PORTLC2__reserved_R			14U
+#define XHC_PORTLC2__reserved_WIDTH		18U
+#define XHC_PORTLC2__reserved_RESETVALUE	0x0U
+#define XHC_PORTLC2__BESLD_L			13U
+#define XHC_PORTLC2__BESLD_R			10U
+#define XHC_PORTLC2__BESLD_WIDTH		4U
+#define XHC_PORTLC2__BESLD_RESETVALUE		0x0U
+#define XHC_PORTLC2__L1T_L			9U
+#define XHC_PORTLC2__L1T_R			2U
+#define XHC_PORTLC2__L1T_WIDTH			8U
+#define XHC_PORTLC2__L1T_RESETVALUE		0x00U
+#define XHC_PORTLC2__HIRDM_L			1U
+#define XHC_PORTLC2__HIRDM_R			0U
+#define XHC_PORTLC2__HIRDM_WIDTH		2U
+#define XHC_PORTLC2__HIRDM_RESETVALUE		0x0U
+#define XHC_PORTLC2_WIDTH			32U
+#define XHC_PORTLC2__WIDTH			32U
+#define XHC_PORTLC2_ALL_L			31U
+#define XHC_PORTLC2_ALL_R			0U
+#define XHC_PORTLC2__ALL_L			31U
+#define XHC_PORTLC2__ALL_R			0U
+#define XHC_PORTLC2_DATAMASK			0xffffffffU
+#define XHC_PORTLC2_RDWRMASK			0x00000000U
+#define XHC_PORTLC2_RESETVALUE			0x00000000U
+
+#define XHC_PORTSC3_OFFSET			0x440U
+#define XHC_PORTSC3_BASE			0x440U
+#define XHC_PORTSC3__WPR			31U
+#define XHC_PORTSC3__WPR_L			31U
+#define XHC_PORTSC3__WPR_R			31U
+#define XHC_PORTSC3__WPR_WIDTH			1U
+#define XHC_PORTSC3__WPR_RESETVALUE		0x0U
+#define XHC_PORTSC3__DNR			30U
+#define XHC_PORTSC3__DNR_L			30U
+#define XHC_PORTSC3__DNR_R			30U
+#define XHC_PORTSC3__DNR_WIDTH			1U
+#define XHC_PORTSC3__DNR_RESETVALUE		0x0U
+#define XHC_PORTSC3__WOE			27U
+#define XHC_PORTSC3__WOE_L			27U
+#define XHC_PORTSC3__WOE_R			27U
+#define XHC_PORTSC3__WOE_WIDTH			1U
+#define XHC_PORTSC3__WOE_RESETVALUE		0x0U
+#define XHC_PORTSC3__WDE			26U
+#define XHC_PORTSC3__WDE_L			26U
+#define XHC_PORTSC3__WDE_R			26U
+#define XHC_PORTSC3__WDE_WIDTH			1U
+#define XHC_PORTSC3__WDE_RESETVALUE		0x0U
+#define XHC_PORTSC3__WCE			25U
+#define XHC_PORTSC3__WCE_L			25U
+#define XHC_PORTSC3__WCE_R			25U
+#define XHC_PORTSC3__WCE_WIDTH			1U
+#define XHC_PORTSC3__WCE_RESETVALUE		0x0U
+#define XHC_PORTSC3__CAS			24U
+#define XHC_PORTSC3__CAS_L			24U
+#define XHC_PORTSC3__CAS_R			24U
+#define XHC_PORTSC3__CAS_WIDTH			1U
+#define XHC_PORTSC3__CAS_RESETVALUE		0x0U
+#define XHC_PORTSC3__CEC			23U
+#define XHC_PORTSC3__CEC_L			23U
+#define XHC_PORTSC3__CEC_R			23U
+#define XHC_PORTSC3__CEC_WIDTH			1U
+#define XHC_PORTSC3__CEC_RESETVALUE		0x0U
+#define XHC_PORTSC3__PLC			22U
+#define XHC_PORTSC3__PLC_L			22U
+#define XHC_PORTSC3__PLC_R			22U
+#define XHC_PORTSC3__PLC_WIDTH			1U
+#define XHC_PORTSC3__PLC_RESETVALUE		0x0U
+#define XHC_PORTSC3__PRC			21U
+#define XHC_PORTSC3__PRC_L			21U
+#define XHC_PORTSC3__PRC_R			21U
+#define XHC_PORTSC3__PRC_WIDTH			1U
+#define XHC_PORTSC3__PRC_RESETVALUE		0x0U
+#define XHC_PORTSC3__OCC			20U
+#define XHC_PORTSC3__OCC_L			20U
+#define XHC_PORTSC3__OCC_R			20U
+#define XHC_PORTSC3__OCC_WIDTH			1U
+#define XHC_PORTSC3__OCC_RESETVALUE		0x0U
+#define XHC_PORTSC3__WRC			19U
+#define XHC_PORTSC3__WRC_L			19U
+#define XHC_PORTSC3__WRC_R			19U
+#define XHC_PORTSC3__WRC_WIDTH			1U
+#define XHC_PORTSC3__WRC_RESETVALUE		0x0U
+#define XHC_PORTSC3__PEC			18U
+#define XHC_PORTSC3__PEC_L			18U
+#define XHC_PORTSC3__PEC_R			18U
+#define XHC_PORTSC3__PEC_WIDTH			1U
+#define XHC_PORTSC3__PEC_RESETVALUE		0x0U
+#define XHC_PORTSC3__CSC			17U
+#define XHC_PORTSC3__CSC_L			17U
+#define XHC_PORTSC3__CSC_R			17U
+#define XHC_PORTSC3__CSC_WIDTH			1U
+#define XHC_PORTSC3__CSC_RESETVALUE		0x0U
+#define XHC_PORTSC3__LWS			16U
+#define XHC_PORTSC3__LWS_L			16U
+#define XHC_PORTSC3__LWS_R			16U
+#define XHC_PORTSC3__LWS_WIDTH			1U
+#define XHC_PORTSC3__LWS_RESETVALUE		0x0U
+#define XHC_PORTSC3__PIC_L			15U
+#define XHC_PORTSC3__PIC_R			14U
+#define XHC_PORTSC3__PIC_WIDTH			2U
+#define XHC_PORTSC3__PIC_RESETVALUE		0x0U
+#define XHC_PORTSC3__PS_L			13U
+#define XHC_PORTSC3__PS_R			10U
+#define XHC_PORTSC3__PS_WIDTH			4U
+#define XHC_PORTSC3__PS_RESETVALUE		0x0U
+#define XHC_PORTSC3__PP				9U
+#define XHC_PORTSC3__PP_L			9U
+#define XHC_PORTSC3__PP_R			9U
+#define XHC_PORTSC3__PP_WIDTH			1U
+#define XHC_PORTSC3__PP_RESETVALUE		0x0U
+#define XHC_PORTSC3__PLS_L			8U
+#define XHC_PORTSC3__PLS_R			5U
+#define XHC_PORTSC3__PLS_WIDTH			4U
+#define XHC_PORTSC3__PLS_RESETVALUE		0x5U
+#define XHC_PORTSC3__PR				4U
+#define XHC_PORTSC3__PR_L			4U
+#define XHC_PORTSC3__PR_R			4U
+#define XHC_PORTSC3__PR_WIDTH			1U
+#define XHC_PORTSC3__PR_RESETVALUE		0x0U
+#define XHC_PORTSC3__OCA			3U
+#define XHC_PORTSC3__OCA_L			3U
+#define XHC_PORTSC3__OCA_R			3U
+#define XHC_PORTSC3__OCA_WIDTH			1U
+#define XHC_PORTSC3__OCA_RESETVALUE		0x0U
+#define XHC_PORTSC3__reserved			2U
+#define XHC_PORTSC3__reserved_L			2U
+#define XHC_PORTSC3__reserved_R			2U
+#define XHC_PORTSC3__reserved_WIDTH		1U
+#define XHC_PORTSC3__reserved_RESETVALUE	0x0U
+#define XHC_PORTSC3__PED			1U
+#define XHC_PORTSC3__PED_L			1U
+#define XHC_PORTSC3__PED_R			1U
+#define XHC_PORTSC3__PED_WIDTH			1U
+#define XHC_PORTSC3__PED_RESETVALUE		0x0U
+#define XHC_PORTSC3__CCS			0U
+#define XHC_PORTSC3__CCS_L			0U
+#define XHC_PORTSC3__CCS_R			0U
+#define XHC_PORTSC3__CCS_WIDTH			1U
+#define XHC_PORTSC3__CCS_RESETVALUE		0x0U
+#define XHC_PORTSC3__RESERVED_L			29U
+#define XHC_PORTSC3__RESERVED_R			28U
+#define XHC_PORTSC3_WIDTH			32U
+#define XHC_PORTSC3__WIDTH			32U
+#define XHC_PORTSC3_ALL_L			31U
+#define XHC_PORTSC3_ALL_R			0U
+#define XHC_PORTSC3__ALL_L			31U
+#define XHC_PORTSC3__ALL_R			0U
+#define XHC_PORTSC3_DATAMASK			0xcfffffffU
+#define XHC_PORTSC3_RDWRMASK			0x30000000U
+#define XHC_PORTSC3_RESETVALUE			0x000000a0U
+
+#define XHC_PORTPM3_OFFSET			0x444U
+#define XHC_PORTPM3_BASE			0x444U
+#define XHC_PORTPM3__PTC_L			31U
+#define XHC_PORTPM3__PTC_R			28U
+#define XHC_PORTPM3__PTC_WIDTH			4U
+#define XHC_PORTPM3__PTC_RESETVALUE		0x0U
+#define XHC_PORTPM3__reserved_L			27U
+#define XHC_PORTPM3__reserved_R			17U
+#define XHC_PORTPM3__reserved_WIDTH		11U
+#define XHC_PORTPM3__reserved_RESETVALUE	0x0U
+#define XHC_PORTPM3__HLE			16U
+#define XHC_PORTPM3__HLE_L			16U
+#define XHC_PORTPM3__HLE_R			16U
+#define XHC_PORTPM3__HLE_WIDTH			1U
+#define XHC_PORTPM3__HLE_RESETVALUE		0x0U
+#define XHC_PORTPM3__L1DS_L			15U
+#define XHC_PORTPM3__L1DS_R			8U
+#define XHC_PORTPM3__L1DS_WIDTH			8U
+#define XHC_PORTPM3__L1DS_RESETVALUE		0x00U
+#define XHC_PORTPM3__BESL_L			7U
+#define XHC_PORTPM3__BESL_R			4U
+#define XHC_PORTPM3__BESL_WIDTH			4U
+#define XHC_PORTPM3__BESL_RESETVALUE		0x0U
+#define XHC_PORTPM3__RWE			3U
+#define XHC_PORTPM3__RWE_L			3U
+#define XHC_PORTPM3__RWE_R			3U
+#define XHC_PORTPM3__RWE_WIDTH			1U
+#define XHC_PORTPM3__RWE_RESETVALUE		0x0U
+#define XHC_PORTPM3__L1S_L			2U
+#define XHC_PORTPM3__L1S_R			0U
+#define XHC_PORTPM3__L1S_WIDTH			3U
+#define XHC_PORTPM3__L1S_RESETVALUE		0x0U
+#define XHC_PORTPM3_WIDTH			32U
+#define XHC_PORTPM3__WIDTH			32U
+#define XHC_PORTPM3_ALL_L			31U
+#define XHC_PORTPM3_ALL_R			0U
+#define XHC_PORTPM3__ALL_L			31U
+#define XHC_PORTPM3__ALL_R			0U
+#define XHC_PORTPM3_DATAMASK			0xffffffffU
+#define XHC_PORTPM3_RDWRMASK			0x00000000U
+#define XHC_PORTPM3_RESETVALUE			0x00000000U
+
+#define XHC_PORTLI3_OFFSET			0x44cU
+#define XHC_PORTLI3_BASE			0x44cU
+#define XHC_PORTLI3__reserved_L			31U
+#define XHC_PORTLI3__reserved_R			0U
+#define XHC_PORTLI3__reserved_WIDTH		32U
+#define XHC_PORTLI3__reserved_RESETVALUE	0x00000000U
+#define XHC_PORTLI3_WIDTH			32U
+#define XHC_PORTLI3__WIDTH			32U
+#define XHC_PORTLI3_ALL_L			31U
+#define XHC_PORTLI3_ALL_R			0U
+#define XHC_PORTLI3__ALL_L			31U
+#define XHC_PORTLI3__ALL_R			0U
+#define XHC_PORTLI3_DATAMASK			0xffffffffU
+#define XHC_PORTLI3_RDWRMASK			0x00000000U
+#define XHC_PORTLI3_RESETVALUE			0x00000000U
+
+#define XHC_MFINDEX_OFFSET			0x4a0U
+#define XHC_MFINDEX_BASE			0x4a0U
+#define XHC_MFINDEX__reserved_L			31U
+#define XHC_MFINDEX__reserved_R			14U
+#define XHC_MFINDEX__reserved_WIDTH		18U
+#define XHC_MFINDEX__reserved_RESETVALUE	0x0U
+#define XHC_MFINDEX__MFI_L			13U
+#define XHC_MFINDEX__MFI_R			0U
+#define XHC_MFINDEX__MFI_WIDTH			14U
+#define XHC_MFINDEX__MFI_RESETVALUE		0x0U
+#define XHC_MFINDEX_WIDTH			32U
+#define XHC_MFINDEX__WIDTH			32U
+#define XHC_MFINDEX_ALL_L			31U
+#define XHC_MFINDEX_ALL_R			0U
+#define XHC_MFINDEX__ALL_L			31U
+#define XHC_MFINDEX__ALL_R			0U
+#define XHC_MFINDEX_DATAMASK			0xffffffffU
+#define XHC_MFINDEX_RDWRMASK			0x00000000U
+#define XHC_MFINDEX_RESETVALUE			0x00000000U
+
+#define XHC_IMAN0_OFFSET			0x4c0U
+#define XHC_IMAN0_BASE				0x4c0U
+#define XHC_IMAN0__reserved_L			31U
+#define XHC_IMAN0__reserved_R			2U
+#define XHC_IMAN0__reserved_WIDTH		30U
+#define XHC_IMAN0__reserved_RESETVALUE		0x0U
+#define XHC_IMAN0__IE				1U
+#define XHC_IMAN0__IE_L				1U
+#define XHC_IMAN0__IE_R				1U
+#define XHC_IMAN0__IE_WIDTH			1U
+#define XHC_IMAN0__IE_RESETVALUE		0x0U
+#define XHC_IMAN0__IP				0U
+#define XHC_IMAN0__IP_L				0U
+#define XHC_IMAN0__IP_R				0U
+#define XHC_IMAN0__IP_WIDTH			1U
+#define XHC_IMAN0__IP_RESETVALUE		0x0U
+#define XHC_IMAN0_WIDTH				32U
+#define XHC_IMAN0__WIDTH			32U
+#define XHC_IMAN0_ALL_L				31U
+#define XHC_IMAN0_ALL_R				0U
+#define XHC_IMAN0__ALL_L			31U
+#define XHC_IMAN0__ALL_R			0U
+#define XHC_IMAN0_DATAMASK			0xffffffffU
+#define XHC_IMAN0_RDWRMASK			0x00000000U
+#define XHC_IMAN0_RESETVALUE			0x00000000U
+
+#define XHC_IMOD0_OFFSET			0x4c4U
+#define XHC_IMOD0_BASE				0x4c4U
+#define XHC_IMOD0__IMODC_L			31U
+#define XHC_IMOD0__IMODC_R			16U
+#define XHC_IMOD0__IMODC_WIDTH			16U
+#define XHC_IMOD0__IMODC_RESETVALUE		0x0000U
+#define XHC_IMOD0__IMODI_L			15U
+#define XHC_IMOD0__IMODI_R			0U
+#define XHC_IMOD0__IMODI_WIDTH			16U
+#define XHC_IMOD0__IMODI_RESETVALUE		0x4000U
+#define XHC_IMOD0_WIDTH				32U
+#define XHC_IMOD0__WIDTH			32U
+#define XHC_IMOD0_ALL_L				31U
+#define XHC_IMOD0_ALL_R				0U
+#define XHC_IMOD0__ALL_L			31U
+#define XHC_IMOD0__ALL_R			0U
+#define XHC_IMOD0_DATAMASK			0xffffffffU
+#define XHC_IMOD0_RDWRMASK			0x00000000U
+#define XHC_IMOD0_RESETVALUE			0x00004000U
+
+#define XHC_ERSTSZ0_OFFSET			0x4c8U
+#define XHC_ERSTSZ0_BASE			0x4c8U
+#define XHC_ERSTSZ0__reserved_L			31U
+#define XHC_ERSTSZ0__reserved_R			16U
+#define XHC_ERSTSZ0__reserved_WIDTH		16U
+#define XHC_ERSTSZ0__reserved_RESETVALUE	0x0000U
+#define XHC_ERSTSZ0__TSZ_L			15U
+#define XHC_ERSTSZ0__TSZ_R			0U
+#define XHC_ERSTSZ0__TSZ_WIDTH			16U
+#define XHC_ERSTSZ0__TSZ_RESETVALUE		0x0000U
+#define XHC_ERSTSZ0_WIDTH			32U
+#define XHC_ERSTSZ0__WIDTH			32U
+#define XHC_ERSTSZ0_ALL_L			31U
+#define XHC_ERSTSZ0_ALL_R			0U
+#define XHC_ERSTSZ0__ALL_L			31U
+#define XHC_ERSTSZ0__ALL_R			0U
+#define XHC_ERSTSZ0_DATAMASK			0xffffffffU
+#define XHC_ERSTSZ0_RDWRMASK			0x00000000U
+#define XHC_ERSTSZ0_RESETVALUE			0x00000000U
+
+#define XHC_ERSTBAL0_OFFSET			0x4d0U
+#define XHC_ERSTBAL0_BASE			0x4d0U
+#define XHC_ERSTBAL0__BAL_L			31U
+#define XHC_ERSTBAL0__BAL_R			4U
+#define XHC_ERSTBAL0__BAL_WIDTH			28U
+#define XHC_ERSTBAL0__BAL_RESETVALUE		0x0000000U
+#define XHC_ERSTBAL0__reserved_L		3U
+#define XHC_ERSTBAL0__reserved_R		0U
+#define XHC_ERSTBAL0__reserved_WIDTH		4U
+#define XHC_ERSTBAL0__reserved_RESETVALUE	0x0U
+#define XHC_ERSTBAL0_WIDTH			32U
+#define XHC_ERSTBAL0__WIDTH			32U
+#define XHC_ERSTBAL0_ALL_L			31U
+#define XHC_ERSTBAL0_ALL_R			0U
+#define XHC_ERSTBAL0__ALL_L			31U
+#define XHC_ERSTBAL0__ALL_R			0U
+#define XHC_ERSTBAL0_DATAMASK			0xffffffffU
+#define XHC_ERSTBAL0_RDWRMASK			0x00000000U
+#define XHC_ERSTBAL0_RESETVALUE			0x00000000U
+
+#define XHC_ERSTBAH0_OFFSET			0x4d4U
+#define XHC_ERSTBAH0_BASE			0x4d4U
+#define XHC_ERSTBAH0__BAH_L			31U
+#define XHC_ERSTBAH0__BAH_R			0U
+#define XHC_ERSTBAH0__BAH_WIDTH			32U
+#define XHC_ERSTBAH0__BAH_RESETVALUE		0x00000000U
+#define XHC_ERSTBAH0_WIDTH			32U
+#define XHC_ERSTBAH0__WIDTH			32U
+#define XHC_ERSTBAH0_ALL_L			31U
+#define XHC_ERSTBAH0_ALL_R			0U
+#define XHC_ERSTBAH0__ALL_L			31U
+#define XHC_ERSTBAH0__ALL_R			0U
+#define XHC_ERSTBAH0_DATAMASK			0xffffffffU
+#define XHC_ERSTBAH0_RDWRMASK			0x00000000U
+#define XHC_ERSTBAH0_RESETVALUE			0x00000000U
+
+#define XHC_ERDPL0_OFFSET			0x4d8U
+#define XHC_ERDPL0_BASE				0x4d8U
+#define XHC_ERDPL0__DPL_L			31U
+#define XHC_ERDPL0__DPL_R			4U
+#define XHC_ERDPL0__DPL_WIDTH			28U
+#define XHC_ERDPL0__DPL_RESETVALUE		0x0000000U
+#define XHC_ERDPL0__EHB				3U
+#define XHC_ERDPL0__EHB_L			3U
+#define XHC_ERDPL0__EHB_R			3U
+#define XHC_ERDPL0__EHB_WIDTH			1U
+#define XHC_ERDPL0__EHB_RESETVALUE		0x0U
+#define XHC_ERDPL0__DESI_L			2U
+#define XHC_ERDPL0__DESI_R			0U
+#define XHC_ERDPL0__DESI_WIDTH			3U
+#define XHC_ERDPL0__DESI_RESETVALUE		0x0U
+#define XHC_ERDPL0_WIDTH			32U
+#define XHC_ERDPL0__WIDTH			32U
+#define XHC_ERDPL0_ALL_L			31U
+#define XHC_ERDPL0_ALL_R			0U
+#define XHC_ERDPL0__ALL_L			31U
+#define XHC_ERDPL0__ALL_R			0U
+#define XHC_ERDPL0_DATAMASK			0xffffffffU
+#define XHC_ERDPL0_RDWRMASK			0x00000000U
+#define XHC_ERDPL0_RESETVALUE			0x00000000U
+
+#define XHC_ERDPH0_OFFSET			0x4dcU
+#define XHC_ERDPH0_BASE				0x4dcU
+#define XHC_ERDPH0__DPH_L			31U
+#define XHC_ERDPH0__DPH_R			0U
+#define XHC_ERDPH0__DPH_WIDTH			32U
+#define XHC_ERDPH0__DPH_RESETVALUE		0x00000000U
+#define XHC_ERDPH0_WIDTH			32U
+#define XHC_ERDPH0__WIDTH			32U
+#define XHC_ERDPH0_ALL_L			31U
+#define XHC_ERDPH0_ALL_R			0U
+#define XHC_ERDPH0__ALL_L			31U
+#define XHC_ERDPH0__ALL_R			0U
+#define XHC_ERDPH0_DATAMASK			0xffffffffU
+#define XHC_ERDPH0_RDWRMASK			0x00000000U
+#define XHC_ERDPH0_RESETVALUE			0x00000000U
+
+#define XHC_IMAN1_OFFSET			0x4e0U
+#define XHC_IMAN1_BASE				0x4e0U
+#define XHC_IMAN1__reserved_L			31U
+#define XHC_IMAN1__reserved_R			2U
+#define XHC_IMAN1__reserved_WIDTH		30U
+#define XHC_IMAN1__reserved_RESETVALUE		0x0U
+#define XHC_IMAN1__IE				1U
+#define XHC_IMAN1__IE_L				1U
+#define XHC_IMAN1__IE_R				1U
+#define XHC_IMAN1__IE_WIDTH			1U
+#define XHC_IMAN1__IE_RESETVALUE		0x0U
+#define XHC_IMAN1__IP				0U
+#define XHC_IMAN1__IP_L				0U
+#define XHC_IMAN1__IP_R				0U
+#define XHC_IMAN1__IP_WIDTH			1U
+#define XHC_IMAN1__IP_RESETVALUE		0x0U
+#define XHC_IMAN1_WIDTH				32U
+#define XHC_IMAN1__WIDTH			32U
+#define XHC_IMAN1_ALL_L				31U
+#define XHC_IMAN1_ALL_R				0U
+#define XHC_IMAN1__ALL_L			31U
+#define XHC_IMAN1__ALL_R			0U
+#define XHC_IMAN1_DATAMASK			0xffffffffU
+#define XHC_IMAN1_RDWRMASK			0x00000000U
+#define XHC_IMAN1_RESETVALUE			0x00000000U
+
+#define XHC_IMOD1_OFFSET			0x4e4U
+#define XHC_IMOD1_BASE				0x4e4U
+#define XHC_IMOD1__IMODC_L			31U
+#define XHC_IMOD1__IMODC_R			16U
+#define XHC_IMOD1__IMODC_WIDTH			16U
+#define XHC_IMOD1__IMODC_RESETVALUE		0x0000U
+#define XHC_IMOD1__IMODI_L			15U
+#define XHC_IMOD1__IMODI_R			0U
+#define XHC_IMOD1__IMODI_WIDTH			16U
+#define XHC_IMOD1__IMODI_RESETVALUE		0x4000U
+#define XHC_IMOD1_WIDTH				32U
+#define XHC_IMOD1__WIDTH			32U
+#define XHC_IMOD1_ALL_L				31U
+#define XHC_IMOD1_ALL_R				0U
+#define XHC_IMOD1__ALL_L			31U
+#define XHC_IMOD1__ALL_R			0U
+#define XHC_IMOD1_DATAMASK			0xffffffffU
+#define XHC_IMOD1_RDWRMASK			0x00000000U
+#define XHC_IMOD1_RESETVALUE			0x00004000U
+
+#define XHC_ERSTSZ1_OFFSET			0x4e8U
+#define XHC_ERSTSZ1_BASE			0x4e8U
+#define XHC_ERSTSZ1__reserved_L			31U
+#define XHC_ERSTSZ1__reserved_R			16U
+#define XHC_ERSTSZ1__reserved_WIDTH		16U
+#define XHC_ERSTSZ1__reserved_RESETVALUE	0x0000U
+#define XHC_ERSTSZ1__TSZ_L			15U
+#define XHC_ERSTSZ1__TSZ_R			0U
+#define XHC_ERSTSZ1__TSZ_WIDTH			16U
+#define XHC_ERSTSZ1__TSZ_RESETVALUE		0x0000U
+#define XHC_ERSTSZ1_WIDTH			32U
+#define XHC_ERSTSZ1__WIDTH			32U
+#define XHC_ERSTSZ1_ALL_L			31U
+#define XHC_ERSTSZ1_ALL_R			0U
+#define XHC_ERSTSZ1__ALL_L			31U
+#define XHC_ERSTSZ1__ALL_R			0U
+#define XHC_ERSTSZ1_DATAMASK			0xffffffffU
+#define XHC_ERSTSZ1_RDWRMASK			0x00000000U
+#define XHC_ERSTSZ1_RESETVALUE			0x00000000U
+
+#define XHC_ERSTBAL1_OFFSET			0x4f0U
+#define XHC_ERSTBAL1_BASE			0x4f0U
+#define XHC_ERSTBAL1__BAL_L			31U
+#define XHC_ERSTBAL1__BAL_R			4U
+#define XHC_ERSTBAL1__BAL_WIDTH			28U
+#define XHC_ERSTBAL1__BAL_RESETVALUE		0x0000000U
+#define XHC_ERSTBAL1__reserved_L		3U
+#define XHC_ERSTBAL1__reserved_R		0U
+#define XHC_ERSTBAL1__reserved_WIDTH		4U
+#define XHC_ERSTBAL1__reserved_RESETVALUE	0x0U
+#define XHC_ERSTBAL1_WIDTH			32U
+#define XHC_ERSTBAL1__WIDTH			32U
+#define XHC_ERSTBAL1_ALL_L			31U
+#define XHC_ERSTBAL1_ALL_R			0U
+#define XHC_ERSTBAL1__ALL_L			31U
+#define XHC_ERSTBAL1__ALL_R			0U
+#define XHC_ERSTBAL1_DATAMASK			0xffffffffU
+#define XHC_ERSTBAL1_RDWRMASK			0x00000000U
+#define XHC_ERSTBAL1_RESETVALUE			0x00000000U
+
+#define XHC_ERSTBAH1_OFFSET			0x4f4U
+#define XHC_ERSTBAH1_BASE			0x4f4U
+#define XHC_ERSTBAH1__BAH_L			31U
+#define XHC_ERSTBAH1__BAH_R			0U
+#define XHC_ERSTBAH1__BAH_WIDTH			32U
+#define XHC_ERSTBAH1__BAH_RESETVALUE		0x00000000U
+#define XHC_ERSTBAH1_WIDTH			32U
+#define XHC_ERSTBAH1__WIDTH			32U
+#define XHC_ERSTBAH1_ALL_L			31U
+#define XHC_ERSTBAH1_ALL_R			0U
+#define XHC_ERSTBAH1__ALL_L			31U
+#define XHC_ERSTBAH1__ALL_R			0U
+#define XHC_ERSTBAH1_DATAMASK			0xffffffffU
+#define XHC_ERSTBAH1_RDWRMASK			0x00000000U
+#define XHC_ERSTBAH1_RESETVALUE			0x00000000U
+
+#define XHC_ERDPL1_OFFSET			0x4f8U
+#define XHC_ERDPL1_BASE				0x4f8U
+#define XHC_ERDPL1__DPL_L			31U
+#define XHC_ERDPL1__DPL_R			4U
+#define XHC_ERDPL1__DPL_WIDTH			28U
+#define XHC_ERDPL1__DPL_RESETVALUE		0x0000000U
+#define XHC_ERDPL1__EHB				3U
+#define XHC_ERDPL1__EHB_L			3U
+#define XHC_ERDPL1__EHB_R			3U
+#define XHC_ERDPL1__EHB_WIDTH			1U
+#define XHC_ERDPL1__EHB_RESETVALUE		0x0U
+#define XHC_ERDPL1__DESI_L			2U
+#define XHC_ERDPL1__DESI_R			0U
+#define XHC_ERDPL1__DESI_WIDTH			3U
+#define XHC_ERDPL1__DESI_RESETVALUE		0x0U
+#define XHC_ERDPL1_WIDTH			32U
+#define XHC_ERDPL1__WIDTH			32U
+#define XHC_ERDPL1_ALL_L			31U
+#define XHC_ERDPL1_ALL_R			0U
+#define XHC_ERDPL1__ALL_L			31U
+#define XHC_ERDPL1__ALL_R			0U
+#define XHC_ERDPL1_DATAMASK			0xffffffffU
+#define XHC_ERDPL1_RDWRMASK			0x00000000U
+#define XHC_ERDPL1_RESETVALUE			0x00000000U
+
+#define XHC_ERDPH1_OFFSET			0x4fcU
+#define XHC_ERDPH1_BASE				0x4fcU
+#define XHC_ERDPH1__DPH_L			31U
+#define XHC_ERDPH1__DPH_R			0U
+#define XHC_ERDPH1__DPH_WIDTH			32U
+#define XHC_ERDPH1__DPH_RESETVALUE		0x00000000U
+#define XHC_ERDPH1_WIDTH			32U
+#define XHC_ERDPH1__WIDTH			32U
+#define XHC_ERDPH1_ALL_L			31U
+#define XHC_ERDPH1_ALL_R			0U
+#define XHC_ERDPH1__ALL_L			31U
+#define XHC_ERDPH1__ALL_R			0U
+#define XHC_ERDPH1_DATAMASK			0xffffffffU
+#define XHC_ERDPH1_RDWRMASK			0x00000000U
+#define XHC_ERDPH1_RESETVALUE			0x00000000U
+
+#define XHC_DBLCMD_OFFSET			0x8c0U
+#define XHC_DBLCMD_BASE				0x8c0U
+#define XHC_DBLCMD__SID_L			31U
+#define XHC_DBLCMD__SID_R			16U
+#define XHC_DBLCMD__SID_WIDTH			16U
+#define XHC_DBLCMD__SID_RESETVALUE		0x0000U
+#define XHC_DBLCMD__reserved_L			15U
+#define XHC_DBLCMD__reserved_R			8U
+#define XHC_DBLCMD__reserved_WIDTH		8U
+#define XHC_DBLCMD__reserved_RESETVALUE		0x00U
+#define XHC_DBLCMD__TGT_L			7U
+#define XHC_DBLCMD__TGT_R			0U
+#define XHC_DBLCMD__TGT_WIDTH			8U
+#define XHC_DBLCMD__TGT_RESETVALUE		0x00U
+#define XHC_DBLCMD_WIDTH			32U
+#define XHC_DBLCMD__WIDTH			32U
+#define XHC_DBLCMD_ALL_L			31U
+#define XHC_DBLCMD_ALL_R			0U
+#define XHC_DBLCMD__ALL_L			31U
+#define XHC_DBLCMD__ALL_R			0U
+#define XHC_DBLCMD_DATAMASK			0xffffffffU
+#define XHC_DBLCMD_RDWRMASK			0x00000000U
+#define XHC_DBLCMD_RESETVALUE			0x00000000U
+
+#define XHC_DBLDVX1_OFFSET			0x8c4U
+#define XHC_DBLDVX1_BASE			0x8c4U
+#define XHC_DBLDVX1__SID_L			31U
+#define XHC_DBLDVX1__SID_R			16U
+#define XHC_DBLDVX1__SID_WIDTH			16U
+#define XHC_DBLDVX1__SID_RESETVALUE		0x0000U
+#define XHC_DBLDVX1__reserved_L			15U
+#define XHC_DBLDVX1__reserved_R			8U
+#define XHC_DBLDVX1__reserved_WIDTH		8U
+#define XHC_DBLDVX1__reserved_RESETVALUE	0x00U
+#define XHC_DBLDVX1__TGT_L			7U
+#define XHC_DBLDVX1__TGT_R			0U
+#define XHC_DBLDVX1__TGT_WIDTH			8U
+#define XHC_DBLDVX1__TGT_RESETVALUE		0x00U
+#define XHC_DBLDVX1_WIDTH			32U
+#define XHC_DBLDVX1__WIDTH			32U
+#define XHC_DBLDVX1_ALL_L			31U
+#define XHC_DBLDVX1_ALL_R			0U
+#define XHC_DBLDVX1__ALL_L			31U
+#define XHC_DBLDVX1__ALL_R			0U
+#define XHC_DBLDVX1_DATAMASK			0xffffffffU
+#define XHC_DBLDVX1_RDWRMASK			0x00000000U
+#define XHC_DBLDVX1_RESETVALUE			0x00000000U
+
+#define XHC_DBLDVX2_OFFSET			0x8c8U
+#define XHC_DBLDVX2_BASE			0x8c8U
+#define XHC_DBLDVX2__SID_L			31U
+#define XHC_DBLDVX2__SID_R			16U
+#define XHC_DBLDVX2__SID_WIDTH			16U
+#define XHC_DBLDVX2__SID_RESETVALUE		0x0000U
+#define XHC_DBLDVX2__reserved_L			15U
+#define XHC_DBLDVX2__reserved_R			8U
+#define XHC_DBLDVX2__reserved_WIDTH		8U
+#define XHC_DBLDVX2__reserved_RESETVALUE	0x00U
+#define XHC_DBLDVX2__TGT_L			7U
+#define XHC_DBLDVX2__TGT_R			0U
+#define XHC_DBLDVX2__TGT_WIDTH			8U
+#define XHC_DBLDVX2__TGT_RESETVALUE		0x00U
+#define XHC_DBLDVX2_WIDTH			32U
+#define XHC_DBLDVX2__WIDTH			32U
+#define XHC_DBLDVX2_ALL_L			31U
+#define XHC_DBLDVX2_ALL_R			0U
+#define XHC_DBLDVX2__ALL_L			31U
+#define XHC_DBLDVX2__ALL_R			0U
+#define XHC_DBLDVX2_DATAMASK			0xffffffffU
+#define XHC_DBLDVX2_RDWRMASK			0x00000000U
+#define XHC_DBLDVX2_RESETVALUE			0x00000000U
+
+#define XHC_DBLDVX3_OFFSET			0x8ccU
+#define XHC_DBLDVX3_BASE			0x8ccU
+#define XHC_DBLDVX3__SID_L			31U
+#define XHC_DBLDVX3__SID_R			16U
+#define XHC_DBLDVX3__SID_WIDTH			16U
+#define XHC_DBLDVX3__SID_RESETVALUE		0x0000U
+#define XHC_DBLDVX3__reserved_L			15U
+#define XHC_DBLDVX3__reserved_R			8U
+#define XHC_DBLDVX3__reserved_WIDTH		8U
+#define XHC_DBLDVX3__reserved_RESETVALUE	0x00U
+#define XHC_DBLDVX3__TGT_L			7U
+#define XHC_DBLDVX3__TGT_R			0U
+#define XHC_DBLDVX3__TGT_WIDTH			8U
+#define XHC_DBLDVX3__TGT_RESETVALUE		0x00U
+#define XHC_DBLDVX3_WIDTH			32U
+#define XHC_DBLDVX3__WIDTH			32U
+#define XHC_DBLDVX3_ALL_L			31U
+#define XHC_DBLDVX3_ALL_R			0U
+#define XHC_DBLDVX3__ALL_L			31U
+#define XHC_DBLDVX3__ALL_R			0U
+#define XHC_DBLDVX3_DATAMASK			0xffffffffU
+#define XHC_DBLDVX3_RDWRMASK			0x00000000U
+#define XHC_DBLDVX3_RESETVALUE			0x00000000U
+
+#define XHC_DBLDVX4_OFFSET			0x8d0U
+#define XHC_DBLDVX4_BASE			0x8d0U
+#define XHC_DBLDVX4__SID_L			31U
+#define XHC_DBLDVX4__SID_R			16U
+#define XHC_DBLDVX4__SID_WIDTH			16U
+#define XHC_DBLDVX4__SID_RESETVALUE		0x0000U
+#define XHC_DBLDVX4__reserved_L			15U
+#define XHC_DBLDVX4__reserved_R			8U
+#define XHC_DBLDVX4__reserved_WIDTH		8U
+#define XHC_DBLDVX4__reserved_RESETVALUE	0x00U
+#define XHC_DBLDVX4__TGT_L			7U
+#define XHC_DBLDVX4__TGT_R			0U
+#define XHC_DBLDVX4__TGT_WIDTH			8U
+#define XHC_DBLDVX4__TGT_RESETVALUE		0x00U
+#define XHC_DBLDVX4_WIDTH			32U
+#define XHC_DBLDVX4__WIDTH			32U
+#define XHC_DBLDVX4_ALL_L			31U
+#define XHC_DBLDVX4_ALL_R			0U
+#define XHC_DBLDVX4__ALL_L			31U
+#define XHC_DBLDVX4__ALL_R			0U
+#define XHC_DBLDVX4_DATAMASK			0xffffffffU
+#define XHC_DBLDVX4_RDWRMASK			0x00000000U
+#define XHC_DBLDVX4_RESETVALUE			0x00000000U
+
+#define XHC_DBLDVX5_OFFSET			0x8d4U
+#define XHC_DBLDVX5_BASE			0x8d4U
+#define XHC_DBLDVX5__SID_L			31U
+#define XHC_DBLDVX5__SID_R			16U
+#define XHC_DBLDVX5__SID_WIDTH			16U
+#define XHC_DBLDVX5__SID_RESETVALUE		0x0000U
+#define XHC_DBLDVX5__reserved_L			15U
+#define XHC_DBLDVX5__reserved_R			8U
+#define XHC_DBLDVX5__reserved_WIDTH		8U
+#define XHC_DBLDVX5__reserved_RESETVALUE	0x00U
+#define XHC_DBLDVX5__TGT_L			7U
+#define XHC_DBLDVX5__TGT_R			0U
+#define XHC_DBLDVX5__TGT_WIDTH			8U
+#define XHC_DBLDVX5__TGT_RESETVALUE		0x00U
+#define XHC_DBLDVX5_WIDTH			32U
+#define XHC_DBLDVX5__WIDTH			32U
+#define XHC_DBLDVX5_ALL_L			31U
+#define XHC_DBLDVX5_ALL_R			0U
+#define XHC_DBLDVX5__ALL_L			31U
+#define XHC_DBLDVX5__ALL_R			0U
+#define XHC_DBLDVX5_DATAMASK			0xffffffffU
+#define XHC_DBLDVX5_RDWRMASK			0x00000000U
+#define XHC_DBLDVX5_RESETVALUE			0x00000000U
+
+#define XHC_DBLDVX6_OFFSET			0x8d8U
+#define XHC_DBLDVX6_BASE			0x8d8U
+#define XHC_DBLDVX6__SID_L			31U
+#define XHC_DBLDVX6__SID_R			16U
+#define XHC_DBLDVX6__SID_WIDTH			16U
+#define XHC_DBLDVX6__SID_RESETVALUE		0x0000U
+#define XHC_DBLDVX6__reserved_L			15U
+#define XHC_DBLDVX6__reserved_R			8U
+#define XHC_DBLDVX6__reserved_WIDTH		8U
+#define XHC_DBLDVX6__reserved_RESETVALUE	0x00U
+#define XHC_DBLDVX6__TGT_L			7U
+#define XHC_DBLDVX6__TGT_R			0U
+#define XHC_DBLDVX6__TGT_WIDTH			8U
+#define XHC_DBLDVX6__TGT_RESETVALUE		0x00U
+#define XHC_DBLDVX6_WIDTH			32U
+#define XHC_DBLDVX6__WIDTH			32U
+#define XHC_DBLDVX6_ALL_L			31U
+#define XHC_DBLDVX6_ALL_R			0U
+#define XHC_DBLDVX6__ALL_L			31U
+#define XHC_DBLDVX6__ALL_R			0U
+#define XHC_DBLDVX6_DATAMASK			0xffffffffU
+#define XHC_DBLDVX6_RDWRMASK			0x00000000U
+#define XHC_DBLDVX6_RESETVALUE			0x00000000U
+
+#define XHC_DBLDVX7_OFFSET			0x8dcU
+#define XHC_DBLDVX7_BASE			0x8dcU
+#define XHC_DBLDVX7__SID_L			31U
+#define XHC_DBLDVX7__SID_R			16U
+#define XHC_DBLDVX7__SID_WIDTH			16U
+#define XHC_DBLDVX7__SID_RESETVALUE		0x0000U
+#define XHC_DBLDVX7__reserved_L			15U
+#define XHC_DBLDVX7__reserved_R			8U
+#define XHC_DBLDVX7__reserved_WIDTH		8U
+#define XHC_DBLDVX7__reserved_RESETVALUE	0x00U
+#define XHC_DBLDVX7__TGT_L			7U
+#define XHC_DBLDVX7__TGT_R			0U
+#define XHC_DBLDVX7__TGT_WIDTH			8U
+#define XHC_DBLDVX7__TGT_RESETVALUE		0x00U
+#define XHC_DBLDVX7_WIDTH			32U
+#define XHC_DBLDVX7__WIDTH			32U
+#define XHC_DBLDVX7_ALL_L			31U
+#define XHC_DBLDVX7_ALL_R			0U
+#define XHC_DBLDVX7__ALL_L			31U
+#define XHC_DBLDVX7__ALL_R			0U
+#define XHC_DBLDVX7_DATAMASK			0xffffffffU
+#define XHC_DBLDVX7_RDWRMASK			0x00000000U
+#define XHC_DBLDVX7_RESETVALUE			0x00000000U
+
+#define XHC_DBLDVX8_OFFSET			0x8e0U
+#define XHC_DBLDVX8_BASE			0x8e0U
+#define XHC_DBLDVX8__SID_L			31U
+#define XHC_DBLDVX8__SID_R			16U
+#define XHC_DBLDVX8__SID_WIDTH			16U
+#define XHC_DBLDVX8__SID_RESETVALUE		0x0000U
+#define XHC_DBLDVX8__reserved_L			15U
+#define XHC_DBLDVX8__reserved_R			8U
+#define XHC_DBLDVX8__reserved_WIDTH		8U
+#define XHC_DBLDVX8__reserved_RESETVALUE	0x00U
+#define XHC_DBLDVX8__TGT_L			7U
+#define XHC_DBLDVX8__TGT_R			0U
+#define XHC_DBLDVX8__TGT_WIDTH			8U
+#define XHC_DBLDVX8__TGT_RESETVALUE		0x00U
+#define XHC_DBLDVX8_WIDTH			32U
+#define XHC_DBLDVX8__WIDTH			32U
+#define XHC_DBLDVX8_ALL_L			31U
+#define XHC_DBLDVX8_ALL_R			0U
+#define XHC_DBLDVX8__ALL_L			31U
+#define XHC_DBLDVX8__ALL_R			0U
+#define XHC_DBLDVX8_DATAMASK			0xffffffffU
+#define XHC_DBLDVX8_RDWRMASK			0x00000000U
+#define XHC_DBLDVX8_RESETVALUE			0x00000000U
+
+#define XHC_DBLDVX9_OFFSET			0x8e4U
+#define XHC_DBLDVX9_BASE			0x8e4U
+#define XHC_DBLDVX9__SID_L			31U
+#define XHC_DBLDVX9__SID_R			16U
+#define XHC_DBLDVX9__SID_WIDTH			16U
+#define XHC_DBLDVX9__SID_RESETVALUE		0x0000U
+#define XHC_DBLDVX9__reserved_L			15U
+#define XHC_DBLDVX9__reserved_R			8U
+#define XHC_DBLDVX9__reserved_WIDTH		8U
+#define XHC_DBLDVX9__reserved_RESETVALUE	0x00U
+#define XHC_DBLDVX9__TGT_L			7U
+#define XHC_DBLDVX9__TGT_R			0U
+#define XHC_DBLDVX9__TGT_WIDTH			8U
+#define XHC_DBLDVX9__TGT_RESETVALUE		0x00U
+#define XHC_DBLDVX9_WIDTH			32U
+#define XHC_DBLDVX9__WIDTH			32U
+#define XHC_DBLDVX9_ALL_L			31U
+#define XHC_DBLDVX9_ALL_R			0U
+#define XHC_DBLDVX9__ALL_L			31U
+#define XHC_DBLDVX9__ALL_R			0U
+#define XHC_DBLDVX9_DATAMASK			0xffffffffU
+#define XHC_DBLDVX9_RDWRMASK			0x00000000U
+#define XHC_DBLDVX9_RESETVALUE			0x00000000U
+
+#define XHC_DBLDVX10_OFFSET			0x8e8U
+#define XHC_DBLDVX10_BASE			0x8e8U
+#define XHC_DBLDVX10__SID_L			31U
+#define XHC_DBLDVX10__SID_R			16U
+#define XHC_DBLDVX10__SID_WIDTH			16U
+#define XHC_DBLDVX10__SID_RESETVALUE		0x0000U
+#define XHC_DBLDVX10__reserved_L		15U
+#define XHC_DBLDVX10__reserved_R		8U
+#define XHC_DBLDVX10__reserved_WIDTH		8U
+#define XHC_DBLDVX10__reserved_RESETVALUE	0x00U
+#define XHC_DBLDVX10__TGT_L			7U
+#define XHC_DBLDVX10__TGT_R			0U
+#define XHC_DBLDVX10__TGT_WIDTH			8U
+#define XHC_DBLDVX10__TGT_RESETVALUE		0x00U
+#define XHC_DBLDVX10_WIDTH			32U
+#define XHC_DBLDVX10__WIDTH			32U
+#define XHC_DBLDVX10_ALL_L			31U
+#define XHC_DBLDVX10_ALL_R			0U
+#define XHC_DBLDVX10__ALL_L			31U
+#define XHC_DBLDVX10__ALL_R			0U
+#define XHC_DBLDVX10_DATAMASK			0xffffffffU
+#define XHC_DBLDVX10_RDWRMASK			0x00000000U
+#define XHC_DBLDVX10_RESETVALUE			0x00000000U
+
+#define XHC_DBLDVX11_OFFSET			0x8ecU
+#define XHC_DBLDVX11_BASE			0x8ecU
+#define XHC_DBLDVX11__SID_L			31U
+#define XHC_DBLDVX11__SID_R			16U
+#define XHC_DBLDVX11__SID_WIDTH			16U
+#define XHC_DBLDVX11__SID_RESETVALUE		0x0000U
+#define XHC_DBLDVX11__reserved_L		15U
+#define XHC_DBLDVX11__reserved_R		8U
+#define XHC_DBLDVX11__reserved_WIDTH		8U
+#define XHC_DBLDVX11__reserved_RESETVALUE	0x00U
+#define XHC_DBLDVX11__TGT_L			7U
+#define XHC_DBLDVX11__TGT_R			0U
+#define XHC_DBLDVX11__TGT_WIDTH			8U
+#define XHC_DBLDVX11__TGT_RESETVALUE		0x00U
+#define XHC_DBLDVX11_WIDTH			32U
+#define XHC_DBLDVX11__WIDTH			32U
+#define XHC_DBLDVX11_ALL_L			31U
+#define XHC_DBLDVX11_ALL_R			0U
+#define XHC_DBLDVX11__ALL_L			31U
+#define XHC_DBLDVX11__ALL_R			0U
+#define XHC_DBLDVX11_DATAMASK			0xffffffffU
+#define XHC_DBLDVX11_RDWRMASK			0x00000000U
+#define XHC_DBLDVX11_RESETVALUE			0x00000000U
+
+#define XHC_DBLDVX12_OFFSET			0x8f0U
+#define XHC_DBLDVX12_BASE			0x8f0U
+#define XHC_DBLDVX12__SID_L			31U
+#define XHC_DBLDVX12__SID_R			16U
+#define XHC_DBLDVX12__SID_WIDTH			16U
+#define XHC_DBLDVX12__SID_RESETVALUE		0x0000U
+#define XHC_DBLDVX12__reserved_L		15U
+#define XHC_DBLDVX12__reserved_R		8U
+#define XHC_DBLDVX12__reserved_WIDTH		8U
+#define XHC_DBLDVX12__reserved_RESETVALUE	0x00U
+#define XHC_DBLDVX12__TGT_L			7U
+#define XHC_DBLDVX12__TGT_R			0U
+#define XHC_DBLDVX12__TGT_WIDTH			8U
+#define XHC_DBLDVX12__TGT_RESETVALUE		0x00U
+#define XHC_DBLDVX12_WIDTH			32U
+#define XHC_DBLDVX12__WIDTH			32U
+#define XHC_DBLDVX12_ALL_L			31U
+#define XHC_DBLDVX12_ALL_R			0U
+#define XHC_DBLDVX12__ALL_L			31U
+#define XHC_DBLDVX12__ALL_R			0U
+#define XHC_DBLDVX12_DATAMASK			0xffffffffU
+#define XHC_DBLDVX12_RDWRMASK			0x00000000U
+#define XHC_DBLDVX12_RESETVALUE			0x00000000U
+
+#define XHC_DBLDVX13_OFFSET			0x8f4U
+#define XHC_DBLDVX13_BASE			0x8f4U
+#define XHC_DBLDVX13__SID_L			31U
+#define XHC_DBLDVX13__SID_R			16U
+#define XHC_DBLDVX13__SID_WIDTH			16U
+#define XHC_DBLDVX13__SID_RESETVALUE		0x0000U
+#define XHC_DBLDVX13__reserved_L		15U
+#define XHC_DBLDVX13__reserved_R		8U
+#define XHC_DBLDVX13__reserved_WIDTH		8U
+#define XHC_DBLDVX13__reserved_RESETVALUE	0x00U
+#define XHC_DBLDVX13__TGT_L			7U
+#define XHC_DBLDVX13__TGT_R			0U
+#define XHC_DBLDVX13__TGT_WIDTH			8U
+#define XHC_DBLDVX13__TGT_RESETVALUE		0x00U
+#define XHC_DBLDVX13_WIDTH			32U
+#define XHC_DBLDVX13__WIDTH			32U
+#define XHC_DBLDVX13_ALL_L			31U
+#define XHC_DBLDVX13_ALL_R			0U
+#define XHC_DBLDVX13__ALL_L			31U
+#define XHC_DBLDVX13__ALL_R			0U
+#define XHC_DBLDVX13_DATAMASK			0xffffffffU
+#define XHC_DBLDVX13_RDWRMASK			0x00000000U
+#define XHC_DBLDVX13_RESETVALUE			0x00000000U
+
+#define XHC_DBLDVX14_OFFSET			0x8f8U
+#define XHC_DBLDVX14_BASE			0x8f8U
+#define XHC_DBLDVX14__SID_L			31U
+#define XHC_DBLDVX14__SID_R			16U
+#define XHC_DBLDVX14__SID_WIDTH			16U
+#define XHC_DBLDVX14__SID_RESETVALUE		0x0000U
+#define XHC_DBLDVX14__reserved_L		15U
+#define XHC_DBLDVX14__reserved_R		8U
+#define XHC_DBLDVX14__reserved_WIDTH		8U
+#define XHC_DBLDVX14__reserved_RESETVALUE	0x00U
+#define XHC_DBLDVX14__TGT_L			7U
+#define XHC_DBLDVX14__TGT_R			0U
+#define XHC_DBLDVX14__TGT_WIDTH			8U
+#define XHC_DBLDVX14__TGT_RESETVALUE		0x00U
+#define XHC_DBLDVX14_WIDTH			32U
+#define XHC_DBLDVX14__WIDTH			32U
+#define XHC_DBLDVX14_ALL_L			31U
+#define XHC_DBLDVX14_ALL_R			0U
+#define XHC_DBLDVX14__ALL_L			31U
+#define XHC_DBLDVX14__ALL_R			0U
+#define XHC_DBLDVX14_DATAMASK			0xffffffffU
+#define XHC_DBLDVX14_RDWRMASK			0x00000000U
+#define XHC_DBLDVX14_RESETVALUE			0x00000000U
+
+#define XHC_DBLDVX15_OFFSET			0x8fcU
+#define XHC_DBLDVX15_BASE			0x8fcU
+#define XHC_DBLDVX15__SID_L			31U
+#define XHC_DBLDVX15__SID_R			16U
+#define XHC_DBLDVX15__SID_WIDTH			16U
+#define XHC_DBLDVX15__SID_RESETVALUE		0x0000U
+#define XHC_DBLDVX15__reserved_L		15U
+#define XHC_DBLDVX15__reserved_R		8U
+#define XHC_DBLDVX15__reserved_WIDTH		8U
+#define XHC_DBLDVX15__reserved_RESETVALUE	0x00U
+#define XHC_DBLDVX15__TGT_L			7U
+#define XHC_DBLDVX15__TGT_R			0U
+#define XHC_DBLDVX15__TGT_WIDTH			8U
+#define XHC_DBLDVX15__TGT_RESETVALUE		0x00U
+#define XHC_DBLDVX15_WIDTH			32U
+#define XHC_DBLDVX15__WIDTH			32U
+#define XHC_DBLDVX15_ALL_L			31U
+#define XHC_DBLDVX15_ALL_R			0U
+#define XHC_DBLDVX15__ALL_L			31U
+#define XHC_DBLDVX15__ALL_R			0U
+#define XHC_DBLDVX15_DATAMASK			0xffffffffU
+#define XHC_DBLDVX15_RDWRMASK			0x00000000U
+#define XHC_DBLDVX15_RESETVALUE			0x00000000U
+
+#define XHC_DBLDVX16_OFFSET			0x900U
+#define XHC_DBLDVX16_BASE			0x900U
+#define XHC_DBLDVX16__SID_L			31U
+#define XHC_DBLDVX16__SID_R			16U
+#define XHC_DBLDVX16__SID_WIDTH			16U
+#define XHC_DBLDVX16__SID_RESETVALUE		0x0000U
+#define XHC_DBLDVX16__reserved_L		15U
+#define XHC_DBLDVX16__reserved_R		8U
+#define XHC_DBLDVX16__reserved_WIDTH		8U
+#define XHC_DBLDVX16__reserved_RESETVALUE	0x00U
+#define XHC_DBLDVX16__TGT_L			7U
+#define XHC_DBLDVX16__TGT_R			0U
+#define XHC_DBLDVX16__TGT_WIDTH			8U
+#define XHC_DBLDVX16__TGT_RESETVALUE		0x00U
+#define XHC_DBLDVX16_WIDTH			32U
+#define XHC_DBLDVX16__WIDTH			32U
+#define XHC_DBLDVX16_ALL_L			31U
+#define XHC_DBLDVX16_ALL_R			0U
+#define XHC_DBLDVX16__ALL_L			31U
+#define XHC_DBLDVX16__ALL_R			0U
+#define XHC_DBLDVX16_DATAMASK			0xffffffffU
+#define XHC_DBLDVX16_RDWRMASK			0x00000000U
+#define XHC_DBLDVX16_RESETVALUE			0x00000000U
+
+#define XHC_ECHSPT3_OFFSET			0x940U
+#define XHC_ECHSPT3_BASE			0x940U
+#define XHC_ECHSPT3__RMAJ_L			31U
+#define XHC_ECHSPT3__RMAJ_R			24U
+#define XHC_ECHSPT3__RMAJ_WIDTH			8U
+#define XHC_ECHSPT3__RMAJ_RESETVALUE		0x00U
+#define XHC_ECHSPT3__RMIN_L			23U
+#define XHC_ECHSPT3__RMIN_R			16U
+#define XHC_ECHSPT3__RMIN_WIDTH			8U
+#define XHC_ECHSPT3__RMIN_RESETVALUE		0x00U
+#define XHC_ECHSPT3__NCP_L			15U
+#define XHC_ECHSPT3__NCP_R			8U
+#define XHC_ECHSPT3__NCP_WIDTH			8U
+#define XHC_ECHSPT3__NCP_RESETVALUE		0x00U
+#define XHC_ECHSPT3__CID_L			7U
+#define XHC_ECHSPT3__CID_R			0U
+#define XHC_ECHSPT3__CID_WIDTH			8U
+#define XHC_ECHSPT3__CID_RESETVALUE		0x02U
+#define XHC_ECHSPT3_WIDTH			32U
+#define XHC_ECHSPT3__WIDTH			32U
+#define XHC_ECHSPT3_ALL_L			31U
+#define XHC_ECHSPT3_ALL_R			0U
+#define XHC_ECHSPT3__ALL_L			31U
+#define XHC_ECHSPT3__ALL_R			0U
+#define XHC_ECHSPT3_DATAMASK			0xffffffffU
+#define XHC_ECHSPT3_RDWRMASK			0x00000000U
+#define XHC_ECHSPT3_RESETVALUE			0x00000002U
+
+#define XHC_PNSTR3_OFFSET			0x944U
+#define XHC_PNSTR3_BASE				0x944U
+#define XHC_PNSTR3__STR_L			31U
+#define XHC_PNSTR3__STR_R			0U
+#define XHC_PNSTR3__STR_WIDTH			32U
+#define XHC_PNSTR3__STR_RESETVALUE		0x20425355U
+#define XHC_PNSTR3_WIDTH			32U
+#define XHC_PNSTR3__WIDTH			32U
+#define XHC_PNSTR3_ALL_L			31U
+#define XHC_PNSTR3_ALL_R			0U
+#define XHC_PNSTR3__ALL_L			31U
+#define XHC_PNSTR3__ALL_R			0U
+#define XHC_PNSTR3_DATAMASK			0xffffffffU
+#define XHC_PNSTR3_RDWRMASK			0x00000000U
+#define XHC_PNSTR3_RESETVALUE			0x20425355U
+
+#define XHC_PSUM3_OFFSET			0x948U
+#define XHC_PSUM3_BASE				0x948U
+#define XHC_PSUM3__PSIC_L			31U
+#define XHC_PSUM3__PSIC_R			28U
+#define XHC_PSUM3__PSIC_WIDTH			4U
+#define XHC_PSUM3__PSIC_RESETVALUE		0x0U
+#define XHC_PSUM3__MHD_L			27U
+#define XHC_PSUM3__MHD_R			25U
+#define XHC_PSUM3__MHD_WIDTH			3U
+#define XHC_PSUM3__MHD_RESETVALUE		0x0U
+#define XHC_PSUM3__BLC				20U
+#define XHC_PSUM3__BLC_L			20U
+#define XHC_PSUM3__BLC_R			20U
+#define XHC_PSUM3__BLC_WIDTH			1U
+#define XHC_PSUM3__BLC_RESETVALUE		0x0U
+#define XHC_PSUM3__HLC				19U
+#define XHC_PSUM3__HLC_L			19U
+#define XHC_PSUM3__HLC_R			19U
+#define XHC_PSUM3__HLC_WIDTH			1U
+#define XHC_PSUM3__HLC_RESETVALUE		0x1U
+#define XHC_PSUM3__IHI				18U
+#define XHC_PSUM3__IHI_L			18U
+#define XHC_PSUM3__IHI_R			18U
+#define XHC_PSUM3__IHI_WIDTH			1U
+#define XHC_PSUM3__IHI_RESETVALUE		0x0U
+#define XHC_PSUM3__HSO				17U
+#define XHC_PSUM3__HSO_L			17U
+#define XHC_PSUM3__HSO_R			17U
+#define XHC_PSUM3__HSO_WIDTH			1U
+#define XHC_PSUM3__HSO_RESETVALUE		0x0U
+#define XHC_PSUM3__reserved			16U
+#define XHC_PSUM3__reserved_L			16U
+#define XHC_PSUM3__reserved_R			16U
+#define XHC_PSUM3__reserved_WIDTH		1U
+#define XHC_PSUM3__reserved_RESETVALUE		0x0U
+#define XHC_PSUM3__CPC_L			15U
+#define XHC_PSUM3__CPC_R			8U
+#define XHC_PSUM3__CPC_WIDTH			8U
+#define XHC_PSUM3__CPC_RESETVALUE		0x00U
+#define XHC_PSUM3__CPO_L			7U
+#define XHC_PSUM3__CPO_R			0U
+#define XHC_PSUM3__CPO_WIDTH			8U
+#define XHC_PSUM3__CPO_RESETVALUE		0x00U
+#define XHC_PSUM3__RESERVED_L			24U
+#define XHC_PSUM3__RESERVED_R			21U
+#define XHC_PSUM3_WIDTH				32U
+#define XHC_PSUM3__WIDTH			32U
+#define XHC_PSUM3_ALL_L				31U
+#define XHC_PSUM3_ALL_R				0U
+#define XHC_PSUM3__ALL_L			31U
+#define XHC_PSUM3__ALL_R			0U
+#define XHC_PSUM3_DATAMASK			0xfe1fffffU
+#define XHC_PSUM3_RDWRMASK			0x01e00000U
+#define XHC_PSUM3_RESETVALUE			0x00080000U
+
+#define XHC_PTSLTYP3_OFFSET			0x94cU
+#define XHC_PTSLTYP3_BASE			0x94cU
+#define XHC_PTSLTYP3__reserved_L		31U
+#define XHC_PTSLTYP3__reserved_R		5U
+#define XHC_PTSLTYP3__reserved_WIDTH		27U
+#define XHC_PTSLTYP3__reserved_RESETVALUE	0x0U
+#define XHC_PTSLTYP3__PST_L			4U
+#define XHC_PTSLTYP3__PST_R			0U
+#define XHC_PTSLTYP3__PST_WIDTH			5U
+#define XHC_PTSLTYP3__PST_RESETVALUE		0x0U
+#define XHC_PTSLTYP3_WIDTH			32U
+#define XHC_PTSLTYP3__WIDTH			32U
+#define XHC_PTSLTYP3_ALL_L			31U
+#define XHC_PTSLTYP3_ALL_R			0U
+#define XHC_PTSLTYP3__ALL_L			31U
+#define XHC_PTSLTYP3__ALL_R			0U
+#define XHC_PTSLTYP3_DATAMASK			0xffffffffU
+#define XHC_PTSLTYP3_RDWRMASK			0x00000000U
+#define XHC_PTSLTYP3_RESETVALUE			0x00000000U
+
+#define XHC_ECHSPT2_OFFSET			0x950U
+#define XHC_ECHSPT2_BASE			0x950U
+#define XHC_ECHSPT2__RMAJ_L			31U
+#define XHC_ECHSPT2__RMAJ_R			24U
+#define XHC_ECHSPT2__RMAJ_WIDTH			8U
+#define XHC_ECHSPT2__RMAJ_RESETVALUE		0x00U
+#define XHC_ECHSPT2__RMIN_L			23U
+#define XHC_ECHSPT2__RMIN_R			16U
+#define XHC_ECHSPT2__RMIN_WIDTH			8U
+#define XHC_ECHSPT2__RMIN_RESETVALUE		0x00U
+#define XHC_ECHSPT2__NCP_L			15U
+#define XHC_ECHSPT2__NCP_R			8U
+#define XHC_ECHSPT2__NCP_WIDTH			8U
+#define XHC_ECHSPT2__NCP_RESETVALUE		0x00U
+#define XHC_ECHSPT2__CID_L			7U
+#define XHC_ECHSPT2__CID_R			0U
+#define XHC_ECHSPT2__CID_WIDTH			8U
+#define XHC_ECHSPT2__CID_RESETVALUE		0x02U
+#define XHC_ECHSPT2_WIDTH			32U
+#define XHC_ECHSPT2__WIDTH			32U
+#define XHC_ECHSPT2_ALL_L			31U
+#define XHC_ECHSPT2_ALL_R			0U
+#define XHC_ECHSPT2__ALL_L			31U
+#define XHC_ECHSPT2__ALL_R			0U
+#define XHC_ECHSPT2_DATAMASK			0xffffffffU
+#define XHC_ECHSPT2_RDWRMASK			0x00000000U
+#define XHC_ECHSPT2_RESETVALUE			0x00000002U
+
+#define XHC_PNSTR2_OFFSET			0x954U
+#define XHC_PNSTR2_BASE				0x954U
+#define XHC_PNSTR2__STR_L			31U
+#define XHC_PNSTR2__STR_R			0U
+#define XHC_PNSTR2__STR_WIDTH			32U
+#define XHC_PNSTR2__STR_RESETVALUE		0x20425355U
+#define XHC_PNSTR2_WIDTH			32U
+#define XHC_PNSTR2__WIDTH			32U
+#define XHC_PNSTR2_ALL_L			31U
+#define XHC_PNSTR2_ALL_R			0U
+#define XHC_PNSTR2__ALL_L			31U
+#define XHC_PNSTR2__ALL_R			0U
+#define XHC_PNSTR2_DATAMASK			0xffffffffU
+#define XHC_PNSTR2_RDWRMASK			0x00000000U
+#define XHC_PNSTR2_RESETVALUE			0x20425355U
+
+#define XHC_PSUM2_OFFSET			0x958U
+#define XHC_PSUM2_BASE				0x958U
+#define XHC_PSUM2__PSIC_L			31U
+#define XHC_PSUM2__PSIC_R			28U
+#define XHC_PSUM2__PSIC_WIDTH			4U
+#define XHC_PSUM2__PSIC_RESETVALUE		0x0U
+#define XHC_PSUM2__MHD_L			27U
+#define XHC_PSUM2__MHD_R			25U
+#define XHC_PSUM2__MHD_WIDTH			3U
+#define XHC_PSUM2__MHD_RESETVALUE		0x0U
+#define XHC_PSUM2__BLC				20U
+#define XHC_PSUM2__BLC_L			20U
+#define XHC_PSUM2__BLC_R			20U
+#define XHC_PSUM2__BLC_WIDTH			1U
+#define XHC_PSUM2__BLC_RESETVALUE		0x0U
+#define XHC_PSUM2__HLC				19U
+#define XHC_PSUM2__HLC_L			19U
+#define XHC_PSUM2__HLC_R			19U
+#define XHC_PSUM2__HLC_WIDTH			1U
+#define XHC_PSUM2__HLC_RESETVALUE		0x1U
+#define XHC_PSUM2__IHI				18U
+#define XHC_PSUM2__IHI_L			18U
+#define XHC_PSUM2__IHI_R			18U
+#define XHC_PSUM2__IHI_WIDTH			1U
+#define XHC_PSUM2__IHI_RESETVALUE		0x0U
+#define XHC_PSUM2__HSO				17U
+#define XHC_PSUM2__HSO_L			17U
+#define XHC_PSUM2__HSO_R			17U
+#define XHC_PSUM2__HSO_WIDTH			1U
+#define XHC_PSUM2__HSO_RESETVALUE		0x0U
+#define XHC_PSUM2__reserved			16U
+#define XHC_PSUM2__reserved_L			16U
+#define XHC_PSUM2__reserved_R			16U
+#define XHC_PSUM2__reserved_WIDTH		1U
+#define XHC_PSUM2__reserved_RESETVALUE		0x0U
+#define XHC_PSUM2__CPC_L			15U
+#define XHC_PSUM2__CPC_R			8U
+#define XHC_PSUM2__CPC_WIDTH			8U
+#define XHC_PSUM2__CPC_RESETVALUE		0x00U
+#define XHC_PSUM2__CPO_L			7U
+#define XHC_PSUM2__CPO_R			0U
+#define XHC_PSUM2__CPO_WIDTH			8U
+#define XHC_PSUM2__CPO_RESETVALUE		0x00U
+#define XHC_PSUM2__RESERVED_L			24U
+#define XHC_PSUM2__RESERVED_R			21U
+#define XHC_PSUM2_WIDTH				32U
+#define XHC_PSUM2__WIDTH			32U
+#define XHC_PSUM2_ALL_L				31U
+#define XHC_PSUM2_ALL_R				0U
+#define XHC_PSUM2__ALL_L			31U
+#define XHC_PSUM2__ALL_R			0U
+#define XHC_PSUM2_DATAMASK			0xfe1fffffU
+#define XHC_PSUM2_RDWRMASK			0x01e00000U
+#define XHC_PSUM2_RESETVALUE			0x00080000U
+
+#define XHC_PTSLTYP2_OFFSET			0x95cU
+#define XHC_PTSLTYP2_BASE			0x95cU
+#define XHC_PTSLTYP2__reserved_L		31U
+#define XHC_PTSLTYP2__reserved_R		5U
+#define XHC_PTSLTYP2__reserved_WIDTH		27U
+#define XHC_PTSLTYP2__reserved_RESETVALUE	0x0U
+#define XHC_PTSLTYP2__PST_L			4U
+#define XHC_PTSLTYP2__PST_R			0U
+#define XHC_PTSLTYP2__PST_WIDTH			5U
+#define XHC_PTSLTYP2__PST_RESETVALUE		0x0U
+#define XHC_PTSLTYP2_WIDTH			32U
+#define XHC_PTSLTYP2__WIDTH			32U
+#define XHC_PTSLTYP2_ALL_L			31U
+#define XHC_PTSLTYP2_ALL_R			0U
+#define XHC_PTSLTYP2__ALL_L			31U
+#define XHC_PTSLTYP2__ALL_R			0U
+#define XHC_PTSLTYP2_DATAMASK			0xffffffffU
+#define XHC_PTSLTYP2_RDWRMASK			0x00000000U
+#define XHC_PTSLTYP2_RESETVALUE			0x00000000U
+
+#define XHC_ECHRSVP_OFFSET			0x960U
+#define XHC_ECHRSVP_BASE			0x960U
+#define XHC_ECHRSVP__reserved_L			31U
+#define XHC_ECHRSVP__reserved_R			16U
+#define XHC_ECHRSVP__reserved_WIDTH		16U
+#define XHC_ECHRSVP__reserved_RESETVALUE	0x0000U
+#define XHC_ECHRSVP__NCP_L			15U
+#define XHC_ECHRSVP__NCP_R			8U
+#define XHC_ECHRSVP__NCP_WIDTH			8U
+#define XHC_ECHRSVP__NCP_RESETVALUE		0x00U
+#define XHC_ECHRSVP__CID_L			7U
+#define XHC_ECHRSVP__CID_R			0U
+#define XHC_ECHRSVP__CID_WIDTH			8U
+#define XHC_ECHRSVP__CID_RESETVALUE		0xffU
+#define XHC_ECHRSVP_WIDTH			32U
+#define XHC_ECHRSVP__WIDTH			32U
+#define XHC_ECHRSVP_ALL_L			31U
+#define XHC_ECHRSVP_ALL_R			0U
+#define XHC_ECHRSVP__ALL_L			31U
+#define XHC_ECHRSVP__ALL_R			0U
+#define XHC_ECHRSVP_DATAMASK			0xffffffffU
+#define XHC_ECHRSVP_RDWRMASK			0x00000000U
+#define XHC_ECHRSVP_RESETVALUE			0x000000ffU
+
+#define XHC_ECHRSVI_OFFSET			0x968U
+#define XHC_ECHRSVI_BASE			0x968U
+#define XHC_ECHRSVI__reserved_L			31U
+#define XHC_ECHRSVI__reserved_R			16U
+#define XHC_ECHRSVI__reserved_WIDTH		16U
+#define XHC_ECHRSVI__reserved_RESETVALUE	0x0000U
+#define XHC_ECHRSVI__NCP_L			15U
+#define XHC_ECHRSVI__NCP_R			8U
+#define XHC_ECHRSVI__NCP_WIDTH			8U
+#define XHC_ECHRSVI__NCP_RESETVALUE		0x00U
+#define XHC_ECHRSVI__CID_L			7U
+#define XHC_ECHRSVI__CID_R			0U
+#define XHC_ECHRSVI__CID_WIDTH			8U
+#define XHC_ECHRSVI__CID_RESETVALUE		0xffU
+#define XHC_ECHRSVI_WIDTH			32U
+#define XHC_ECHRSVI__WIDTH			32U
+#define XHC_ECHRSVI_ALL_L			31U
+#define XHC_ECHRSVI_ALL_R			0U
+#define XHC_ECHRSVI__ALL_L			31U
+#define XHC_ECHRSVI__ALL_R			0U
+#define XHC_ECHRSVI_DATAMASK			0xffffffffU
+#define XHC_ECHRSVI_RDWRMASK			0x00000000U
+#define XHC_ECHRSVI_RESETVALUE			0x000000ffU
+
+#define XHC_ECHRSVM_OFFSET			0xae8U
+#define XHC_ECHRSVM_BASE			0xae8U
+#define XHC_ECHRSVM__reserved_L			31U
+#define XHC_ECHRSVM__reserved_R			16U
+#define XHC_ECHRSVM__reserved_WIDTH		16U
+#define XHC_ECHRSVM__reserved_RESETVALUE	0x0000U
+#define XHC_ECHRSVM__NCP_L			15U
+#define XHC_ECHRSVM__NCP_R			8U
+#define XHC_ECHRSVM__NCP_WIDTH			8U
+#define XHC_ECHRSVM__NCP_RESETVALUE		0x00U
+#define XHC_ECHRSVM__CID_L			7U
+#define XHC_ECHRSVM__CID_R			0U
+#define XHC_ECHRSVM__CID_WIDTH			8U
+#define XHC_ECHRSVM__CID_RESETVALUE		0xffU
+#define XHC_ECHRSVM_WIDTH			32U
+#define XHC_ECHRSVM__WIDTH			32U
+#define XHC_ECHRSVM_ALL_L			31U
+#define XHC_ECHRSVM_ALL_R			0U
+#define XHC_ECHRSVM__ALL_L			31U
+#define XHC_ECHRSVM__ALL_R			0U
+#define XHC_ECHRSVM_DATAMASK			0xffffffffU
+#define XHC_ECHRSVM_RDWRMASK			0x00000000U
+#define XHC_ECHRSVM_RESETVALUE			0x000000ffU
+
+#define XHC_ECHRSVD_OFFSET			0xaf8U
+#define XHC_ECHRSVD_BASE			0xaf8U
+#define XHC_ECHRSVD__reserved_L			31U
+#define XHC_ECHRSVD__reserved_R			16U
+#define XHC_ECHRSVD__reserved_WIDTH		16U
+#define XHC_ECHRSVD__reserved_RESETVALUE	0x0000U
+#define XHC_ECHRSVD__NCP_L			15U
+#define XHC_ECHRSVD__NCP_R			8U
+#define XHC_ECHRSVD__NCP_WIDTH			8U
+#define XHC_ECHRSVD__NCP_RESETVALUE		0x00U
+#define XHC_ECHRSVD__CID_L			7U
+#define XHC_ECHRSVD__CID_R			0U
+#define XHC_ECHRSVD__CID_WIDTH			8U
+#define XHC_ECHRSVD__CID_RESETVALUE		0xffU
+#define XHC_ECHRSVD_WIDTH			32U
+#define XHC_ECHRSVD__WIDTH			32U
+#define XHC_ECHRSVD_ALL_L			31U
+#define XHC_ECHRSVD_ALL_R			0U
+#define XHC_ECHRSVD__ALL_L			31U
+#define XHC_ECHRSVD__ALL_R			0U
+#define XHC_ECHRSVD_DATAMASK			0xffffffffU
+#define XHC_ECHRSVD_RDWRMASK			0x00000000U
+#define XHC_ECHRSVD_RESETVALUE			0x000000ffU
+
+#define XHC_ECHRSVO_OFFSET			0xb38U
+#define XHC_ECHRSVO_BASE			0xb38U
+#define XHC_ECHRSVO__reserved_L			31U
+#define XHC_ECHRSVO__reserved_R			16U
+#define XHC_ECHRSVO__reserved_WIDTH		16U
+#define XHC_ECHRSVO__reserved_RESETVALUE	0x0000U
+#define XHC_ECHRSVO__NCP_L			15U
+#define XHC_ECHRSVO__NCP_R			8U
+#define XHC_ECHRSVO__NCP_WIDTH			8U
+#define XHC_ECHRSVO__NCP_RESETVALUE		0x00U
+#define XHC_ECHRSVO__CID_L			7U
+#define XHC_ECHRSVO__CID_R			0U
+#define XHC_ECHRSVO__CID_WIDTH			8U
+#define XHC_ECHRSVO__CID_RESETVALUE		0xffU
+#define XHC_ECHRSVO_WIDTH			32U
+#define XHC_ECHRSVO__WIDTH			32U
+#define XHC_ECHRSVO_ALL_L			31U
+#define XHC_ECHRSVO_ALL_R			0U
+#define XHC_ECHRSVO__ALL_L			31U
+#define XHC_ECHRSVO__ALL_R			0U
+#define XHC_ECHRSVO_DATAMASK			0xffffffffU
+#define XHC_ECHRSVO_RDWRMASK			0x00000000U
+#define XHC_ECHRSVO_RESETVALUE			0x000000ffU
+
+#define XHC_ECHCTT_OFFSET			0xbf0U
+#define XHC_ECHCTT_BASE				0xbf0U
+#define XHC_ECHCTT__reserved_L			31U
+#define XHC_ECHCTT__reserved_R			16U
+#define XHC_ECHCTT__reserved_WIDTH		16U
+#define XHC_ECHCTT__reserved_RESETVALUE		0x0000U
+#define XHC_ECHCTT__NCP_L			15U
+#define XHC_ECHCTT__NCP_R			8U
+#define XHC_ECHCTT__NCP_WIDTH			8U
+#define XHC_ECHCTT__NCP_RESETVALUE		0x04U
+#define XHC_ECHCTT__CID_L			7U
+#define XHC_ECHCTT__CID_R			0U
+#define XHC_ECHCTT__CID_WIDTH			8U
+#define XHC_ECHCTT__CID_RESETVALUE		0xe0U
+#define XHC_ECHCTT_WIDTH			32U
+#define XHC_ECHCTT__WIDTH			32U
+#define XHC_ECHCTT_ALL_L			31U
+#define XHC_ECHCTT_ALL_R			0U
+#define XHC_ECHCTT__ALL_L			31U
+#define XHC_ECHCTT__ALL_R			0U
+#define XHC_ECHCTT_DATAMASK			0xffffffffU
+#define XHC_ECHCTT_RDWRMASK			0x00000000U
+#define XHC_ECHCTT_RESETVALUE			0x000004e0U
+
+#define XHC_CTTMTS0_OFFSET			0xbf8U
+#define XHC_CTTMTS0_BASE			0xbf8U
+#define XHC_CTTMTS0__DCM			31U
+#define XHC_CTTMTS0__DCM_L			31U
+#define XHC_CTTMTS0__DCM_R			31U
+#define XHC_CTTMTS0__DCM_WIDTH			1U
+#define XHC_CTTMTS0__DCM_RESETVALUE		0x0U
+#define XHC_CTTMTS0__reserved_L			30U
+#define XHC_CTTMTS0__reserved_R			10U
+#define XHC_CTTMTS0__reserved_WIDTH		21U
+#define XHC_CTTMTS0__reserved_RESETVALUE	0x0U
+#define XHC_CTTMTS0__SLA_L			9U
+#define XHC_CTTMTS0__SLA_R			0U
+#define XHC_CTTMTS0__SLA_WIDTH			10U
+#define XHC_CTTMTS0__SLA_RESETVALUE		0x0U
+#define XHC_CTTMTS0_WIDTH			32U
+#define XHC_CTTMTS0__WIDTH			32U
+#define XHC_CTTMTS0_ALL_L			31U
+#define XHC_CTTMTS0_ALL_R			0U
+#define XHC_CTTMTS0__ALL_L			31U
+#define XHC_CTTMTS0__ALL_R			0U
+#define XHC_CTTMTS0_DATAMASK			0xffffffffU
+#define XHC_CTTMTS0_RDWRMASK			0x00000000U
+#define XHC_CTTMTS0_RESETVALUE			0x00000000U
+
+#define XHC_CTTMTS1_OFFSET			0xbfcU
+#define XHC_CTTMTS1_BASE			0xbfcU
+#define XHC_CTTMTS1__TXF_L			25U
+#define XHC_CTTMTS1__TXF_R			16U
+#define XHC_CTTMTS1__TXF_WIDTH			10U
+#define XHC_CTTMTS1__TXF_RESETVALUE		0x0U
+#define XHC_CTTMTS1__reserved_L			15U
+#define XHC_CTTMTS1__reserved_R			10U
+#define XHC_CTTMTS1__reserved_WIDTH		6U
+#define XHC_CTTMTS1__reserved_RESETVALUE	0x0U
+#define XHC_CTTMTS1__RXF_L			9U
+#define XHC_CTTMTS1__RXF_R			0U
+#define XHC_CTTMTS1__RXF_WIDTH			10U
+#define XHC_CTTMTS1__RXF_RESETVALUE		0x0U
+#define XHC_CTTMTS1__RESERVED_L			31U
+#define XHC_CTTMTS1__RESERVED_R			26U
+#define XHC_CTTMTS1_WIDTH			26U
+#define XHC_CTTMTS1__WIDTH			26U
+#define XHC_CTTMTS1_ALL_L			25U
+#define XHC_CTTMTS1_ALL_R			0U
+#define XHC_CTTMTS1__ALL_L			25U
+#define XHC_CTTMTS1__ALL_R			0U
+#define XHC_CTTMTS1_DATAMASK			0x03ffffffU
+#define XHC_CTTMTS1_RDWRMASK			0xfc000000U
+#define XHC_CTTMTS1_RESETVALUE			0x0000000U
+
+#define XHC_ECHBIU_OFFSET			0xc00U
+#define XHC_ECHBIU_BASE				0xc00U
+#define XHC_ECHBIU__CLK_L			31U
+#define XHC_ECHBIU__CLK_R			21U
+#define XHC_ECHBIU__CLK_WIDTH			11U
+#define XHC_ECHBIU__CLK_RESETVALUE		0x0U
+#define XHC_ECHBIU__reserved_L			20U
+#define XHC_ECHBIU__reserved_R			19U
+#define XHC_ECHBIU__reserved_WIDTH		2U
+#define XHC_ECHBIU__reserved_RESETVALUE		0x0U
+#define XHC_ECHBIU__WID_L			18U
+#define XHC_ECHBIU__WID_R			16U
+#define XHC_ECHBIU__WID_WIDTH			3U
+#define XHC_ECHBIU__WID_RESETVALUE		0x0U
+#define XHC_ECHBIU__NCP_L			15U
+#define XHC_ECHBIU__NCP_R			8U
+#define XHC_ECHBIU__NCP_WIDTH			8U
+#define XHC_ECHBIU__NCP_RESETVALUE		0x08U
+#define XHC_ECHBIU__CID_L			7U
+#define XHC_ECHBIU__CID_R			0U
+#define XHC_ECHBIU__CID_WIDTH			8U
+#define XHC_ECHBIU__CID_RESETVALUE		0xc0U
+#define XHC_ECHBIU_WIDTH			32U
+#define XHC_ECHBIU__WIDTH			32U
+#define XHC_ECHBIU_ALL_L			31U
+#define XHC_ECHBIU_ALL_R			0U
+#define XHC_ECHBIU__ALL_L			31U
+#define XHC_ECHBIU__ALL_R			0U
+#define XHC_ECHBIU_DATAMASK			0xffffffffU
+#define XHC_ECHBIU_RDWRMASK			0x00000000U
+#define XHC_ECHBIU_RESETVALUE			0x000008c0U
+
+#define XHC_BIUSPC_OFFSET			0xc04U
+#define XHC_BIUSPC_BASE				0xc04U
+#define XHC_BIUSPC__MAJ_L			31U
+#define XHC_BIUSPC__MAJ_R			28U
+#define XHC_BIUSPC__MAJ_WIDTH			4U
+#define XHC_BIUSPC__MAJ_RESETVALUE		0x0U
+#define XHC_BIUSPC__MIN_L			27U
+#define XHC_BIUSPC__MIN_R			24U
+#define XHC_BIUSPC__MIN_WIDTH			4U
+#define XHC_BIUSPC__MIN_RESETVALUE		0x0U
+#define XHC_BIUSPC__RLS_L			23U
+#define XHC_BIUSPC__RLS_R			20U
+#define XHC_BIUSPC__RLS_WIDTH			4U
+#define XHC_BIUSPC__RLS_RESETVALUE		0x0U
+#define XHC_BIUSPC__reserved_L			19U
+#define XHC_BIUSPC__reserved_R			4U
+#define XHC_BIUSPC__reserved_WIDTH		16U
+#define XHC_BIUSPC__reserved_RESETVALUE		0x0000U
+#define XHC_BIUSPC__SPI_L			3U
+#define XHC_BIUSPC__SPI_R			2U
+#define XHC_BIUSPC__SPI_WIDTH			2U
+#define XHC_BIUSPC__SPI_RESETVALUE		0x3U
+#define XHC_BIUSPC__TYP_L			1U
+#define XHC_BIUSPC__TYP_R			0U
+#define XHC_BIUSPC__TYP_WIDTH			2U
+#define XHC_BIUSPC__TYP_RESETVALUE		0x0U
+#define XHC_BIUSPC_WIDTH			32U
+#define XHC_BIUSPC__WIDTH			32U
+#define XHC_BIUSPC_ALL_L			31U
+#define XHC_BIUSPC_ALL_R			0U
+#define XHC_BIUSPC__ALL_L			31U
+#define XHC_BIUSPC__ALL_R			0U
+#define XHC_BIUSPC_DATAMASK			0xffffffffU
+#define XHC_BIUSPC_RDWRMASK			0x00000000U
+#define XHC_BIUSPC_RESETVALUE			0x0000000cU
+
+#define XHC_AXIWRA_OFFSET			0xc08U
+#define XHC_AXIWRA_BASE				0xc08U
+#define XHC_AXIWRA__WTS_L			31U
+#define XHC_AXIWRA__WTS_R			28U
+#define XHC_AXIWRA__WTS_WIDTH			4U
+#define XHC_AXIWRA__WTS_RESETVALUE		0x2U
+#define XHC_AXIWRA__WUA_L			24U
+#define XHC_AXIWRA__WUA_R			16U
+#define XHC_AXIWRA__WUA_WIDTH			9U
+#define XHC_AXIWRA__WUA_RESETVALUE		0x0U
+#define XHC_AXIWRA__reserved_L			15U
+#define XHC_AXIWRA__reserved_R			10U
+#define XHC_AXIWRA__reserved_WIDTH		6U
+#define XHC_AXIWRA__reserved_RESETVALUE		0x0U
+#define XHC_AXIWRA__BYP				9U
+#define XHC_AXIWRA__BYP_L			9U
+#define XHC_AXIWRA__BYP_R			9U
+#define XHC_AXIWRA__BYP_WIDTH			1U
+#define XHC_AXIWRA__BYP_RESETVALUE		0x0U
+#define XHC_AXIWRA__WSA_L			8U
+#define XHC_AXIWRA__WSA_R			0U
+#define XHC_AXIWRA__WSA_WIDTH			9U
+#define XHC_AXIWRA__WSA_RESETVALUE		0x0U
+#define XHC_AXIWRA__RESERVED_L			27U
+#define XHC_AXIWRA__RESERVED_R			25U
+#define XHC_AXIWRA_WIDTH			32U
+#define XHC_AXIWRA__WIDTH			32U
+#define XHC_AXIWRA_ALL_L			31U
+#define XHC_AXIWRA_ALL_R			0U
+#define XHC_AXIWRA__ALL_L			31U
+#define XHC_AXIWRA__ALL_R			0U
+#define XHC_AXIWRA_DATAMASK			0xf1ffffffU
+#define XHC_AXIWRA_RDWRMASK			0x0e000000U
+#define XHC_AXIWRA_RESETVALUE			0x20000000U
+
+#define XHC_AXIRDA_OFFSET			0xc0cU
+#define XHC_AXIRDA_BASE				0xc0cU
+#define XHC_AXIRDA__RTS_L			31U
+#define XHC_AXIRDA__RTS_R			28U
+#define XHC_AXIRDA__RTS_WIDTH			4U
+#define XHC_AXIRDA__RTS_RESETVALUE		0x2U
+#define XHC_AXIRDA__RFPC			27U
+#define XHC_AXIRDA__RFPC_L			27U
+#define XHC_AXIRDA__RFPC_R			27U
+#define XHC_AXIRDA__RFPC_WIDTH			1U
+#define XHC_AXIRDA__RFPC_RESETVALUE		0x0U
+#define XHC_AXIRDA__RUA_L			24U
+#define XHC_AXIRDA__RUA_R			16U
+#define XHC_AXIRDA__RUA_WIDTH			9U
+#define XHC_AXIRDA__RUA_RESETVALUE		0x0U
+#define XHC_AXIRDA__reserved_L			15U
+#define XHC_AXIRDA__reserved_R			9U
+#define XHC_AXIRDA__reserved_WIDTH		7U
+#define XHC_AXIRDA__reserved_RESETVALUE		0x0U
+#define XHC_AXIRDA__RSA_L			8U
+#define XHC_AXIRDA__RSA_R			0U
+#define XHC_AXIRDA__RSA_WIDTH			9U
+#define XHC_AXIRDA__RSA_RESETVALUE		0x0U
+#define XHC_AXIRDA__RESERVED_L			26U
+#define XHC_AXIRDA__RESERVED_R			25U
+#define XHC_AXIRDA_WIDTH			32U
+#define XHC_AXIRDA__WIDTH			32U
+#define XHC_AXIRDA_ALL_L			31U
+#define XHC_AXIRDA_ALL_R			0U
+#define XHC_AXIRDA__ALL_L			31U
+#define XHC_AXIRDA__ALL_R			0U
+#define XHC_AXIRDA_DATAMASK			0xf9ffffffU
+#define XHC_AXIRDA_RDWRMASK			0x06000000U
+#define XHC_AXIRDA_RESETVALUE			0x20000000U
+
+#define XHC_AXILPM_OFFSET			0xc10U
+#define XHC_AXILPM_BASE				0xc10U
+#define XHC_AXILPM__ENB				31U
+#define XHC_AXILPM__ENB_L			31U
+#define XHC_AXILPM__ENB_R			31U
+#define XHC_AXILPM__ENB_WIDTH			1U
+#define XHC_AXILPM__ENB_RESETVALUE		0x0U
+#define XHC_AXILPM__reserved_L			30U
+#define XHC_AXILPM__reserved_R			3U
+#define XHC_AXILPM__reserved_WIDTH		28U
+#define XHC_AXILPM__reserved_RESETVALUE		0x0000000U
+#define XHC_AXILPM__ITT_L			2U
+#define XHC_AXILPM__ITT_R			0U
+#define XHC_AXILPM__ITT_WIDTH			3U
+#define XHC_AXILPM__ITT_RESETVALUE		0x0U
+#define XHC_AXILPM_WIDTH			32U
+#define XHC_AXILPM__WIDTH			32U
+#define XHC_AXILPM_ALL_L			31U
+#define XHC_AXILPM_ALL_R			0U
+#define XHC_AXILPM__ALL_L			31U
+#define XHC_AXILPM__ALL_R			0U
+#define XHC_AXILPM_DATAMASK			0xffffffffU
+#define XHC_AXILPM_RDWRMASK			0x00000000U
+#define XHC_AXILPM_RESETVALUE			0x00000000U
+
+#define XHC_AXIQOS_OFFSET			0xc14U
+#define XHC_AXIQOS_BASE				0xc14U
+#define XHC_AXIQOS__WQOS3_L			31U
+#define XHC_AXIQOS__WQOS3_R			28U
+#define XHC_AXIQOS__WQOS3_WIDTH			4U
+#define XHC_AXIQOS__WQOS3_RESETVALUE		0x0U
+#define XHC_AXIQOS__WQOS2_L			27U
+#define XHC_AXIQOS__WQOS2_R			24U
+#define XHC_AXIQOS__WQOS2_WIDTH			4U
+#define XHC_AXIQOS__WQOS2_RESETVALUE		0x0U
+#define XHC_AXIQOS__WQOS1_L			23U
+#define XHC_AXIQOS__WQOS1_R			20U
+#define XHC_AXIQOS__WQOS1_WIDTH			4U
+#define XHC_AXIQOS__WQOS1_RESETVALUE		0x0U
+#define XHC_AXIQOS__WQOS0_L			19U
+#define XHC_AXIQOS__WQOS0_R			16U
+#define XHC_AXIQOS__WQOS0_WIDTH			4U
+#define XHC_AXIQOS__WQOS0_RESETVALUE		0x0U
+#define XHC_AXIQOS__RQOS3_L			15U
+#define XHC_AXIQOS__RQOS3_R			12U
+#define XHC_AXIQOS__RQOS3_WIDTH			4U
+#define XHC_AXIQOS__RQOS3_RESETVALUE		0x0U
+#define XHC_AXIQOS__RQOS2_L			11U
+#define XHC_AXIQOS__RQOS2_R			8U
+#define XHC_AXIQOS__RQOS2_WIDTH			4U
+#define XHC_AXIQOS__RQOS2_RESETVALUE		0x0U
+#define XHC_AXIQOS__RQOS1_L			7U
+#define XHC_AXIQOS__RQOS1_R			4U
+#define XHC_AXIQOS__RQOS1_WIDTH			4U
+#define XHC_AXIQOS__RQOS1_RESETVALUE		0x0U
+#define XHC_AXIQOS__RQOS0_L			3U
+#define XHC_AXIQOS__RQOS0_R			0U
+#define XHC_AXIQOS__RQOS0_WIDTH			4U
+#define XHC_AXIQOS__RQOS0_RESETVALUE		0x0U
+#define XHC_AXIQOS_WIDTH			32U
+#define XHC_AXIQOS__WIDTH			32U
+#define XHC_AXIQOS_ALL_L			31U
+#define XHC_AXIQOS_ALL_R			0U
+#define XHC_AXIQOS__ALL_L			31U
+#define XHC_AXIQOS__ALL_R			0U
+#define XHC_AXIQOS_DATAMASK			0xffffffffU
+#define XHC_AXIQOS_RDWRMASK			0x00000000U
+#define XHC_AXIQOS_RESETVALUE			0x00000000U
+
+#define XHC_ECHCSR_OFFSET			0xc20U
+#define XHC_ECHCSR_BASE				0xc20U
+#define XHC_ECHCSR__CLK_L			31U
+#define XHC_ECHCSR__CLK_R			21U
+#define XHC_ECHCSR__CLK_WIDTH			11U
+#define XHC_ECHCSR__CLK_RESETVALUE		0x0U
+#define XHC_ECHCSR__reserved_L			20U
+#define XHC_ECHCSR__reserved_R			19U
+#define XHC_ECHCSR__reserved_WIDTH		2U
+#define XHC_ECHCSR__reserved_RESETVALUE		0x0U
+#define XHC_ECHCSR__WID_L			18U
+#define XHC_ECHCSR__WID_R			16U
+#define XHC_ECHCSR__WID_WIDTH			3U
+#define XHC_ECHCSR__WID_RESETVALUE		0x0U
+#define XHC_ECHCSR__NCP_L			15U
+#define XHC_ECHCSR__NCP_R			8U
+#define XHC_ECHCSR__NCP_WIDTH			8U
+#define XHC_ECHCSR__NCP_RESETVALUE		0x04U
+#define XHC_ECHCSR__CID_L			7U
+#define XHC_ECHCSR__CID_R			0U
+#define XHC_ECHCSR__CID_WIDTH			8U
+#define XHC_ECHCSR__CID_RESETVALUE		0xc1U
+#define XHC_ECHCSR_WIDTH			32U
+#define XHC_ECHCSR__WIDTH			32U
+#define XHC_ECHCSR_ALL_L			31U
+#define XHC_ECHCSR_ALL_R			0U
+#define XHC_ECHCSR__ALL_L			31U
+#define XHC_ECHCSR__ALL_R			0U
+#define XHC_ECHCSR_DATAMASK			0xffffffffU
+#define XHC_ECHCSR_RDWRMASK			0x00000000U
+#define XHC_ECHCSR_RESETVALUE			0x000004c1U
+
+#define XHC_CSRSPC_OFFSET			0xc24U
+#define XHC_CSRSPC_BASE				0xc24U
+#define XHC_CSRSPC__MAJ_L			31U
+#define XHC_CSRSPC__MAJ_R			28U
+#define XHC_CSRSPC__MAJ_WIDTH			4U
+#define XHC_CSRSPC__MAJ_RESETVALUE		0x0U
+#define XHC_CSRSPC__MIN_L			27U
+#define XHC_CSRSPC__MIN_R			24U
+#define XHC_CSRSPC__MIN_WIDTH			4U
+#define XHC_CSRSPC__MIN_RESETVALUE		0x0U
+#define XHC_CSRSPC__RLS_L			23U
+#define XHC_CSRSPC__RLS_R			20U
+#define XHC_CSRSPC__RLS_WIDTH			4U
+#define XHC_CSRSPC__RLS_RESETVALUE		0x0U
+#define XHC_CSRSPC__reserved_L			19U
+#define XHC_CSRSPC__reserved_R			3U
+#define XHC_CSRSPC__reserved_WIDTH		17U
+#define XHC_CSRSPC__reserved_RESETVALUE		0x0U
+#define XHC_CSRSPC__ASP				2U
+#define XHC_CSRSPC__ASP_L			2U
+#define XHC_CSRSPC__ASP_R			2U
+#define XHC_CSRSPC__ASP_WIDTH			1U
+#define XHC_CSRSPC__ASP_RESETVALUE		0x0U
+#define XHC_CSRSPC__TYP_L			1U
+#define XHC_CSRSPC__TYP_R			0U
+#define XHC_CSRSPC__TYP_WIDTH			2U
+#define XHC_CSRSPC__TYP_RESETVALUE		0x0U
+#define XHC_CSRSPC_WIDTH			32U
+#define XHC_CSRSPC__WIDTH			32U
+#define XHC_CSRSPC_ALL_L			31U
+#define XHC_CSRSPC_ALL_R			0U
+#define XHC_CSRSPC__ALL_L			31U
+#define XHC_CSRSPC__ALL_R			0U
+#define XHC_CSRSPC_DATAMASK			0xffffffffU
+#define XHC_CSRSPC_RDWRMASK			0x00000000U
+#define XHC_CSRSPC_RESETVALUE			0x00000000U
+
+#define XHC_ECHAIU_OFFSET			0xc30U
+#define XHC_ECHAIU_BASE				0xc30U
+#define XHC_ECHAIU__DMA_L			31U
+#define XHC_ECHAIU__DMA_R			30U
+#define XHC_ECHAIU__DMA_WIDTH			2U
+#define XHC_ECHAIU__DMA_RESETVALUE		0x1U
+#define XHC_ECHAIU__PBRS_L			29U
+#define XHC_ECHAIU__PBRS_R			28U
+#define XHC_ECHAIU__PBRS_WIDTH			2U
+#define XHC_ECHAIU__PBRS_RESETVALUE		0x0U
+#define XHC_ECHAIU__PBR2_L			27U
+#define XHC_ECHAIU__PBR2_R			26U
+#define XHC_ECHAIU__PBR2_WIDTH			2U
+#define XHC_ECHAIU__PBR2_RESETVALUE		0x0U
+#define XHC_ECHAIU__SCHS_L			25U
+#define XHC_ECHAIU__SCHS_R			24U
+#define XHC_ECHAIU__SCHS_WIDTH			2U
+#define XHC_ECHAIU__SCHS_RESETVALUE		0x0U
+#define XHC_ECHAIU__SCH2_L			23U
+#define XHC_ECHAIU__SCH2_R			22U
+#define XHC_ECHAIU__SCH2_WIDTH			2U
+#define XHC_ECHAIU__SCH2_RESETVALUE		0x0U
+#define XHC_ECHAIU__CHMS_L			21U
+#define XHC_ECHAIU__CHMS_R			20U
+#define XHC_ECHAIU__CHMS_WIDTH			2U
+#define XHC_ECHAIU__CHMS_RESETVALUE		0x3U
+#define XHC_ECHAIU__CHM2_L			19U
+#define XHC_ECHAIU__CHM2_R			18U
+#define XHC_ECHAIU__CHM2_WIDTH			2U
+#define XHC_ECHAIU__CHM2_RESETVALUE		0x0U
+#define XHC_ECHAIU__reserved_L			17U
+#define XHC_ECHAIU__reserved_R			16U
+#define XHC_ECHAIU__reserved_WIDTH		2U
+#define XHC_ECHAIU__reserved_RESETVALUE		0x0U
+#define XHC_ECHAIU__NCP_L			15U
+#define XHC_ECHAIU__NCP_R			8U
+#define XHC_ECHAIU__NCP_WIDTH			8U
+#define XHC_ECHAIU__NCP_RESETVALUE		0x04U
+#define XHC_ECHAIU__CID_L			7U
+#define XHC_ECHAIU__CID_R			0U
+#define XHC_ECHAIU__CID_WIDTH			8U
+#define XHC_ECHAIU__CID_RESETVALUE		0xc2U
+#define XHC_ECHAIU_WIDTH			32U
+#define XHC_ECHAIU__WIDTH			32U
+#define XHC_ECHAIU_ALL_L			31U
+#define XHC_ECHAIU_ALL_R			0U
+#define XHC_ECHAIU__ALL_L			31U
+#define XHC_ECHAIU__ALL_R			0U
+#define XHC_ECHAIU_DATAMASK			0xffffffffU
+#define XHC_ECHAIU_RDWRMASK			0x00000000U
+#define XHC_ECHAIU_RESETVALUE			0x403004c2U
+
+#define XHC_AIUDMA_OFFSET			0xc34U
+#define XHC_AIUDMA_BASE				0xc34U
+#define XHC_AIUDMA__WRMB_L			31U
+#define XHC_AIUDMA__WRMB_R			28U
+#define XHC_AIUDMA__WRMB_WIDTH			4U
+#define XHC_AIUDMA__WRMB_RESETVALUE		0x0U
+#define XHC_AIUDMA__WRD_L			27U
+#define XHC_AIUDMA__WRD_R			26U
+#define XHC_AIUDMA__WRD_WIDTH			2U
+#define XHC_AIUDMA__WRD_RESETVALUE		0x0U
+#define XHC_AIUDMA__WED_L			25U
+#define XHC_AIUDMA__WED_R			24U
+#define XHC_AIUDMA__WED_WIDTH			2U
+#define XHC_AIUDMA__WED_RESETVALUE		0x0U
+#define XHC_AIUDMA__WMS_L			23U
+#define XHC_AIUDMA__WMS_R			22U
+#define XHC_AIUDMA__WMS_WIDTH			2U
+#define XHC_AIUDMA__WMS_RESETVALUE		0x0U
+#define XHC_AIUDMA__WMI_L			21U
+#define XHC_AIUDMA__WMI_R			20U
+#define XHC_AIUDMA__WMI_WIDTH			2U
+#define XHC_AIUDMA__WMI_RESETVALUE		0x0U
+#define XHC_AIUDMA__WPF_L			19U
+#define XHC_AIUDMA__WPF_R			16U
+#define XHC_AIUDMA__WPF_WIDTH			4U
+#define XHC_AIUDMA__WPF_RESETVALUE		0x6U
+#define XHC_AIUDMA__RRMB_L			15U
+#define XHC_AIUDMA__RRMB_R			12U
+#define XHC_AIUDMA__RRMB_WIDTH			4U
+#define XHC_AIUDMA__RRMB_RESETVALUE		0x0U
+#define XHC_AIUDMA__RTD_L			11U
+#define XHC_AIUDMA__RTD_R			10U
+#define XHC_AIUDMA__RTD_WIDTH			2U
+#define XHC_AIUDMA__RTD_RESETVALUE		0x0U
+#define XHC_AIUDMA__RTF_L			9U
+#define XHC_AIUDMA__RTF_R			8U
+#define XHC_AIUDMA__RTF_WIDTH			2U
+#define XHC_AIUDMA__RTF_RESETVALUE		0x0U
+#define XHC_AIUDMA__RM_S_L			7U
+#define XHC_AIUDMA__RM_S_R			6U
+#define XHC_AIUDMA__RM_S_WIDTH			2U
+#define XHC_AIUDMA__RM_S_RESETVALUE		0x0U
+#define XHC_AIUDMA__TFBS_L			5U
+#define XHC_AIUDMA__TFBS_R			3U
+#define XHC_AIUDMA__TFBS_WIDTH			3U
+#define XHC_AIUDMA__TFBS_RESETVALUE		0x0U
+#define XHC_AIUDMA__reserved_L			2U
+#define XHC_AIUDMA__reserved_R			0U
+#define XHC_AIUDMA__reserved_WIDTH		3U
+#define XHC_AIUDMA__reserved_RESETVALUE		0x0U
+#define XHC_AIUDMA_WIDTH			32U
+#define XHC_AIUDMA__WIDTH			32U
+#define XHC_AIUDMA_ALL_L			31U
+#define XHC_AIUDMA_ALL_R			0U
+#define XHC_AIUDMA__ALL_L			31U
+#define XHC_AIUDMA__ALL_R			0U
+#define XHC_AIUDMA_DATAMASK			0xffffffffU
+#define XHC_AIUDMA_RDWRMASK			0x00000000U
+#define XHC_AIUDMA_RESETVALUE			0x00060000U
+
+#define XHC_AIUFLA_OFFSET			0xc38U
+#define XHC_AIUFLA_BASE				0xc38U
+#define XHC_AIUFLA__ACLK_L			31U
+#define XHC_AIUFLA__ACLK_R			23U
+#define XHC_AIUFLA__ACLK_WIDTH			9U
+#define XHC_AIUFLA__ACLK_RESETVALUE		0x0U
+#define XHC_AIUFLA__MFLV_L			22U
+#define XHC_AIUFLA__MFLV_R			7U
+#define XHC_AIUFLA__MFLV_WIDTH			16U
+#define XHC_AIUFLA__MFLV_RESETVALUE		0x0000U
+#define XHC_AIUFLA__NFC				6U
+#define XHC_AIUFLA__NFC_L			6U
+#define XHC_AIUFLA__NFC_R			6U
+#define XHC_AIUFLA__NFC_WIDTH			1U
+#define XHC_AIUFLA__NFC_RESETVALUE		0x1U
+#define XHC_AIUFLA__FLADJ_L			5U
+#define XHC_AIUFLA__FLADJ_R			0U
+#define XHC_AIUFLA__FLADJ_WIDTH			6U
+#define XHC_AIUFLA__FLADJ_RESETVALUE		0x20U
+#define XHC_AIUFLA_WIDTH			32U
+#define XHC_AIUFLA__WIDTH			32U
+#define XHC_AIUFLA_ALL_L			31U
+#define XHC_AIUFLA_ALL_R			0U
+#define XHC_AIUFLA__ALL_L			31U
+#define XHC_AIUFLA__ALL_R			0U
+#define XHC_AIUFLA_DATAMASK			0xffffffffU
+#define XHC_AIUFLA_RDWRMASK			0x00000000U
+#define XHC_AIUFLA_RESETVALUE			0x00000060U
+
+#define XHC_AIUCFG_OFFSET			0xc3cU
+#define XHC_AIUCFG_BASE				0xc3cU
+#define XHC_AIUCFG__ISO_L			30U
+#define XHC_AIUCFG__ISO_R			28U
+#define XHC_AIUCFG__ISO_WIDTH			3U
+#define XHC_AIUCFG__ISO_RESETVALUE		0x0U
+#define XHC_AIUCFG__EPC_L			26U
+#define XHC_AIUCFG__EPC_R			24U
+#define XHC_AIUCFG__EPC_WIDTH			3U
+#define XHC_AIUCFG__EPC_RESETVALUE		0x5U
+#define XHC_AIUCFG__PTQ_L			22U
+#define XHC_AIUCFG__PTQ_R			20U
+#define XHC_AIUCFG__PTQ_WIDTH			3U
+#define XHC_AIUCFG__PTQ_RESETVALUE		0x3U
+#define XHC_AIUCFG__NTQ_L			18U
+#define XHC_AIUCFG__NTQ_R			16U
+#define XHC_AIUCFG__NTQ_WIDTH			3U
+#define XHC_AIUCFG__NTQ_RESETVALUE		0x3U
+#define XHC_AIUCFG__HID				15U
+#define XHC_AIUCFG__HID_L			15U
+#define XHC_AIUCFG__HID_R			15U
+#define XHC_AIUCFG__HID_WIDTH			1U
+#define XHC_AIUCFG__HID_RESETVALUE		0x0U
+#define XHC_AIUCFG__EPS_L			14U
+#define XHC_AIUCFG__EPS_R			12U
+#define XHC_AIUCFG__EPS_WIDTH			3U
+#define XHC_AIUCFG__EPS_RESETVALUE		0x0U
+#define XHC_AIUCFG__reserved_L			11U
+#define XHC_AIUCFG__reserved_R			9U
+#define XHC_AIUCFG__reserved_WIDTH		3U
+#define XHC_AIUCFG__reserved_RESETVALUE		0x0U
+#define XHC_AIUCFG__PEP2_L			8U
+#define XHC_AIUCFG__PEP2_R			6U
+#define XHC_AIUCFG__PEP2_WIDTH			3U
+#define XHC_AIUCFG__PEP2_RESETVALUE		0x4U
+#define XHC_AIUCFG__MELADJ_L			5U
+#define XHC_AIUCFG__MELADJ_R			0U
+#define XHC_AIUCFG__MELADJ_WIDTH		6U
+#define XHC_AIUCFG__MELADJ_RESETVALUE		0x0U
+#define XHC_AIUCFG__RESERVED_0			31U
+#define XHC_AIUCFG__RESERVED_0_L		31U
+#define XHC_AIUCFG__RESERVED_0_R		31U
+#define XHC_AIUCFG__RESERVED_1			27U
+#define XHC_AIUCFG__RESERVED_1_L		27U
+#define XHC_AIUCFG__RESERVED_1_R		27U
+#define XHC_AIUCFG__RESERVED_2			23U
+#define XHC_AIUCFG__RESERVED_2_L		23U
+#define XHC_AIUCFG__RESERVED_2_R		23U
+#define XHC_AIUCFG__RESERVED_3			19U
+#define XHC_AIUCFG__RESERVED_3_L		19U
+#define XHC_AIUCFG__RESERVED_3_R		19U
+#define XHC_AIUCFG_WIDTH			31U
+#define XHC_AIUCFG__WIDTH			31U
+#define XHC_AIUCFG_ALL_L			30U
+#define XHC_AIUCFG_ALL_R			0U
+#define XHC_AIUCFG__ALL_L			30U
+#define XHC_AIUCFG__ALL_R			0U
+#define XHC_AIUCFG_DATAMASK			0x7777ffffU
+#define XHC_AIUCFG_RDWRMASK			0x88880000U
+#define XHC_AIUCFG_RESETVALUE			0x05330100U
+
+#define XHC_ECHFSC_OFFSET			0xc40U
+#define XHC_ECHFSC_BASE				0xc40U
+#define XHC_ECHFSC__reserved_L			31U
+#define XHC_ECHFSC__reserved_R			24U
+#define XHC_ECHFSC__reserved_WIDTH		8U
+#define XHC_ECHFSC__reserved_RESETVALUE		0x00U
+#define XHC_ECHFSC__WRMB_L			23U
+#define XHC_ECHFSC__WRMB_R			20U
+#define XHC_ECHFSC__WRMB_WIDTH			4U
+#define XHC_ECHFSC__WRMB_RESETVALUE		0x0U
+#define XHC_ECHFSC__RRMB_L			19U
+#define XHC_ECHFSC__RRMB_R			16U
+#define XHC_ECHFSC__RRMB_WIDTH			4U
+#define XHC_ECHFSC__RRMB_RESETVALUE		0x0U
+#define XHC_ECHFSC__NCP_L			15U
+#define XHC_ECHFSC__NCP_R			8U
+#define XHC_ECHFSC__NCP_WIDTH			8U
+#define XHC_ECHFSC__NCP_RESETVALUE		0x50U
+#define XHC_ECHFSC__CID_L			7U
+#define XHC_ECHFSC__CID_R			0U
+#define XHC_ECHFSC__CID_WIDTH			8U
+#define XHC_ECHFSC__CID_RESETVALUE		0xc3U
+#define XHC_ECHFSC_WIDTH			32U
+#define XHC_ECHFSC__WIDTH			32U
+#define XHC_ECHFSC_ALL_L			31U
+#define XHC_ECHFSC_ALL_R			0U
+#define XHC_ECHFSC__ALL_L			31U
+#define XHC_ECHFSC__ALL_R			0U
+#define XHC_ECHFSC_DATAMASK			0xffffffffU
+#define XHC_ECHFSC_RDWRMASK			0x00000000U
+#define XHC_ECHFSC_RESETVALUE			0x000050c3U
+
+#define XHC_FSCPOC_OFFSET			0xc54U
+#define XHC_FSCPOC_BASE				0xc54U
+#define XHC_FSCPOC__NCS_L			31U
+#define XHC_FSCPOC__NCS_R			28U
+#define XHC_FSCPOC__NCS_WIDTH			4U
+#define XHC_FSCPOC__NCS_RESETVALUE		0x0U
+#define XHC_FSCPOC__FSIZ_L			22U
+#define XHC_FSCPOC__FSIZ_R			18U
+#define XHC_FSCPOC__FSIZ_WIDTH			5U
+#define XHC_FSCPOC__FSIZ_RESETVALUE		0x0U
+#define XHC_FSCPOC__PSIZ_L			16U
+#define XHC_FSCPOC__PSIZ_R			12U
+#define XHC_FSCPOC__PSIZ_WIDTH			5U
+#define XHC_FSCPOC__PSIZ_RESETVALUE		0x0U
+#define XHC_FSCPOC__reserved_L			11U
+#define XHC_FSCPOC__reserved_R			5U
+#define XHC_FSCPOC__reserved_WIDTH		7U
+#define XHC_FSCPOC__reserved_RESETVALUE		0x0U
+#define XHC_FSCPOC__TSIZ_L			4U
+#define XHC_FSCPOC__TSIZ_R			0U
+#define XHC_FSCPOC__TSIZ_WIDTH			5U
+#define XHC_FSCPOC__TSIZ_RESETVALUE		0x0U
+#define XHC_FSCPOC__RESERVED_L			27U
+#define XHC_FSCPOC__RESERVED_R			23U
+#define XHC_FSCPOC_WIDTH			32U
+#define XHC_FSCPOC__WIDTH			32U
+#define XHC_FSCPOC_ALL_L			31U
+#define XHC_FSCPOC_ALL_R			0U
+#define XHC_FSCPOC__ALL_L			31U
+#define XHC_FSCPOC__ALL_R			0U
+#define XHC_FSCPOC_DATAMASK			0xf07dffffU
+#define XHC_FSCPOC_RDWRMASK			0x0f820000U
+#define XHC_FSCPOC_RESETVALUE			0x00000000U
+
+#define XHC_FSCGOC_OFFSET			0xc58U
+#define XHC_FSCGOC_BASE				0xc58U
+#define XHC_FSCGOC__NCS_L			31U
+#define XHC_FSCGOC__NCS_R			28U
+#define XHC_FSCGOC__NCS_WIDTH			4U
+#define XHC_FSCGOC__NCS_RESETVALUE		0x0U
+#define XHC_FSCGOC__FSIZ_L			22U
+#define XHC_FSCGOC__FSIZ_R			18U
+#define XHC_FSCGOC__FSIZ_WIDTH			5U
+#define XHC_FSCGOC__FSIZ_RESETVALUE		0x0U
+#define XHC_FSCGOC__PSIZ_L			16U
+#define XHC_FSCGOC__PSIZ_R			12U
+#define XHC_FSCGOC__PSIZ_WIDTH			5U
+#define XHC_FSCGOC__PSIZ_RESETVALUE		0x0U
+#define XHC_FSCGOC__reserved_L			11U
+#define XHC_FSCGOC__reserved_R			5U
+#define XHC_FSCGOC__reserved_WIDTH		7U
+#define XHC_FSCGOC__reserved_RESETVALUE		0x0U
+#define XHC_FSCGOC__TSIZ_L			4U
+#define XHC_FSCGOC__TSIZ_R			0U
+#define XHC_FSCGOC__TSIZ_WIDTH			5U
+#define XHC_FSCGOC__TSIZ_RESETVALUE		0x0U
+#define XHC_FSCGOC__RESERVED_L			27U
+#define XHC_FSCGOC__RESERVED_R			23U
+#define XHC_FSCGOC_WIDTH			32U
+#define XHC_FSCGOC__WIDTH			32U
+#define XHC_FSCGOC_ALL_L			31U
+#define XHC_FSCGOC_ALL_R			0U
+#define XHC_FSCGOC__ALL_L			31U
+#define XHC_FSCGOC__ALL_R			0U
+#define XHC_FSCGOC_DATAMASK			0xf07dffffU
+#define XHC_FSCGOC_RDWRMASK			0x0f820000U
+#define XHC_FSCGOC_RESETVALUE			0x00000000U
+
+#define XHC_FSCNOC_OFFSET			0xc5cU
+#define XHC_FSCNOC_BASE				0xc5cU
+#define XHC_FSCNOC__NCS_L			31U
+#define XHC_FSCNOC__NCS_R			28U
+#define XHC_FSCNOC__NCS_WIDTH			4U
+#define XHC_FSCNOC__NCS_RESETVALUE		0x0U
+#define XHC_FSCNOC__FSIZ_L			22U
+#define XHC_FSCNOC__FSIZ_R			18U
+#define XHC_FSCNOC__FSIZ_WIDTH			5U
+#define XHC_FSCNOC__FSIZ_RESETVALUE		0x0U
+#define XHC_FSCNOC__PSIZ_L			16U
+#define XHC_FSCNOC__PSIZ_R			12U
+#define XHC_FSCNOC__PSIZ_WIDTH			5U
+#define XHC_FSCNOC__PSIZ_RESETVALUE		0x0U
+#define XHC_FSCNOC__reserved_L			11U
+#define XHC_FSCNOC__reserved_R			5U
+#define XHC_FSCNOC__reserved_WIDTH		7U
+#define XHC_FSCNOC__reserved_RESETVALUE		0x0U
+#define XHC_FSCNOC__TSIZ_L			4U
+#define XHC_FSCNOC__TSIZ_R			0U
+#define XHC_FSCNOC__TSIZ_WIDTH			5U
+#define XHC_FSCNOC__TSIZ_RESETVALUE		0x0U
+#define XHC_FSCNOC__RESERVED_L			27U
+#define XHC_FSCNOC__RESERVED_R			23U
+#define XHC_FSCNOC_WIDTH			32U
+#define XHC_FSCNOC__WIDTH			32U
+#define XHC_FSCNOC_ALL_L			31U
+#define XHC_FSCNOC_ALL_R			0U
+#define XHC_FSCNOC__ALL_L			31U
+#define XHC_FSCNOC__ALL_R			0U
+#define XHC_FSCNOC_DATAMASK			0xf07dffffU
+#define XHC_FSCNOC_RDWRMASK			0x0f820000U
+#define XHC_FSCNOC_RESETVALUE			0x00000000U
+
+#define XHC_FSCAIC_OFFSET			0xc60U
+#define XHC_FSCAIC_BASE				0xc60U
+#define XHC_FSCAIC__FSIZ_L			22U
+#define XHC_FSCAIC__FSIZ_R			18U
+#define XHC_FSCAIC__FSIZ_WIDTH			5U
+#define XHC_FSCAIC__FSIZ_RESETVALUE		0x0U
+#define XHC_FSCAIC__PSIZ_L			16U
+#define XHC_FSCAIC__PSIZ_R			12U
+#define XHC_FSCAIC__PSIZ_WIDTH			5U
+#define XHC_FSCAIC__PSIZ_RESETVALUE		0x0U
+#define XHC_FSCAIC__reserved_L			11U
+#define XHC_FSCAIC__reserved_R			0U
+#define XHC_FSCAIC__reserved_WIDTH		12U
+#define XHC_FSCAIC__reserved_RESETVALUE		0x000U
+#define XHC_FSCAIC__RESERVED_L			31U
+#define XHC_FSCAIC__RESERVED_R			23U
+#define XHC_FSCAIC_WIDTH			23U
+#define XHC_FSCAIC__WIDTH			23U
+#define XHC_FSCAIC_ALL_L			22U
+#define XHC_FSCAIC_ALL_R			0U
+#define XHC_FSCAIC__ALL_L			22U
+#define XHC_FSCAIC__ALL_R			0U
+#define XHC_FSCAIC_DATAMASK			0x007dffffU
+#define XHC_FSCAIC_RDWRMASK			0xff820000U
+#define XHC_FSCAIC_RESETVALUE			0x000000U
+
+#define XHC_FSCPIC_OFFSET			0xc64U
+#define XHC_FSCPIC_BASE				0xc64U
+#define XHC_FSCPIC__NCS_L			31U
+#define XHC_FSCPIC__NCS_R			28U
+#define XHC_FSCPIC__NCS_WIDTH			4U
+#define XHC_FSCPIC__NCS_RESETVALUE		0x0U
+#define XHC_FSCPIC__reserved_L			27U
+#define XHC_FSCPIC__reserved_R			5U
+#define XHC_FSCPIC__reserved_WIDTH		23U
+#define XHC_FSCPIC__reserved_RESETVALUE		0x0U
+#define XHC_FSCPIC__TSIZ_L			4U
+#define XHC_FSCPIC__TSIZ_R			0U
+#define XHC_FSCPIC__TSIZ_WIDTH			5U
+#define XHC_FSCPIC__TSIZ_RESETVALUE		0x0U
+#define XHC_FSCPIC_WIDTH			32U
+#define XHC_FSCPIC__WIDTH			32U
+#define XHC_FSCPIC_ALL_L			31U
+#define XHC_FSCPIC_ALL_R			0U
+#define XHC_FSCPIC__ALL_L			31U
+#define XHC_FSCPIC__ALL_R			0U
+#define XHC_FSCPIC_DATAMASK			0xffffffffU
+#define XHC_FSCPIC_RDWRMASK			0x00000000U
+#define XHC_FSCPIC_RESETVALUE			0x00000000U
+
+#define XHC_FSCGIC_OFFSET			0xc68U
+#define XHC_FSCGIC_BASE				0xc68U
+#define XHC_FSCGIC__NCS_L			31U
+#define XHC_FSCGIC__NCS_R			28U
+#define XHC_FSCGIC__NCS_WIDTH			4U
+#define XHC_FSCGIC__NCS_RESETVALUE		0x0U
+#define XHC_FSCGIC__reserved_L			27U
+#define XHC_FSCGIC__reserved_R			5U
+#define XHC_FSCGIC__reserved_WIDTH		23U
+#define XHC_FSCGIC__reserved_RESETVALUE		0x0U
+#define XHC_FSCGIC__TSIZ_L			4U
+#define XHC_FSCGIC__TSIZ_R			0U
+#define XHC_FSCGIC__TSIZ_WIDTH			5U
+#define XHC_FSCGIC__TSIZ_RESETVALUE		0x0U
+#define XHC_FSCGIC_WIDTH			32U
+#define XHC_FSCGIC__WIDTH			32U
+#define XHC_FSCGIC_ALL_L			31U
+#define XHC_FSCGIC_ALL_R			0U
+#define XHC_FSCGIC__ALL_L			31U
+#define XHC_FSCGIC__ALL_R			0U
+#define XHC_FSCGIC_DATAMASK			0xffffffffU
+#define XHC_FSCGIC_RDWRMASK			0x00000000U
+#define XHC_FSCGIC_RESETVALUE			0x00000000U
+
+#define XHC_FSCNIC_OFFSET			0xc6cU
+#define XHC_FSCNIC_BASE				0xc6cU
+#define XHC_FSCNIC__NCS_L			31U
+#define XHC_FSCNIC__NCS_R			28U
+#define XHC_FSCNIC__NCS_WIDTH			4U
+#define XHC_FSCNIC__NCS_RESETVALUE		0x0U
+#define XHC_FSCNIC__reserved_L			27U
+#define XHC_FSCNIC__reserved_R			5U
+#define XHC_FSCNIC__reserved_WIDTH		23U
+#define XHC_FSCNIC__reserved_RESETVALUE		0x0U
+#define XHC_FSCNIC__TSIZ_L			4U
+#define XHC_FSCNIC__TSIZ_R			0U
+#define XHC_FSCNIC__TSIZ_WIDTH			5U
+#define XHC_FSCNIC__TSIZ_RESETVALUE		0x0U
+#define XHC_FSCNIC_WIDTH			32U
+#define XHC_FSCNIC__WIDTH			32U
+#define XHC_FSCNIC_ALL_L			31U
+#define XHC_FSCNIC_ALL_R			0U
+#define XHC_FSCNIC__ALL_L			31U
+#define XHC_FSCNIC__ALL_R			0U
+#define XHC_FSCNIC_DATAMASK			0xffffffffU
+#define XHC_FSCNIC_RDWRMASK			0x00000000U
+#define XHC_FSCNIC_RESETVALUE			0x00000000U
+
+#define XHC_ECHPRT_OFFSET			0xc70U
+#define XHC_ECHPRT_BASE				0xc70U
+#define XHC_ECHPRT__TDP				31U
+#define XHC_ECHPRT__TDP_L			31U
+#define XHC_ECHPRT__TDP_R			31U
+#define XHC_ECHPRT__TDP_WIDTH			1U
+#define XHC_ECHPRT__TDP_RESETVALUE		0x0U
+#define XHC_ECHPRT__RDP				30U
+#define XHC_ECHPRT__RDP_L			30U
+#define XHC_ECHPRT__RDP_R			30U
+#define XHC_ECHPRT__RDP_WIDTH			1U
+#define XHC_ECHPRT__RDP_RESETVALUE		0x0U
+#define XHC_ECHPRT__reserved_L			29U
+#define XHC_ECHPRT__reserved_R			25U
+#define XHC_ECHPRT__reserved_WIDTH		5U
+#define XHC_ECHPRT__reserved_RESETVALUE		0x0U
+#define XHC_ECHPRT__MFT_L			24U
+#define XHC_ECHPRT__MFT_R			17U
+#define XHC_ECHPRT__MFT_WIDTH			8U
+#define XHC_ECHPRT__MFT_RESETVALUE		0x7dU
+#define XHC_ECHPRT__HST				16U
+#define XHC_ECHPRT__HST_L			16U
+#define XHC_ECHPRT__HST_R			16U
+#define XHC_ECHPRT__HST_WIDTH			1U
+#define XHC_ECHPRT__HST_RESETVALUE		0x0U
+#define XHC_ECHPRT__NCP_L			15U
+#define XHC_ECHPRT__NCP_R			8U
+#define XHC_ECHPRT__NCP_WIDTH			8U
+#define XHC_ECHPRT__NCP_RESETVALUE		0x04U
+#define XHC_ECHPRT__CID_L			7U
+#define XHC_ECHPRT__CID_R			0U
+#define XHC_ECHPRT__CID_WIDTH			8U
+#define XHC_ECHPRT__CID_RESETVALUE		0xc4U
+#define XHC_ECHPRT_WIDTH			32U
+#define XHC_ECHPRT__WIDTH			32U
+#define XHC_ECHPRT_ALL_L			31U
+#define XHC_ECHPRT_ALL_R			0U
+#define XHC_ECHPRT__ALL_L			31U
+#define XHC_ECHPRT__ALL_R			0U
+#define XHC_ECHPRT_DATAMASK			0xffffffffU
+#define XHC_ECHPRT_RDWRMASK			0x00000000U
+#define XHC_ECHPRT_RESETVALUE			0x00fa04c4U
+
+#define XHC_PRTHSC_OFFSET			0xc78U
+#define XHC_PRTHSC_BASE				0xc78U
+#define XHC_PRTHSC__TMR_L			31U
+#define XHC_PRTHSC__TMR_R			16U
+#define XHC_PRTHSC__TMR_WIDTH			16U
+#define XHC_PRTHSC__TMR_RESETVALUE		0x0000U
+#define XHC_PRTHSC__RSL_L			7U
+#define XHC_PRTHSC__RSL_R			6U
+#define XHC_PRTHSC__RSL_WIDTH			2U
+#define XHC_PRTHSC__RSL_RESETVALUE		0x0U
+#define XHC_PRTHSC__AS_M_L			5U
+#define XHC_PRTHSC__AS_M_R			4U
+#define XHC_PRTHSC__AS_M_WIDTH			2U
+#define XHC_PRTHSC__AS_M_RESETVALUE		0x0U
+#define XHC_PRTHSC__CMD_L			3U
+#define XHC_PRTHSC__CMD_R			2U
+#define XHC_PRTHSC__CMD_WIDTH			2U
+#define XHC_PRTHSC__CMD_RESETVALUE		0x0U
+#define XHC_PRTHSC__reserved			1U
+#define XHC_PRTHSC__reserved_L			1U
+#define XHC_PRTHSC__reserved_R			1U
+#define XHC_PRTHSC__reserved_WIDTH		1U
+#define XHC_PRTHSC__reserved_RESETVALUE		0x0U
+#define XHC_PRTHSC__STB				0U
+#define XHC_PRTHSC__STB_L			0U
+#define XHC_PRTHSC__STB_R			0U
+#define XHC_PRTHSC__STB_WIDTH			1U
+#define XHC_PRTHSC__STB_RESETVALUE		0x0U
+#define XHC_PRTHSC__RESERVED_L			15U
+#define XHC_PRTHSC__RESERVED_R			8U
+#define XHC_PRTHSC_WIDTH			32U
+#define XHC_PRTHSC__WIDTH			32U
+#define XHC_PRTHSC_ALL_L			31U
+#define XHC_PRTHSC_ALL_R			0U
+#define XHC_PRTHSC__ALL_L			31U
+#define XHC_PRTHSC__ALL_R			0U
+#define XHC_PRTHSC_DATAMASK			0xffff00ffU
+#define XHC_PRTHSC_RDWRMASK			0x0000ff00U
+#define XHC_PRTHSC_RESETVALUE			0x00000000U
+
+#define XHC_PRTHSR_OFFSET			0xc7cU
+#define XHC_PRTHSR_BASE				0xc7cU
+#define XHC_PRTHSR__RDLY_L			31U
+#define XHC_PRTHSR__RDLY_R			24U
+#define XHC_PRTHSR__RDLY_WIDTH			8U
+#define XHC_PRTHSR__RDLY_RESETVALUE		0x00U
+#define XHC_PRTHSR__TDPP_L			23U
+#define XHC_PRTHSR__TDPP_R			16U
+#define XHC_PRTHSR__TDPP_WIDTH			8U
+#define XHC_PRTHSR__TDPP_RESETVALUE		0x00U
+#define XHC_PRTHSR__RDPP_L			15U
+#define XHC_PRTHSR__RDPP_R			8U
+#define XHC_PRTHSR__RDPP_WIDTH			8U
+#define XHC_PRTHSR__RDPP_RESETVALUE		0x00U
+#define XHC_PRTHSR__TRTY_L			7U
+#define XHC_PRTHSR__TRTY_R			0U
+#define XHC_PRTHSR__TRTY_WIDTH			8U
+#define XHC_PRTHSR__TRTY_RESETVALUE		0x00U
+#define XHC_PRTHSR_WIDTH			32U
+#define XHC_PRTHSR__WIDTH			32U
+#define XHC_PRTHSR_ALL_L			31U
+#define XHC_PRTHSR_ALL_R			0U
+#define XHC_PRTHSR__ALL_L			31U
+#define XHC_PRTHSR__ALL_R			0U
+#define XHC_PRTHSR_DATAMASK			0xffffffffU
+#define XHC_PRTHSR_RDWRMASK			0x00000000U
+#define XHC_PRTHSR_RESETVALUE			0x00000000U
+
+#define XHC_ECHRHS_OFFSET			0xc80U
+#define XHC_ECHRHS_BASE				0xc80U
+#define XHC_ECHRHS__RPO_L			30U
+#define XHC_ECHRHS__RPO_R			24U
+#define XHC_ECHRHS__RPO_WIDTH			7U
+#define XHC_ECHRHS__RPO_RESETVALUE		0x0U
+#define XHC_ECHRHS__reserved_L			23U
+#define XHC_ECHRHS__reserved_R			22U
+#define XHC_ECHRHS__reserved_WIDTH		2U
+#define XHC_ECHRHS__reserved_RESETVALUE		0x0U
+#define XHC_ECHRHS__RPN_L			21U
+#define XHC_ECHRHS__RPN_R			20U
+#define XHC_ECHRHS__RPN_WIDTH			2U
+#define XHC_ECHRHS__RPN_RESETVALUE		0x0U
+#define XHC_ECHRHS__DNR_L			19U
+#define XHC_ECHRHS__DNR_R			16U
+#define XHC_ECHRHS__DNR_WIDTH			4U
+#define XHC_ECHRHS__DNR_RESETVALUE		0x0U
+#define XHC_ECHRHS__NCP_L			15U
+#define XHC_ECHRHS__NCP_R			8U
+#define XHC_ECHRHS__NCP_WIDTH			8U
+#define XHC_ECHRHS__NCP_RESETVALUE		0x0cU
+#define XHC_ECHRHS__CID_L			7U
+#define XHC_ECHRHS__CID_R			0U
+#define XHC_ECHRHS__CID_WIDTH			8U
+#define XHC_ECHRHS__CID_RESETVALUE		0xc8U
+#define XHC_ECHRHS__RESERVED			31U
+#define XHC_ECHRHS__RESERVED_L			31U
+#define XHC_ECHRHS__RESERVED_R			31U
+#define XHC_ECHRHS_WIDTH			31U
+#define XHC_ECHRHS__WIDTH			31U
+#define XHC_ECHRHS_ALL_L			30U
+#define XHC_ECHRHS_ALL_R			0U
+#define XHC_ECHRHS__ALL_L			30U
+#define XHC_ECHRHS__ALL_R			0U
+#define XHC_ECHRHS_DATAMASK			0x7fffffffU
+#define XHC_ECHRHS_RDWRMASK			0x80000000U
+#define XHC_ECHRHS_RESETVALUE			0x00000cc8U
+
+#define XHC_RHSDES_OFFSET			0xc84U
+#define XHC_RHSDES_BASE				0xc84U
+#define XHC_RHSDES__PIS3_L			31U
+#define XHC_RHSDES__PIS3_R			30U
+#define XHC_RHSDES__PIS3_WIDTH			2U
+#define XHC_RHSDES__PIS3_RESETVALUE		0x0U
+#define XHC_RHSDES__HIST3			24U
+#define XHC_RHSDES__HIST3_L			24U
+#define XHC_RHSDES__HIST3_R			24U
+#define XHC_RHSDES__HIST3_WIDTH			1U
+#define XHC_RHSDES__HIST3_RESETVALUE		0x0U
+#define XHC_RHSDES__PIS2_L			23U
+#define XHC_RHSDES__PIS2_R			22U
+#define XHC_RHSDES__PIS2_WIDTH			2U
+#define XHC_RHSDES__PIS2_RESETVALUE		0x0U
+#define XHC_RHSDES__HIST2			16U
+#define XHC_RHSDES__HIST2_L			16U
+#define XHC_RHSDES__HIST2_R			16U
+#define XHC_RHSDES__HIST2_WIDTH			1U
+#define XHC_RHSDES__HIST2_RESETVALUE		0x0U
+#define XHC_RHSDES__PIS1_L			15U
+#define XHC_RHSDES__PIS1_R			14U
+#define XHC_RHSDES__PIS1_WIDTH			2U
+#define XHC_RHSDES__PIS1_RESETVALUE		0x0U
+#define XHC_RHSDES__HIST1			8U
+#define XHC_RHSDES__HIST1_L			8U
+#define XHC_RHSDES__HIST1_R			8U
+#define XHC_RHSDES__HIST1_WIDTH			1U
+#define XHC_RHSDES__HIST1_RESETVALUE		0x0U
+#define XHC_RHSDES__PIS0_L			7U
+#define XHC_RHSDES__PIS0_R			6U
+#define XHC_RHSDES__PIS0_WIDTH			2U
+#define XHC_RHSDES__PIS0_RESETVALUE		0x0U
+#define XHC_RHSDES__reserved_L			5U
+#define XHC_RHSDES__reserved_R			1U
+#define XHC_RHSDES__reserved_WIDTH		5U
+#define XHC_RHSDES__reserved_RESETVALUE		0x0U
+#define XHC_RHSDES__HIST0			0U
+#define XHC_RHSDES__HIST0_L			0U
+#define XHC_RHSDES__HIST0_R			0U
+#define XHC_RHSDES__HIST0_WIDTH			1U
+#define XHC_RHSDES__HIST0_RESETVALUE		0x0U
+#define XHC_RHSDES__RESERVED_0_L		29U
+#define XHC_RHSDES__RESERVED_0_R		25U
+#define XHC_RHSDES__RESERVED_1_L		21U
+#define XHC_RHSDES__RESERVED_1_R		17U
+#define XHC_RHSDES__RESERVED_2_L		13U
+#define XHC_RHSDES__RESERVED_2_R		9U
+#define XHC_RHSDES__RESERVED_L			29U
+#define XHC_RHSDES__RESERVED_R			25U
+#define XHC_RHSDES_WIDTH			32U
+#define XHC_RHSDES__WIDTH			32U
+#define XHC_RHSDES_ALL_L			31U
+#define XHC_RHSDES_ALL_R			0U
+#define XHC_RHSDES__ALL_L			31U
+#define XHC_RHSDES__ALL_R			0U
+#define XHC_RHSDES_DATAMASK			0xc1c1c1ffU
+#define XHC_RHSDES_RDWRMASK			0x3e3e3e00U
+#define XHC_RHSDES_RESETVALUE			0x00000000U
+
+#define XHC_RHSHSC0_OFFSET			0xc90U
+#define XHC_RHSHSC0_BASE			0xc90U
+#define XHC_RHSHSC0__TMR_L			31U
+#define XHC_RHSHSC0__TMR_R			16U
+#define XHC_RHSHSC0__TMR_WIDTH			16U
+#define XHC_RHSHSC0__TMR_RESETVALUE		0x0000U
+#define XHC_RHSHSC0__RSL_L			7U
+#define XHC_RHSHSC0__RSL_R			6U
+#define XHC_RHSHSC0__RSL_WIDTH			2U
+#define XHC_RHSHSC0__RSL_RESETVALUE		0x0U
+#define XHC_RHSHSC0__AS_M_L			5U
+#define XHC_RHSHSC0__AS_M_R			4U
+#define XHC_RHSHSC0__AS_M_WIDTH			2U
+#define XHC_RHSHSC0__AS_M_RESETVALUE		0x0U
+#define XHC_RHSHSC0__CMD_L			3U
+#define XHC_RHSHSC0__CMD_R			2U
+#define XHC_RHSHSC0__CMD_WIDTH			2U
+#define XHC_RHSHSC0__CMD_RESETVALUE		0x0U
+#define XHC_RHSHSC0__reserved			1U
+#define XHC_RHSHSC0__reserved_L			1U
+#define XHC_RHSHSC0__reserved_R			1U
+#define XHC_RHSHSC0__reserved_WIDTH		1U
+#define XHC_RHSHSC0__reserved_RESETVALUE	0x0U
+#define XHC_RHSHSC0__STB			0U
+#define XHC_RHSHSC0__STB_L			0U
+#define XHC_RHSHSC0__STB_R			0U
+#define XHC_RHSHSC0__STB_WIDTH			1U
+#define XHC_RHSHSC0__STB_RESETVALUE		0x0U
+#define XHC_RHSHSC0__RESERVED_L			15U
+#define XHC_RHSHSC0__RESERVED_R			8U
+#define XHC_RHSHSC0_WIDTH			32U
+#define XHC_RHSHSC0__WIDTH			32U
+#define XHC_RHSHSC0_ALL_L			31U
+#define XHC_RHSHSC0_ALL_R			0U
+#define XHC_RHSHSC0__ALL_L			31U
+#define XHC_RHSHSC0__ALL_R			0U
+#define XHC_RHSHSC0_DATAMASK			0xffff00ffU
+#define XHC_RHSHSC0_RDWRMASK			0x0000ff00U
+#define XHC_RHSHSC0_RESETVALUE			0x00000000U
+
+#define XHC_RHSHSR0_OFFSET			0xc94U
+#define XHC_RHSHSR0_BASE			0xc94U
+#define XHC_RHSHSR0__C2U_L			31U
+#define XHC_RHSHSR0__C2U_R			24U
+#define XHC_RHSHSR0__C2U_WIDTH			8U
+#define XHC_RHSHSR0__C2U_RESETVALUE		0x00U
+#define XHC_RHSHSR0__C1U_L			23U
+#define XHC_RHSHSR0__C1U_R			16U
+#define XHC_RHSHSR0__C1U_WIDTH			8U
+#define XHC_RHSHSR0__C1U_RESETVALUE		0x00U
+#define XHC_RHSHSR0__RCV_L			15U
+#define XHC_RHSHSR0__RCV_R			8U
+#define XHC_RHSHSR0__RCV_WIDTH			8U
+#define XHC_RHSHSR0__RCV_RESETVALUE		0x00U
+#define XHC_RHSHSR0__RTY_L			7U
+#define XHC_RHSHSR0__RTY_R			0U
+#define XHC_RHSHSR0__RTY_WIDTH			8U
+#define XHC_RHSHSR0__RTY_RESETVALUE		0x00U
+#define XHC_RHSHSR0_WIDTH			32U
+#define XHC_RHSHSR0__WIDTH			32U
+#define XHC_RHSHSR0_ALL_L			31U
+#define XHC_RHSHSR0_ALL_R			0U
+#define XHC_RHSHSR0__ALL_L			31U
+#define XHC_RHSHSR0__ALL_R			0U
+#define XHC_RHSHSR0_DATAMASK			0xffffffffU
+#define XHC_RHSHSR0_RDWRMASK			0x00000000U
+#define XHC_RHSHSR0_RESETVALUE			0x00000000U
+
+#define XHC_RHSHSC1_OFFSET			0xc98U
+#define XHC_RHSHSC1_BASE			0xc98U
+#define XHC_RHSHSC1__TMR_L			31U
+#define XHC_RHSHSC1__TMR_R			16U
+#define XHC_RHSHSC1__TMR_WIDTH			16U
+#define XHC_RHSHSC1__TMR_RESETVALUE		0x0000U
+#define XHC_RHSHSC1__RSL_L			7U
+#define XHC_RHSHSC1__RSL_R			6U
+#define XHC_RHSHSC1__RSL_WIDTH			2U
+#define XHC_RHSHSC1__RSL_RESETVALUE		0x0U
+#define XHC_RHSHSC1__AS_M_L			5U
+#define XHC_RHSHSC1__AS_M_R			4U
+#define XHC_RHSHSC1__AS_M_WIDTH			2U
+#define XHC_RHSHSC1__AS_M_RESETVALUE		0x0U
+#define XHC_RHSHSC1__CMD_L			3U
+#define XHC_RHSHSC1__CMD_R			2U
+#define XHC_RHSHSC1__CMD_WIDTH			2U
+#define XHC_RHSHSC1__CMD_RESETVALUE		0x0U
+#define XHC_RHSHSC1__reserved			1U
+#define XHC_RHSHSC1__reserved_L			1U
+#define XHC_RHSHSC1__reserved_R			1U
+#define XHC_RHSHSC1__reserved_WIDTH		1U
+#define XHC_RHSHSC1__reserved_RESETVALUE	0x0U
+#define XHC_RHSHSC1__STB			0U
+#define XHC_RHSHSC1__STB_L			0U
+#define XHC_RHSHSC1__STB_R			0U
+#define XHC_RHSHSC1__STB_WIDTH			1U
+#define XHC_RHSHSC1__STB_RESETVALUE		0x0U
+#define XHC_RHSHSC1__RESERVED_L			15U
+#define XHC_RHSHSC1__RESERVED_R			8U
+#define XHC_RHSHSC1_WIDTH			32U
+#define XHC_RHSHSC1__WIDTH			32U
+#define XHC_RHSHSC1_ALL_L			31U
+#define XHC_RHSHSC1_ALL_R			0U
+#define XHC_RHSHSC1__ALL_L			31U
+#define XHC_RHSHSC1__ALL_R			0U
+#define XHC_RHSHSC1_DATAMASK			0xffff00ffU
+#define XHC_RHSHSC1_RDWRMASK			0x0000ff00U
+#define XHC_RHSHSC1_RESETVALUE			0x00000000U
+
+#define XHC_RHSHSR1_OFFSET			0xc9cU
+#define XHC_RHSHSR1_BASE			0xc9cU
+#define XHC_RHSHSR1__C2U_L			31U
+#define XHC_RHSHSR1__C2U_R			24U
+#define XHC_RHSHSR1__C2U_WIDTH			8U
+#define XHC_RHSHSR1__C2U_RESETVALUE		0x00U
+#define XHC_RHSHSR1__C1U_L			23U
+#define XHC_RHSHSR1__C1U_R			16U
+#define XHC_RHSHSR1__C1U_WIDTH			8U
+#define XHC_RHSHSR1__C1U_RESETVALUE		0x00U
+#define XHC_RHSHSR1__RCV_L			15U
+#define XHC_RHSHSR1__RCV_R			8U
+#define XHC_RHSHSR1__RCV_WIDTH			8U
+#define XHC_RHSHSR1__RCV_RESETVALUE		0x00U
+#define XHC_RHSHSR1__RTY_L			7U
+#define XHC_RHSHSR1__RTY_R			0U
+#define XHC_RHSHSR1__RTY_WIDTH			8U
+#define XHC_RHSHSR1__RTY_RESETVALUE		0x00U
+#define XHC_RHSHSR1_WIDTH			32U
+#define XHC_RHSHSR1__WIDTH			32U
+#define XHC_RHSHSR1_ALL_L			31U
+#define XHC_RHSHSR1_ALL_R			0U
+#define XHC_RHSHSR1__ALL_L			31U
+#define XHC_RHSHSR1__ALL_R			0U
+#define XHC_RHSHSR1_DATAMASK			0xffffffffU
+#define XHC_RHSHSR1_RDWRMASK			0x00000000U
+#define XHC_RHSHSR1_RESETVALUE			0x00000000U
+
+#define XHC_RHSHSC2_OFFSET			0xca0U
+#define XHC_RHSHSC2_BASE			0xca0U
+#define XHC_RHSHSC2__TMR_L			31U
+#define XHC_RHSHSC2__TMR_R			16U
+#define XHC_RHSHSC2__TMR_WIDTH			16U
+#define XHC_RHSHSC2__TMR_RESETVALUE		0x0000U
+#define XHC_RHSHSC2__RSL_L			7U
+#define XHC_RHSHSC2__RSL_R			6U
+#define XHC_RHSHSC2__RSL_WIDTH			2U
+#define XHC_RHSHSC2__RSL_RESETVALUE		0x0U
+#define XHC_RHSHSC2__AS_M_L			5U
+#define XHC_RHSHSC2__AS_M_R			4U
+#define XHC_RHSHSC2__AS_M_WIDTH			2U
+#define XHC_RHSHSC2__AS_M_RESETVALUE		0x0U
+#define XHC_RHSHSC2__CMD_L			3U
+#define XHC_RHSHSC2__CMD_R			2U
+#define XHC_RHSHSC2__CMD_WIDTH			2U
+#define XHC_RHSHSC2__CMD_RESETVALUE		0x0U
+#define XHC_RHSHSC2__reserved			1U
+#define XHC_RHSHSC2__reserved_L			1U
+#define XHC_RHSHSC2__reserved_R			1U
+#define XHC_RHSHSC2__reserved_WIDTH		1U
+#define XHC_RHSHSC2__reserved_RESETVALUE	0x0U
+#define XHC_RHSHSC2__STB			0U
+#define XHC_RHSHSC2__STB_L			0U
+#define XHC_RHSHSC2__STB_R			0U
+#define XHC_RHSHSC2__STB_WIDTH			1U
+#define XHC_RHSHSC2__STB_RESETVALUE		0x0U
+#define XHC_RHSHSC2__RESERVED_L			15U
+#define XHC_RHSHSC2__RESERVED_R			8U
+#define XHC_RHSHSC2_WIDTH			32U
+#define XHC_RHSHSC2__WIDTH			32U
+#define XHC_RHSHSC2_ALL_L			31U
+#define XHC_RHSHSC2_ALL_R			0U
+#define XHC_RHSHSC2__ALL_L			31U
+#define XHC_RHSHSC2__ALL_R			0U
+#define XHC_RHSHSC2_DATAMASK			0xffff00ffU
+#define XHC_RHSHSC2_RDWRMASK			0x0000ff00U
+#define XHC_RHSHSC2_RESETVALUE			0x00000000U
+
+#define XHC_RHSHSR2_OFFSET			0xca4U
+#define XHC_RHSHSR2_BASE			0xca4U
+#define XHC_RHSHSR2__C2U_L			31U
+#define XHC_RHSHSR2__C2U_R			24U
+#define XHC_RHSHSR2__C2U_WIDTH			8U
+#define XHC_RHSHSR2__C2U_RESETVALUE		0x00U
+#define XHC_RHSHSR2__C1U_L			23U
+#define XHC_RHSHSR2__C1U_R			16U
+#define XHC_RHSHSR2__C1U_WIDTH			8U
+#define XHC_RHSHSR2__C1U_RESETVALUE		0x00U
+#define XHC_RHSHSR2__RCV_L			15U
+#define XHC_RHSHSR2__RCV_R			8U
+#define XHC_RHSHSR2__RCV_WIDTH			8U
+#define XHC_RHSHSR2__RCV_RESETVALUE		0x00U
+#define XHC_RHSHSR2__RTY_L			7U
+#define XHC_RHSHSR2__RTY_R			0U
+#define XHC_RHSHSR2__RTY_WIDTH			8U
+#define XHC_RHSHSR2__RTY_RESETVALUE		0x00U
+#define XHC_RHSHSR2_WIDTH			32U
+#define XHC_RHSHSR2__WIDTH			32U
+#define XHC_RHSHSR2_ALL_L			31U
+#define XHC_RHSHSR2_ALL_R			0U
+#define XHC_RHSHSR2__ALL_L			31U
+#define XHC_RHSHSR2__ALL_R			0U
+#define XHC_RHSHSR2_DATAMASK			0xffffffffU
+#define XHC_RHSHSR2_RDWRMASK			0x00000000U
+#define XHC_RHSHSR2_RESETVALUE			0x00000000U
+
+#define XHC_RHSHSC3_OFFSET			0xca8U
+#define XHC_RHSHSC3_BASE			0xca8U
+#define XHC_RHSHSC3__TMR_L			31U
+#define XHC_RHSHSC3__TMR_R			16U
+#define XHC_RHSHSC3__TMR_WIDTH			16U
+#define XHC_RHSHSC3__TMR_RESETVALUE		0x0000U
+#define XHC_RHSHSC3__RSL_L			7U
+#define XHC_RHSHSC3__RSL_R			6U
+#define XHC_RHSHSC3__RSL_WIDTH			2U
+#define XHC_RHSHSC3__RSL_RESETVALUE		0x0U
+#define XHC_RHSHSC3__AS_M_L			5U
+#define XHC_RHSHSC3__AS_M_R			4U
+#define XHC_RHSHSC3__AS_M_WIDTH			2U
+#define XHC_RHSHSC3__AS_M_RESETVALUE		0x0U
+#define XHC_RHSHSC3__CMD_L			3U
+#define XHC_RHSHSC3__CMD_R			2U
+#define XHC_RHSHSC3__CMD_WIDTH			2U
+#define XHC_RHSHSC3__CMD_RESETVALUE		0x0U
+#define XHC_RHSHSC3__reserved			1U
+#define XHC_RHSHSC3__reserved_L			1U
+#define XHC_RHSHSC3__reserved_R			1U
+#define XHC_RHSHSC3__reserved_WIDTH		1U
+#define XHC_RHSHSC3__reserved_RESETVALUE	0x0U
+#define XHC_RHSHSC3__STB			0U
+#define XHC_RHSHSC3__STB_L			0U
+#define XHC_RHSHSC3__STB_R			0U
+#define XHC_RHSHSC3__STB_WIDTH			1U
+#define XHC_RHSHSC3__STB_RESETVALUE		0x0U
+#define XHC_RHSHSC3__RESERVED_L			15U
+#define XHC_RHSHSC3__RESERVED_R			8U
+#define XHC_RHSHSC3_WIDTH			32U
+#define XHC_RHSHSC3__WIDTH			32U
+#define XHC_RHSHSC3_ALL_L			31U
+#define XHC_RHSHSC3_ALL_R			0U
+#define XHC_RHSHSC3__ALL_L			31U
+#define XHC_RHSHSC3__ALL_R			0U
+#define XHC_RHSHSC3_DATAMASK			0xffff00ffU
+#define XHC_RHSHSC3_RDWRMASK			0x0000ff00U
+#define XHC_RHSHSC3_RESETVALUE			0x00000000U
+
+#define XHC_RHSHSR3_OFFSET			0xcacU
+#define XHC_RHSHSR3_BASE			0xcacU
+#define XHC_RHSHSR3__C2U_L			31U
+#define XHC_RHSHSR3__C2U_R			24U
+#define XHC_RHSHSR3__C2U_WIDTH			8U
+#define XHC_RHSHSR3__C2U_RESETVALUE		0x00U
+#define XHC_RHSHSR3__C1U_L			23U
+#define XHC_RHSHSR3__C1U_R			16U
+#define XHC_RHSHSR3__C1U_WIDTH			8U
+#define XHC_RHSHSR3__C1U_RESETVALUE		0x00U
+#define XHC_RHSHSR3__RCV_L			15U
+#define XHC_RHSHSR3__RCV_R			8U
+#define XHC_RHSHSR3__RCV_WIDTH			8U
+#define XHC_RHSHSR3__RCV_RESETVALUE		0x00U
+#define XHC_RHSHSR3__RTY_L			7U
+#define XHC_RHSHSR3__RTY_R			0U
+#define XHC_RHSHSR3__RTY_WIDTH			8U
+#define XHC_RHSHSR3__RTY_RESETVALUE		0x00U
+#define XHC_RHSHSR3_WIDTH			32U
+#define XHC_RHSHSR3__WIDTH			32U
+#define XHC_RHSHSR3_ALL_L			31U
+#define XHC_RHSHSR3_ALL_R			0U
+#define XHC_RHSHSR3__ALL_L			31U
+#define XHC_RHSHSR3__ALL_R			0U
+#define XHC_RHSHSR3_DATAMASK			0xffffffffU
+#define XHC_RHSHSR3_RDWRMASK			0x00000000U
+#define XHC_RHSHSR3_RESETVALUE			0x00000000U
+
+#define XHC_ECHSSP_OFFSET			0xcb0U
+#define XHC_ECHSSP_BASE				0xcb0U
+#define XHC_ECHSSP__reserved_L			31U
+#define XHC_ECHSSP__reserved_R			16U
+#define XHC_ECHSSP__reserved_WIDTH		16U
+#define XHC_ECHSSP__reserved_RESETVALUE		0x0000U
+#define XHC_ECHSSP__NCP_L			15U
+#define XHC_ECHSSP__NCP_R			8U
+#define XHC_ECHSSP__NCP_WIDTH			8U
+#define XHC_ECHSSP__NCP_RESETVALUE		0x04U
+#define XHC_ECHSSP__CID_L			7U
+#define XHC_ECHSSP__CID_R			0U
+#define XHC_ECHSSP__CID_WIDTH			8U
+#define XHC_ECHSSP__CID_RESETVALUE		0xc6U
+#define XHC_ECHSSP_WIDTH			32U
+#define XHC_ECHSSP__WIDTH			32U
+#define XHC_ECHSSP_ALL_L			31U
+#define XHC_ECHSSP_ALL_R			0U
+#define XHC_ECHSSP__ALL_L			31U
+#define XHC_ECHSSP__ALL_R			0U
+#define XHC_ECHSSP_DATAMASK			0xffffffffU
+#define XHC_ECHSSP_RDWRMASK			0x00000000U
+#define XHC_ECHSSP_RESETVALUE			0x000004c6U
+
+#define XHC_SSPVER_OFFSET			0xcb4U
+#define XHC_SSPVER_BASE				0xcb4U
+#define XHC_SSPVER__MAJ_L			31U
+#define XHC_SSPVER__MAJ_R			28U
+#define XHC_SSPVER__MAJ_WIDTH			4U
+#define XHC_SSPVER__MAJ_RESETVALUE		0x0U
+#define XHC_SSPVER__MIN_L			27U
+#define XHC_SSPVER__MIN_R			24U
+#define XHC_SSPVER__MIN_WIDTH			4U
+#define XHC_SSPVER__MIN_RESETVALUE		0x0U
+#define XHC_SSPVER__RLS_L			23U
+#define XHC_SSPVER__RLS_R			20U
+#define XHC_SSPVER__RLS_WIDTH			4U
+#define XHC_SSPVER__RLS_RESETVALUE		0x0U
+#define XHC_SSPVER__reserved_L			19U
+#define XHC_SSPVER__reserved_R			0U
+#define XHC_SSPVER__reserved_WIDTH		20U
+#define XHC_SSPVER__reserved_RESETVALUE		0x00000U
+#define XHC_SSPVER_WIDTH			32U
+#define XHC_SSPVER__WIDTH			32U
+#define XHC_SSPVER_ALL_L			31U
+#define XHC_SSPVER_ALL_R			0U
+#define XHC_SSPVER__ALL_L			31U
+#define XHC_SSPVER__ALL_R			0U
+#define XHC_SSPVER_DATAMASK			0xffffffffU
+#define XHC_SSPVER_RDWRMASK			0x00000000U
+#define XHC_SSPVER_RESETVALUE			0x00000000U
+
+#define XHC_SSPMGN_OFFSET			0xcb8U
+#define XHC_SSPMGN_BASE				0xcb8U
+#define XHC_SSPMGN__MGN_L			31U
+#define XHC_SSPMGN__MGN_R			0U
+#define XHC_SSPMGN__MGN_WIDTH			32U
+#define XHC_SSPMGN__MGN_RESETVALUE		0x4b535040U
+#define XHC_SSPMGN_WIDTH			32U
+#define XHC_SSPMGN__WIDTH			32U
+#define XHC_SSPMGN_ALL_L			31U
+#define XHC_SSPMGN_ALL_R			0U
+#define XHC_SSPMGN__ALL_L			31U
+#define XHC_SSPMGN__ALL_R			0U
+#define XHC_SSPMGN_DATAMASK			0xffffffffU
+#define XHC_SSPMGN_RDWRMASK			0x00000000U
+#define XHC_SSPMGN_RESETVALUE			0x4b535040U
+
+#define XHC_ECHFSC2_OFFSET			0xcc0U
+#define XHC_ECHFSC2_BASE			0xcc0U
+#define XHC_ECHFSC2__reserved_L			31U
+#define XHC_ECHFSC2__reserved_R			16U
+#define XHC_ECHFSC2__reserved_WIDTH		16U
+#define XHC_ECHFSC2__reserved_RESETVALUE	0x0000U
+#define XHC_ECHFSC2__NCP_L			15U
+#define XHC_ECHFSC2__NCP_R			8U
+#define XHC_ECHFSC2__NCP_WIDTH			8U
+#define XHC_ECHFSC2__NCP_RESETVALUE		0x50U
+#define XHC_ECHFSC2__CID_L			7U
+#define XHC_ECHFSC2__CID_R			0U
+#define XHC_ECHFSC2__CID_WIDTH			8U
+#define XHC_ECHFSC2__CID_RESETVALUE		0xc7U
+#define XHC_ECHFSC2_WIDTH			32U
+#define XHC_ECHFSC2__WIDTH			32U
+#define XHC_ECHFSC2_ALL_L			31U
+#define XHC_ECHFSC2_ALL_R			0U
+#define XHC_ECHFSC2__ALL_L			31U
+#define XHC_ECHFSC2__ALL_R			0U
+#define XHC_ECHFSC2_DATAMASK			0xffffffffU
+#define XHC_ECHFSC2_RDWRMASK			0x00000000U
+#define XHC_ECHFSC2_RESETVALUE			0x000050c7U
+
+#define XHC_FSC2POC_OFFSET			0xcd4U
+#define XHC_FSC2POC_BASE			0xcd4U
+#define XHC_FSC2POC__NCS_L			31U
+#define XHC_FSC2POC__NCS_R			28U
+#define XHC_FSC2POC__NCS_WIDTH			4U
+#define XHC_FSC2POC__NCS_RESETVALUE		0x0U
+#define XHC_FSC2POC__FSIZ_L			22U
+#define XHC_FSC2POC__FSIZ_R			18U
+#define XHC_FSC2POC__FSIZ_WIDTH			5U
+#define XHC_FSC2POC__FSIZ_RESETVALUE		0x0U
+#define XHC_FSC2POC__PSIZ_L			16U
+#define XHC_FSC2POC__PSIZ_R			12U
+#define XHC_FSC2POC__PSIZ_WIDTH			5U
+#define XHC_FSC2POC__PSIZ_RESETVALUE		0x0U
+#define XHC_FSC2POC__reserved_L			11U
+#define XHC_FSC2POC__reserved_R			5U
+#define XHC_FSC2POC__reserved_WIDTH		7U
+#define XHC_FSC2POC__reserved_RESETVALUE	0x0U
+#define XHC_FSC2POC__TSIZ_L			4U
+#define XHC_FSC2POC__TSIZ_R			0U
+#define XHC_FSC2POC__TSIZ_WIDTH			5U
+#define XHC_FSC2POC__TSIZ_RESETVALUE		0x0U
+#define XHC_FSC2POC__RESERVED_L			27U
+#define XHC_FSC2POC__RESERVED_R			23U
+#define XHC_FSC2POC_WIDTH			32U
+#define XHC_FSC2POC__WIDTH			32U
+#define XHC_FSC2POC_ALL_L			31U
+#define XHC_FSC2POC_ALL_R			0U
+#define XHC_FSC2POC__ALL_L			31U
+#define XHC_FSC2POC__ALL_R			0U
+#define XHC_FSC2POC_DATAMASK			0xf07dffffU
+#define XHC_FSC2POC_RDWRMASK			0x0f820000U
+#define XHC_FSC2POC_RESETVALUE			0x00000000U
+
+#define XHC_FSC2GOC_OFFSET			0xcd8U
+#define XHC_FSC2GOC_BASE			0xcd8U
+#define XHC_FSC2GOC__NCS_L			31U
+#define XHC_FSC2GOC__NCS_R			28U
+#define XHC_FSC2GOC__NCS_WIDTH			4U
+#define XHC_FSC2GOC__NCS_RESETVALUE		0x0U
+#define XHC_FSC2GOC__FSIZ_L			22U
+#define XHC_FSC2GOC__FSIZ_R			18U
+#define XHC_FSC2GOC__FSIZ_WIDTH			5U
+#define XHC_FSC2GOC__FSIZ_RESETVALUE		0x0U
+#define XHC_FSC2GOC__PSIZ_L			16U
+#define XHC_FSC2GOC__PSIZ_R			12U
+#define XHC_FSC2GOC__PSIZ_WIDTH			5U
+#define XHC_FSC2GOC__PSIZ_RESETVALUE		0x0U
+#define XHC_FSC2GOC__reserved_L			11U
+#define XHC_FSC2GOC__reserved_R			5U
+#define XHC_FSC2GOC__reserved_WIDTH		7U
+#define XHC_FSC2GOC__reserved_RESETVALUE	0x0U
+#define XHC_FSC2GOC__TSIZ_L			4U
+#define XHC_FSC2GOC__TSIZ_R			0U
+#define XHC_FSC2GOC__TSIZ_WIDTH			5U
+#define XHC_FSC2GOC__TSIZ_RESETVALUE		0x0U
+#define XHC_FSC2GOC__RESERVED_L			27U
+#define XHC_FSC2GOC__RESERVED_R			23U
+#define XHC_FSC2GOC_WIDTH			32U
+#define XHC_FSC2GOC__WIDTH			32U
+#define XHC_FSC2GOC_ALL_L			31U
+#define XHC_FSC2GOC_ALL_R			0U
+#define XHC_FSC2GOC__ALL_L			31U
+#define XHC_FSC2GOC__ALL_R			0U
+#define XHC_FSC2GOC_DATAMASK			0xf07dffffU
+#define XHC_FSC2GOC_RDWRMASK			0x0f820000U
+#define XHC_FSC2GOC_RESETVALUE			0x00000000U
+
+#define XHC_FSC2NOC_OFFSET			0xcdcU
+#define XHC_FSC2NOC_BASE			0xcdcU
+#define XHC_FSC2NOC__NCS_L			31U
+#define XHC_FSC2NOC__NCS_R			28U
+#define XHC_FSC2NOC__NCS_WIDTH			4U
+#define XHC_FSC2NOC__NCS_RESETVALUE		0x0U
+#define XHC_FSC2NOC__FSIZ_L			22U
+#define XHC_FSC2NOC__FSIZ_R			18U
+#define XHC_FSC2NOC__FSIZ_WIDTH			5U
+#define XHC_FSC2NOC__FSIZ_RESETVALUE		0x0U
+#define XHC_FSC2NOC__PSIZ_L			16U
+#define XHC_FSC2NOC__PSIZ_R			12U
+#define XHC_FSC2NOC__PSIZ_WIDTH			5U
+#define XHC_FSC2NOC__PSIZ_RESETVALUE		0x0U
+#define XHC_FSC2NOC__reserved_L			11U
+#define XHC_FSC2NOC__reserved_R			5U
+#define XHC_FSC2NOC__reserved_WIDTH		7U
+#define XHC_FSC2NOC__reserved_RESETVALUE	0x0U
+#define XHC_FSC2NOC__TSIZ_L			4U
+#define XHC_FSC2NOC__TSIZ_R			0U
+#define XHC_FSC2NOC__TSIZ_WIDTH			5U
+#define XHC_FSC2NOC__TSIZ_RESETVALUE		0x0U
+#define XHC_FSC2NOC__RESERVED_L			27U
+#define XHC_FSC2NOC__RESERVED_R			23U
+#define XHC_FSC2NOC_WIDTH			32U
+#define XHC_FSC2NOC__WIDTH			32U
+#define XHC_FSC2NOC_ALL_L			31U
+#define XHC_FSC2NOC_ALL_R			0U
+#define XHC_FSC2NOC__ALL_L			31U
+#define XHC_FSC2NOC__ALL_R			0U
+#define XHC_FSC2NOC_DATAMASK			0xf07dffffU
+#define XHC_FSC2NOC_RDWRMASK			0x0f820000U
+#define XHC_FSC2NOC_RESETVALUE			0x00000000U
+
+#define XHC_FSC2AIC_OFFSET			0xce0U
+#define XHC_FSC2AIC_BASE			0xce0U
+#define XHC_FSC2AIC__FSIZ_L			22U
+#define XHC_FSC2AIC__FSIZ_R			18U
+#define XHC_FSC2AIC__FSIZ_WIDTH			5U
+#define XHC_FSC2AIC__FSIZ_RESETVALUE		0x0U
+#define XHC_FSC2AIC__PSIZ_L			16U
+#define XHC_FSC2AIC__PSIZ_R			12U
+#define XHC_FSC2AIC__PSIZ_WIDTH			5U
+#define XHC_FSC2AIC__PSIZ_RESETVALUE		0x0U
+#define XHC_FSC2AIC__reserved_L			11U
+#define XHC_FSC2AIC__reserved_R			0U
+#define XHC_FSC2AIC__reserved_WIDTH		12U
+#define XHC_FSC2AIC__reserved_RESETVALUE	0x000U
+#define XHC_FSC2AIC__RESERVED_L			31U
+#define XHC_FSC2AIC__RESERVED_R			23U
+#define XHC_FSC2AIC_WIDTH			23U
+#define XHC_FSC2AIC__WIDTH			23U
+#define XHC_FSC2AIC_ALL_L			22U
+#define XHC_FSC2AIC_ALL_R			0U
+#define XHC_FSC2AIC__ALL_L			22U
+#define XHC_FSC2AIC__ALL_R			0U
+#define XHC_FSC2AIC_DATAMASK			0x007dffffU
+#define XHC_FSC2AIC_RDWRMASK			0xff820000U
+#define XHC_FSC2AIC_RESETVALUE			0x000000U
+
+#define XHC_FSC2PIC_OFFSET			0xce4U
+#define XHC_FSC2PIC_BASE			0xce4U
+#define XHC_FSC2PIC__NCS_L			31U
+#define XHC_FSC2PIC__NCS_R			28U
+#define XHC_FSC2PIC__NCS_WIDTH			4U
+#define XHC_FSC2PIC__NCS_RESETVALUE		0x0U
+#define XHC_FSC2PIC__reserved_L			27U
+#define XHC_FSC2PIC__reserved_R			5U
+#define XHC_FSC2PIC__reserved_WIDTH		23U
+#define XHC_FSC2PIC__reserved_RESETVALUE	0x0U
+#define XHC_FSC2PIC__TSIZ_L			4U
+#define XHC_FSC2PIC__TSIZ_R			0U
+#define XHC_FSC2PIC__TSIZ_WIDTH			5U
+#define XHC_FSC2PIC__TSIZ_RESETVALUE		0x0U
+#define XHC_FSC2PIC_WIDTH			32U
+#define XHC_FSC2PIC__WIDTH			32U
+#define XHC_FSC2PIC_ALL_L			31U
+#define XHC_FSC2PIC_ALL_R			0U
+#define XHC_FSC2PIC__ALL_L			31U
+#define XHC_FSC2PIC__ALL_R			0U
+#define XHC_FSC2PIC_DATAMASK			0xffffffffU
+#define XHC_FSC2PIC_RDWRMASK			0x00000000U
+#define XHC_FSC2PIC_RESETVALUE			0x00000000U
+
+#define XHC_FSC2GIC_OFFSET			0xce8U
+#define XHC_FSC2GIC_BASE			0xce8U
+#define XHC_FSC2GIC__NCS_L			31U
+#define XHC_FSC2GIC__NCS_R			28U
+#define XHC_FSC2GIC__NCS_WIDTH			4U
+#define XHC_FSC2GIC__NCS_RESETVALUE		0x0U
+#define XHC_FSC2GIC__reserved_L			27U
+#define XHC_FSC2GIC__reserved_R			5U
+#define XHC_FSC2GIC__reserved_WIDTH		23U
+#define XHC_FSC2GIC__reserved_RESETVALUE	0x0U
+#define XHC_FSC2GIC__TSIZ_L			4U
+#define XHC_FSC2GIC__TSIZ_R			0U
+#define XHC_FSC2GIC__TSIZ_WIDTH			5U
+#define XHC_FSC2GIC__TSIZ_RESETVALUE		0x0U
+#define XHC_FSC2GIC_WIDTH			32U
+#define XHC_FSC2GIC__WIDTH			32U
+#define XHC_FSC2GIC_ALL_L			31U
+#define XHC_FSC2GIC_ALL_R			0U
+#define XHC_FSC2GIC__ALL_L			31U
+#define XHC_FSC2GIC__ALL_R			0U
+#define XHC_FSC2GIC_DATAMASK			0xffffffffU
+#define XHC_FSC2GIC_RDWRMASK			0x00000000U
+#define XHC_FSC2GIC_RESETVALUE			0x00000000U
+
+#define XHC_FSC2NIC_OFFSET			0xcecU
+#define XHC_FSC2NIC_BASE			0xcecU
+#define XHC_FSC2NIC__NCS_L			31U
+#define XHC_FSC2NIC__NCS_R			28U
+#define XHC_FSC2NIC__NCS_WIDTH			4U
+#define XHC_FSC2NIC__NCS_RESETVALUE		0x0U
+#define XHC_FSC2NIC__reserved_L			27U
+#define XHC_FSC2NIC__reserved_R			5U
+#define XHC_FSC2NIC__reserved_WIDTH		23U
+#define XHC_FSC2NIC__reserved_RESETVALUE	0x0U
+#define XHC_FSC2NIC__TSIZ_L			4U
+#define XHC_FSC2NIC__TSIZ_R			0U
+#define XHC_FSC2NIC__TSIZ_WIDTH			5U
+#define XHC_FSC2NIC__TSIZ_RESETVALUE		0x0U
+#define XHC_FSC2NIC_WIDTH			32U
+#define XHC_FSC2NIC__WIDTH			32U
+#define XHC_FSC2NIC_ALL_L			31U
+#define XHC_FSC2NIC_ALL_R			0U
+#define XHC_FSC2NIC__ALL_L			31U
+#define XHC_FSC2NIC__ALL_R			0U
+#define XHC_FSC2NIC_DATAMASK			0xffffffffU
+#define XHC_FSC2NIC_RDWRMASK			0x00000000U
+#define XHC_FSC2NIC_RESETVALUE			0x00000000U
+
+#define XHC_ECHPRT2_OFFSET			0xcf0U
+#define XHC_ECHPRT2_BASE			0xcf0U
+#define XHC_ECHPRT2__HDP			31U
+#define XHC_ECHPRT2__HDP_L			31U
+#define XHC_ECHPRT2__HDP_R			31U
+#define XHC_ECHPRT2__HDP_WIDTH			1U
+#define XHC_ECHPRT2__HDP_RESETVALUE		0x0U
+#define XHC_ECHPRT2__FDP			30U
+#define XHC_ECHPRT2__FDP_L			30U
+#define XHC_ECHPRT2__FDP_R			30U
+#define XHC_ECHPRT2__FDP_WIDTH			1U
+#define XHC_ECHPRT2__FDP_RESETVALUE		0x0U
+#define XHC_ECHPRT2__reserved_L			29U
+#define XHC_ECHPRT2__reserved_R			17U
+#define XHC_ECHPRT2__reserved_WIDTH		13U
+#define XHC_ECHPRT2__reserved_RESETVALUE	0x0U
+#define XHC_ECHPRT2__HST			16U
+#define XHC_ECHPRT2__HST_L			16U
+#define XHC_ECHPRT2__HST_R			16U
+#define XHC_ECHPRT2__HST_WIDTH			1U
+#define XHC_ECHPRT2__HST_RESETVALUE		0x0U
+#define XHC_ECHPRT2__NCP_L			15U
+#define XHC_ECHPRT2__NCP_R			8U
+#define XHC_ECHPRT2__NCP_WIDTH			8U
+#define XHC_ECHPRT2__NCP_RESETVALUE		0x04U
+#define XHC_ECHPRT2__CID_L			7U
+#define XHC_ECHPRT2__CID_R			0U
+#define XHC_ECHPRT2__CID_WIDTH			8U
+#define XHC_ECHPRT2__CID_RESETVALUE		0xc8U
+#define XHC_ECHPRT2_WIDTH			32U
+#define XHC_ECHPRT2__WIDTH			32U
+#define XHC_ECHPRT2_ALL_L			31U
+#define XHC_ECHPRT2_ALL_R			0U
+#define XHC_ECHPRT2__ALL_L			31U
+#define XHC_ECHPRT2__ALL_R			0U
+#define XHC_ECHPRT2_DATAMASK			0xffffffffU
+#define XHC_ECHPRT2_RDWRMASK			0x00000000U
+#define XHC_ECHPRT2_RESETVALUE			0x000004c8U
+
+#define XHC_PRT2HSC_OFFSET			0xcf8U
+#define XHC_PRT2HSC_BASE			0xcf8U
+#define XHC_PRT2HSC__TMR_L			31U
+#define XHC_PRT2HSC__TMR_R			16U
+#define XHC_PRT2HSC__TMR_WIDTH			16U
+#define XHC_PRT2HSC__TMR_RESETVALUE		0x0000U
+#define XHC_PRT2HSC__RSL_L			7U
+#define XHC_PRT2HSC__RSL_R			6U
+#define XHC_PRT2HSC__RSL_WIDTH			2U
+#define XHC_PRT2HSC__RSL_RESETVALUE		0x0U
+#define XHC_PRT2HSC__AS_M_L			5U
+#define XHC_PRT2HSC__AS_M_R			4U
+#define XHC_PRT2HSC__AS_M_WIDTH			2U
+#define XHC_PRT2HSC__AS_M_RESETVALUE		0x0U
+#define XHC_PRT2HSC__CMD_L			3U
+#define XHC_PRT2HSC__CMD_R			2U
+#define XHC_PRT2HSC__CMD_WIDTH			2U
+#define XHC_PRT2HSC__CMD_RESETVALUE		0x0U
+#define XHC_PRT2HSC__reserved			1U
+#define XHC_PRT2HSC__reserved_L			1U
+#define XHC_PRT2HSC__reserved_R			1U
+#define XHC_PRT2HSC__reserved_WIDTH		1U
+#define XHC_PRT2HSC__reserved_RESETVALUE	0x0U
+#define XHC_PRT2HSC__STB			0U
+#define XHC_PRT2HSC__STB_L			0U
+#define XHC_PRT2HSC__STB_R			0U
+#define XHC_PRT2HSC__STB_WIDTH			1U
+#define XHC_PRT2HSC__STB_RESETVALUE		0x0U
+#define XHC_PRT2HSC__RESERVED_L			15U
+#define XHC_PRT2HSC__RESERVED_R			8U
+#define XHC_PRT2HSC_WIDTH			32U
+#define XHC_PRT2HSC__WIDTH			32U
+#define XHC_PRT2HSC_ALL_L			31U
+#define XHC_PRT2HSC_ALL_R			0U
+#define XHC_PRT2HSC__ALL_L			31U
+#define XHC_PRT2HSC__ALL_R			0U
+#define XHC_PRT2HSC_DATAMASK			0xffff00ffU
+#define XHC_PRT2HSC_RDWRMASK			0x0000ff00U
+#define XHC_PRT2HSC_RESETVALUE			0x00000000U
+
+#define XHC_PRT2HSR_OFFSET			0xcfcU
+#define XHC_PRT2HSR_BASE			0xcfcU
+#define XHC_PRT2HSR__RNAK_L			31U
+#define XHC_PRT2HSR__RNAK_R			24U
+#define XHC_PRT2HSR__RNAK_WIDTH			8U
+#define XHC_PRT2HSR__RNAK_RESETVALUE		0x00U
+#define XHC_PRT2HSR__HSTX_L			23U
+#define XHC_PRT2HSR__HSTX_R			16U
+#define XHC_PRT2HSR__HSTX_WIDTH			8U
+#define XHC_PRT2HSR__HSTX_RESETVALUE		0x00U
+#define XHC_PRT2HSR__HSRX_L			15U
+#define XHC_PRT2HSR__HSRX_R			8U
+#define XHC_PRT2HSR__HSRX_WIDTH			8U
+#define XHC_PRT2HSR__HSRX_RESETVALUE		0x00U
+#define XHC_PRT2HSR__SPLT_L			7U
+#define XHC_PRT2HSR__SPLT_R			0U
+#define XHC_PRT2HSR__SPLT_WIDTH			8U
+#define XHC_PRT2HSR__SPLT_RESETVALUE		0x00U
+#define XHC_PRT2HSR_WIDTH			32U
+#define XHC_PRT2HSR__WIDTH			32U
+#define XHC_PRT2HSR_ALL_L			31U
+#define XHC_PRT2HSR_ALL_R			0U
+#define XHC_PRT2HSR__ALL_L			31U
+#define XHC_PRT2HSR__ALL_R			0U
+#define XHC_PRT2HSR_DATAMASK			0xffffffffU
+#define XHC_PRT2HSR_RDWRMASK			0x00000000U
+#define XHC_PRT2HSR_RESETVALUE			0x00000000U
+
+#define XHC_ECHRH2_OFFSET			0xd00U
+#define XHC_ECHRH2_BASE				0xd00U
+#define XHC_ECHRH2__MTT				31U
+#define XHC_ECHRH2__MTT_L			31U
+#define XHC_ECHRH2__MTT_R			31U
+#define XHC_ECHRH2__MTT_WIDTH			1U
+#define XHC_ECHRH2__MTT_RESETVALUE		0x0U
+#define XHC_ECHRH2__RPO_L			30U
+#define XHC_ECHRH2__RPO_R			24U
+#define XHC_ECHRH2__RPO_WIDTH			7U
+#define XHC_ECHRH2__RPO_RESETVALUE		0x0U
+#define XHC_ECHRH2__reserved_L			23U
+#define XHC_ECHRH2__reserved_R			22U
+#define XHC_ECHRH2__reserved_WIDTH		2U
+#define XHC_ECHRH2__reserved_RESETVALUE		0x0U
+#define XHC_ECHRH2__RPN_L			21U
+#define XHC_ECHRH2__RPN_R			20U
+#define XHC_ECHRH2__RPN_WIDTH			2U
+#define XHC_ECHRH2__RPN_RESETVALUE		0x0U
+#define XHC_ECHRH2__DNR_L			19U
+#define XHC_ECHRH2__DNR_R			16U
+#define XHC_ECHRH2__DNR_WIDTH			4U
+#define XHC_ECHRH2__DNR_RESETVALUE		0x0U
+#define XHC_ECHRH2__NCP_L			15U
+#define XHC_ECHRH2__NCP_R			8U
+#define XHC_ECHRH2__NCP_WIDTH			8U
+#define XHC_ECHRH2__NCP_RESETVALUE		0x0cU
+#define XHC_ECHRH2__CID_L			7U
+#define XHC_ECHRH2__CID_R			0U
+#define XHC_ECHRH2__CID_WIDTH			8U
+#define XHC_ECHRH2__CID_RESETVALUE		0xc9U
+#define XHC_ECHRH2_WIDTH			32U
+#define XHC_ECHRH2__WIDTH			32U
+#define XHC_ECHRH2_ALL_L			31U
+#define XHC_ECHRH2_ALL_R			0U
+#define XHC_ECHRH2__ALL_L			31U
+#define XHC_ECHRH2__ALL_R			0U
+#define XHC_ECHRH2_DATAMASK			0xffffffffU
+#define XHC_ECHRH2_RDWRMASK			0x00000000U
+#define XHC_ECHRH2_RESETVALUE			0x00000cc9U
+
+#define XHC_RH2DES_OFFSET			0xd04U
+#define XHC_RH2DES_BASE				0xd04U
+#define XHC_RH2DES__PIS3_L			31U
+#define XHC_RH2DES__PIS3_R			30U
+#define XHC_RH2DES__PIS3_WIDTH			2U
+#define XHC_RH2DES__PIS3_RESETVALUE		0x0U
+#define XHC_RH2DES__HIST3			24U
+#define XHC_RH2DES__HIST3_L			24U
+#define XHC_RH2DES__HIST3_R			24U
+#define XHC_RH2DES__HIST3_WIDTH			1U
+#define XHC_RH2DES__HIST3_RESETVALUE		0x0U
+#define XHC_RH2DES__PIS2_L			23U
+#define XHC_RH2DES__PIS2_R			22U
+#define XHC_RH2DES__PIS2_WIDTH			2U
+#define XHC_RH2DES__PIS2_RESETVALUE		0x0U
+#define XHC_RH2DES__HIST2			16U
+#define XHC_RH2DES__HIST2_L			16U
+#define XHC_RH2DES__HIST2_R			16U
+#define XHC_RH2DES__HIST2_WIDTH			1U
+#define XHC_RH2DES__HIST2_RESETVALUE		0x0U
+#define XHC_RH2DES__PIS1_L			15U
+#define XHC_RH2DES__PIS1_R			14U
+#define XHC_RH2DES__PIS1_WIDTH			2U
+#define XHC_RH2DES__PIS1_RESETVALUE		0x0U
+#define XHC_RH2DES__HIST1			8U
+#define XHC_RH2DES__HIST1_L			8U
+#define XHC_RH2DES__HIST1_R			8U
+#define XHC_RH2DES__HIST1_WIDTH			1U
+#define XHC_RH2DES__HIST1_RESETVALUE		0x0U
+#define XHC_RH2DES__PIS0_L			7U
+#define XHC_RH2DES__PIS0_R			6U
+#define XHC_RH2DES__PIS0_WIDTH			2U
+#define XHC_RH2DES__PIS0_RESETVALUE		0x0U
+#define XHC_RH2DES__reserved_L			5U
+#define XHC_RH2DES__reserved_R			1U
+#define XHC_RH2DES__reserved_WIDTH		5U
+#define XHC_RH2DES__reserved_RESETVALUE		0x0U
+#define XHC_RH2DES__HIST0			0U
+#define XHC_RH2DES__HIST0_L			0U
+#define XHC_RH2DES__HIST0_R			0U
+#define XHC_RH2DES__HIST0_WIDTH			1U
+#define XHC_RH2DES__HIST0_RESETVALUE		0x0U
+#define XHC_RH2DES__RESERVED_0_L		29U
+#define XHC_RH2DES__RESERVED_0_R		25U
+#define XHC_RH2DES__RESERVED_1_L		21U
+#define XHC_RH2DES__RESERVED_1_R		17U
+#define XHC_RH2DES__RESERVED_2_L		13U
+#define XHC_RH2DES__RESERVED_2_R		9U
+#define XHC_RH2DES__RESERVED_L			29U
+#define XHC_RH2DES__RESERVED_R			25U
+#define XHC_RH2DES_WIDTH			32U
+#define XHC_RH2DES__WIDTH			32U
+#define XHC_RH2DES_ALL_L			31U
+#define XHC_RH2DES_ALL_R			0U
+#define XHC_RH2DES__ALL_L			31U
+#define XHC_RH2DES__ALL_R			0U
+#define XHC_RH2DES_DATAMASK			0xc1c1c1ffU
+#define XHC_RH2DES_RDWRMASK			0x3e3e3e00U
+#define XHC_RH2DES_RESETVALUE			0x00000000U
+
+#define XHC_RH2HSC0_OFFSET			0xd10U
+#define XHC_RH2HSC0_BASE			0xd10U
+#define XHC_RH2HSC0__TMR_L			31U
+#define XHC_RH2HSC0__TMR_R			16U
+#define XHC_RH2HSC0__TMR_WIDTH			16U
+#define XHC_RH2HSC0__TMR_RESETVALUE		0x0000U
+#define XHC_RH2HSC0__RSL_L			7U
+#define XHC_RH2HSC0__RSL_R			6U
+#define XHC_RH2HSC0__RSL_WIDTH			2U
+#define XHC_RH2HSC0__RSL_RESETVALUE		0x0U
+#define XHC_RH2HSC0__AS_M_L			5U
+#define XHC_RH2HSC0__AS_M_R			4U
+#define XHC_RH2HSC0__AS_M_WIDTH			2U
+#define XHC_RH2HSC0__AS_M_RESETVALUE		0x0U
+#define XHC_RH2HSC0__CMD_L			3U
+#define XHC_RH2HSC0__CMD_R			2U
+#define XHC_RH2HSC0__CMD_WIDTH			2U
+#define XHC_RH2HSC0__CMD_RESETVALUE		0x0U
+#define XHC_RH2HSC0__reserved			1U
+#define XHC_RH2HSC0__reserved_L			1U
+#define XHC_RH2HSC0__reserved_R			1U
+#define XHC_RH2HSC0__reserved_WIDTH		1U
+#define XHC_RH2HSC0__reserved_RESETVALUE	0x0U
+#define XHC_RH2HSC0__STB			0U
+#define XHC_RH2HSC0__STB_L			0U
+#define XHC_RH2HSC0__STB_R			0U
+#define XHC_RH2HSC0__STB_WIDTH			1U
+#define XHC_RH2HSC0__STB_RESETVALUE		0x0U
+#define XHC_RH2HSC0__RESERVED_L			15U
+#define XHC_RH2HSC0__RESERVED_R			8U
+#define XHC_RH2HSC0_WIDTH			32U
+#define XHC_RH2HSC0__WIDTH			32U
+#define XHC_RH2HSC0_ALL_L			31U
+#define XHC_RH2HSC0_ALL_R			0U
+#define XHC_RH2HSC0__ALL_L			31U
+#define XHC_RH2HSC0__ALL_R			0U
+#define XHC_RH2HSC0_DATAMASK			0xffff00ffU
+#define XHC_RH2HSC0_RDWRMASK			0x0000ff00U
+#define XHC_RH2HSC0_RESETVALUE			0x00000000U
+
+#define XHC_RH2HSR0_OFFSET			0xd14U
+#define XHC_RH2HSR0_BASE			0xd14U
+#define XHC_RH2HSR0__C2U_L			31U
+#define XHC_RH2HSR0__C2U_R			24U
+#define XHC_RH2HSR0__C2U_WIDTH			8U
+#define XHC_RH2HSR0__C2U_RESETVALUE		0x00U
+#define XHC_RH2HSR0__C1U_L			23U
+#define XHC_RH2HSR0__C1U_R			16U
+#define XHC_RH2HSR0__C1U_WIDTH			8U
+#define XHC_RH2HSR0__C1U_RESETVALUE		0x00U
+#define XHC_RH2HSR0__reserved_L			15U
+#define XHC_RH2HSR0__reserved_R			8U
+#define XHC_RH2HSR0__reserved_WIDTH		8U
+#define XHC_RH2HSR0__reserved_RESETVALUE	0x00U
+#define XHC_RH2HSR0__RTY_L			7U
+#define XHC_RH2HSR0__RTY_R			0U
+#define XHC_RH2HSR0__RTY_WIDTH			8U
+#define XHC_RH2HSR0__RTY_RESETVALUE		0x00U
+#define XHC_RH2HSR0_WIDTH			32U
+#define XHC_RH2HSR0__WIDTH			32U
+#define XHC_RH2HSR0_ALL_L			31U
+#define XHC_RH2HSR0_ALL_R			0U
+#define XHC_RH2HSR0__ALL_L			31U
+#define XHC_RH2HSR0__ALL_R			0U
+#define XHC_RH2HSR0_DATAMASK			0xffffffffU
+#define XHC_RH2HSR0_RDWRMASK			0x00000000U
+#define XHC_RH2HSR0_RESETVALUE			0x00000000U
+
+#define XHC_RH2HSC1_OFFSET			0xd18U
+#define XHC_RH2HSC1_BASE			0xd18U
+#define XHC_RH2HSC1__TMR_L			31U
+#define XHC_RH2HSC1__TMR_R			16U
+#define XHC_RH2HSC1__TMR_WIDTH			16U
+#define XHC_RH2HSC1__TMR_RESETVALUE		0x0000U
+#define XHC_RH2HSC1__RSL_L			7U
+#define XHC_RH2HSC1__RSL_R			6U
+#define XHC_RH2HSC1__RSL_WIDTH			2U
+#define XHC_RH2HSC1__RSL_RESETVALUE		0x0U
+#define XHC_RH2HSC1__AS_M_L			5U
+#define XHC_RH2HSC1__AS_M_R			4U
+#define XHC_RH2HSC1__AS_M_WIDTH			2U
+#define XHC_RH2HSC1__AS_M_RESETVALUE		0x0U
+#define XHC_RH2HSC1__CMD_L			3U
+#define XHC_RH2HSC1__CMD_R			2U
+#define XHC_RH2HSC1__CMD_WIDTH			2U
+#define XHC_RH2HSC1__CMD_RESETVALUE		0x0U
+#define XHC_RH2HSC1__reserved			1U
+#define XHC_RH2HSC1__reserved_L			1U
+#define XHC_RH2HSC1__reserved_R			1U
+#define XHC_RH2HSC1__reserved_WIDTH		1U
+#define XHC_RH2HSC1__reserved_RESETVALUE	0x0U
+#define XHC_RH2HSC1__STB			0U
+#define XHC_RH2HSC1__STB_L			0U
+#define XHC_RH2HSC1__STB_R			0U
+#define XHC_RH2HSC1__STB_WIDTH			1U
+#define XHC_RH2HSC1__STB_RESETVALUE		0x0U
+#define XHC_RH2HSC1__RESERVED_L			15U
+#define XHC_RH2HSC1__RESERVED_R			8U
+#define XHC_RH2HSC1_WIDTH			32U
+#define XHC_RH2HSC1__WIDTH			32U
+#define XHC_RH2HSC1_ALL_L			31U
+#define XHC_RH2HSC1_ALL_R			0U
+#define XHC_RH2HSC1__ALL_L			31U
+#define XHC_RH2HSC1__ALL_R			0U
+#define XHC_RH2HSC1_DATAMASK			0xffff00ffU
+#define XHC_RH2HSC1_RDWRMASK			0x0000ff00U
+#define XHC_RH2HSC1_RESETVALUE			0x00000000U
+
+#define XHC_RH2HSR1_OFFSET			0xd1cU
+#define XHC_RH2HSR1_BASE			0xd1cU
+#define XHC_RH2HSR1__C2U_L			31U
+#define XHC_RH2HSR1__C2U_R			24U
+#define XHC_RH2HSR1__C2U_WIDTH			8U
+#define XHC_RH2HSR1__C2U_RESETVALUE		0x00U
+#define XHC_RH2HSR1__C1U_L			23U
+#define XHC_RH2HSR1__C1U_R			16U
+#define XHC_RH2HSR1__C1U_WIDTH			8U
+#define XHC_RH2HSR1__C1U_RESETVALUE		0x00U
+#define XHC_RH2HSR1__reserved_L			15U
+#define XHC_RH2HSR1__reserved_R			8U
+#define XHC_RH2HSR1__reserved_WIDTH		8U
+#define XHC_RH2HSR1__reserved_RESETVALUE	0x00U
+#define XHC_RH2HSR1__RTY_L			7U
+#define XHC_RH2HSR1__RTY_R			0U
+#define XHC_RH2HSR1__RTY_WIDTH			8U
+#define XHC_RH2HSR1__RTY_RESETVALUE		0x00U
+#define XHC_RH2HSR1_WIDTH			32U
+#define XHC_RH2HSR1__WIDTH			32U
+#define XHC_RH2HSR1_ALL_L			31U
+#define XHC_RH2HSR1_ALL_R			0U
+#define XHC_RH2HSR1__ALL_L			31U
+#define XHC_RH2HSR1__ALL_R			0U
+#define XHC_RH2HSR1_DATAMASK			0xffffffffU
+#define XHC_RH2HSR1_RDWRMASK			0x00000000U
+#define XHC_RH2HSR1_RESETVALUE			0x00000000U
+
+#define XHC_RH2HSC2_OFFSET			0xd20U
+#define XHC_RH2HSC2_BASE			0xd20U
+#define XHC_RH2HSC2__TMR_L			31U
+#define XHC_RH2HSC2__TMR_R			16U
+#define XHC_RH2HSC2__TMR_WIDTH			16U
+#define XHC_RH2HSC2__TMR_RESETVALUE		0x0000U
+#define XHC_RH2HSC2__RSL_L			7U
+#define XHC_RH2HSC2__RSL_R			6U
+#define XHC_RH2HSC2__RSL_WIDTH			2U
+#define XHC_RH2HSC2__RSL_RESETVALUE		0x0U
+#define XHC_RH2HSC2__AS_M_L			5U
+#define XHC_RH2HSC2__AS_M_R			4U
+#define XHC_RH2HSC2__AS_M_WIDTH			2U
+#define XHC_RH2HSC2__AS_M_RESETVALUE		0x0U
+#define XHC_RH2HSC2__CMD_L			3U
+#define XHC_RH2HSC2__CMD_R			2U
+#define XHC_RH2HSC2__CMD_WIDTH			2U
+#define XHC_RH2HSC2__CMD_RESETVALUE		0x0U
+#define XHC_RH2HSC2__reserved			1U
+#define XHC_RH2HSC2__reserved_L			1U
+#define XHC_RH2HSC2__reserved_R			1U
+#define XHC_RH2HSC2__reserved_WIDTH		1U
+#define XHC_RH2HSC2__reserved_RESETVALUE	0x0U
+#define XHC_RH2HSC2__STB			0U
+#define XHC_RH2HSC2__STB_L			0U
+#define XHC_RH2HSC2__STB_R			0U
+#define XHC_RH2HSC2__STB_WIDTH			1U
+#define XHC_RH2HSC2__STB_RESETVALUE		0x0U
+#define XHC_RH2HSC2__RESERVED_L			15U
+#define XHC_RH2HSC2__RESERVED_R			8U
+#define XHC_RH2HSC2_WIDTH			32U
+#define XHC_RH2HSC2__WIDTH			32U
+#define XHC_RH2HSC2_ALL_L			31U
+#define XHC_RH2HSC2_ALL_R			0U
+#define XHC_RH2HSC2__ALL_L			31U
+#define XHC_RH2HSC2__ALL_R			0U
+#define XHC_RH2HSC2_DATAMASK			0xffff00ffU
+#define XHC_RH2HSC2_RDWRMASK			0x0000ff00U
+#define XHC_RH2HSC2_RESETVALUE			0x00000000U
+
+#define XHC_RH2HSR2_OFFSET			0xd24U
+#define XHC_RH2HSR2_BASE			0xd24U
+#define XHC_RH2HSR2__C2U_L			31U
+#define XHC_RH2HSR2__C2U_R			24U
+#define XHC_RH2HSR2__C2U_WIDTH			8U
+#define XHC_RH2HSR2__C2U_RESETVALUE		0x00U
+#define XHC_RH2HSR2__C1U_L			23U
+#define XHC_RH2HSR2__C1U_R			16U
+#define XHC_RH2HSR2__C1U_WIDTH			8U
+#define XHC_RH2HSR2__C1U_RESETVALUE		0x00U
+#define XHC_RH2HSR2__reserved_L			15U
+#define XHC_RH2HSR2__reserved_R			8U
+#define XHC_RH2HSR2__reserved_WIDTH		8U
+#define XHC_RH2HSR2__reserved_RESETVALUE	0x00U
+#define XHC_RH2HSR2__RTY_L			7U
+#define XHC_RH2HSR2__RTY_R			0U
+#define XHC_RH2HSR2__RTY_WIDTH			8U
+#define XHC_RH2HSR2__RTY_RESETVALUE		0x00U
+#define XHC_RH2HSR2_WIDTH			32U
+#define XHC_RH2HSR2__WIDTH			32U
+#define XHC_RH2HSR2_ALL_L			31U
+#define XHC_RH2HSR2_ALL_R			0U
+#define XHC_RH2HSR2__ALL_L			31U
+#define XHC_RH2HSR2__ALL_R			0U
+#define XHC_RH2HSR2_DATAMASK			0xffffffffU
+#define XHC_RH2HSR2_RDWRMASK			0x00000000U
+#define XHC_RH2HSR2_RESETVALUE			0x00000000U
+
+#define XHC_RH2HSC3_OFFSET			0xd28U
+#define XHC_RH2HSC3_BASE			0xd28U
+#define XHC_RH2HSC3__TMR_L			31U
+#define XHC_RH2HSC3__TMR_R			16U
+#define XHC_RH2HSC3__TMR_WIDTH			16U
+#define XHC_RH2HSC3__TMR_RESETVALUE		0x0000U
+#define XHC_RH2HSC3__RSL_L			7U
+#define XHC_RH2HSC3__RSL_R			6U
+#define XHC_RH2HSC3__RSL_WIDTH			2U
+#define XHC_RH2HSC3__RSL_RESETVALUE		0x0U
+#define XHC_RH2HSC3__AS_M_L			5U
+#define XHC_RH2HSC3__AS_M_R			4U
+#define XHC_RH2HSC3__AS_M_WIDTH			2U
+#define XHC_RH2HSC3__AS_M_RESETVALUE		0x0U
+#define XHC_RH2HSC3__CMD_L			3U
+#define XHC_RH2HSC3__CMD_R			2U
+#define XHC_RH2HSC3__CMD_WIDTH			2U
+#define XHC_RH2HSC3__CMD_RESETVALUE		0x0U
+#define XHC_RH2HSC3__reserved			1U
+#define XHC_RH2HSC3__reserved_L			1U
+#define XHC_RH2HSC3__reserved_R			1U
+#define XHC_RH2HSC3__reserved_WIDTH		1U
+#define XHC_RH2HSC3__reserved_RESETVALUE	0x0U
+#define XHC_RH2HSC3__STB			0U
+#define XHC_RH2HSC3__STB_L			0U
+#define XHC_RH2HSC3__STB_R			0U
+#define XHC_RH2HSC3__STB_WIDTH			1U
+#define XHC_RH2HSC3__STB_RESETVALUE		0x0U
+#define XHC_RH2HSC3__RESERVED_L			15U
+#define XHC_RH2HSC3__RESERVED_R			8U
+#define XHC_RH2HSC3_WIDTH			32U
+#define XHC_RH2HSC3__WIDTH			32U
+#define XHC_RH2HSC3_ALL_L			31U
+#define XHC_RH2HSC3_ALL_R			0U
+#define XHC_RH2HSC3__ALL_L			31U
+#define XHC_RH2HSC3__ALL_R			0U
+#define XHC_RH2HSC3_DATAMASK			0xffff00ffU
+#define XHC_RH2HSC3_RDWRMASK			0x0000ff00U
+#define XHC_RH2HSC3_RESETVALUE			0x00000000U
+
+#define XHC_RH2HSR3_OFFSET			0xd2cU
+#define XHC_RH2HSR3_BASE			0xd2cU
+#define XHC_RH2HSR3__C2U_L			31U
+#define XHC_RH2HSR3__C2U_R			24U
+#define XHC_RH2HSR3__C2U_WIDTH			8U
+#define XHC_RH2HSR3__C2U_RESETVALUE		0x00U
+#define XHC_RH2HSR3__C1U_L			23U
+#define XHC_RH2HSR3__C1U_R			16U
+#define XHC_RH2HSR3__C1U_WIDTH			8U
+#define XHC_RH2HSR3__C1U_RESETVALUE		0x00U
+#define XHC_RH2HSR3__reserved_L			15U
+#define XHC_RH2HSR3__reserved_R			8U
+#define XHC_RH2HSR3__reserved_WIDTH		8U
+#define XHC_RH2HSR3__reserved_RESETVALUE	0x00U
+#define XHC_RH2HSR3__RTY_L			7U
+#define XHC_RH2HSR3__RTY_R			0U
+#define XHC_RH2HSR3__RTY_WIDTH			8U
+#define XHC_RH2HSR3__RTY_RESETVALUE		0x00U
+#define XHC_RH2HSR3_WIDTH			32U
+#define XHC_RH2HSR3__WIDTH			32U
+#define XHC_RH2HSR3_ALL_L			31U
+#define XHC_RH2HSR3_ALL_R			0U
+#define XHC_RH2HSR3__ALL_L			31U
+#define XHC_RH2HSR3__ALL_R			0U
+#define XHC_RH2HSR3_DATAMASK			0xffffffffU
+#define XHC_RH2HSR3_RDWRMASK			0x00000000U
+#define XHC_RH2HSR3_RESETVALUE			0x00000000U
+
+#define XHC_ECHU2P_OFFSET			0xd30U
+#define XHC_ECHU2P_BASE				0xd30U
+#define XHC_ECHU2P__reserved_L			31U
+#define XHC_ECHU2P__reserved_R			16U
+#define XHC_ECHU2P__reserved_WIDTH		16U
+#define XHC_ECHU2P__reserved_RESETVALUE		0x0000U
+#define XHC_ECHU2P__NCP_L			15U
+#define XHC_ECHU2P__NCP_R			8U
+#define XHC_ECHU2P__NCP_WIDTH			8U
+#define XHC_ECHU2P__NCP_RESETVALUE		0x04U
+#define XHC_ECHU2P__CID_L			7U
+#define XHC_ECHU2P__CID_R			0U
+#define XHC_ECHU2P__CID_WIDTH			8U
+#define XHC_ECHU2P__CID_RESETVALUE		0xcaU
+#define XHC_ECHU2P_WIDTH			32U
+#define XHC_ECHU2P__WIDTH			32U
+#define XHC_ECHU2P_ALL_L			31U
+#define XHC_ECHU2P_ALL_R			0U
+#define XHC_ECHU2P__ALL_L			31U
+#define XHC_ECHU2P__ALL_R			0U
+#define XHC_ECHU2P_DATAMASK			0xffffffffU
+#define XHC_ECHU2P_RDWRMASK			0x00000000U
+#define XHC_ECHU2P_RESETVALUE			0x000004caU
+
+#define XHC_U2PVER_OFFSET			0xd34U
+#define XHC_U2PVER_BASE				0xd34U
+#define XHC_U2PVER__MAJ_L			31U
+#define XHC_U2PVER__MAJ_R			28U
+#define XHC_U2PVER__MAJ_WIDTH			4U
+#define XHC_U2PVER__MAJ_RESETVALUE		0x0U
+#define XHC_U2PVER__MIN_L			27U
+#define XHC_U2PVER__MIN_R			24U
+#define XHC_U2PVER__MIN_WIDTH			4U
+#define XHC_U2PVER__MIN_RESETVALUE		0x0U
+#define XHC_U2PVER__RLS_L			23U
+#define XHC_U2PVER__RLS_R			20U
+#define XHC_U2PVER__RLS_WIDTH			4U
+#define XHC_U2PVER__RLS_RESETVALUE		0x0U
+#define XHC_U2PVER__reserved_L			19U
+#define XHC_U2PVER__reserved_R			0U
+#define XHC_U2PVER__reserved_WIDTH		20U
+#define XHC_U2PVER__reserved_RESETVALUE		0x00000U
+#define XHC_U2PVER_WIDTH			32U
+#define XHC_U2PVER__WIDTH			32U
+#define XHC_U2PVER_ALL_L			31U
+#define XHC_U2PVER_ALL_R			0U
+#define XHC_U2PVER__ALL_L			31U
+#define XHC_U2PVER__ALL_R			0U
+#define XHC_U2PVER_DATAMASK			0xffffffffU
+#define XHC_U2PVER_RDWRMASK			0x00000000U
+#define XHC_U2PVER_RESETVALUE			0x00000000U
+
+#define XHC_U2PMGN_OFFSET			0xd38U
+#define XHC_U2PMGN_BASE				0xd38U
+#define XHC_U2PMGN__MGN_L			31U
+#define XHC_U2PMGN__MGN_R			0U
+#define XHC_U2PMGN__MGN_WIDTH			32U
+#define XHC_U2PMGN__MGN_RESETVALUE		0x4b534b4dU
+#define XHC_U2PMGN_WIDTH			32U
+#define XHC_U2PMGN__WIDTH			32U
+#define XHC_U2PMGN_ALL_L			31U
+#define XHC_U2PMGN_ALL_R			0U
+#define XHC_U2PMGN__ALL_L			31U
+#define XHC_U2PMGN__ALL_R			0U
+#define XHC_U2PMGN_DATAMASK			0xffffffffU
+#define XHC_U2PMGN_RDWRMASK			0x00000000U
+#define XHC_U2PMGN_RESETVALUE			0x4b534b4dU
+
+#define XHC_ECHRSV2_OFFSET			0xd40U
+#define XHC_ECHRSV2_BASE			0xd40U
+#define XHC_ECHRSV2__reserved_L			31U
+#define XHC_ECHRSV2__reserved_R			16U
+#define XHC_ECHRSV2__reserved_WIDTH		16U
+#define XHC_ECHRSV2__reserved_RESETVALUE	0x0000U
+#define XHC_ECHRSV2__NCP_L			15U
+#define XHC_ECHRSV2__NCP_R			8U
+#define XHC_ECHRSV2__NCP_WIDTH			8U
+#define XHC_ECHRSV2__NCP_RESETVALUE		0x00U
+#define XHC_ECHRSV2__CID_L			7U
+#define XHC_ECHRSV2__CID_R			0U
+#define XHC_ECHRSV2__CID_WIDTH			8U
+#define XHC_ECHRSV2__CID_RESETVALUE		0xffU
+#define XHC_ECHRSV2_WIDTH			32U
+#define XHC_ECHRSV2__WIDTH			32U
+#define XHC_ECHRSV2_ALL_L			31U
+#define XHC_ECHRSV2_ALL_R			0U
+#define XHC_ECHRSV2__ALL_L			31U
+#define XHC_ECHRSV2__ALL_R			0U
+#define XHC_ECHRSV2_DATAMASK			0xffffffffU
+#define XHC_ECHRSV2_RDWRMASK			0x00000000U
+#define XHC_ECHRSV2_RESETVALUE			0x000000ffU
+
+#define XHC_ECHIRA_OFFSET			0xf90U
+#define XHC_ECHIRA_BASE				0xf90U
+#define XHC_ECHIRA__reserved_L			31U
+#define XHC_ECHIRA__reserved_R			16U
+#define XHC_ECHIRA__reserved_WIDTH		16U
+#define XHC_ECHIRA__reserved_RESETVALUE		0x0000U
+#define XHC_ECHIRA__NCP_L			15U
+#define XHC_ECHIRA__NCP_R			8U
+#define XHC_ECHIRA__NCP_WIDTH			8U
+#define XHC_ECHIRA__NCP_RESETVALUE		0x04U
+#define XHC_ECHIRA__CID_L			7U
+#define XHC_ECHIRA__CID_R			0U
+#define XHC_ECHIRA__CID_WIDTH			8U
+#define XHC_ECHIRA__CID_RESETVALUE		0xfdU
+#define XHC_ECHIRA_WIDTH			32U
+#define XHC_ECHIRA__WIDTH			32U
+#define XHC_ECHIRA_ALL_L			31U
+#define XHC_ECHIRA_ALL_R			0U
+#define XHC_ECHIRA__ALL_L			31U
+#define XHC_ECHIRA__ALL_R			0U
+#define XHC_ECHIRA_DATAMASK			0xffffffffU
+#define XHC_ECHIRA_RDWRMASK			0x00000000U
+#define XHC_ECHIRA_RESETVALUE			0x000004fdU
+
+#define XHC_IRAADR_OFFSET			0xf98U
+#define XHC_IRAADR_BASE				0xf98U
+#define XHC_IRAADR__ADR_L			23U
+#define XHC_IRAADR__ADR_R			2U
+#define XHC_IRAADR__ADR_WIDTH			22U
+#define XHC_IRAADR__ADR_RESETVALUE		0x0U
+#define XHC_IRAADR__reserved			1U
+#define XHC_IRAADR__reserved_L			1U
+#define XHC_IRAADR__reserved_R			1U
+#define XHC_IRAADR__reserved_WIDTH		1U
+#define XHC_IRAADR__reserved_RESETVALUE		0x0U
+#define XHC_IRAADR__MOD				0U
+#define XHC_IRAADR__MOD_L			0U
+#define XHC_IRAADR__MOD_R			0U
+#define XHC_IRAADR__MOD_WIDTH			1U
+#define XHC_IRAADR__MOD_RESETVALUE		0x0U
+#define XHC_IRAADR__RESERVED_L			31U
+#define XHC_IRAADR__RESERVED_R			24U
+#define XHC_IRAADR_WIDTH			24U
+#define XHC_IRAADR__WIDTH			24U
+#define XHC_IRAADR_ALL_L			23U
+#define XHC_IRAADR_ALL_R			0U
+#define XHC_IRAADR__ALL_L			23U
+#define XHC_IRAADR__ALL_R			0U
+#define XHC_IRAADR_DATAMASK			0x00ffffffU
+#define XHC_IRAADR_RDWRMASK			0xff000000U
+#define XHC_IRAADR_RESETVALUE			0x000000U
+
+#define XHC_IRADAT_OFFSET			0xf9cU
+#define XHC_IRADAT_BASE			0xf9cU
+#define XHC_IRADAT__DAT_L			31U
+#define XHC_IRADAT__DAT_R			0U
+#define XHC_IRADAT__DAT_WIDTH			32U
+#define XHC_IRADAT__DAT_RESETVALUE			0x00000000U
+#define XHC_IRADAT_WIDTH			32U
+#define XHC_IRADAT__WIDTH			32U
+#define XHC_IRADAT_ALL_L			31U
+#define XHC_IRADAT_ALL_R			0U
+#define XHC_IRADAT__ALL_L			31U
+#define XHC_IRADAT__ALL_R			0U
+#define XHC_IRADAT_DATAMASK			0xffffffffU
+#define XHC_IRADAT_RDWRMASK			0x00000000U
+#define XHC_IRADAT_RESETVALUE			0x00000000U
+
+
+#define XHC_ECHHST_OFFSET			0xfa0U
+#define XHC_ECHHST_BASE				0xfa0U
+#define XHC_ECHHST__CCC				31U
+#define XHC_ECHHST__CCC_L			31U
+#define XHC_ECHHST__CCC_R			31U
+#define XHC_ECHHST__CCC_WIDTH			1U
+#define XHC_ECHHST__CCC_RESETVALUE		0x1U
+#define XHC_ECHHST__PME				30U
+#define XHC_ECHHST__PME_L			30U
+#define XHC_ECHHST__PME_R			30U
+#define XHC_ECHHST__PME_WIDTH			1U
+#define XHC_ECHHST__PME_RESETVALUE		0x0U
+#define XHC_ECHHST__AUX_L			29U
+#define XHC_ECHHST__AUX_R			24U
+#define XHC_ECHHST__AUX_WIDTH			6U
+#define XHC_ECHHST__AUX_RESETVALUE		0x0U
+#define XHC_ECHHST__IRA				20U
+#define XHC_ECHHST__IRA_L			20U
+#define XHC_ECHHST__IRA_R			20U
+#define XHC_ECHHST__IRA_WIDTH			1U
+#define XHC_ECHHST__IRA_RESETVALUE		0x0U
+#define XHC_ECHHST__ULS				19U
+#define XHC_ECHHST__ULS_L			19U
+#define XHC_ECHHST__ULS_R			19U
+#define XHC_ECHHST__ULS_WIDTH			1U
+#define XHC_ECHHST__ULS_RESETVALUE		0x0U
+#define XHC_ECHHST__reserved			18U
+#define XHC_ECHHST__reserved_L			18U
+#define XHC_ECHHST__reserved_R			18U
+#define XHC_ECHHST__reserved_WIDTH		1U
+#define XHC_ECHHST__reserved_RESETVALUE		0x0U
+#define XHC_ECHHST__TEDA			17U
+#define XHC_ECHHST__TEDA_L			17U
+#define XHC_ECHHST__TEDA_R			17U
+#define XHC_ECHHST__TEDA_WIDTH			1U
+#define XHC_ECHHST__TEDA_RESETVALUE		0x0U
+#define XHC_ECHHST__FSW				16U
+#define XHC_ECHHST__FSW_L			16U
+#define XHC_ECHHST__FSW_R			16U
+#define XHC_ECHHST__FSW_WIDTH			1U
+#define XHC_ECHHST__FSW_RESETVALUE		0x1U
+#define XHC_ECHHST__NCP_L			15U
+#define XHC_ECHHST__NCP_R			8U
+#define XHC_ECHHST__NCP_WIDTH			8U
+#define XHC_ECHHST__NCP_RESETVALUE		0x04U
+#define XHC_ECHHST__CID_L			7U
+#define XHC_ECHHST__CID_R			0U
+#define XHC_ECHHST__CID_WIDTH			8U
+#define XHC_ECHHST__CID_RESETVALUE		0xfcU
+#define XHC_ECHHST__RESERVED_L			23U
+#define XHC_ECHHST__RESERVED_R			21U
+#define XHC_ECHHST_WIDTH			32U
+#define XHC_ECHHST__WIDTH			32U
+#define XHC_ECHHST_ALL_L			31U
+#define XHC_ECHHST_ALL_R			0U
+#define XHC_ECHHST__ALL_L			31U
+#define XHC_ECHHST__ALL_R			0U
+#define XHC_ECHHST_DATAMASK			0xff1fffffU
+#define XHC_ECHHST_RDWRMASK			0x00e00000U
+#define XHC_ECHHST_RESETVALUE			0x800104fcU
+
+#define XHC_HSTDBG_OFFSET			0xfa4U
+#define XHC_HSTDBG_BASE				0xfa4U
+#define XHC_HSTDBG__ETE				31U
+#define XHC_HSTDBG__ETE_L			31U
+#define XHC_HSTDBG__ETE_R			31U
+#define XHC_HSTDBG__ETE_WIDTH			1U
+#define XHC_HSTDBG__ETE_RESETVALUE		0x0U
+#define XHC_HSTDBG__reserved_L			30U
+#define XHC_HSTDBG__reserved_R			16U
+#define XHC_HSTDBG__reserved_WIDTH		15U
+#define XHC_HSTDBG__reserved_RESETVALUE		0x0U
+#define XHC_HSTDBG__OUTP_L			15U
+#define XHC_HSTDBG__OUTP_R			8U
+#define XHC_HSTDBG__OUTP_WIDTH			8U
+#define XHC_HSTDBG__OUTP_RESETVALUE		0x00U
+#define XHC_HSTDBG__INP_L			7U
+#define XHC_HSTDBG__INP_R			0U
+#define XHC_HSTDBG__INP_WIDTH			8U
+#define XHC_HSTDBG__INP_RESETVALUE		0x00U
+#define XHC_HSTDBG_WIDTH			32U
+#define XHC_HSTDBG__WIDTH			32U
+#define XHC_HSTDBG_ALL_L			31U
+#define XHC_HSTDBG_ALL_R			0U
+#define XHC_HSTDBG__ALL_L			31U
+#define XHC_HSTDBG__ALL_R			0U
+#define XHC_HSTDBG_DATAMASK			0xffffffffU
+#define XHC_HSTDBG_RDWRMASK			0x00000000U
+#define XHC_HSTDBG_RESETVALUE			0x00000000U
+
+#define XHC_HSTNPL_OFFSET			0xfa8U
+#define XHC_HSTNPL_BASE				0xfa8U
+#define XHC_HSTNPL__NPL_L			31U
+#define XHC_HSTNPL__NPL_R			9U
+#define XHC_HSTNPL__NPL_WIDTH			23U
+#define XHC_HSTNPL__NPL_RESETVALUE		0x0U
+#define XHC_HSTNPL__reserved_L			8U
+#define XHC_HSTNPL__reserved_R			0U
+#define XHC_HSTNPL__reserved_WIDTH		9U
+#define XHC_HSTNPL__reserved_RESETVALUE		0x0U
+#define XHC_HSTNPL_WIDTH			32U
+#define XHC_HSTNPL__WIDTH			32U
+#define XHC_HSTNPL_ALL_L			31U
+#define XHC_HSTNPL_ALL_R			0U
+#define XHC_HSTNPL__ALL_L			31U
+#define XHC_HSTNPL__ALL_R			0U
+#define XHC_HSTNPL_DATAMASK			0xffffffffU
+#define XHC_HSTNPL_RDWRMASK			0x00000000U
+#define XHC_HSTNPL_RESETVALUE			0x00000000U
+
+#define XHC_HSTNPH_OFFSET			0xfacU
+#define XHC_HSTNPH_BASE				0xfacU
+#define XHC_HSTNPH__NPH_L			31U
+#define XHC_HSTNPH__NPH_R			0U
+#define XHC_HSTNPH__NPH_WIDTH			32U
+#define XHC_HSTNPH__NPH_RESETVALUE		0x00000000U
+#define XHC_HSTNPH_WIDTH			32U
+#define XHC_HSTNPH__WIDTH			32U
+#define XHC_HSTNPH_ALL_L			31U
+#define XHC_HSTNPH_ALL_R			0U
+#define XHC_HSTNPH__ALL_L			31U
+#define XHC_HSTNPH__ALL_R			0U
+#define XHC_HSTNPH_DATAMASK			0xffffffffU
+#define XHC_HSTNPH_RDWRMASK			0x00000000U
+#define XHC_HSTNPH_RESETVALUE			0x00000000U
+
+#define XHC_ECHRBV_OFFSET			0xfb0U
+#define XHC_ECHRBV_BASE				0xfb0U
+#define XHC_ECHRBV__MAJ_L			31U
+#define XHC_ECHRBV__MAJ_R			28U
+#define XHC_ECHRBV__MAJ_WIDTH			4U
+#define XHC_ECHRBV__MAJ_RESETVALUE		0x0U
+#define XHC_ECHRBV__MIN_L			27U
+#define XHC_ECHRBV__MIN_R			24U
+#define XHC_ECHRBV__MIN_WIDTH			4U
+#define XHC_ECHRBV__MIN_RESETVALUE		0x0U
+#define XHC_ECHRBV__RLS_L			23U
+#define XHC_ECHRBV__RLS_R			16U
+#define XHC_ECHRBV__RLS_WIDTH			8U
+#define XHC_ECHRBV__RLS_RESETVALUE		0x00U
+#define XHC_ECHRBV__NCP_L			15U
+#define XHC_ECHRBV__NCP_R			8U
+#define XHC_ECHRBV__NCP_WIDTH			8U
+#define XHC_ECHRBV__NCP_RESETVALUE		0x00U
+#define XHC_ECHRBV__CID_L			7U
+#define XHC_ECHRBV__CID_R			0U
+#define XHC_ECHRBV__CID_WIDTH			8U
+#define XHC_ECHRBV__CID_RESETVALUE		0xfeU
+#define XHC_ECHRBV_WIDTH			32U
+#define XHC_ECHRBV__WIDTH			32U
+#define XHC_ECHRBV_ALL_L			31U
+#define XHC_ECHRBV_ALL_R			0U
+#define XHC_ECHRBV__ALL_L			31U
+#define XHC_ECHRBV__ALL_R			0U
+#define XHC_ECHRBV_DATAMASK			0xffffffffU
+#define XHC_ECHRBV_RDWRMASK			0x00000000U
+#define XHC_ECHRBV_RESETVALUE			0x000000feU
+
+#define XHC_RBVPDT_OFFSET			0xfb4U
+#define XHC_RBVPDT_BASE				0xfb4U
+#define XHC_RBVPDT__VDR_L			31U
+#define XHC_RBVPDT__VDR_R			16U
+#define XHC_RBVPDT__VDR_WIDTH			16U
+#define XHC_RBVPDT__VDR_RESETVALUE		0x0a5cU
+#define XHC_RBVPDT__PDT_L			15U
+#define XHC_RBVPDT__PDT_R			0U
+#define XHC_RBVPDT__PDT_WIDTH			16U
+#define XHC_RBVPDT__PDT_RESETVALUE		0x0000U
+#define XHC_RBVPDT_WIDTH			32U
+#define XHC_RBVPDT__WIDTH			32U
+#define XHC_RBVPDT_ALL_L			31U
+#define XHC_RBVPDT_ALL_R			0U
+#define XHC_RBVPDT__ALL_L			31U
+#define XHC_RBVPDT__ALL_R			0U
+#define XHC_RBVPDT_DATAMASK			0xffffffffU
+#define XHC_RBVPDT_RDWRMASK			0x00000000U
+#define XHC_RBVPDT_RESETVALUE			0x0a5c0000U
+
+#define XHC_RBVMGN_OFFSET			0xfbcU
+#define XHC_RBVMGN_BASE				0xfbcU
+#define XHC_RBVMGN__MGN_L			31U
+#define XHC_RBVMGN__MGN_R			0U
+#define XHC_RBVMGN__MGN_WIDTH			32U
+#define XHC_RBVMGN__MGN_RESETVALUE		0x52535354U
+#define XHC_RBVMGN_WIDTH			32U
+#define XHC_RBVMGN__WIDTH			32U
+#define XHC_RBVMGN_ALL_L			31U
+#define XHC_RBVMGN_ALL_R			0U
+#define XHC_RBVMGN__ALL_L			31U
+#define XHC_RBVMGN__ALL_R			0U
+#define XHC_RBVMGN_DATAMASK			0xffffffffU
+#define XHC_RBVMGN_RDWRMASK			0x00000000U
+#define XHC_RBVMGN_RESETVALUE			0x52535354U
+
+/* PORTSC field defines */
+#define XHC_PORTSC__PS_LINK_STATE_U0		0U
+#define XHC_PORTSC__PS_LINK_STATE_U1		1U
+#define XHC_PORTSC__PS_LINK_STATE_U2		2U
+#define XHC_PORTSC__PS_LINK_STATE_U3		3U
+#define XHC_PORTSC__PS_LINK_STATE_DISABLED	4U
+#define XHC_PORTSC__PS_LINK_STATE_RX_DETECT	5U
+#define XHC_PORTSC__PS_LINK_STATE_INACTIVE	6U
+#define XHC_PORTSC__PS_LINK_STATE_POLLING	7U
+#define XHC_PORTSC__PS_LINK_STATE_RECOVERY	8U
+#define XHC_PORTSC__PS_LINK_STATE_HOT_RESET	9U
+#define XHC_PORTSC__PS_LINK_STATE_COMPLIANCE	10U
+#define XHC_PORTSC__PS_LINK_STATE_TEST		11U
+#define XHC_PORTSC__PS_LINK_STATE_RESUME	15U
+
+#define XHC_PORTSC__PS_SPEED_UNDEFINED		0U
+#define XHC_PORTSC__PS_FS			1U
+#define XHC_PORTSC__PS_LS			2U
+#define XHC_PORTSC__PS_HS			3U
+#define XHC_PORTSC__PS_SS			4U
+
+/* macros and inline functions */
+
+/* write 64bit ptr 'p' to destination 'd' with offset 'v' */
+inline void WRITE64_REG_PTRL(uint32_t r, uint32_t *p)
+{
+	uint32_t *ptr = (uint32_t *) (uint64_t) (XHC_BASE + r);
+
+	*ptr = (uint32_t) ((uint64_t) p & (uint64_t) 0xffffffffU);
+}
+
+inline void WRITE64_REG_PTRH(uint32_t r, uint32_t *p)
+{
+	uint32_t *ptr = (uint32_t *) (uint64_t) (XHC_BASE + r);
+
+	*ptr = (uint32_t) ((uint64_t) p >> 32U);
+}
+
+#define XHC_REG_RD(addr)   mmio_read_32(XHC_BASE + addr)
+
+#define XHC_REG_WR(addr, val) mmio_write_32(XHC_BASE+addr, val)
+
+#endif				/* USBH_XHCI_REGS_H */
+
diff --git a/include/plat/marvell/armada/a8k/common/efuse_def.h b/include/plat/marvell/armada/a8k/common/efuse_def.h
new file mode 100644
index 0000000..ff1d4a3
--- /dev/null
+++ b/include/plat/marvell/armada/a8k/common/efuse_def.h
@@ -0,0 +1,33 @@
+/*
+ * Copyright (C) 2021 Marvell International Ltd.
+ *
+ * SPDX-License-Identifier:     BSD-3-Clause
+ * https://spdx.org/licenses
+ */
+
+#ifndef EFUSE_DEF_H
+#define EFUSE_DEF_H
+
+#include <platform_def.h>
+
+#define MVEBU_AP_EFUSE_SRV_CTRL_REG	(MVEBU_AP_GEN_MGMT_BASE + 0x8)
+#define EFUSE_SRV_CTRL_LD_SELECT_OFFS	6
+#define EFUSE_SRV_CTRL_LD_SELECT_MASK	(1 << EFUSE_SRV_CTRL_LD_SELECT_OFFS)
+
+#define MVEBU_AP_LD_EFUSE_BASE		(MVEBU_AP_GEN_MGMT_BASE + 0xF00)
+/* Bits [31:0] - 32 data bits total */
+#define MVEBU_AP_LDX_31_0_EFUSE_OFFS	(MVEBU_AP_LD_EFUSE_BASE)
+/* Bits [62:32] - 31 data bits total 32nd bit is parity for bits [62:0]*/
+#define MVEBU_AP_LDX_62_32_EFUSE_OFFS	(MVEBU_AP_LD_EFUSE_BASE + 0x4)
+/* Bits [94:63] - 32 data bits total */
+#define MVEBU_AP_LDX_94_63_EFUSE_OFFS	(MVEBU_AP_LD_EFUSE_BASE + 0x8)
+/* Bits [125:95] - 31 data bits total, 32nd bit is parity for bits [125:63] */
+#define MVEBU_AP_LDX_125_95_EFUSE_OFFS	(MVEBU_AP_LD_EFUSE_BASE + 0xC)
+/* Bits [157:126] - 32 data bits total */
+#define MVEBU_AP_LDX_126_157_EFUSE_OFFS	(MVEBU_AP_LD_EFUSE_BASE + 0x10)
+/* Bits [188:158] - 31 data bits total, 32nd bit is parity for bits [188:126] */
+#define MVEBU_AP_LDX_188_158_EFUSE_OFFS	(MVEBU_AP_LD_EFUSE_BASE + 0x14)
+/* Bits [220:189] - 32 data bits total */
+#define MVEBU_AP_LDX_220_189_EFUSE_OFFS	(MVEBU_AP_LD_EFUSE_BASE + 0x18)
+
+#endif /* EFUSE_DEF_H */
diff --git a/plat/arm/board/fvp/fdts/fvp_fw_config.dts b/plat/arm/board/fvp/fdts/fvp_fw_config.dts
index 9fb566b..074a50a 100644
--- a/plat/arm/board/fvp/fdts/fvp_fw_config.dts
+++ b/plat/arm/board/fvp/fdts/fvp_fw_config.dts
@@ -42,10 +42,12 @@
 			id = <TOS_FW_CONFIG_ID>;
 		};
 
+#if !defined(SPD_spmd)
 		nt_fw-config {
 			load-address = <0x0 0x80000000>;
 			max-size = <0x200>;
 			id = <NT_FW_CONFIG_ID>;
 		};
+#endif
 	};
 };
diff --git a/plat/arm/board/tc0/include/platform_def.h b/plat/arm/board/tc0/include/platform_def.h
index 30b5ab7..b169d77 100644
--- a/plat/arm/board/tc0/include/platform_def.h
+++ b/plat/arm/board/tc0/include/platform_def.h
@@ -1,5 +1,5 @@
 /*
- * Copyright (c) 2020, Arm Limited. All rights reserved.
+ * Copyright (c) 2020-2021, Arm Limited. All rights reserved.
  *
  * SPDX-License-Identifier: BSD-3-Clause
  */
@@ -220,7 +220,7 @@
 /* GIC related constants */
 #define PLAT_ARM_GICD_BASE		UL(0x30000000)
 #define PLAT_ARM_GICC_BASE		UL(0x2C000000)
-#define PLAT_ARM_GICR_BASE		UL(0x30140000)
+#define PLAT_ARM_GICR_BASE		UL(0x30080000)
 
 /*
  * PLAT_CSS_MAX_SCP_BL2_SIZE is calculated using the current
diff --git a/plat/arm/common/arm_bl31_setup.c b/plat/arm/common/arm_bl31_setup.c
index 6dd4587..b819888 100644
--- a/plat/arm/common/arm_bl31_setup.c
+++ b/plat/arm/common/arm_bl31_setup.c
@@ -148,14 +148,6 @@
 	bl33_image_ep_info.spsr = arm_get_spsr_for_bl33_entry();
 	SET_SECURITY_STATE(bl33_image_ep_info.h.attr, NON_SECURE);
 
-#if defined(SPD_spmd) && !(ARM_LINUX_KERNEL_AS_BL33)
-	/*
-	 * Hafnium in normal world expects its manifest address in x0, which
-	 * is loaded at base of DRAM.
-	 */
-	bl33_image_ep_info.args.arg0 = (u_register_t)ARM_DRAM1_BASE;
-#endif
-
 #else /* RESET_TO_BL31 */
 
 	/*
@@ -206,6 +198,14 @@
 	bl33_image_ep_info.args.arg2 = 0U;
 	bl33_image_ep_info.args.arg3 = 0U;
 # endif
+
+#if defined(SPD_spmd)
+	/*
+	 * Hafnium in normal world expects its manifest address in x0, In CI
+	 * configuration manifest is preloaded at 0x80000000(start of DRAM).
+	 */
+	bl33_image_ep_info.args.arg0 = (u_register_t)ARM_DRAM1_BASE;
+#endif
 }
 
 void bl31_early_platform_setup2(u_register_t arg0, u_register_t arg1,
diff --git a/plat/brcm/board/common/board_common.mk b/plat/brcm/board/common/board_common.mk
index 2945749..3b3e92d 100644
--- a/plat/brcm/board/common/board_common.mk
+++ b/plat/brcm/board/common/board_common.mk
@@ -118,7 +118,8 @@
 
 PLAT_INCLUDES		+=	-Iplat/brcm/board/common \
 				-Iinclude/drivers/brcm \
-				-Iinclude/drivers/brcm/emmc
+				-Iinclude/drivers/brcm/emmc \
+				-Iinclude/drivers/brcm/mdio
 
 PLAT_BL_COMMON_SOURCES	+=	plat/brcm/common/brcm_common.c \
 				plat/brcm/board/common/cmn_sec.c \
diff --git a/plat/brcm/board/stingray/driver/sr_usb.h b/plat/brcm/board/stingray/driver/sr_usb.h
new file mode 100644
index 0000000..5033683
--- /dev/null
+++ b/plat/brcm/board/stingray/driver/sr_usb.h
@@ -0,0 +1,135 @@
+/*
+ * Copyright (c) 2019 - 2021, Broadcom
+ *
+ * SPDX-License-Identifier: BSD-3-Clause
+ */
+
+#ifndef SR_USB_H
+#define SR_USB_H
+
+#define CDRU_PM_RESET_N_R	BIT(CDRU_MISC_RESET_CONTROL__CDRU_PM_RESET_N_R)
+#define CDRU_USBSS_RESET_N	BIT(CDRU_MISC_RESET_CONTROL__CDRU_USBSS_RESET_N)
+#define CDRU_MISC_CLK_USBSS \
+			BIT(CDRU_MISC_CLK_ENABLE_CONTROL__CDRU_USBSS_CLK_EN_R)
+
+#define RESCAL_I_RSTB			BIT(26)
+#define RESCAL_I_PWRDNB			BIT(27)
+
+#define DRDU3_U3PHY_CTRL		0x68500014
+#define	PHY_RESET			BIT(1)
+#define	POR_RESET			BIT(28)
+#define	MDIO_RESET			BIT(29)
+
+#define DRDU3_PWR_CTRL			0x6850002c
+#define POWER_CTRL_OVRD			BIT(2)
+
+#define USB3H_U3PHY_CTRL		0x68510014
+#define USB3H_U3SOFT_RST_N		BIT(30)
+
+#define USB3H_PWR_CTRL			0x68510028
+
+#define USB3_PHY_MDIO_BLOCK_BASE_REG	0x1f
+#define BDC_AXI_SOFT_RST_N_OFFSET	0
+#define XHC_AXI_SOFT_RST_N_OFFSET	1
+#define MDIO_BUS_ID			3
+#define USB3H_PHY_ID			5
+#define USB3DRD_PHY_ID			2
+
+#define USB3_PHY_RXPMD_BLOCK_BASE	0x8020
+#define USB3_PHY_RXPMD_REG1		0x1
+#define USB3_PHY_RXPMD_REG2		0x2
+#define USB3_PHY_RXPMD_REG5		0x5
+#define USB3_PHY_RXPMD_REG7		0x7
+
+#define USB3_PHY_TXPMD_BLOCK_BASE	0x8040
+#define USB3_PHY_TXPMD_REG1		0x1
+#define USB3_PHY_TXPMD_REG2		0x2
+
+#define USB3_PHY_ANA_BLOCK_BASE		0x8090
+#define USB3_PHY_ANA_REG0		0x0
+#define USB3_PHY_ANA_REG1		0x1
+#define USB3_PHY_ANA_REG2		0x2
+#define USB3_PHY_ANA_REG5		0x5
+#define USB3_PHY_ANA_REG8		0x8
+#define USB3_PHY_ANA_REG11		0xb
+
+#define USB3_PHY_AEQ_BLOCK_BASE		0x80e0
+#define USB3_PHY_AEQ_REG1		0x1
+#define USB3_PHY_AEQ_REG3		0x3
+
+#ifdef USB_DMA_COHERENT
+#define DRDU3_U3XHC_SOFT_RST_N		BIT(31)
+#define DRDU3_U3BDC_SOFT_RST_N		BIT(30)
+
+#define DRDU3_SOFT_RESET_CTRL		0x68500030
+#define DRDU3_XHC_AXI_SOFT_RST_N	BIT(1)
+#define DRDU3_BDC_AXI_SOFT_RST_N	BIT(0)
+
+#define DRDU2_PHY_CTRL			0x6852000c
+#define DRDU2_U2SOFT_RST_N		BIT(29)
+
+#define USB3H_SOFT_RESET_CTRL		0x6851002c
+#define USB3H_XHC_AXI_SOFT_RST_N	BIT(1)
+
+#define DRDU2_SOFT_RESET_CTRL		0x68520020
+#define DRDU2_BDC_AXI_SOFT_RST_N	BIT(0)
+
+#define DRD2U3H_XHC_REGS_AXIWRA		0x68511c08
+#define DRD2U3H_XHC_REGS_AXIRDA		0x68511c0c
+#define DRDU2D_BDC_REGS_AXIWRA		0x68521c08
+#define DRDU2D_BDC_REGS_AXIRDA		0x68521c0c
+#define DRDU3H_XHC_REGS_AXIWRA		0x68501c08
+#define DRDU3H_XHC_REGS_AXIRDA		0x68501c0c
+#define DRDU3D_BDC_REGS_AXIWRA		0x68502c08
+#define DRDU3D_BDC_REGS_AXIRDA		0x68502c0c
+/* cacheable write-back, allocate on both reads and writes */
+#define USBAXI_AWCACHE		0xf
+#define USBAXI_ARCACHE		0xf
+/* non-secure */
+#define USBAXI_AWPROT		0x8
+#define USBAXI_ARPROT		0x8
+#define USBAXIWR_SA_VAL		((USBAXI_AWCACHE << 4 | USBAXI_AWPROT) << 0)
+#define USBAXIWR_SA_MASK	((0xf << 4 | 0xf) << 0)
+#define USBAXIWR_UA_VAL		((USBAXI_AWCACHE << 4 | USBAXI_AWPROT) << 16)
+#define USBAXIWR_UA_MASK	((0xf << 4 | 0xf) << 0)
+#define USBAXIRD_SA_VAL		((USBAXI_ARCACHE << 4 | USBAXI_ARPROT) << 0)
+#define USBAXIRD_SA_MASK	((0xf << 4 | 0xf) << 0)
+#define USBAXIRD_UA_VAL		((USBAXI_ARCACHE << 4 | USBAXI_ARPROT) << 16)
+#define USBAXIRD_UA_MASK	((0xf << 4 | 0xf) << 0)
+#endif /* USB_DMA_COHERENT */
+
+#define ICFG_DRDU3_SID_CTRL		0x6850001c
+#define ICFG_USB3H_SID_CTRL		0x6851001c
+#define ICFG_DRDU2_SID_CTRL		0x68520010
+#define ICFG_USB_SID_SHIFT		5
+#define ICFG_USB_SID_AWADDR_OFFSET	0x0
+#define ICFG_USB_SID_ARADDR_OFFSET	0x4
+
+#define USBIC_GPV_BASE			0x68600000
+#define USBIC_GPV_SECURITY0		(USBIC_GPV_BASE + 0x8)
+#define USBIC_GPV_SECURITY0_FIELD	BIT(0)
+#define USBIC_GPV_SECURITY1		(USBIC_GPV_BASE + 0xc)
+#define USBIC_GPV_SECURITY1_FIELD	(BIT(0) | BIT(1))
+#define USBIC_GPV_SECURITY2		(USBIC_GPV_BASE + 0x10)
+#define USBIC_GPV_SECURITY2_FIELD	(BIT(0) | BIT(1))
+#define USBIC_GPV_SECURITY4		(USBIC_GPV_BASE + 0x18)
+#define USBIC_GPV_SECURITY4_FIELD	BIT(0)
+#define USBIC_GPV_SECURITY10		(USBIC_GPV_BASE + 0x30)
+#define USBIC_GPV_SECURITY10_FIELD	(0x7 << 0)
+
+#define USBSS_TZPCDECPROT_BASE		0x68540800
+#define USBSS_TZPCDECPROT0set		(USBSS_TZPCDECPROT_BASE + 0x4)
+#define USBSS_TZPCDECPROT0clr		(USBSS_TZPCDECPROT_BASE + 0x8)
+#define DECPROT0_USBSS_DRD2U3H		BIT(3)
+#define DECPROT0_USBSS_DRDU2H		BIT(2)
+#define DECPROT0_USBSS_DRDU3D		BIT(1)
+#define DECPROT0_USBSS_DRDU2D		BIT(0)
+#define USBSS_TZPCDECPROT0 \
+		(DECPROT0_USBSS_DRD2U3H | \
+		DECPROT0_USBSS_DRDU2H |   \
+		DECPROT0_USBSS_DRDU3D |   \
+		DECPROT0_USBSS_DRDU2D)
+
+int32_t usb_device_init(unsigned int);
+
+#endif /* SR_USB_H */
diff --git a/plat/brcm/board/stingray/driver/usb.c b/plat/brcm/board/stingray/driver/usb.c
new file mode 100644
index 0000000..4a84141
--- /dev/null
+++ b/plat/brcm/board/stingray/driver/usb.c
@@ -0,0 +1,296 @@
+/*
+ * Copyright (c) 2019 - 2021, Broadcom
+ *
+ * SPDX-License-Identifier: BSD-3-Clause
+ */
+
+#include <stdint.h>
+
+#include <common/debug.h>
+#include <drivers/delay_timer.h>
+#include <lib/mmio.h>
+
+#include <mdio.h>
+#include <platform_usb.h>
+#include <sr_utils.h>
+#include "sr_usb.h"
+#include <usbh_xhci_regs.h>
+
+static uint32_t usb_func = USB3_DRD | USB3H_USB2DRD;
+
+static void usb_pm_rescal_init(void)
+{
+	uint32_t data;
+	uint32_t try;
+
+	mmio_setbits_32(CDRU_MISC_RESET_CONTROL, CDRU_PM_RESET_N_R);
+	/* release reset */
+	mmio_setbits_32(CDRU_CHIP_TOP_SPARE_REG0, RESCAL_I_RSTB);
+	udelay(10U);
+	/* power up */
+	mmio_setbits_32(CDRU_CHIP_TOP_SPARE_REG0,
+			RESCAL_I_RSTB | RESCAL_I_PWRDNB);
+	try = 1000U;
+	do {
+		udelay(1U);
+		data = mmio_read_32(CDRU_CHIP_TOP_SPARE_REG1);
+		try--;
+	} while ((data & RESCAL_I_PWRDNB) == 0x0U && (try != 0U));
+
+	if (try == 0U) {
+		ERROR("CDRU_CHIP_TOP_SPARE_REG1: 0x%x\n", data);
+	}
+
+	INFO("USB and PM Rescal Init done..\n");
+}
+
+const unsigned int xhc_portsc_reg_offset[MAX_USB_PORTS] = {
+	XHC_PORTSC1_OFFSET,
+	XHC_PORTSC2_OFFSET,
+	XHC_PORTSC3_OFFSET,
+};
+
+static void usb3h_usb2drd_init(void)
+{
+	uint32_t val;
+
+	INFO("USB3H + USB 2DRD init\n");
+	mmio_clrbits_32(USB3H_U3PHY_CTRL, POR_RESET);
+	val = mmio_read_32(USB3H_PWR_CTRL);
+	val &= ~(0x3U << POWER_CTRL_OVRD);
+	val |= (1U << POWER_CTRL_OVRD);
+	mmio_write_32(USB3H_PWR_CTRL, val);
+	mmio_setbits_32(USB3H_U3PHY_CTRL, PHY_RESET);
+	/* Phy to come out of reset */
+	udelay(2U);
+	mmio_clrbits_32(USB3H_U3PHY_CTRL, MDIO_RESET);
+
+	/* MDIO in reset */
+	udelay(2U);
+	mmio_setbits_32(USB3H_U3PHY_CTRL, MDIO_RESET);
+
+	/* After MDIO reset release */
+	udelay(2U);
+
+	/* USB 3.0 phy Analog Block Initialization */
+	mdio_write(MDIO_BUS_ID, USB3H_PHY_ID, USB3_PHY_MDIO_BLOCK_BASE_REG,
+			USB3_PHY_ANA_BLOCK_BASE);
+	mdio_write(MDIO_BUS_ID, USB3H_PHY_ID, USB3_PHY_ANA_REG0, 0x4646U);
+	mdio_write(MDIO_BUS_ID, USB3H_PHY_ID, USB3_PHY_ANA_REG1, 0x80c9U);
+	mdio_write(MDIO_BUS_ID, USB3H_PHY_ID, USB3_PHY_ANA_REG2, 0x88a6U);
+	mdio_write(MDIO_BUS_ID, USB3H_PHY_ID, USB3_PHY_ANA_REG5, 0x7c12U);
+	mdio_write(MDIO_BUS_ID, USB3H_PHY_ID, USB3_PHY_ANA_REG8, 0x1d07U);
+	mdio_write(MDIO_BUS_ID, USB3H_PHY_ID, USB3_PHY_ANA_REG11, 0x25cU);
+
+	/* USB 3.0 phy RXPMD Block initialization*/
+	mdio_write(MDIO_BUS_ID, USB3H_PHY_ID, USB3_PHY_MDIO_BLOCK_BASE_REG,
+			USB3_PHY_RXPMD_BLOCK_BASE);
+	mdio_write(MDIO_BUS_ID, USB3H_PHY_ID, USB3_PHY_RXPMD_REG1, 0x4052U);
+	mdio_write(MDIO_BUS_ID, USB3H_PHY_ID, USB3_PHY_RXPMD_REG2, 0x4cU);
+	mdio_write(MDIO_BUS_ID, USB3H_PHY_ID, USB3_PHY_RXPMD_REG5, 0x7U);
+	mdio_write(MDIO_BUS_ID, USB3H_PHY_ID, USB3_PHY_RXPMD_REG7, 0x173U);
+
+	/* USB 3.0 phy AEQ Block initialization*/
+	mdio_write(MDIO_BUS_ID, USB3H_PHY_ID, USB3_PHY_MDIO_BLOCK_BASE_REG,
+			USB3_PHY_AEQ_BLOCK_BASE);
+	mdio_write(MDIO_BUS_ID, USB3H_PHY_ID, USB3_PHY_AEQ_REG1, 0x3000U);
+	mdio_write(MDIO_BUS_ID, USB3H_PHY_ID, USB3_PHY_AEQ_REG3, 0x2c70U);
+
+	/* USB 3.0 phy TXPMD Block initialization*/
+	mdio_write(MDIO_BUS_ID, USB3H_PHY_ID, USB3_PHY_MDIO_BLOCK_BASE_REG,
+			USB3_PHY_TXPMD_BLOCK_BASE);
+	mdio_write(MDIO_BUS_ID, USB3H_PHY_ID, USB3_PHY_TXPMD_REG1, 0x100fU);
+	mdio_write(MDIO_BUS_ID, USB3H_PHY_ID, USB3_PHY_TXPMD_REG2, 0x238cU);
+}
+
+static void usb3drd_init(void)
+{
+	uint32_t val;
+
+	INFO("USB3DRD init\n");
+	mmio_clrbits_32(DRDU3_U3PHY_CTRL, POR_RESET);
+	val = mmio_read_32(DRDU3_PWR_CTRL);
+	val &= ~(0x3U << POWER_CTRL_OVRD);
+	val |= (1U << POWER_CTRL_OVRD);
+	mmio_write_32(DRDU3_PWR_CTRL, val);
+	mmio_setbits_32(DRDU3_U3PHY_CTRL, PHY_RESET);
+	/* Phy to come out of reset */
+	udelay(2U);
+	mmio_clrbits_32(DRDU3_U3PHY_CTRL, MDIO_RESET);
+
+	/* MDIO in reset */
+	udelay(2U);
+	mmio_setbits_32(DRDU3_U3PHY_CTRL, MDIO_RESET);
+
+	/* After MDIO reset release */
+	udelay(2U);
+
+	/* USB 3.0 DRD phy Analog Block Initialization */
+	mdio_write(MDIO_BUS_ID, USB3DRD_PHY_ID, USB3_PHY_MDIO_BLOCK_BASE_REG,
+			USB3_PHY_ANA_BLOCK_BASE);
+	mdio_write(MDIO_BUS_ID, USB3DRD_PHY_ID, USB3_PHY_ANA_REG0, 0x4646U);
+	mdio_write(MDIO_BUS_ID, USB3DRD_PHY_ID, USB3_PHY_ANA_REG1, 0x80c9U);
+	mdio_write(MDIO_BUS_ID, USB3DRD_PHY_ID, USB3_PHY_ANA_REG2, 0x88a6U);
+	mdio_write(MDIO_BUS_ID, USB3DRD_PHY_ID, USB3_PHY_ANA_REG5, 0x7c12U);
+	mdio_write(MDIO_BUS_ID, USB3DRD_PHY_ID, USB3_PHY_ANA_REG8, 0x1d07U);
+	mdio_write(MDIO_BUS_ID, USB3DRD_PHY_ID, USB3_PHY_ANA_REG11, 0x25cU);
+
+	/* USB 3.0 DRD phy RXPMD Block initialization*/
+	mdio_write(MDIO_BUS_ID, USB3DRD_PHY_ID, USB3_PHY_MDIO_BLOCK_BASE_REG,
+			USB3_PHY_RXPMD_BLOCK_BASE);
+	mdio_write(MDIO_BUS_ID, USB3DRD_PHY_ID, USB3_PHY_RXPMD_REG1, 0x4052U);
+	mdio_write(MDIO_BUS_ID, USB3DRD_PHY_ID, USB3_PHY_RXPMD_REG2, 0x4cU);
+	mdio_write(MDIO_BUS_ID, USB3DRD_PHY_ID, USB3_PHY_RXPMD_REG5, 0x7U);
+	mdio_write(MDIO_BUS_ID, USB3DRD_PHY_ID, USB3_PHY_RXPMD_REG7, 0x173U);
+
+	/* USB 3.0 DRD phy AEQ Block initialization*/
+	mdio_write(MDIO_BUS_ID, USB3DRD_PHY_ID, USB3_PHY_MDIO_BLOCK_BASE_REG,
+			USB3_PHY_AEQ_BLOCK_BASE);
+	mdio_write(MDIO_BUS_ID, USB3DRD_PHY_ID, USB3_PHY_AEQ_REG1, 0x3000U);
+	mdio_write(MDIO_BUS_ID, USB3DRD_PHY_ID, USB3_PHY_AEQ_REG3, 0x2c70U);
+
+	/* USB 3.0 DRD phy TXPMD Block initialization*/
+	mdio_write(MDIO_BUS_ID, USB3DRD_PHY_ID, USB3_PHY_MDIO_BLOCK_BASE_REG,
+			USB3_PHY_TXPMD_BLOCK_BASE);
+	mdio_write(MDIO_BUS_ID, USB3DRD_PHY_ID, USB3_PHY_TXPMD_REG1, 0x100fU);
+	mdio_write(MDIO_BUS_ID, USB3DRD_PHY_ID, USB3_PHY_TXPMD_REG2, 0x238cU);
+}
+
+static void usb3_phy_init(void)
+{
+	usb_pm_rescal_init();
+
+	if ((usb_func & USB3H_USB2DRD) != 0U) {
+		usb3h_usb2drd_init();
+	}
+
+	if ((usb_func & USB3_DRD) != 0U) {
+		usb3drd_init();
+	}
+}
+
+#ifdef USB_DMA_COHERENT
+void usb_enable_coherence(void)
+{
+	if (usb_func & USB3H_USB2DRD) {
+		mmio_setbits_32(USB3H_SOFT_RESET_CTRL,
+				USB3H_XHC_AXI_SOFT_RST_N);
+		mmio_setbits_32(DRDU2_SOFT_RESET_CTRL,
+				DRDU2_BDC_AXI_SOFT_RST_N);
+		mmio_setbits_32(USB3H_U3PHY_CTRL, USB3H_U3SOFT_RST_N);
+		mmio_setbits_32(DRDU2_PHY_CTRL, DRDU2_U2SOFT_RST_N);
+
+		mmio_clrsetbits_32(DRD2U3H_XHC_REGS_AXIWRA,
+				   (USBAXIWR_UA_MASK | USBAXIWR_SA_MASK),
+				   (USBAXIWR_UA_VAL | USBAXIWR_SA_VAL));
+
+		mmio_clrsetbits_32(DRD2U3H_XHC_REGS_AXIRDA,
+				   (USBAXIRD_UA_MASK | USBAXIRD_SA_MASK),
+				   (USBAXIRD_UA_VAL | USBAXIRD_SA_VAL));
+
+		mmio_clrsetbits_32(DRDU2D_BDC_REGS_AXIWRA,
+				   (USBAXIWR_UA_MASK | USBAXIWR_SA_MASK),
+				   (USBAXIWR_UA_VAL | USBAXIWR_SA_VAL));
+
+		mmio_clrsetbits_32(DRDU2D_BDC_REGS_AXIRDA,
+				   (USBAXIRD_UA_MASK | USBAXIRD_SA_MASK),
+				   (USBAXIRD_UA_VAL | USBAXIRD_SA_VAL));
+
+	}
+
+	if (usb_func & USB3_DRD) {
+		mmio_setbits_32(DRDU3_SOFT_RESET_CTRL,
+				(DRDU3_XHC_AXI_SOFT_RST_N |
+				DRDU3_BDC_AXI_SOFT_RST_N));
+		mmio_setbits_32(DRDU3_U3PHY_CTRL,
+				(DRDU3_U3XHC_SOFT_RST_N |
+				DRDU3_U3BDC_SOFT_RST_N));
+
+		mmio_clrsetbits_32(DRDU3H_XHC_REGS_AXIWRA,
+				   (USBAXIWR_UA_MASK | USBAXIWR_SA_MASK),
+				   (USBAXIWR_UA_VAL | USBAXIWR_SA_VAL));
+
+		mmio_clrsetbits_32(DRDU3H_XHC_REGS_AXIRDA,
+				   (USBAXIRD_UA_MASK | USBAXIRD_SA_MASK),
+				   (USBAXIRD_UA_VAL | USBAXIRD_SA_VAL));
+
+		mmio_clrsetbits_32(DRDU3D_BDC_REGS_AXIWRA,
+				   (USBAXIWR_UA_MASK | USBAXIWR_SA_MASK),
+				   (USBAXIWR_UA_VAL | USBAXIWR_SA_VAL));
+
+		mmio_clrsetbits_32(DRDU3D_BDC_REGS_AXIRDA,
+				   (USBAXIRD_UA_MASK | USBAXIRD_SA_MASK),
+				   (USBAXIRD_UA_VAL | USBAXIRD_SA_VAL));
+	}
+}
+#endif
+
+void xhci_phy_init(void)
+{
+	uint32_t val;
+
+	INFO("usb init start\n");
+	mmio_setbits_32(CDRU_MISC_CLK_ENABLE_CONTROL,
+			CDRU_MISC_CLK_USBSS);
+
+	mmio_setbits_32(CDRU_MISC_RESET_CONTROL, CDRU_USBSS_RESET_N);
+
+	if (usb_func & USB3_DRD) {
+		VERBOSE(" - configure stream_id = 0x6800 for DRDU3\n");
+		val = SR_SID_VAL(0x3U, 0x1U, 0x0U) << ICFG_USB_SID_SHIFT;
+		mmio_write_32(ICFG_DRDU3_SID_CTRL + ICFG_USB_SID_AWADDR_OFFSET,
+				val);
+		mmio_write_32(ICFG_DRDU3_SID_CTRL + ICFG_USB_SID_ARADDR_OFFSET,
+				val);
+
+		/*
+		 * DRDU3 Device USB Space, DRDU3 Host USB Space,
+		 * DRDU3 SS Config
+		 */
+		mmio_setbits_32(USBIC_GPV_SECURITY10,
+				USBIC_GPV_SECURITY10_FIELD);
+	}
+
+	if (usb_func & USB3H_USB2DRD) {
+		VERBOSE(" - configure stream_id = 0x6801 for USB3H\n");
+		val = SR_SID_VAL(0x3U, 0x1U, 0x1U) << ICFG_USB_SID_SHIFT;
+		mmio_write_32(ICFG_USB3H_SID_CTRL + ICFG_USB_SID_AWADDR_OFFSET,
+				val);
+		mmio_write_32(ICFG_USB3H_SID_CTRL + ICFG_USB_SID_ARADDR_OFFSET,
+				val);
+
+		VERBOSE(" - configure stream_id = 0x6802 for DRDU2\n");
+		val = SR_SID_VAL(0x3U, 0x1U, 0x2U) << ICFG_USB_SID_SHIFT;
+		mmio_write_32(ICFG_DRDU2_SID_CTRL + ICFG_USB_SID_AWADDR_OFFSET,
+				val);
+		mmio_write_32(ICFG_DRDU2_SID_CTRL + ICFG_USB_SID_ARADDR_OFFSET,
+				val);
+
+		/* DRDU2 APB Bridge:DRDU2 USB Device, USB3H SS Config */
+		mmio_setbits_32(USBIC_GPV_SECURITY1, USBIC_GPV_SECURITY1_FIELD);
+
+		/*
+		 * USB3H APB Bridge:DRDU2 Host + USB3 Host USB Space,
+		 * USB3H SS Config
+		 */
+		mmio_setbits_32(USBIC_GPV_SECURITY2, USBIC_GPV_SECURITY2_FIELD);
+	}
+
+	/* Configure Host masters as non-Secure */
+	mmio_setbits_32(USBSS_TZPCDECPROT0set, USBSS_TZPCDECPROT0);
+
+	/* CCN Slave on USBIC */
+	mmio_setbits_32(USBIC_GPV_SECURITY0, USBIC_GPV_SECURITY0_FIELD);
+
+	/* SLAVE_8:IDM Register Space */
+	mmio_setbits_32(USBIC_GPV_SECURITY4, USBIC_GPV_SECURITY4_FIELD);
+
+	usb3_phy_init();
+#ifdef USB_DMA_COHERENT
+	usb_enable_coherence();
+#endif
+
+	usb_device_init(usb_func);
+
+	INFO("PLAT USB: init done.\n");
+}
diff --git a/plat/brcm/board/stingray/driver/usb_phy.c b/plat/brcm/board/stingray/driver/usb_phy.c
new file mode 100644
index 0000000..54c98e1
--- /dev/null
+++ b/plat/brcm/board/stingray/driver/usb_phy.c
@@ -0,0 +1,601 @@
+/*
+ * Copyright (c) 2019 - 2021, Broadcom
+ *
+ * SPDX-License-Identifier: BSD-3-Clause
+ */
+
+#include <platform_usb.h>
+#include <usb_phy.h>
+
+#define USB_PHY_ALREADY_STARTED	(-2)
+#define USB_MAX_DEVICES		 2
+#define USB3H_USB2DRD_PHY	 0
+#define USB3_DRD_PHY		 1
+
+/* Common bit fields for all the USB2 phy */
+#define USB2_PHY_ISO		DRDU2_U2PHY_ISO
+#define USB2_AFE_PLL_PWRDWNB	DRDU2_U2AFE_PLL_PWRDWNB
+#define USB2_AFE_BG_PWRDWNB	DRDU2_U2AFE_BG_PWRDWNB
+#define USB2_AFE_LDO_PWRDWNB	DRDU2_U2AFE_LDO_PWRDWNB
+#define USB2_CTRL_CORERDY	DRDU2_U2CTRL_CORERDY
+
+#define USB2_PHY_PCTL_MASK	DRDU2_U2PHY_PCTL_MASK
+#define USB2_PHY_PCTL_OFFSET	DRDU2_U2PHY_PCTL_OFFSET
+#define USB2_PHY_PCTL_VAL	U2PHY_PCTL_VAL
+
+#define USB2_PLL_RESETB		DRDU2_U2PLL_RESETB
+#define USB2_PHY_RESETB		DRDU2_U2PHY_RESETB
+
+static usb_phy_port_t usb_phy_port[2U][MAX_NR_PORTS];
+
+static usb_phy_t usb_phy_info[2U] = {
+	{DRDU2_U2PLL_NDIV_FRAC, USB3H_PIPE_CTRL, 0U, USB3H_DRDU2_PHY},
+	{0U, 0U, DRDU3_PIPE_CTRL, DRDU3_PHY}
+};
+
+typedef struct {
+	void *pcd_id;
+} usb_platform_dev;
+
+/* index 0: USB3H + USB2 DRD, 1: USB3 DRD */
+static usb_platform_dev xhci_devices_configs[USB_MAX_DEVICES] = {
+	{&usb_phy_info[0U]},
+	{&usb_phy_info[1U]}
+};
+
+static int32_t pll_lock_check(uint32_t address, uint32_t bit)
+{
+	uint32_t retry;
+	uint32_t data;
+
+	retry = PLL_LOCK_RETRY_COUNT;
+	do {
+		data = mmio_read_32(address);
+		if ((data & bit) != 0U) {
+			return 0;
+		}
+		udelay(1);
+	} while (--retry != 0);
+
+	ERROR("%s(): FAIL (0x%08x)\n", __func__, address);
+	return -1;
+}
+
+/*
+ * USB2 PHY using external FSM bringup sequence
+ * Total #3 USB2 phys. All phys has the same
+ * bringup sequence. Register bit fields for
+ * some of the PHY's are different.
+ * Bit fields which are different are passed using
+ * struct u2_phy_ext_fsm with bit-fields and register addr.
+ */
+
+static void u2_phy_ext_fsm_power_on(struct u2_phy_ext_fsm *u2_phy)
+{
+	mmio_setbits_32(u2_phy->phy_ctrl_reg, USB2_PHY_ISO);
+	/* Delay as per external FSM spec */
+	udelay(10U);
+
+	mmio_setbits_32(u2_phy->phy_ctrl_reg, u2_phy->phy_iddq);
+	/* Delay as per external FSM spec */
+	udelay(10U);
+
+	mmio_clrbits_32(u2_phy->phy_ctrl_reg,
+			(USB2_AFE_BG_PWRDWNB |
+			 USB2_AFE_PLL_PWRDWNB |
+			 USB2_AFE_LDO_PWRDWNB |
+			 USB2_CTRL_CORERDY));
+
+	mmio_clrsetbits_32(u2_phy->phy_ctrl_reg,
+			   (USB2_PHY_PCTL_MASK << USB2_PHY_PCTL_OFFSET),
+			   (USB2_PHY_PCTL_VAL << USB2_PHY_PCTL_OFFSET));
+	/* Delay as per external FSM spec */
+	udelay(160U);
+
+	mmio_setbits_32(u2_phy->phy_ctrl_reg, USB2_CTRL_CORERDY);
+	/* Delay as per external FSM spec */
+	udelay(50U);
+
+	mmio_setbits_32(u2_phy->phy_ctrl_reg, USB2_AFE_BG_PWRDWNB);
+	/* Delay as per external FSM spec */
+	udelay(200U);
+
+	mmio_setbits_32(u2_phy->pwr_ctrl_reg, u2_phy->pwr_onin);
+	mmio_setbits_32(u2_phy->phy_ctrl_reg, USB2_AFE_LDO_PWRDWNB);
+	/* Delay as per external FSM spec */
+	udelay(10U);
+
+	mmio_setbits_32(u2_phy->pwr_ctrl_reg, u2_phy->pwr_okin);
+	/* Delay as per external FSM spec */
+	udelay(10U);
+
+	mmio_setbits_32(u2_phy->phy_ctrl_reg, USB2_AFE_PLL_PWRDWNB);
+	/* Delay as per external FSM spec */
+	udelay(10U);
+
+	mmio_clrbits_32(u2_phy->phy_ctrl_reg, USB2_PHY_ISO);
+	/* Delay as per external FSM spec */
+	udelay(10U);
+	mmio_clrbits_32(u2_phy->phy_ctrl_reg, u2_phy->phy_iddq);
+	/* Delay as per external FSM spec */
+	udelay(1U);
+
+	mmio_setbits_32(u2_phy->pll_ctrl_reg, USB2_PLL_RESETB);
+	mmio_setbits_32(u2_phy->phy_ctrl_reg, USB2_PHY_RESETB);
+
+}
+
+static int32_t usb3h_u2_phy_power_on(uint32_t base)
+{
+	int32_t status;
+	struct u2_phy_ext_fsm u2_phy;
+
+	u2_phy.pll_ctrl_reg = base + USB3H_U2PLL_CTRL;
+	u2_phy.phy_ctrl_reg = base + USB3H_U2PHY_CTRL;
+	u2_phy.phy_iddq = USB3H_U2PHY_IDDQ;
+	u2_phy.pwr_ctrl_reg = base + USB3H_PWR_CTRL;
+	u2_phy.pwr_okin = USB3H_PWR_CTRL_U2PHY_DFE_SWITCH_PWROKIN;
+	u2_phy.pwr_onin = USB3H_PWR_CTRL_U2PHY_DFE_SWITCH_PWRONIN;
+
+	u2_phy_ext_fsm_power_on(&u2_phy);
+
+	status = pll_lock_check(base + USB3H_U2PLL_CTRL, USB3H_U2PLL_LOCK);
+	if (status != 0) {
+		/* re-try by toggling the PLL reset */
+		mmio_clrbits_32(base + USB3H_U2PLL_CTRL,
+				(uint32_t)USB3H_U2PLL_RESETB);
+		mmio_setbits_32(base + USB3H_U2PLL_CTRL, USB3H_U2PLL_RESETB);
+		status = pll_lock_check(base + USB3H_U2PLL_CTRL,
+					USB3H_U2PLL_LOCK);
+		if (status != 0)
+			ERROR("%s() re-try PLL lock FAIL (0x%08x)\n", __func__,
+			      base + USB3H_U2PLL_CTRL);
+	}
+
+	mmio_clrsetbits_32(base + USB3H_U2PHY_CTRL,
+			   (USB3H_U2PHY_PCTL_MASK << USB3H_U2PHY_PCTL_OFFSET),
+			   (U2PHY_PCTL_NON_DRV_LOW << USB3H_U2PHY_PCTL_OFFSET));
+	return status;
+}
+
+static int32_t usb3h_u3_phy_power_on(uint32_t base)
+{
+	int32_t status;
+
+	/* Set pctl with mode and soft reset */
+	mmio_clrsetbits_32(base + USB3H_U3PHY_CTRL,
+			   (USB3H_U3PHY_PCTL_MASK << USB3H_U3PHY_PCTL_OFFSET),
+			   (U3PHY_PCTL_VAL << USB3H_U3PHY_PCTL_OFFSET));
+
+	mmio_clrbits_32(base + USB3H_U3PHY_PLL_CTRL,
+			(uint32_t) USB3H_U3SSPLL_SUSPEND_EN);
+	mmio_setbits_32(base + USB3H_U3PHY_PLL_CTRL, USB3H_U3PLL_SEQ_START);
+	mmio_setbits_32(base + USB3H_U3PHY_PLL_CTRL, USB3H_U3PLL_RESETB);
+
+	/* Time to stabilize the PLL Control */
+	mdelay(1U);
+
+	status = pll_lock_check(base + USB3H_U3PHY_PLL_CTRL,
+				USB3H_U3PLL_SS_LOCK);
+
+	return status;
+}
+
+static int32_t drdu3_u2_phy_power_on(uint32_t base)
+{
+	int32_t status;
+	struct u2_phy_ext_fsm u2_phy;
+
+	u2_phy.pll_ctrl_reg = base + DRDU3_U2PLL_CTRL;
+	u2_phy.phy_ctrl_reg = base + DRDU3_U2PHY_CTRL;
+	u2_phy.phy_iddq = DRDU3_U2PHY_IDDQ;
+	u2_phy.pwr_ctrl_reg = base + DRDU3_PWR_CTRL;
+	u2_phy.pwr_okin = DRDU3_U2PHY_DFE_SWITCH_PWROKIN;
+	u2_phy.pwr_onin = DRDU3_U2PHY_DFE_SWITCH_PWRONIN;
+
+	u2_phy_ext_fsm_power_on(&u2_phy);
+
+	status = pll_lock_check(base + DRDU3_U2PLL_CTRL, DRDU3_U2PLL_LOCK);
+	if (status != 0) {
+		/* re-try by toggling the PLL reset */
+		mmio_clrbits_32(base + DRDU3_U2PLL_CTRL,
+				(uint32_t)DRDU2_U2PLL_RESETB);
+		mmio_setbits_32(base + DRDU3_U2PLL_CTRL, DRDU3_U2PLL_RESETB);
+
+		status = pll_lock_check(base + DRDU3_U2PLL_CTRL,
+					DRDU3_U2PLL_LOCK);
+		if (status != 0) {
+			ERROR("%s() re-try PLL lock FAIL (0x%08x)\n", __func__,
+			      base + DRDU3_U2PLL_CTRL);
+		}
+	}
+	mmio_clrsetbits_32(base + DRDU3_U2PHY_CTRL,
+			   (DRDU3_U2PHY_PCTL_MASK << DRDU3_U2PHY_PCTL_OFFSET),
+			   (U2PHY_PCTL_NON_DRV_LOW << DRDU3_U2PHY_PCTL_OFFSET));
+
+	return status;
+}
+
+static int32_t drdu3_u3_phy_power_on(uint32_t base)
+{
+	int32_t status;
+
+	/* Set pctl with mode and soft reset */
+	mmio_clrsetbits_32(base + DRDU3_U3PHY_CTRL,
+			   (DRDU3_U3PHY_PCTL_MASK << DRDU3_U3PHY_PCTL_OFFSET),
+			   (U3PHY_PCTL_VAL << DRDU3_U3PHY_PCTL_OFFSET));
+
+	mmio_clrbits_32(base + DRDU3_U3PHY_PLL_CTRL,
+			(uint32_t) DRDU3_U3SSPLL_SUSPEND_EN);
+	mmio_setbits_32(base + DRDU3_U3PHY_PLL_CTRL, DRDU3_U3PLL_SEQ_START);
+	mmio_setbits_32(base + DRDU3_U3PHY_PLL_CTRL, DRDU3_U3PLL_RESETB);
+
+	/* Time to stabilize the PLL Control */
+	mdelay(1U);
+
+	status = pll_lock_check(base + DRDU3_U3PHY_PLL_CTRL,
+				DRDU3_U3PLL_SS_LOCK);
+
+	return status;
+}
+
+static int32_t drdu2_u2_phy_power_on(uint32_t base)
+{
+	int32_t status;
+	struct u2_phy_ext_fsm u2_phy;
+
+	u2_phy.pll_ctrl_reg = base + DRDU2_U2PLL_CTRL;
+	u2_phy.phy_ctrl_reg = base + DRDU2_PHY_CTRL;
+	u2_phy.phy_iddq = DRDU2_U2IDDQ;
+	u2_phy.pwr_ctrl_reg = base + DRDU2_PWR_CTRL;
+	u2_phy.pwr_okin = DRDU2_U2PHY_DFE_SWITCH_PWROKIN_I;
+	u2_phy.pwr_onin = DRDU2_U2PHY_DFE_SWITCH_PWRONIN_I;
+
+	u2_phy_ext_fsm_power_on(&u2_phy);
+
+	status = pll_lock_check(base + DRDU2_U2PLL_CTRL, DRDU2_U2PLL_LOCK);
+	if (status != 0) {
+		/* re-try by toggling the PLL reset */
+		mmio_clrbits_32(base + DRDU2_U2PLL_CTRL,
+				(uint32_t)DRDU2_U2PLL_RESETB);
+		mmio_setbits_32(base + DRDU2_U2PLL_CTRL, DRDU2_U2PLL_RESETB);
+
+		status = pll_lock_check(base + DRDU2_U2PLL_CTRL,
+					DRDU2_U2PLL_LOCK);
+		if (status != 0)
+			ERROR("%s() re-try PLL lock FAIL (0x%08x)\n", __func__,
+			      base + DRDU2_U2PLL_CTRL);
+	}
+	mmio_clrsetbits_32(base + DRDU2_PHY_CTRL,
+			   (DRDU2_U2PHY_PCTL_MASK << DRDU2_U2PHY_PCTL_OFFSET),
+			   (U2PHY_PCTL_NON_DRV_LOW << DRDU2_U2PHY_PCTL_OFFSET));
+
+	return status;
+}
+
+void u3h_u2drd_phy_reset(usb_phy_port_t *phy_port)
+{
+	usb_phy_t *phy = phy_port->p;
+
+	switch (phy_port->port_id) {
+	case USB3HS_PORT:
+		mmio_clrbits_32(phy->usb3hreg + USB3H_U2PHY_CTRL,
+				(uint32_t) USB3H_U2CTRL_CORERDY);
+		mmio_setbits_32(phy->usb3hreg + USB3H_U2PHY_CTRL,
+				USB3H_U2CTRL_CORERDY);
+		break;
+	case DRDU2_PORT:
+		mmio_clrbits_32(phy->drdu2reg + DRDU2_PHY_CTRL,
+				(uint32_t) DRDU2_U2CTRL_CORERDY);
+		mmio_setbits_32(phy->drdu2reg + DRDU2_PHY_CTRL,
+				DRDU2_U2CTRL_CORERDY);
+		break;
+	}
+}
+
+void u3drd_phy_reset(usb_phy_port_t *phy_port)
+{
+	usb_phy_t *phy = phy_port->p;
+
+	if (phy_port->port_id == DRD3HS_PORT) {
+		mmio_clrbits_32(phy->drdu3reg + DRDU3_U2PHY_CTRL,
+				(uint32_t) DRDU3_U2CTRL_CORERDY);
+		mmio_setbits_32(phy->drdu3reg + DRDU3_U2PHY_CTRL,
+				DRDU3_U2CTRL_CORERDY);
+	}
+}
+
+static int32_t u3h_u2drd_phy_power_on(usb_phy_port_t *phy_port)
+{
+	usb_phy_t *phy = phy_port->p;
+	int32_t status;
+
+	switch (phy_port->port_id) {
+	case USB3SS_PORT:
+		mmio_clrbits_32(phy->usb3hreg + USB3H_PHY_PWR_CTRL,
+				(uint32_t) USB3H_DISABLE_USB30_P0);
+		status = usb3h_u3_phy_power_on(phy->usb3hreg);
+		if (status != 0) {
+			goto err_usb3h_phy_on;
+		}
+		break;
+	case USB3HS_PORT:
+		mmio_clrbits_32(phy->usb3hreg + USB3H_PHY_PWR_CTRL,
+				(uint32_t) USB3H_DISABLE_EUSB_P1);
+		mmio_setbits_32(AXI_DEBUG_CTRL,
+				AXI_DBG_CTRL_SSPHY_DRD_MODE_DISABLE);
+		mmio_setbits_32(USB3H_DEBUG_CTRL,
+				USB3H_DBG_CTRL_SSPHY_DRD_MODE_DISABLE);
+
+		mmio_clrbits_32(phy->usb3hreg + USB3H_PWR_CTRL,
+				USB3H_PWR_CTRL_U2PHY_DFE_SWITCH_PWRONIN);
+		/* Delay as per external FSM spec */
+		udelay(10U);
+		mmio_clrbits_32(phy->usb3hreg + USB3H_PWR_CTRL,
+				USB3H_PWR_CTRL_U2PHY_DFE_SWITCH_PWROKIN);
+		status = usb3h_u2_phy_power_on(phy->usb3hreg);
+		if (status != 0) {
+			goto err_usb3h_phy_on;
+		}
+		break;
+	case DRDU2_PORT:
+		mmio_clrbits_32(phy->usb3hreg + USB3H_PHY_PWR_CTRL,
+				(uint32_t) USB3H_DISABLE_EUSB_P0);
+		mmio_setbits_32(AXI_DEBUG_CTRL,
+				AXI_DBG_CTRL_SSPHY_DRD_MODE_DISABLE);
+		mmio_setbits_32(USB3H_DEBUG_CTRL,
+				USB3H_DBG_CTRL_SSPHY_DRD_MODE_DISABLE);
+
+		mmio_clrbits_32(phy->usb3hreg + DRDU2_PWR_CTRL,
+				DRDU2_U2PHY_DFE_SWITCH_PWRONIN_I);
+		/* Delay as per external FSM spec */
+		udelay(10U);
+		mmio_clrbits_32(phy->usb3hreg + DRDU2_PWR_CTRL,
+				DRDU2_U2PHY_DFE_SWITCH_PWROKIN_I);
+
+		status = drdu2_u2_phy_power_on(phy->drdu2reg);
+		if (status != 0) {
+			mmio_setbits_32(phy->usb3hreg + USB3H_PHY_PWR_CTRL,
+					USB3H_DISABLE_EUSB_P0);
+			goto err_drdu2_phy_on;
+		}
+		break;
+	}
+
+	/* Device Mode */
+	if (phy_port->port_id == DRDU2_PORT) {
+		mmio_write_32(phy->drdu2reg + DRDU2_SOFT_RESET_CTRL,
+			      DRDU2_BDC_AXI_SOFT_RST_N);
+		mmio_setbits_32(phy->drdu2reg + DRDU2_PHY_CTRL,
+				DRDU2_U2SOFT_RST_N);
+	}
+	/* Host Mode */
+	mmio_write_32(phy->usb3hreg + USB3H_SOFT_RESET_CTRL,
+		      USB3H_XHC_AXI_SOFT_RST_N);
+	mmio_setbits_32(phy->usb3hreg + USB3H_U3PHY_CTRL, USB3H_U3SOFT_RST_N);
+
+	return 0U;
+ err_usb3h_phy_on:mmio_setbits_32(phy->usb3hreg + USB3H_PHY_PWR_CTRL,
+			(USB3H_DISABLE_EUSB_P1 |
+			 USB3H_DISABLE_USB30_P0));
+ err_drdu2_phy_on:
+
+	return status;
+}
+
+static int32_t u3drd_phy_power_on(usb_phy_port_t *phy_port)
+{
+	usb_phy_t *phy = phy_port->p;
+	int32_t status;
+
+	switch (phy_port->port_id) {
+	case DRD3SS_PORT:
+		mmio_clrbits_32(phy->drdu3reg + DRDU3_PHY_PWR_CTRL,
+				(uint32_t) DRDU3_DISABLE_USB30_P0);
+
+		status = drdu3_u3_phy_power_on(phy->drdu3reg);
+		if (status != 0) {
+			goto err_drdu3_phy_on;
+		}
+		break;
+	case DRD3HS_PORT:
+		mmio_clrbits_32(phy->drdu3reg + DRDU3_PHY_PWR_CTRL,
+				(uint32_t) DRDU3_DISABLE_EUSB_P0);
+		mmio_setbits_32(AXI_DEBUG_CTRL,
+				AXI_DBG_CTRL_SSPHY_DRD_MODE_DISABLE);
+		mmio_setbits_32(USB3H_DEBUG_CTRL,
+				USB3H_DBG_CTRL_SSPHY_DRD_MODE_DISABLE);
+
+		mmio_clrbits_32(phy->drdu3reg + DRDU3_PWR_CTRL,
+				DRDU3_U2PHY_DFE_SWITCH_PWRONIN);
+		/* Delay as per external FSM spec */
+		udelay(10U);
+		mmio_clrbits_32(phy->drdu3reg + DRDU3_PWR_CTRL,
+				DRDU3_U2PHY_DFE_SWITCH_PWROKIN);
+
+		status = drdu3_u2_phy_power_on(phy->drdu3reg);
+		if (status != 0) {
+			goto err_drdu3_phy_on;
+		}
+
+		/* Host Mode */
+		mmio_setbits_32(phy->drdu3reg + DRDU3_SOFT_RESET_CTRL,
+				DRDU3_XHC_AXI_SOFT_RST_N);
+		mmio_setbits_32(phy->drdu3reg + DRDU3_U3PHY_CTRL,
+				DRDU3_U3XHC_SOFT_RST_N);
+		/* Device Mode */
+		mmio_setbits_32(phy->drdu3reg + DRDU3_SOFT_RESET_CTRL,
+				DRDU3_BDC_AXI_SOFT_RST_N);
+		mmio_setbits_32(phy->drdu3reg + DRDU3_U3PHY_CTRL,
+				DRDU3_U3BDC_SOFT_RST_N);
+		break;
+	}
+
+	return 0U;
+ err_drdu3_phy_on:mmio_setbits_32(phy->drdu3reg + DRDU3_PHY_PWR_CTRL,
+			(DRDU3_DISABLE_EUSB_P0 |
+			 DRDU3_DISABLE_USB30_P0));
+
+	return status;
+}
+
+static void u3h_u2drd_phy_power_off(usb_phy_port_t *phy_port)
+{
+	usb_phy_t *p = phy_port->p;
+
+	switch (phy_port->port_id) {
+	case USB3SS_PORT:
+		mmio_setbits_32(p->usb3hreg + USB3H_PHY_PWR_CTRL,
+				USB3H_DISABLE_USB30_P0);
+		break;
+	case USB3HS_PORT:
+		mmio_setbits_32(p->usb3hreg + USB3H_PHY_PWR_CTRL,
+				USB3H_DISABLE_EUSB_P1);
+		break;
+	case DRDU2_PORT:
+		mmio_setbits_32(p->usb3hreg + USB3H_PHY_PWR_CTRL,
+				USB3H_DISABLE_EUSB_P0);
+		break;
+	}
+}
+
+static void u3drd_phy_power_off(usb_phy_port_t *phy_port)
+{
+	usb_phy_t *p = phy_port->p;
+
+	switch (phy_port->port_id) {
+	case DRD3SS_PORT:
+		mmio_setbits_32(p->drdu3reg + DRDU3_PHY_PWR_CTRL,
+				DRDU3_DISABLE_USB30_P0);
+		break;
+	case DRD3HS_PORT:
+		mmio_setbits_32(p->drdu3reg + DRDU3_PHY_PWR_CTRL,
+				DRDU3_DISABLE_EUSB_P0);
+		break;
+	}
+}
+
+int32_t usb_info_fill(usb_phy_t *phy_info)
+{
+	int32_t index;
+
+	if (phy_info->initialized != 0U) {
+		return USB_PHY_ALREADY_STARTED;
+	}
+
+	if (phy_info->phy_id == USB3H_DRDU2_PHY) {
+		phy_info->phy_port = usb_phy_port[USB3H_DRDU2_PHY - 1U];
+		phy_info->ports_enabled = 0x7U;
+	} else {
+		phy_info->phy_port = usb_phy_port[DRDU3_PHY - 1U];
+		phy_info->ports_enabled = 0x3U;
+	}
+
+	for (index = MAX_NR_PORTS - 1U; index > -1; index--) {
+		phy_info->phy_port[index].enabled = (phy_info->ports_enabled
+						     >> index) & 0x1U;
+		phy_info->phy_port[index].p = phy_info;
+		phy_info->phy_port[index].port_id = index;
+	}
+
+	return 0U;
+}
+
+int32_t usb_phy_init(usb_platform_dev *device)
+{
+	int32_t status;
+	usb_phy_t *phy_info;
+	uint32_t index;
+
+	phy_info = (usb_phy_t *)device->pcd_id;
+
+	status = usb_info_fill(phy_info);
+	if (status != 0) {
+		return (status == USB_PHY_ALREADY_STARTED) ? 0 : status;
+	}
+
+	for (index = 0U; index < MAX_NR_PORTS; index++) {
+		if (phy_info->phy_port[index].enabled != 0U) {
+			switch (phy_info->phy_id) {
+			case USB3H_DRDU2_PHY:
+				status =
+				    u3h_u2drd_phy_power_on(&phy_info->
+							   phy_port[index]);
+				break;
+			default:
+				status =
+				    u3drd_phy_power_on(&phy_info->
+						       phy_port[index]);
+			}
+		}
+	}
+
+	phy_info->initialized = !status;
+	return status;
+}
+
+void usb_phy_shutdown(usb_platform_dev *device)
+{
+	usb_phy_t *phy_info;
+	uint32_t index;
+
+	phy_info = (usb_phy_t *)device->pcd_id;
+
+	phy_info->initialized = 0U;
+
+	for (index = 0U; index < MAX_NR_PORTS; index++) {
+		if (phy_info->phy_port[index].enabled != 0U) {
+			switch (phy_info->phy_id) {
+			case USB3H_DRDU2_PHY:
+				u3h_u2drd_phy_power_off(&phy_info->
+							phy_port[index]);
+				break;
+			case DRDU3_PHY:
+				u3drd_phy_power_off(&phy_info->phy_port[index]);
+				break;
+			default:
+				INFO("%s: invalid phy id 0x%x\n", __func__,
+				     phy_info->phy_id);
+			}
+		}
+	}
+}
+
+int32_t usb_xhci_init(usb_platform_dev *device)
+{
+	int32_t status;
+
+	status = usb_phy_init(device);
+	if (status == USB_PHY_ALREADY_STARTED) {
+		status = 0U;
+	}
+
+	return status;
+}
+
+int32_t usb_device_init(unsigned int usb_func)
+{
+	int32_t status;
+	int32_t devices_initialized = 0U;
+
+	if ((usb_func & USB3H_USB2DRD) != 0U) {
+		status = usb_xhci_init(
+				&xhci_devices_configs[USB3H_USB2DRD_PHY]);
+		if (status == 0) {
+			devices_initialized++;
+		} else {
+			ERROR("%s(): USB3H_USB2DRD init failure\n", __func__);
+		}
+	}
+
+	if ((usb_func & USB3_DRD) != 0U) {
+		status = usb_xhci_init(&xhci_devices_configs[USB3_DRD_PHY]);
+		if (status == 0) {
+			devices_initialized++;
+		} else {
+			ERROR("%s(): USB3_DRD init failure\n", __func__);
+		}
+	}
+
+	return devices_initialized;
+}
diff --git a/plat/brcm/board/stingray/include/platform_usb.h b/plat/brcm/board/stingray/include/platform_usb.h
new file mode 100644
index 0000000..5b5309f
--- /dev/null
+++ b/plat/brcm/board/stingray/include/platform_usb.h
@@ -0,0 +1,19 @@
+/*
+ * Copyright (c) 2019 - 2021, Broadcom
+ *
+ * SPDX-License-Identifier: BSD-3-Clause
+ */
+
+#ifndef PLATFORM_USB_H
+#define PLATFORM_USB_H
+
+#include <platform_def.h>
+
+#define USB3_DRD		BIT(0U)
+#define USB3H_USB2DRD		BIT(1U)
+
+extern const unsigned int xhc_portsc_reg_offset[MAX_USB_PORTS];
+
+void xhci_phy_init(void);
+
+#endif /* PLATFORM_USB_H */
diff --git a/plat/brcm/board/stingray/include/sr_def.h b/plat/brcm/board/stingray/include/sr_def.h
index be0dee1..277836e 100644
--- a/plat/brcm/board/stingray/include/sr_def.h
+++ b/plat/brcm/board/stingray/include/sr_def.h
@@ -1,5 +1,5 @@
 /*
- * Copyright (c) 2016-2020, Broadcom
+ * Copyright (c) 2016-2021, Broadcom
  *
  * SPDX-License-Identifier: BSD-3-Clause
  */
@@ -193,6 +193,11 @@
 #define PLAT_CHIP_REV_GET	(mmio_read_32(ICFG_CHIP_REVISION_ID))
 
 /*******************************************************************************
+ * CMIC MII (MDIO) related constant
+ ******************************************************************************/
+#define PLAT_CMIC_MIIM_BASE	0x68920000U
+
+/*******************************************************************************
  * Timers related constants
  ******************************************************************************/
 /* ChipcommonG_tim0_TIM_TIMER1Load 0x68930000 */
diff --git a/plat/brcm/board/stingray/include/usb_phy.h b/plat/brcm/board/stingray/include/usb_phy.h
new file mode 100644
index 0000000..7d83182
--- /dev/null
+++ b/plat/brcm/board/stingray/include/usb_phy.h
@@ -0,0 +1,244 @@
+/*
+ * Copyright (c) 2017 - 2021, Broadcom
+ *
+ * SPDX-License-Identifier: BSD-3-Clause
+ */
+
+#ifndef USB_PHY_H
+#define USB_PHY_H
+
+#include <stdint.h>
+
+#include <common/debug.h>
+#include <drivers/delay_timer.h>
+#include <lib/mmio.h>
+
+#include <platform_def.h>
+
+#define DRDU2_U2PLL_NDIV_FRAC_OFFSET            0x0U
+
+#define DRDU2_U2PLL_NDIV_INT                    0x4U
+
+#define DRDU2_U2PLL_CTRL                        0x8U
+#define DRDU2_U2PLL_LOCK                        BIT(6U)
+#define DRDU2_U2PLL_RESETB                      BIT(5U)
+#define DRDU2_U2PLL_PDIV_MASK                   0xFU
+#define DRDU2_U2PLL_PDIV_OFFSET                 1U
+#define DRDU2_U2PLL_SUSPEND_EN                  BIT(0U)
+
+#define DRDU2_PHY_CTRL                          0x0CU
+#define DRDU2_U2IDDQ                            BIT(30U)
+#define DRDU2_U2SOFT_RST_N                      BIT(29U)
+#define DRDU2_U2PHY_ON_FLAG                     BIT(22U)
+#define DRDU2_U2PHY_PCTL_MASK                   0xFFFFU
+#define DRDU2_U2PHY_PCTL_OFFSET                 6U
+#define DRDU2_U2PHY_RESETB                      BIT(5U)
+#define DRDU2_U2PHY_ISO                         BIT(4U)
+#define DRDU2_U2AFE_BG_PWRDWNB                  BIT(3U)
+#define DRDU2_U2AFE_PLL_PWRDWNB                 BIT(2U)
+#define DRDU2_U2AFE_LDO_PWRDWNB                 BIT(1U)
+#define DRDU2_U2CTRL_CORERDY                    BIT(0U)
+
+#define DRDU2_STRAP_CTRL                        0x18U
+#define DRDU2_FORCE_HOST_MODE                   BIT(5U)
+#define DRDU2_FORCE_DEVICE_MODE                 BIT(4U)
+#define BDC_USB_STP_SPD_MASK                    0x7U
+#define BDC_USB_STP_SPD_OFFSET                  0U
+
+#define DRDU2_PWR_CTRL                          0x1CU
+#define DRDU2_U2PHY_DFE_SWITCH_PWROKIN_I        BIT(2U)
+#define DRDU2_U2PHY_DFE_SWITCH_PWRONIN_I        BIT(1U)
+
+#define DRDU2_SOFT_RESET_CTRL                   0x20U
+#define DRDU2_BDC_AXI_SOFT_RST_N                BIT(0U)
+
+#define USB3H_U2PLL_NDIV_FRAC                   0x4U
+
+#define USB3H_U2PLL_NDIV_INT                    0x8U
+
+#define USB3H_U2PLL_CTRL                        0xCU
+#define USB3H_U2PLL_LOCK                        BIT(6U)
+#define USB3H_U2PLL_RESETB                      BIT(5U)
+#define USB3H_U2PLL_PDIV_MASK                   0xFU
+#define USB3H_U2PLL_PDIV_OFFSET                 1U
+
+#define USB3H_U2PHY_CTRL                        0x10U
+#define USB3H_U2PHY_ON_FLAG                     22U
+#define USB3H_U2PHY_PCTL_MASK                   0xFFFFU
+#define USB3H_U2PHY_PCTL_OFFSET                 6U
+#define USB3H_U2PHY_IDDQ                        BIT(29U)
+#define USB3H_U2PHY_RESETB                      BIT(5U)
+#define USB3H_U2PHY_ISO                         BIT(4U)
+#define USB3H_U2AFE_BG_PWRDWNB                  BIT(3U)
+#define USB3H_U2AFE_PLL_PWRDWNB                 BIT(2U)
+#define USB3H_U2AFE_LDO_PWRDWNB                 BIT(1U)
+#define USB3H_U2CTRL_CORERDY                    BIT(0U)
+
+#define USB3H_U3PHY_CTRL                        0x14U
+#define USB3H_U3SOFT_RST_N                      BIT(30U)
+#define USB3H_U3MDIO_RESETB_I                   BIT(29U)
+#define USB3H_U3POR_RESET_I                     BIT(28U)
+#define USB3H_U3PHY_PCTL_MASK                   0xFFFFU
+#define USB3H_U3PHY_PCTL_OFFSET                 2U
+#define USB3H_U3PHY_RESETB                      BIT(1U)
+
+#define USB3H_U3PHY_PLL_CTRL                    0x18U
+#define USB3H_U3PLL_REFCLK_MASK                 0x7U
+#define USB3H_U3PLL_REFCLK_OFFSET               4U
+#define USB3H_U3PLL_SS_LOCK                     BIT(3U)
+#define USB3H_U3PLL_SEQ_START                   BIT(2U)
+#define USB3H_U3SSPLL_SUSPEND_EN                BIT(1U)
+#define USB3H_U3PLL_RESETB                      BIT(0U)
+
+#define USB3H_PWR_CTRL                          0x28U
+#define USB3H_PWR_CTRL_OVERRIDE_I_R             4U
+#define USB3H_PWR_CTRL_U2PHY_DFE_SWITCH_PWROKIN BIT(11U)
+#define USB3H_PWR_CTRL_U2PHY_DFE_SWITCH_PWRONIN BIT(10U)
+
+#define USB3H_SOFT_RESET_CTRL                   0x2CU
+#define USB3H_XHC_AXI_SOFT_RST_N                BIT(1U)
+
+#define USB3H_PHY_PWR_CTRL                      0x38U
+#define USB3H_DISABLE_USB30_P0                  BIT(2U)
+#define USB3H_DISABLE_EUSB_P1                   BIT(1U)
+#define USB3H_DISABLE_EUSB_P0                   BIT(0U)
+
+
+#define DRDU3_U2PLL_NDIV_FRAC                   0x4U
+
+#define DRDU3_U2PLL_NDIV_INT                    0x8U
+
+#define DRDU3_U2PLL_CTRL                        0xCU
+#define DRDU3_U2PLL_LOCK                        BIT(6U)
+#define DRDU3_U2PLL_RESETB                      BIT(5U)
+#define DRDU3_U2PLL_PDIV_MASK                   0xFU
+#define DRDU3_U2PLL_PDIV_OFFSET                 1U
+
+#define DRDU3_U2PHY_CTRL                        0x10U
+#define DRDU3_U2PHY_IDDQ                        BIT(29U)
+#define DRDU3_U2PHY_ON_FLAG                     BIT(22U)
+#define DRDU3_U2PHY_PCTL_MASK                   0xFFFFU
+#define DRDU3_U2PHY_PCTL_OFFSET                 6U
+#define DRDU3_U2PHY_RESETB                      BIT(5U)
+#define DRDU3_U2PHY_ISO                         BIT(4U)
+#define DRDU3_U2AFE_BG_PWRDWNB                  BIT(3U)
+#define DRDU3_U2AFE_PLL_PWRDWNB                 BIT(2U)
+#define DRDU3_U2AFE_LDO_PWRDWNB                 BIT(1U)
+#define DRDU3_U2CTRL_CORERDY                    BIT(0U)
+
+#define DRDU3_U3PHY_CTRL                        0x14U
+#define DRDU3_U3XHC_SOFT_RST_N                  BIT(31U)
+#define DRDU3_U3BDC_SOFT_RST_N                  BIT(30U)
+#define DRDU3_U3MDIO_RESETB_I                   BIT(29U)
+#define DRDU3_U3POR_RESET_I                     BIT(28U)
+#define DRDU3_U3PHY_PCTL_MASK                   0xFFFFU
+#define DRDU3_U3PHY_PCTL_OFFSET                 2U
+#define DRDU3_U3PHY_RESETB                      BIT(1U)
+
+#define DRDU3_U3PHY_PLL_CTRL                    0x18U
+#define DRDU3_U3PLL_REFCLK_MASK                 0x7U
+#define DRDU3_U3PLL_REFCLK_OFFSET               4U
+#define DRDU3_U3PLL_SS_LOCK                     BIT(3U)
+#define DRDU3_U3PLL_SEQ_START                   BIT(2U)
+#define DRDU3_U3SSPLL_SUSPEND_EN                BIT(1U)
+#define DRDU3_U3PLL_RESETB                      BIT(0U)
+
+#define DRDU3_STRAP_CTRL                        0x28U
+#define BDC_USB_STP_SPD_MASK                    0x7U
+#define BDC_USB_STP_SPD_OFFSET                  0U
+#define BDC_USB_STP_SPD_SS                      0x0U
+#define BDC_USB_STP_SPD_HS                      0x2U
+
+#define DRDU3_PWR_CTRL                          0x2cU
+#define DRDU3_U2PHY_DFE_SWITCH_PWROKIN          BIT(12U)
+#define DRDU3_U2PHY_DFE_SWITCH_PWRONIN          BIT(11U)
+#define DRDU3_PWR_CTRL_OVERRIDE_I_R             4U
+
+#define DRDU3_SOFT_RESET_CTRL                   0x30U
+#define DRDU3_XHC_AXI_SOFT_RST_N                BIT(1U)
+#define DRDU3_BDC_AXI_SOFT_RST_N                BIT(0U)
+
+#define DRDU3_PHY_PWR_CTRL                      0x3cU
+#define DRDU3_DISABLE_USB30_P0                  BIT(2U)
+#define DRDU3_DISABLE_EUSB_P1                   BIT(1U)
+#define DRDU3_DISABLE_EUSB_P0                   BIT(0U)
+
+#define PLL_REFCLK_PAD                          0x0U
+#define PLL_REFCLK_25MHZ                        0x1U
+#define PLL_REFCLK_96MHZ                        0x2U
+#define PLL_REFCLK_INTERNAL                     0x3U
+/* USB PLL lock time out for 10 ms */
+#define PLL_LOCK_RETRY_COUNT                    10000U
+
+
+#define U2PLL_NDIV_INT_VAL                      0x13U
+#define U2PLL_NDIV_FRAC_VAL                     0x1005U
+#define U2PLL_PDIV_VAL                          0x1U
+/*
+ * Using external FSM
+ * BIT-3:2: device mode; mode is not effect
+ * BIT-1: soft reset active low
+ */
+#define U2PHY_PCTL_VAL                          0x0003U
+/* Non-driving signal low */
+#define U2PHY_PCTL_NON_DRV_LOW                  0x0002U
+#define U3PHY_PCTL_VAL                          0x0006U
+
+#define MAX_NR_PORTS                            3U
+
+#define USB3H_DRDU2_PHY                         1U
+#define DRDU3_PHY                               2U
+
+#define USB_HOST_MODE                           1U
+#define USB_DEV_MODE                            2U
+
+#define USB3SS_PORT                             0U
+#define DRDU2_PORT                              1U
+#define USB3HS_PORT                             2U
+
+#define DRD3SS_PORT                             0U
+#define DRD3HS_PORT                             1U
+
+#define SR_USB_PHY_COUNT                        2U
+
+#define DRDU3_PIPE_CTRL			0x68500000U
+#define DRDU3H_XHC_REGS_CPLIVER		0x68501000U
+#define USB3H_PIPE_CTRL			0x68510000U
+#define DRD2U3H_XHC_REGS_CPLIVER	0x68511000U
+#define DRDU2_U2PLL_NDIV_FRAC		0x68520000U
+
+#define AXI_DEBUG_CTRL				0x68500038U
+#define AXI_DBG_CTRL_SSPHY_DRD_MODE_DISABLE	BIT(12U)
+
+#define USB3H_DEBUG_CTRL			0x68510034U
+#define USB3H_DBG_CTRL_SSPHY_DRD_MODE_DISABLE	BIT(7U)
+
+typedef struct _usb_phy_port usb_phy_port_t;
+
+typedef struct {
+	uint32_t drdu2reg;
+	uint32_t usb3hreg;
+	uint32_t drdu3reg;
+	uint32_t phy_id;
+	uint32_t ports_enabled;
+	uint32_t initialized;
+	usb_phy_port_t *phy_port;
+} usb_phy_t;
+
+struct _usb_phy_port {
+	uint32_t port_id;
+	uint32_t mode;
+	uint32_t enabled;
+	usb_phy_t *p;
+};
+
+struct u2_phy_ext_fsm {
+	uint32_t pll_ctrl_reg;
+	uint32_t phy_ctrl_reg;
+	uint32_t phy_iddq;
+	uint32_t pwr_ctrl_reg;
+	uint32_t pwr_okin;
+	uint32_t pwr_onin;
+};
+
+#endif /* USB_PHY_H */
diff --git a/plat/brcm/board/stingray/platform.mk b/plat/brcm/board/stingray/platform.mk
index c5509bb..aa2fe86 100644
--- a/plat/brcm/board/stingray/platform.mk
+++ b/plat/brcm/board/stingray/platform.mk
@@ -1,5 +1,5 @@
 #
-# Copyright (c) 2019-2020, Broadcom
+# Copyright (c) 2019-2021, Broadcom
 #
 # SPDX-License-Identifier: BSD-3-Clause
 #
@@ -73,6 +73,12 @@
 BOARD_CFG := bcm958742t
 endif
 
+# Use USB
+ifeq (${USE_USB},yes)
+$(info Using USB)
+$(eval $(call add_define,USE_USB))
+endif
+
 # Use PAXB
 ifeq (${USE_PAXB},yes)
 $(info Using PAXB)
@@ -190,17 +196,22 @@
 				plat/${SOC_DIR}/src/tz_sec.c \
 				drivers/arm/tzc/tzc400.c \
 				plat/${SOC_DIR}/driver/plat_emmc.c \
-				plat/${SOC_DIR}/src/topology.c
+				plat/${SOC_DIR}/src/topology.c \
+				drivers/brcm/mdio/mdio.c
 
 ifeq (${USE_CHIMP},yes)
 PLAT_BL_COMMON_SOURCES	+=	drivers/brcm/chimp.c
 endif
 
+ifeq (${USE_USB},yes)
+PLAT_BL_COMMON_SOURCES	+=	plat/${SOC_DIR}/driver/usb.c \
+				plat/${SOC_DIR}/driver/usb_phy.c
+endif
+
 BL2_SOURCES		+=	plat/${SOC_DIR}/driver/ihost_pll_config.c \
 				plat/${SOC_DIR}/src/bl2_setup.c \
 				plat/${SOC_DIR}/driver/swreg.c
 
-
 ifeq (${USE_DDR},yes)
 PLAT_INCLUDES		+=	-Iplat/${SOC_DIR}/driver/ddr/soc/include
 else
diff --git a/plat/brcm/board/stingray/src/bl31_setup.c b/plat/brcm/board/stingray/src/bl31_setup.c
index a2a274d..04df6a0 100644
--- a/plat/brcm/board/stingray/src/bl31_setup.c
+++ b/plat/brcm/board/stingray/src/bl31_setup.c
@@ -1,5 +1,5 @@
 /*
- * Copyright (c) 2015 - 2020, Broadcom
+ * Copyright (c) 2015 - 2021, Broadcom
  *
  * SPDX-License-Identifier: BSD-3-Clause
  */
@@ -28,6 +28,9 @@
 #include <paxb.h>
 #include <paxc.h>
 #include <platform_def.h>
+#ifdef USE_USB
+#include <platform_usb.h>
+#endif
 #include <sdio.h>
 #include <sr_utils.h>
 #include <timer_sync.h>
diff --git a/plat/hisilicon/hikey/hikey_bl1_setup.c b/plat/hisilicon/hikey/hikey_bl1_setup.c
index 86e4fd6..01c48ec 100644
--- a/plat/hisilicon/hikey/hikey_bl1_setup.c
+++ b/plat/hisilicon/hikey/hikey_bl1_setup.c
@@ -1,5 +1,5 @@
 /*
- * Copyright (c) 2017-2018, ARM Limited and Contributors. All rights reserved.
+ * Copyright (c) 2017-2021, ARM Limited and Contributors. All rights reserved.
  *
  * SPDX-License-Identifier: BSD-3-Clause
  */
@@ -27,6 +27,7 @@
 /* Data structure which holds the extents of the trusted RAM for BL1 */
 static meminfo_t bl1_tzram_layout;
 static console_t console;
+static struct mmc_device_info mmc_info;
 
 enum {
 	BOOT_NORMAL = 0,
@@ -78,7 +79,6 @@
 void bl1_platform_setup(void)
 {
 	dw_mmc_params_t params;
-	struct mmc_device_info info;
 
 	assert((HIKEY_BL1_MMC_DESC_BASE >= SRAM_BASE) &&
 	       ((SRAM_BASE + SRAM_SIZE) >=
@@ -99,8 +99,8 @@
 	params.clk_rate = 24 * 1000 * 1000;
 	params.bus_width = MMC_BUS_WIDTH_8;
 	params.flags = MMC_FLAG_CMD23;
-	info.mmc_dev_type = MMC_IS_EMMC;
-	dw_mmc_init(&params, &info);
+	mmc_info.mmc_dev_type = MMC_IS_EMMC;
+	dw_mmc_init(&params, &mmc_info);
 
 	hikey_io_setup();
 }
diff --git a/plat/hisilicon/hikey/hikey_bl2_setup.c b/plat/hisilicon/hikey/hikey_bl2_setup.c
index feb7f8a..a90f12c 100644
--- a/plat/hisilicon/hikey/hikey_bl2_setup.c
+++ b/plat/hisilicon/hikey/hikey_bl2_setup.c
@@ -1,5 +1,5 @@
 /*
- * Copyright (c) 2017-2018, ARM Limited and Contributors. All rights reserved.
+ * Copyright (c) 2017-2021, ARM Limited and Contributors. All rights reserved.
  *
  * SPDX-License-Identifier: BSD-3-Clause
  */
@@ -33,6 +33,7 @@
 
 static meminfo_t bl2_el3_tzram_layout;
 static console_t console;
+static struct mmc_device_info mmc_info;
 
 enum {
 	BOOT_MODE_RECOVERY = 0,
@@ -290,7 +291,6 @@
 void bl2_platform_setup(void)
 {
 	dw_mmc_params_t params;
-	struct mmc_device_info info;
 
 	hikey_sp804_init();
 	hikey_gpio_init();
@@ -322,8 +322,8 @@
 	params.clk_rate = 24 * 1000 * 1000;
 	params.bus_width = MMC_BUS_WIDTH_8;
 	params.flags = MMC_FLAG_CMD23;
-	info.mmc_dev_type = MMC_IS_EMMC;
-	dw_mmc_init(&params, &info);
+	mmc_info.mmc_dev_type = MMC_IS_EMMC;
+	dw_mmc_init(&params, &mmc_info);
 
 	hikey_io_setup();
 }
diff --git a/plat/hisilicon/poplar/bl1_plat_setup.c b/plat/hisilicon/poplar/bl1_plat_setup.c
index 047ba62..acc1f0e 100644
--- a/plat/hisilicon/poplar/bl1_plat_setup.c
+++ b/plat/hisilicon/poplar/bl1_plat_setup.c
@@ -1,5 +1,5 @@
 /*
- * Copyright (c) 2017-2018, ARM Limited and Contributors. All rights reserved.
+ * Copyright (c) 2017-2021, ARM Limited and Contributors. All rights reserved.
  *
  * SPDX-License-Identifier: BSD-3-Clause
  */
@@ -30,6 +30,10 @@
 static meminfo_t bl2_tzram_layout;
 static console_t console;
 
+#if !POPLAR_RECOVERY
+static struct mmc_device_info mmc_info;
+#endif
+
 /*
  * Cannot use default weak implementation in bl1_main.c because BL1 RW data is
  * not at the top of the secure memory.
@@ -90,7 +94,6 @@
 {
 	int i;
 #if !POPLAR_RECOVERY
-	struct mmc_device_info info;
 	dw_mmc_params_t params = EMMC_INIT_PARAMS(POPLAR_EMMC_DESC_BASE);
 #endif
 
@@ -103,8 +106,8 @@
 #if !POPLAR_RECOVERY
 	/* SoC-specific emmc register are initialized/configured by bootrom */
 	INFO("BL1: initializing emmc\n");
-	info.mmc_dev_type = MMC_IS_EMMC;
-	dw_mmc_init(&params, &info);
+	mmc_info.mmc_dev_type = MMC_IS_EMMC;
+	dw_mmc_init(&params, &mmc_info);
 #endif
 
 	plat_io_setup();
diff --git a/plat/hisilicon/poplar/bl2_plat_setup.c b/plat/hisilicon/poplar/bl2_plat_setup.c
index 482935c..ee46772 100644
--- a/plat/hisilicon/poplar/bl2_plat_setup.c
+++ b/plat/hisilicon/poplar/bl2_plat_setup.c
@@ -1,5 +1,5 @@
 /*
- * Copyright (c) 2017, ARM Limited and Contributors. All rights reserved.
+ * Copyright (c) 2017-2021, ARM Limited and Contributors. All rights reserved.
  *
  * SPDX-License-Identifier: BSD-3-Clause
  */
@@ -26,6 +26,9 @@
 
 static meminfo_t bl2_tzram_layout __aligned(CACHE_WRITEBACK_GRANULE);
 static console_t console;
+#if !POPLAR_RECOVERY
+static struct mmc_device_info mmc_info;
+#endif
 
 /*******************************************************************************
  * Transfer SCP_BL2 from Trusted RAM using the SCP Download protocol.
@@ -171,8 +174,6 @@
 {
 	struct meminfo *mem_layout = (struct meminfo *)arg1;
 #if !POPLAR_RECOVERY
-	struct mmc_device_info info;
-
 	dw_mmc_params_t params = EMMC_INIT_PARAMS(POPLAR_EMMC_DESC_BASE);
 #endif
 
@@ -187,8 +188,8 @@
 #if !POPLAR_RECOVERY
 	/* SoC-specific emmc register are initialized/configured by bootrom */
 	INFO("BL2: initializing emmc\n");
-	info.mmc_dev_type = MMC_IS_EMMC;
-	dw_mmc_init(&params, &info);
+	mmc_info.mmc_dev_type = MMC_IS_EMMC;
+	dw_mmc_init(&params, &mmc_info);
 #endif
 
 	plat_io_setup();
diff --git a/plat/intel/soc/agilex/bl2_plat_setup.c b/plat/intel/soc/agilex/bl2_plat_setup.c
index f002947..b6b3e16 100644
--- a/plat/intel/soc/agilex/bl2_plat_setup.c
+++ b/plat/intel/soc/agilex/bl2_plat_setup.c
@@ -1,6 +1,6 @@
 /*
- * Copyright (c) 2019-2020, ARM Limited and Contributors. All rights reserved.
- * Copyright (c) 2019-2020, Intel Corporation. All rights reserved.
+ * Copyright (c) 2019-2021, ARM Limited and Contributors. All rights reserved.
+ * Copyright (c) 2019-2021, Intel Corporation. All rights reserved.
  *
  * SPDX-License-Identifier: BSD-3-Clause
  */
@@ -29,6 +29,7 @@
 #include "socfpga_system_manager.h"
 #include "wdt/watchdog.h"
 
+static struct mmc_device_info mmc_info;
 
 const mmap_region_t agilex_plat_mmap[] = {
 	MAP_REGION_FLAT(DRAM_BASE, DRAM_SIZE,
@@ -87,7 +88,6 @@
 void bl2_el3_plat_arch_setup(void)
 {
 
-	struct mmc_device_info info;
 	const mmap_region_t bl_regions[] = {
 		MAP_REGION_FLAT(BL2_BASE, BL2_END - BL2_BASE,
 			MT_MEMORY | MT_RW | MT_SECURE),
@@ -110,12 +110,12 @@
 
 	dw_mmc_params_t params = EMMC_INIT_PARAMS(0x100000, get_mmc_clk());
 
-	info.mmc_dev_type = MMC_IS_SD;
-	info.ocr_voltage = OCR_3_3_3_4 | OCR_3_2_3_3;
+	mmc_info.mmc_dev_type = MMC_IS_SD;
+	mmc_info.ocr_voltage = OCR_3_3_3_4 | OCR_3_2_3_3;
 
 	switch (boot_source) {
 	case BOOT_SOURCE_SDMMC:
-		dw_mmc_init(&params, &info);
+		dw_mmc_init(&params, &mmc_info);
 		socfpga_io_setup(boot_source);
 		break;
 
diff --git a/plat/intel/soc/stratix10/bl2_plat_setup.c b/plat/intel/soc/stratix10/bl2_plat_setup.c
index 721a690..ecf1f01 100644
--- a/plat/intel/soc/stratix10/bl2_plat_setup.c
+++ b/plat/intel/soc/stratix10/bl2_plat_setup.c
@@ -1,6 +1,6 @@
 /*
- * Copyright (c) 2019-2020, ARM Limited and Contributors. All rights reserved.
- * Copyright (c) 2019-2020, Intel Corporation. All rights reserved.
+ * Copyright (c) 2019-2021, ARM Limited and Contributors. All rights reserved.
+ * Copyright (c) 2019-2021, Intel Corporation. All rights reserved.
  *
  * SPDX-License-Identifier: BSD-3-Clause
  */
@@ -27,6 +27,7 @@
 #include "s10_pinmux.h"
 #include "wdt/watchdog.h"
 
+static struct mmc_device_info mmc_info;
 
 const mmap_region_t plat_stratix10_mmap[] = {
 	MAP_REGION_FLAT(DRAM_BASE, DRAM_SIZE,
@@ -83,7 +84,6 @@
 void bl2_el3_plat_arch_setup(void)
 {
 
-	struct mmc_device_info info;
 	const mmap_region_t bl_regions[] = {
 		MAP_REGION_FLAT(BL2_BASE, BL2_END - BL2_BASE,
 			MT_MEMORY | MT_RW | MT_SECURE),
@@ -106,12 +106,12 @@
 
 	dw_mmc_params_t params = EMMC_INIT_PARAMS(0x100000, get_mmc_clk());
 
-	info.mmc_dev_type = MMC_IS_SD;
-	info.ocr_voltage = OCR_3_3_3_4 | OCR_3_2_3_3;
+	mmc_info.mmc_dev_type = MMC_IS_SD;
+	mmc_info.ocr_voltage = OCR_3_3_3_4 | OCR_3_2_3_3;
 
 	switch (boot_source) {
 	case BOOT_SOURCE_SDMMC:
-		dw_mmc_init(&params, &info);
+		dw_mmc_init(&params, &mmc_info);
 		socfpga_io_setup(boot_source);
 		break;
 
diff --git a/plat/marvell/armada/a8k/common/a8k_common.mk b/plat/marvell/armada/a8k/common/a8k_common.mk
index 8a463ea..90883f2 100644
--- a/plat/marvell/armada/a8k/common/a8k_common.mk
+++ b/plat/marvell/armada/a8k/common/a8k_common.mk
@@ -10,13 +10,14 @@
 MARVELL_DRV_BASE	:= drivers/marvell
 MARVELL_COMMON_BASE	:= plat/marvell/armada/common
 
-MARVELL_SVC_TEST		:= 0
+MARVELL_SVC_TEST	:= 0
 $(eval $(call add_define,MARVELL_SVC_TEST))
 
 ERRATA_A72_859971	:= 1
 
 # Enable MSS support for a8k family
 MSS_SUPPORT		:= 1
+$(eval $(call add_define,MSS_SUPPORT))
 
 # Disable EL3 cache for power management
 BL31_CACHE_DISABLE	:= 0
@@ -112,11 +113,17 @@
 				$(MARVELL_DRV_BASE)/amb_adec.c	\
 				$(MARVELL_DRV_BASE)/ccu.c	\
 				$(MARVELL_DRV_BASE)/cache_llc.c	\
-				$(MARVELL_DRV_BASE)/comphy/phy-comphy-cp110.c \
-				$(MARVELL_DRV_BASE)/mc_trustzone/mc_trustzone.c \
-				$(MARVELL_DRV_BASE)/mg_conf_cm3/mg_conf_cm3.c \
+				$(MARVELL_DRV_BASE)/comphy/phy-comphy-cp110.c	\
+				$(MARVELL_DRV_BASE)/mc_trustzone/mc_trustzone.c	\
+				$(MARVELL_DRV_BASE)/secure_dfx_access/armada_thermal.c	\
+				$(MARVELL_DRV_BASE)/secure_dfx_access/misc_dfx.c	\
+				$(MARVELL_DRV_BASE)/ddr_phy_access.c	\
 				drivers/rambus/trng_ip_76.c
 
+ifeq (${MSS_SUPPORT}, 1)
+MARVELL_DRV		+=	$(MARVELL_DRV_BASE)/mg_conf_cm3/mg_conf_cm3.c
+endif
+
 BL31_PORTING_SOURCES	:=	$(BOARD_DIR)/board/marvell_plat_config.c
 
 ifeq ($(SYSTEM_POWER_SUPPORT),1)
@@ -139,6 +146,8 @@
 # Add trace functionality for PM
 BL31_SOURCES		+=	$(PLAT_COMMON_BASE)/plat_pm_trace.c
 
+
+ifeq (${MSS_SUPPORT}, 1)
 # Force builds with BL2 image on a80x0 platforms
 ifndef SCP_BL2
  $(error "Error: SCP_BL2 image is mandatory for a8k family")
@@ -146,6 +155,7 @@
 
 # MSS (SCP) build
 include $(PLAT_COMMON_BASE)/mss/mss_a8k.mk
+endif
 
 # BLE (ROM context execution code, AKA binary extension)
 BLE_PATH	?=  $(PLAT_COMMON_BASE)/ble
diff --git a/plat/marvell/armada/a8k/common/include/a8k_plat_def.h b/plat/marvell/armada/a8k/common/include/a8k_plat_def.h
index de80315..3a0fd4b 100644
--- a/plat/marvell/armada/a8k/common/include/a8k_plat_def.h
+++ b/plat/marvell/armada/a8k/common/include/a8k_plat_def.h
@@ -64,7 +64,8 @@
 #define MVEBU_AP_GPIO_DATA_IN		(MVEBU_AP_GPIO_REGS + 0x10)
 #define MVEBU_AP_I2C_BASE		(MVEBU_REGS_BASE + 0x511000)
 #define MVEBU_CP0_I2C_BASE		(MVEBU_CP_REGS_BASE(0) + 0x701000)
-#define MVEBU_AP_EXT_TSEN_BASE		(MVEBU_RFU_BASE + 0x8084)
+#define MVEBU_AP_GEN_MGMT_BASE		(MVEBU_RFU_BASE + 0x8000)
+#define MVEBU_AP_EXT_TSEN_BASE		(MVEBU_AP_GEN_MGMT_BASE + 0x84)
 
 #define MVEBU_AP_MC_TRUSTZONE_REG_LOW(ap, win)	(MVEBU_REGS_BASE_AP(ap) + \
 							0x20080 + ((win) * 0x8))
diff --git a/plat/marvell/armada/a8k/common/mss/mss_a8k.mk b/plat/marvell/armada/a8k/common/mss/mss_a8k.mk
index d8d4921..315fc87 100644
--- a/plat/marvell/armada/a8k/common/mss/mss_a8k.mk
+++ b/plat/marvell/armada/a8k/common/mss/mss_a8k.mk
@@ -11,7 +11,8 @@
 BL2_SOURCES		+=	$(A8K_MSS_SOURCE)/mss_bl2_setup.c \
 				$(MARVELL_MOCHI_DRV)
 
-BL31_SOURCES		+=	$(A8K_MSS_SOURCE)/mss_pm_ipc.c
+BL31_SOURCES		+=	$(A8K_MSS_SOURCE)/mss_pm_ipc.c \
+				$(A8K_MSS_SOURCE)/mss_bl31_setup.c
 
 PLAT_INCLUDES		+=	-I$(A8K_MSS_SOURCE)
 
diff --git a/plat/marvell/armada/a8k/common/mss/mss_bl2_setup.c b/plat/marvell/armada/a8k/common/mss/mss_bl2_setup.c
index 71fa2b8..dee2d5b 100644
--- a/plat/marvell/armada/a8k/common/mss/mss_bl2_setup.c
+++ b/plat/marvell/armada/a8k/common/mss/mss_bl2_setup.c
@@ -16,7 +16,7 @@
 
 #include <armada_common.h>
 #include <marvell_plat_priv.h> /* timer functionality */
-
+#include "mss_defs.h"
 #include "mss_scp_bootloader.h"
 
 /* MSS windows configuration */
@@ -30,10 +30,6 @@
 #define MSS_EXTERNAL_ADDR_MASK		0xfffffff
 #define MSS_INTERNAL_ACCESS_BIT		28
 
-#define MSS_AP_REGS_OFFSET		0x580000
-#define MSS_CP_SRAM_OFFSET		0x220000
-#define MSS_CP_REGS_OFFSET		0x280000
-
 struct addr_map_win ccu_mem_map[] = {
 	{MVEBU_CP_REGS_BASE(0), 0x4000000, IO_0_TID}
 };
@@ -130,11 +126,7 @@
 
 uintptr_t bl2_plat_get_cp_mss_sram(int ap_idx, int cp_idx)
 {
-	if (is_secure()) {
-		return MVEBU_CP_REGS_BASE(cp_idx) + MSS_CP_SRAM_OFFSET;
-	}
-
-	return 0; /* SRAM will not be used */
+	return MVEBU_CP_REGS_BASE(cp_idx) + MSS_CP_SRAM_OFFSET;
 }
 
 uintptr_t bl2_plat_get_ap_mss_regs(int ap_idx)
diff --git a/plat/marvell/armada/a8k/common/mss/mss_bl31_setup.c b/plat/marvell/armada/a8k/common/mss/mss_bl31_setup.c
new file mode 100644
index 0000000..52a8929
--- /dev/null
+++ b/plat/marvell/armada/a8k/common/mss/mss_bl31_setup.c
@@ -0,0 +1,37 @@
+/*
+ * Copyright (C) 2021 Marvell International Ltd.
+ *
+ * SPDX-License-Identifier:     BSD-3-Clause
+ * https://spdx.org/licenses
+ */
+
+#include <platform_def.h>
+
+#include <common/bl_common.h>
+#include <common/debug.h>
+#include <lib/mmio.h>
+
+#include <armada_common.h>
+
+#include "mss_defs.h"
+
+void mss_start_cp_cm3(int cp)
+{
+	uint32_t magic;
+	uintptr_t sram = MVEBU_CP_REGS_BASE(cp) + MSS_CP_SRAM_OFFSET;
+	uintptr_t regs = MVEBU_CP_REGS_BASE(cp) + MSS_CP_REGS_OFFSET;
+
+	magic = mmio_read_32(sram);
+
+	/* Make sure the FW was loaded */
+	if (magic != MSS_FW_READY_MAGIC) {
+		return;
+	}
+
+	NOTICE("Starting CP%d MSS CPU\n", cp);
+	/* remove the magic */
+	mmio_write_32(sram, 0);
+	/* Release M3 from reset */
+	mmio_write_32(MSS_M3_RSTCR(regs),
+		      (MSS_M3_RSTCR_RST_OFF << MSS_M3_RSTCR_RST_OFFSET));
+}
diff --git a/plat/marvell/armada/a8k/common/mss/mss_defs.h b/plat/marvell/armada/a8k/common/mss/mss_defs.h
new file mode 100644
index 0000000..6956461
--- /dev/null
+++ b/plat/marvell/armada/a8k/common/mss/mss_defs.h
@@ -0,0 +1,33 @@
+/*
+ * Copyright (C) 2021 Marvell International Ltd.
+ *
+ * SPDX-License-Identifier:     BSD-3-Clause
+ * https://spdx.org/licenses
+ */
+
+#ifndef MSS_DEFS_H
+#define MSS_DEFS_H
+
+#define MSS_DMA_SRCBR(base)		(base + 0xC0)
+#define MSS_DMA_DSTBR(base)		(base + 0xC4)
+#define MSS_DMA_CTRLR(base)		(base + 0xC8)
+#define MSS_M3_RSTCR(base)		(base + 0xFC)
+
+#define MSS_DMA_CTRLR_SIZE_OFFSET	(0)
+#define MSS_DMA_CTRLR_REQ_OFFSET	(15)
+#define MSS_DMA_CTRLR_REQ_SET		(1)
+#define MSS_DMA_CTRLR_ACK_OFFSET	(12)
+#define MSS_DMA_CTRLR_ACK_MASK		(0x1)
+#define MSS_DMA_CTRLR_ACK_READY		(1)
+#define MSS_M3_RSTCR_RST_OFFSET		(0)
+#define MSS_M3_RSTCR_RST_OFF		(1)
+
+#define MSS_FW_READY_MAGIC		0x46575144 /* FWRD */
+
+#define MSS_AP_REGS_OFFSET		0x00580000
+#define MSS_CP_SRAM_OFFSET		0x00220000
+#define MSS_CP_REGS_OFFSET		0x00280000
+
+void mss_start_cp_cm3(int cp);
+
+#endif /* MSS_DEFS_H */
diff --git a/plat/marvell/armada/a8k/common/plat_bl31_setup.c b/plat/marvell/armada/a8k/common/plat_bl31_setup.c
index 552c9b2..db85cce 100644
--- a/plat/marvell/armada/a8k/common/plat_bl31_setup.c
+++ b/plat/marvell/armada/a8k/common/plat_bl31_setup.c
@@ -16,8 +16,11 @@
 #include <marvell_pm.h>
 #include <mc_trustzone/mc_trustzone.h>
 #include <plat_marvell.h>
+#if MSS_SUPPORT
 #include <mss_ipc_drv.h>
 #include <mss_mem.h>
+#include <mss_defs.h>
+#endif
 
 /* In Armada-8k family AP806/AP807, CP0 connected to PIDI
  * and CP1 connected to IHB via MCI #0
@@ -51,6 +54,7 @@
 	mmio_write_32(MVEBU_CP_MPP_REGS(0, 4), reg | 0x2200000);
 }
 
+#if MSS_SUPPORT
 void marvell_bl31_mss_init(void)
 {
 	struct mss_pm_ctrl_block *mss_pm_crtl =
@@ -70,6 +74,7 @@
 	if (mss_pm_crtl->ipc_state == IPC_INITIALIZED)
 		mv_pm_ipc_init(mss_pm_crtl->ipc_base_address | MVEBU_REGS_BASE);
 }
+#endif
 
 _Bool is_pm_fw_running(void)
 {
@@ -120,16 +125,22 @@
 			   STREAM_ID_BASE + (cp * MAX_STREAM_ID_PER_CP));
 
 		marvell_bl31_mpp_init(cp);
+
+#if MSS_SUPPORT
+		/* Release CP MSS CPU from reset once the CP init is done */
+		mss_start_cp_cm3(cp);
+#endif
 	}
 
 	for (cp = 1; cp < CP_COUNT; cp++)
 		mci_link_tune(cp - 1);
 
+#if MSS_SUPPORT
 	/* initialize IPC between MSS and ATF */
 	if (mailbox[MBOX_IDX_MAGIC] != MVEBU_MAILBOX_MAGIC_NUM ||
 	    mailbox[MBOX_IDX_SUSPEND_MAGIC] != MVEBU_MAILBOX_SUSPEND_STATE)
 		marvell_bl31_mss_init();
-
+#endif
 	/* Configure GPIO */
 	marvell_gpio_config();
 
diff --git a/plat/marvell/armada/a8k/common/plat_ble_setup.c b/plat/marvell/armada/a8k/common/plat_ble_setup.c
index 4114327..9c5ee15 100644
--- a/plat/marvell/armada/a8k/common/plat_ble_setup.c
+++ b/plat/marvell/armada/a8k/common/plat_ble_setup.c
@@ -14,6 +14,7 @@
 #include <drivers/marvell/mochi/cp110_setup.h>
 
 #include <armada_common.h>
+#include <efuse_def.h>
 #include <mv_ddr_if.h>
 #include <mvebu_def.h>
 #include <plat_marvell.h>
@@ -27,7 +28,6 @@
 #define MMAP_RESTORE_SAVED		1
 
 /* SAR clock settings */
-#define MVEBU_AP_GEN_MGMT_BASE		(MVEBU_RFU_BASE + 0x8000)
 #define MVEBU_AP_SAR_REG_BASE(r)	(MVEBU_AP_GEN_MGMT_BASE + 0x200 +\
 								((r) << 2))
 
@@ -82,11 +82,6 @@
 					 (0x1 << AVS_SOFT_RESET_OFFSET) | \
 					 (0x1 << AVS_ENABLE_OFFSET))
 
-#define MVEBU_AP_EFUSE_SRV_CTRL_REG	(MVEBU_AP_GEN_MGMT_BASE + 0x8)
-#define EFUSE_SRV_CTRL_LD_SELECT_OFFS	6
-#define EFUSE_SRV_CTRL_LD_SEL_USER_MASK	(1 << EFUSE_SRV_CTRL_LD_SELECT_OFFS)
-
-
 /*
  * - Identification information in the LD-0 eFuse:
  *	DRO:           LD0[74:65] - Not used by the SW
@@ -96,14 +91,7 @@
  *	Cluster 1 PWR: LD0[193] - if set to 1, power down CPU Cluster-1
  *				  resulting in 2 CPUs active only (7020)
  */
-#define MVEBU_AP_LD_EFUSE_BASE		(MVEBU_AP_GEN_MGMT_BASE + 0xF00)
-/* Bits [94:63] - 32 data bits total */
-#define MVEBU_AP_LD0_94_63_EFUSE_OFFS	(MVEBU_AP_LD_EFUSE_BASE + 0x8)
-/* Bits [125:95] - 31 data bits total, 32nd bit is parity for bits [125:63] */
-#define MVEBU_AP_LD0_125_95_EFUSE_OFFS	(MVEBU_AP_LD_EFUSE_BASE + 0xC)
-/* Bits [220:189] - 32 data bits total */
-#define MVEBU_AP_LD0_220_189_EFUSE_OFFS	(MVEBU_AP_LD_EFUSE_BASE + 0x18)
-/* Offsets for the above 2 fields combined into single 64-bit value [125:63] */
+/* Offsets for 2 efuse fields combined into single 64-bit value [125:63] */
 #define EFUSE_AP_LD0_DRO_OFFS		2		/* LD0[74:65] */
 #define EFUSE_AP_LD0_DRO_MASK		0x3FF
 #define EFUSE_AP_LD0_REVID_OFFS		12		/* LD0[78:75] */
@@ -376,20 +364,20 @@
 	uint8_t	 avs_data_bits, min_sw_ver, svc_fields;
 	unsigned int ap_type;
 
-	/* Set access to LD0 */
+	/* Get test EERPOM data */
 	avs_workpoint = avs_update_from_eeprom(0);
 	if (avs_workpoint)
 		goto set_aws_wp;
 
 	/* Set access to LD0 */
 	reg_val = mmio_read_32(MVEBU_AP_EFUSE_SRV_CTRL_REG);
-	reg_val &= ~EFUSE_SRV_CTRL_LD_SELECT_OFFS;
+	reg_val &= ~EFUSE_SRV_CTRL_LD_SELECT_MASK;
 	mmio_write_32(MVEBU_AP_EFUSE_SRV_CTRL_REG, reg_val);
 
 	/* Obtain the value of LD0[125:63] */
-	efuse = mmio_read_32(MVEBU_AP_LD0_125_95_EFUSE_OFFS);
+	efuse = mmio_read_32(MVEBU_AP_LDX_125_95_EFUSE_OFFS);
 	efuse <<= 32;
-	efuse |= mmio_read_32(MVEBU_AP_LD0_94_63_EFUSE_OFFS);
+	efuse |= mmio_read_32(MVEBU_AP_LDX_94_63_EFUSE_OFFS);
 
 	/* SW Revision:
 	 * Starting from SW revision 1 the SVC flow is supported.
@@ -452,7 +440,7 @@
 			perr[i] = 1; /* register the error */
 	}
 
-	single_cluster = mmio_read_32(MVEBU_AP_LD0_220_189_EFUSE_OFFS);
+	single_cluster = mmio_read_32(MVEBU_AP_LDX_220_189_EFUSE_OFFS);
 	single_cluster = (single_cluster >> EFUSE_AP_LD0_CLUSTER_DOWN_OFFS) & 1;
 
 	device_id = cp110_device_id_get(MVEBU_CP_REGS_BASE(0));
diff --git a/plat/marvell/armada/a8k/common/plat_pm.c b/plat/marvell/armada/a8k/common/plat_pm.c
index 96e95c2..9ea9276 100644
--- a/plat/marvell/armada/a8k/common/plat_pm.c
+++ b/plat/marvell/armada/a8k/common/plat_pm.c
@@ -18,7 +18,9 @@
 
 #include <armada_common.h>
 #include <marvell_pm.h>
+#if MSS_SUPPORT
 #include <mss_pm_ipc.h>
+#endif
 #include <plat_marvell.h>
 #include <plat_pm_trace.h>
 
@@ -396,6 +398,7 @@
 	/* Power up CPU (CPUs 1-3 are powered off at start of BLE) */
 	plat_marvell_cpu_powerup(mpidr);
 
+#if MSS_SUPPORT
 	if (is_pm_fw_running()) {
 		unsigned int target =
 				((mpidr & 0xFF) + (((mpidr >> 8) & 0xFF) * 2));
@@ -417,11 +420,12 @@
 
 		/* trace message */
 		PM_TRACE(TRACE_PWR_DOMAIN_ON | target);
-	} else {
+	} else
+#endif
+	{
 		/* proprietary CPU ON exection flow */
 		plat_marvell_cpu_on(mpidr);
 	}
-
 	return 0;
 }
 
@@ -441,6 +445,7 @@
  */
 static void a8k_pwr_domain_off(const psci_power_state_t *target_state)
 {
+#if MSS_SUPPORT
 	if (is_pm_fw_running()) {
 		unsigned int idx = plat_my_core_pos();
 
@@ -466,6 +471,7 @@
 	} else {
 		INFO("%s: is not supported without SCP\n", __func__);
 	}
+#endif
 }
 
 /* Get PM config to power off the SoC */
@@ -586,6 +592,7 @@
  */
 static void a8k_pwr_domain_suspend(const psci_power_state_t *target_state)
 {
+#if MSS_SUPPORT
 	if (is_pm_fw_running()) {
 		unsigned int idx;
 
@@ -610,7 +617,9 @@
 
 		/* trace message */
 		PM_TRACE(TRACE_PWR_DOMAIN_SUSPEND);
-	} else {
+	} else
+#endif
+	{
 		uintptr_t *mailbox = (void *)PLAT_MARVELL_MAILBOX_BASE;
 
 		INFO("Suspending to RAM\n");
diff --git a/plat/marvell/armada/a8k/common/plat_pm_trace.c b/plat/marvell/armada/a8k/common/plat_pm_trace.c
index f589ff3..e02a893 100644
--- a/plat/marvell/armada/a8k/common/plat_pm_trace.c
+++ b/plat/marvell/armada/a8k/common/plat_pm_trace.c
@@ -8,10 +8,11 @@
 #include <lib/mmio.h>
 #include <plat/common/platform.h>
 
+#if MSS_SUPPORT
 #include <mss_mem.h>
-#include <plat_pm_trace.h>
 
 #ifdef PM_TRACE_ENABLE
+#include <plat_pm_trace.h>
 
 /* core trace APIs */
 core_trace_func funcTbl[PLATFORM_CORE_COUNT] = {
@@ -90,3 +91,4 @@
 		     AP_MSS_ATF_TRACE_SIZE_MASK));
 }
 #endif /* PM_TRACE_ENABLE */
+#endif /* MSS_SUPPORT */
diff --git a/plat/marvell/armada/common/marvell_common.mk b/plat/marvell/armada/common/marvell_common.mk
index 04eb51c..f0e6edf 100644
--- a/plat/marvell/armada/common/marvell_common.mk
+++ b/plat/marvell/armada/common/marvell_common.mk
@@ -6,10 +6,6 @@
 MARVELL_PLAT_BASE		:= plat/marvell/armada
 MARVELL_PLAT_INCLUDE_BASE	:= include/plat/marvell/armada
 
-include plat/marvell/version.mk
-
-VERSION_STRING			+=(Marvell-${SUBVERSION})
-
 SEPARATE_CODE_AND_RODATA	:= 1
 
 # flag to switch from PLL to ARO
diff --git a/plat/marvell/armada/common/mrvl_sip_svc.c b/plat/marvell/armada/common/mrvl_sip_svc.c
index 64187fb..c4c5c0e 100644
--- a/plat/marvell/armada/common/mrvl_sip_svc.c
+++ b/plat/marvell/armada/common/mrvl_sip_svc.c
@@ -16,6 +16,8 @@
 #include <plat_marvell.h>
 
 #include "comphy/phy-comphy-cp110.h"
+#include "secure_dfx_access/dfx.h"
+#include "ddr_phy_access.h"
 #include <stdbool.h>
 
 /* #define DEBUG_COMPHY */
@@ -37,6 +39,9 @@
 #define MV_SIP_LLC_ENABLE	0x82000011
 #define MV_SIP_PMU_IRQ_ENABLE	0x82000012
 #define MV_SIP_PMU_IRQ_DISABLE	0x82000013
+#define MV_SIP_DFX		0x82000014
+#define MV_SIP_DDR_PHY_WRITE	0x82000015
+#define MV_SIP_DDR_PHY_READ	0x82000016
 
 /* TRNG */
 #define MV_SIP_RNG_64		0xC200FF11
@@ -45,6 +50,9 @@
 #define MVEBU_COMPHY_OFFSET	0x441000
 #define MVEBU_CP_BASE_MASK	(~0xffffff)
 
+/* Common PHY register */
+#define COMPHY_TRX_TRAIN_CTRL_REG_0_OFFS	0x120a2c
+
 /* This macro is used to identify COMPHY related calls from SMC function ID */
 #define is_comphy_fid(fid)	\
 	((fid) >= MV_SIP_COMPHY_POWER_ON && (fid) <= MV_SIP_COMPHY_DIG_RESET)
@@ -71,8 +79,7 @@
 			       void *handle,
 			       u_register_t flags)
 {
-	u_register_t ret;
-	uint32_t w2[2] = {0, 0};
+	u_register_t ret, read, x5 = x1;
 	int i;
 
 	debug("%s: got SMC (0x%x) x1 0x%lx, x2 0x%lx, x3 0x%lx\n",
@@ -86,6 +93,7 @@
 			SMC_RET1(handle, SMC_UNK);
 		}
 
+		x5 = x1 + COMPHY_TRX_TRAIN_CTRL_REG_0_OFFS;
 		x1 += MVEBU_COMPHY_OFFSET;
 
 		if (x2 >= MAX_LANE_NR) {
@@ -100,7 +108,7 @@
 	/* Comphy related FID's */
 	case MV_SIP_COMPHY_POWER_ON:
 		/* x1:  comphy_base, x2: comphy_index, x3: comphy_mode */
-		ret = mvebu_cp110_comphy_power_on(x1, x2, x3);
+		ret = mvebu_cp110_comphy_power_on(x1, x2, x3, x5);
 		SMC_RET1(handle, ret);
 	case MV_SIP_COMPHY_POWER_OFF:
 		/* x1:  comphy_base, x2: comphy_index */
@@ -136,9 +144,33 @@
 		mvebu_pmu_interrupt_disable();
 		SMC_RET1(handle, 0);
 #endif
+	case MV_SIP_DFX:
+		if (x1 >= MV_SIP_DFX_THERMAL_INIT &&
+		    x1 <= MV_SIP_DFX_THERMAL_SEL_CHANNEL) {
+			ret = mvebu_dfx_thermal_handle(x1, &read, x2, x3);
+			SMC_RET2(handle, ret, read);
+		}
+		if (x1 >= MV_SIP_DFX_SREAD && x1 <= MV_SIP_DFX_SWRITE) {
+			ret = mvebu_dfx_misc_handle(x1, &read, x2, x3);
+			SMC_RET2(handle, ret, read);
+		}
+
+		SMC_RET1(handle, SMC_UNK);
+	case MV_SIP_DDR_PHY_WRITE:
+		ret = mvebu_ddr_phy_write(x1, x2);
+		SMC_RET1(handle, ret);
+	case MV_SIP_DDR_PHY_READ:
+		read = 0;
+		ret = mvebu_ddr_phy_read(x1, (uint16_t *)&read);
+		SMC_RET2(handle, ret, read);
 	case MV_SIP_RNG_64:
-		ret = eip76_rng_get_random((uint8_t *)&w2, 4 * (x1 % 2 + 1));
-		SMC_RET3(handle, ret, w2[0], w2[1]);
+		if ((x1 % 2 + 1) > sizeof(read)/4) {
+			ERROR("%s: Maximum %ld random bytes per SMC call\n",
+			      __func__, sizeof(read));
+			SMC_RET1(handle, SMC_UNK);
+		}
+		ret = eip76_rng_get_random((uint8_t *)&read, 4 * (x1 % 2 + 1));
+		SMC_RET2(handle, ret, read);
 	default:
 		ERROR("%s: unhandled SMC (0x%x)\n", __func__, smc_fid);
 		SMC_RET1(handle, SMC_UNK);
diff --git a/plat/marvell/armada/common/mss/mss_scp_bootloader.c b/plat/marvell/armada/common/mss/mss_scp_bootloader.c
index f669a77..fbede1b 100644
--- a/plat/marvell/armada/common/mss/mss_scp_bootloader.c
+++ b/plat/marvell/armada/common/mss/mss_scp_bootloader.c
@@ -19,22 +19,9 @@
 #include <mss_scp_bootloader.h>
 #include <mss_ipc_drv.h>
 #include <mss_mem.h>
+#include <mss_defs.h>
 #include <mss_scp_bl2_format.h>
 
-#define MSS_DMA_SRCBR(base)		(base + 0xC0)
-#define MSS_DMA_DSTBR(base)		(base + 0xC4)
-#define MSS_DMA_CTRLR(base)		(base + 0xC8)
-#define MSS_M3_RSTCR(base)		(base + 0xFC)
-
-#define MSS_DMA_CTRLR_SIZE_OFFSET	(0)
-#define MSS_DMA_CTRLR_REQ_OFFSET	(15)
-#define MSS_DMA_CTRLR_REQ_SET		(1)
-#define MSS_DMA_CTRLR_ACK_OFFSET	(12)
-#define MSS_DMA_CTRLR_ACK_MASK		(0x1)
-#define MSS_DMA_CTRLR_ACK_READY		(1)
-#define MSS_M3_RSTCR_RST_OFFSET		(0)
-#define MSS_M3_RSTCR_RST_OFF		(1)
-
 #define MSS_DMA_TIMEOUT			1000
 #define MSS_EXTERNAL_SPACE		0x50000000
 #define MSS_EXTERNAL_ADDR_MASK		0xfffffff
@@ -85,9 +72,9 @@
 		/* Poll DMA_ACK at MSS_DMACTLR until it is ready */
 		timeout = MSS_DMA_TIMEOUT;
 		while (timeout > 0U) {
-			if ((mmio_read_32(MSS_DMA_CTRLR(mss_regs)) >>
-					  (MSS_DMA_CTRLR_ACK_OFFSET &
-					   MSS_DMA_CTRLR_ACK_MASK))
+			if (((mmio_read_32(MSS_DMA_CTRLR(mss_regs)) >>
+					  MSS_DMA_CTRLR_ACK_OFFSET) &
+					  MSS_DMA_CTRLR_ACK_MASK)
 					  == MSS_DMA_CTRLR_ACK_READY) {
 				break;
 			}
@@ -161,15 +148,20 @@
 
 	bl2_plat_configure_mss_windows(mss_regs);
 
-	/* Wipe the MSS SRAM after using it as copy buffer */
-	if (sram) {
+	if (sram != 0) {
+		/* Wipe the MSS SRAM after using it as copy buffer */
 		memset((void *)sram, 0, MSS_SRAM_SIZE);
+		NOTICE("CP MSS startup is postponed\n");
+		/* FW loaded, but CPU startup postponed until final CP setup */
+		mmio_write_32(sram, MSS_FW_READY_MAGIC);
+		dsb();
+	} else {
+		/* Release M3 from reset */
+		mmio_write_32(MSS_M3_RSTCR(mss_regs),
+			      (MSS_M3_RSTCR_RST_OFF <<
+			       MSS_M3_RSTCR_RST_OFFSET));
 	}
 
-	/* Release M3 from reset */
-	mmio_write_32(MSS_M3_RSTCR(mss_regs),
-		     (MSS_M3_RSTCR_RST_OFF << MSS_M3_RSTCR_RST_OFFSET));
-
 	NOTICE("Done\n");
 
 	return 0;
diff --git a/plat/marvell/version.mk b/plat/marvell/version.mk
deleted file mode 100644
index bb22255..0000000
--- a/plat/marvell/version.mk
+++ /dev/null
@@ -1 +0,0 @@
-SUBVERSION = devel-18.12.2
diff --git a/plat/st/common/bl2_io_storage.c b/plat/st/common/bl2_io_storage.c
index 3ec7d40..6dedc98 100644
--- a/plat/st/common/bl2_io_storage.c
+++ b/plat/st/common/bl2_io_storage.c
@@ -1,5 +1,5 @@
 /*
- * Copyright (c) 2015-2019, ARM Limited and Contributors. All rights reserved.
+ * Copyright (c) 2015-2021, ARM Limited and Contributors. All rights reserved.
  *
  * SPDX-License-Identifier: BSD-3-Clause
  */
@@ -39,6 +39,7 @@
 static uintptr_t storage_dev_handle;
 
 #if STM32MP_SDMMC || STM32MP_EMMC
+static struct mmc_device_info mmc_info;
 static io_block_spec_t gpt_block_spec = {
 	.offset = 0,
 	.length = 34 * MMC_BLOCK_SIZE, /* Size of GPT table */
@@ -276,13 +277,11 @@
 	uint8_t idx;
 	struct stm32image_part_info *part;
 	struct stm32_sdmmc2_params params;
-	struct mmc_device_info device_info;
 	const partition_entry_t *entry;
 
-	zeromem(&device_info, sizeof(struct mmc_device_info));
 	zeromem(&params, sizeof(struct stm32_sdmmc2_params));
 
-	device_info.mmc_dev_type = mmc_dev_type;
+	mmc_info.mmc_dev_type = mmc_dev_type;
 
 	switch (boot_interface_instance) {
 	case 1:
@@ -304,7 +303,7 @@
 		break;
 	}
 
-	params.device_info = &device_info;
+	params.device_info = &mmc_info;
 	if (stm32_sdmmc2_mmc_init(&params) != 0) {
 		ERROR("SDMMC%u init failed\n", boot_interface_instance);
 		panic();
diff --git a/plat/xilinx/versal/bl31_versal_setup.c b/plat/xilinx/versal/bl31_versal_setup.c
index 5e870ff..de36efc 100644
--- a/plat/xilinx/versal/bl31_versal_setup.c
+++ b/plat/xilinx/versal/bl31_versal_setup.c
@@ -1,5 +1,5 @@
 /*
- * Copyright (c) 2018-2020, ARM Limited and Contributors. All rights reserved.
+ * Copyright (c) 2018-2021, ARM Limited and Contributors. All rights reserved.
  *
  * SPDX-License-Identifier: BSD-3-Clause
  */
@@ -11,6 +11,7 @@
 #include <bl31/bl31.h>
 #include <common/bl_common.h>
 #include <common/debug.h>
+#include <drivers/arm/dcc.h>
 #include <drivers/arm/pl011.h>
 #include <drivers/console.h>
 #include <lib/mmio.h>
@@ -22,7 +23,6 @@
 
 static entry_point_info_t bl32_image_ep_info;
 static entry_point_info_t bl33_image_ep_info;
-static console_t versal_runtime_console;
 
 /*
  * Return a pointer to the 'entry_point_info' structure of the next image for
@@ -64,18 +64,26 @@
 {
 	uint64_t atf_handoff_addr;
 
-	/* Initialize the console to provide early debug support */
-	int rc = console_pl011_register(VERSAL_UART_BASE,
-					VERSAL_UART_CLOCK,
-					VERSAL_UART_BAUDRATE,
-					&versal_runtime_console);
-	if (rc == 0) {
-		panic();
-	}
-
-	console_set_scope(&versal_runtime_console, CONSOLE_FLAG_BOOT |
-			  CONSOLE_FLAG_RUNTIME);
+	if (VERSAL_CONSOLE_IS(pl011)) {
+		static console_t versal_runtime_console;
+		/* Initialize the console to provide early debug support */
+		int rc = console_pl011_register(VERSAL_UART_BASE,
+						VERSAL_UART_CLOCK,
+						VERSAL_UART_BAUDRATE,
+						&versal_runtime_console);
+		if (rc == 0) {
+			panic();
+		}
 
+		console_set_scope(&versal_runtime_console, CONSOLE_FLAG_BOOT |
+				  CONSOLE_FLAG_RUNTIME);
+	} else if (VERSAL_CONSOLE_IS(dcc)) {
+		/* Initialize the dcc console for debug */
+		int rc = console_dcc_register();
+		if (rc == 0) {
+			panic();
+		}
+	}
 	/* Initialize the platform config for future decision making */
 	versal_config_setup();
 	/* There are no parameters from BL2 if BL31 is a reset vector */
diff --git a/plat/xilinx/versal/include/versal_def.h b/plat/xilinx/versal/include/versal_def.h
index 810e5d8..001fb04 100644
--- a/plat/xilinx/versal/include/versal_def.h
+++ b/plat/xilinx/versal/include/versal_def.h
@@ -1,5 +1,5 @@
 /*
- * Copyright (c) 2018-2020, ARM Limited and Contributors. All rights reserved.
+ * Copyright (c) 2018-2021, ARM Limited and Contributors. All rights reserved.
  *
  * SPDX-License-Identifier: BSD-3-Clause
  */
@@ -67,7 +67,7 @@
 #define VERSAL_UART0_BASE		0xFF000000
 #define VERSAL_UART1_BASE		0xFF010000
 
-#if VERSAL_CONSOLE_IS(pl011)
+#if VERSAL_CONSOLE_IS(pl011) || VERSAL_CONSOLE_IS(dcc)
 # define VERSAL_UART_BASE	VERSAL_UART0_BASE
 #elif VERSAL_CONSOLE_IS(pl011_1)
 # define VERSAL_UART_BASE	VERSAL_UART1_BASE
diff --git a/plat/xilinx/versal/platform.mk b/plat/xilinx/versal/platform.mk
index 1007e55..ccbc084 100644
--- a/plat/xilinx/versal/platform.mk
+++ b/plat/xilinx/versal/platform.mk
@@ -1,4 +1,4 @@
-# Copyright (c) 2018-2020, ARM Limited and Contributors. All rights reserved.
+# Copyright (c) 2018-2021, ARM Limited and Contributors. All rights reserved.
 #
 # SPDX-License-Identifier: BSD-3-Clause
 
@@ -34,9 +34,6 @@
 VERSAL_PLATFORM ?= silicon
 $(eval $(call add_define_val,VERSAL_PLATFORM,VERSAL_PLATFORM_ID_${VERSAL_PLATFORM}))
 
-VERSAL_CONSOLE	?=	pl011
-$(eval $(call add_define_val,VERSAL_CONSOLE,VERSAL_CONSOLE_ID_${VERSAL_CONSOLE}))
-
 PLAT_INCLUDES		:=	-Iinclude/plat/arm/common/			\
 				-Iplat/xilinx/common/include/			\
 				-Iplat/xilinx/common/ipi_mailbox_service/	\
@@ -48,6 +45,7 @@
 
 PLAT_BL_COMMON_SOURCES	:=	lib/xlat_tables/xlat_tables_common.c		\
 				lib/xlat_tables/aarch64/xlat_tables.c		\
+				drivers/arm/dcc/dcc_console.c			\
 				drivers/delay_timer/delay_timer.c		\
 				drivers/delay_timer/generic_delay_timer.c	\
 				${GICV3_SOURCES}				\
@@ -59,6 +57,14 @@
 				plat/xilinx/versal/aarch64/versal_helpers.S	\
 				plat/xilinx/versal/aarch64/versal_common.c
 
+VERSAL_CONSOLE	?=	pl011
+ifeq (${VERSAL_CONSOLE}, $(filter ${VERSAL_CONSOLE},pl011 pl011_0 pl011_1 dcc))
+else
+  $(error "Please define VERSAL_CONSOLE")
+endif
+
+$(eval $(call add_define_val,VERSAL_CONSOLE,VERSAL_CONSOLE_ID_${VERSAL_CONSOLE}))
+
 BL31_SOURCES		+=	drivers/arm/cci/cci.c				\
 				lib/cpus/aarch64/cortex_a72.S			\
 				plat/common/plat_psci_common.c			\
diff --git a/plat/xilinx/zynqmp/bl31_zynqmp_setup.c b/plat/xilinx/zynqmp/bl31_zynqmp_setup.c
index d4cd7f6..4a09b4b 100644
--- a/plat/xilinx/zynqmp/bl31_zynqmp_setup.c
+++ b/plat/xilinx/zynqmp/bl31_zynqmp_setup.c
@@ -1,5 +1,5 @@
 /*
- * Copyright (c) 2013-2020, ARM Limited and Contributors. All rights reserved.
+ * Copyright (c) 2013-2021, ARM Limited and Contributors. All rights reserved.
  *
  * SPDX-License-Identifier: BSD-3-Clause
  */
@@ -10,6 +10,7 @@
 #include <bl31/bl31.h>
 #include <common/bl_common.h>
 #include <common/debug.h>
+#include <drivers/arm/dcc.h>
 #include <drivers/console.h>
 #include <plat/arm/common/plat_arm.h>
 #include <plat/common/platform.h>
@@ -62,15 +63,23 @@
 				u_register_t arg2, u_register_t arg3)
 {
 	uint64_t atf_handoff_addr;
-	/* Register the console to provide early debug support */
-	static console_t bl31_boot_console;
-	(void)console_cdns_register(ZYNQMP_UART_BASE,
-				       zynqmp_get_uart_clk(),
-				       ZYNQMP_UART_BAUDRATE,
-				       &bl31_boot_console);
-	console_set_scope(&bl31_boot_console,
-			  CONSOLE_FLAG_RUNTIME | CONSOLE_FLAG_BOOT);
 
+	if (ZYNQMP_CONSOLE_IS(cadence)) {
+		/* Register the console to provide early debug support */
+		static console_t bl31_boot_console;
+		(void)console_cdns_register(ZYNQMP_UART_BASE,
+					       zynqmp_get_uart_clk(),
+					       ZYNQMP_UART_BAUDRATE,
+					       &bl31_boot_console);
+		console_set_scope(&bl31_boot_console,
+				  CONSOLE_FLAG_RUNTIME | CONSOLE_FLAG_BOOT);
+	} else if (ZYNQMP_CONSOLE_IS(dcc)) {
+		/* Initialize the dcc console for debug */
+		int rc = console_dcc_register();
+		if (rc == 0) {
+			panic();
+		}
+	}
 	/* Initialize the platform config for future decision making */
 	zynqmp_config_setup();
 
diff --git a/plat/xilinx/zynqmp/platform.mk b/plat/xilinx/zynqmp/platform.mk
index 6e700b9..921a6e1 100644
--- a/plat/xilinx/zynqmp/platform.mk
+++ b/plat/xilinx/zynqmp/platform.mk
@@ -1,5 +1,5 @@
 #
-# Copyright (c) 2013-2020, ARM Limited and Contributors. All rights reserved.
+# Copyright (c) 2013-2021, ARM Limited and Contributors. All rights reserved.
 #
 # SPDX-License-Identifier: BSD-3-Clause
 
@@ -41,8 +41,6 @@
     $(eval $(call add_define,ZYNQMP_BL32_MEM_SIZE))
 endif
 
-ZYNQMP_CONSOLE	?=	cadence
-$(eval $(call add_define_val,ZYNQMP_CONSOLE,ZYNQMP_CONSOLE_ID_${ZYNQMP_CONSOLE}))
 
 ifdef ZYNQMP_WDT_RESTART
 $(eval $(call add_define,ZYNQMP_WDT_RESTART))
@@ -64,6 +62,7 @@
 
 PLAT_BL_COMMON_SOURCES	:=	lib/xlat_tables/xlat_tables_common.c		\
 				lib/xlat_tables/aarch64/xlat_tables.c		\
+				drivers/arm/dcc/dcc_console.c			\
 				drivers/delay_timer/delay_timer.c		\
 				drivers/delay_timer/generic_delay_timer.c	\
 				${GICV2_SOURCES}				\
@@ -78,6 +77,13 @@
 				plat/xilinx/zynqmp/aarch64/zynqmp_helpers.S	\
 				plat/xilinx/zynqmp/aarch64/zynqmp_common.c
 
+ZYNQMP_CONSOLE	?=	cadence
+ifeq (${ZYNQMP_CONSOLE}, $(filter ${ZYNQMP_CONSOLE},cadence cadence0 cadence1 dcc))
+else
+  $(error "Please define ZYNQMP_CONSOLE")
+endif
+$(eval $(call add_define_val,ZYNQMP_CONSOLE,ZYNQMP_CONSOLE_ID_${ZYNQMP_CONSOLE}))
+
 BL31_SOURCES		+=	drivers/arm/cci/cci.c				\
 				lib/cpus/aarch64/aem_generic.S			\
 				lib/cpus/aarch64/cortex_a53.S			\
diff --git a/services/std_svc/spm_mm/spm_mm_setup.c b/services/std_svc/spm_mm/spm_mm_setup.c
index 32562c3..9d681c2 100644
--- a/services/std_svc/spm_mm/spm_mm_setup.c
+++ b/services/std_svc/spm_mm/spm_mm_setup.c
@@ -1,5 +1,6 @@
 /*
  * Copyright (c) 2017-2020, ARM Limited and Contributors. All rights reserved.
+ * Copyright (c) 2021, NVIDIA Corporation. All rights reserved.
  *
  * SPDX-License-Identifier: BSD-3-Clause
  */
@@ -26,6 +27,10 @@
 {
 	cpu_context_t *ctx = &(sp_ctx->cpu_ctx);
 
+	/* Pointer to the MP information from the platform port. */
+	const spm_mm_boot_info_t *sp_boot_info =
+			plat_get_secure_partition_boot_info(NULL);
+
 	/*
 	 * Initialize CPU context
 	 * ----------------------
@@ -36,7 +41,7 @@
 	SET_PARAM_HEAD(&ep_info, PARAM_EP, VERSION_1, SECURE | EP_ST_ENABLE);
 
 	/* Setup entrypoint and SPSR */
-	ep_info.pc = BL32_BASE;
+	ep_info.pc = sp_boot_info->sp_image_base;
 	ep_info.spsr = SPSR_64(MODE_EL0, MODE_SP_EL0, DISABLE_ALL_EXCEPTIONS);
 
 	/*
@@ -53,8 +58,8 @@
 	 *
 	 * X4 to X7 = 0
 	 */
-	ep_info.args.arg0 = PLAT_SPM_BUF_BASE;
-	ep_info.args.arg1 = PLAT_SPM_BUF_SIZE;
+	ep_info.args.arg0 = sp_boot_info->sp_shared_buf_base;
+	ep_info.args.arg1 = sp_boot_info->sp_shared_buf_size;
 	ep_info.args.arg2 = PLAT_SPM_COOKIE_0;
 	ep_info.args.arg3 = PLAT_SPM_COOKIE_1;
 
@@ -66,7 +71,7 @@
 	 * implementation defined means. The value will be 0 otherwise.
 	 */
 	write_ctx_reg(get_gpregs_ctx(ctx), CTX_GPREG_SP_EL0,
-			PLAT_SP_IMAGE_STACK_BASE + PLAT_SP_IMAGE_STACK_PCPU_SIZE);
+			sp_boot_info->sp_stack_base + sp_boot_info->sp_pcpu_stack_size);
 
 	/*
 	 * Setup translation tables
@@ -84,10 +89,10 @@
 	unsigned int max_granule_mask = max_granule - 1U;
 
 	/* Base must be aligned to the max granularity */
-	assert((PLAT_SP_IMAGE_NS_BUF_BASE & max_granule_mask) == 0);
+	assert((sp_boot_info->sp_ns_comm_buf_base & max_granule_mask) == 0);
 
 	/* Size must be a multiple of the max granularity */
-	assert((PLAT_SP_IMAGE_NS_BUF_SIZE & max_granule_mask) == 0);
+	assert((sp_boot_info->sp_ns_comm_buf_size & max_granule_mask) == 0);
 
 #endif /* ENABLE_ASSERTIONS */
 
@@ -191,16 +196,14 @@
 	 * ----------------------------------------------------------
 	 */
 
-	void *shared_buf_ptr = (void *) PLAT_SPM_BUF_BASE;
+	void *shared_buf_ptr = (void *) sp_boot_info->sp_shared_buf_base;
 
 	/* Copy the boot information into the shared buffer with the SP. */
 	assert((uintptr_t)shared_buf_ptr + sizeof(spm_mm_boot_info_t)
-	       <= (PLAT_SPM_BUF_BASE + PLAT_SPM_BUF_SIZE));
+	       <= (sp_boot_info->sp_shared_buf_base + sp_boot_info->sp_shared_buf_size));
 
-	assert(PLAT_SPM_BUF_BASE <= (UINTPTR_MAX - PLAT_SPM_BUF_SIZE + 1));
-
-	const spm_mm_boot_info_t *sp_boot_info =
-			plat_get_secure_partition_boot_info(NULL);
+	assert(sp_boot_info->sp_shared_buf_base <=
+				(UINTPTR_MAX - sp_boot_info->sp_shared_buf_size + 1));
 
 	assert(sp_boot_info != NULL);
 
@@ -234,7 +237,7 @@
 	assert(sp_boot_info->num_cpus <= PLATFORM_CORE_COUNT);
 
 	assert((uintptr_t)shared_buf_ptr
-	       <= (PLAT_SPM_BUF_BASE + PLAT_SPM_BUF_SIZE -
+	       <= (sp_boot_info->sp_shared_buf_base + sp_boot_info->sp_shared_buf_size -
 		       (sp_boot_info->num_cpus * sizeof(*sp_mp_info))));
 
 	memcpy(shared_buf_ptr, (const void *) sp_mp_info,
diff --git a/tools/fiptool/Makefile b/tools/fiptool/Makefile
index b75907d..11d2e7b 100644
--- a/tools/fiptool/Makefile
+++ b/tools/fiptool/Makefile
@@ -44,11 +44,7 @@
 
 .PHONY: all clean distclean
 
-# Clean before build as old fiptool might be created with
-# including different PLAT_FIPTOOL_HELPER_MK.
-all:
-	${MAKE}	clean
-	${MAKE}	${PROJECT}
+all: ${PROJECT}
 
 ${PROJECT}: ${OBJECTS} Makefile
 	@echo "  HOSTLD  $@"