Merge "mediatek: move uart.h to common folder" into integration
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 e55ce3c..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
 
@@ -219,6 +219,16 @@
         binary and sys-init code from the WTP directory which sets DDR and CPU
         clocks according to DDR_TOPOLOGY and CLOCKSPRESET options.
 
+        CZ.NIC as part of Turris project released free and open source WTMI
+        application firmware ``wtmi_app.bin`` for all Armada 3720 devices.
+        This firmware includes additional features like access to Hardware
+        Random Number Generator of Armada 3720 SoC which original Marvell's
+        ``fuse.bin`` image does not have.
+
+        CZ.NIC's Armada 3720 Secure Firmware is available at website:
+
+            https://gitlab.nic.cz/turris/mox-boot-builder/
+
 - WTP
 
         For Armada37x0 only, use this parameter to point to wtptools source code
@@ -274,21 +284,25 @@
         CROSS_COMPILE=aarch64-linux-gnu- mrvl_bootimage
 
 Here is full example how to build production release of Marvell firmware image (concatenated
-binary of Marvell secure firmware, TF-A and U-Boot) for EspressoBin board (PLAT=a3700) with
-1GHz CPU (CLOCKSPRESET=CPU_1000_DDR_800) and 1GB DDR4 RAM (DDR_TOPOLOGY=5):
+binary of Marvell's A3720 sys-init, CZ.NIC's Armada 3720 Secure Firmware, TF-A and U-Boot) for
+EspressoBin board (PLAT=a3700) with 1GHz CPU (CLOCKSPRESET=CPU_1000_DDR_800) and
+1GB DDR4 RAM (DDR_TOPOLOGY=5):
 
 .. code:: shell
 
-    > git clone https://review.trustedfirmware.org/TF-A/trusted-firmware-a
-    > git clone https://gitlab.denx.de/u-boot/u-boot.git
+    > git clone https://git.trustedfirmware.org/TF-A/trusted-firmware-a.git
+    > git clone https://source.denx.de/u-boot/u-boot.git
     > git clone https://github.com/weidai11/cryptopp.git
-    > git clone https://github.com/MarvellEmbeddedProcessors/mv-ddr-marvell.git -b master
-    > git clone https://github.com/MarvellEmbeddedProcessors/A3700-utils-marvell.git -b master
+    > git clone https://github.com/MarvellEmbeddedProcessors/mv-ddr-marvell.git
+    > git clone https://github.com/MarvellEmbeddedProcessors/A3700-utils-marvell.git
+    > git clone https://gitlab.nic.cz/turris/mox-boot-builder.git
     > make -C u-boot CROSS_COMPILE=aarch64-linux-gnu- mvebu_espressobin-88f3720_defconfig u-boot.bin
+    > make -C mox-boot-builder CROSS_CM3=arm-linux-gnueabi- wtmi_app.bin
     > make -C trusted-firmware-a CROSS_COMPILE=aarch64-linux-gnu- CROSS_CM3=arm-linux-gnueabi- \
         USE_COHERENT_MEM=0 PLAT=a3700 CLOCKSPRESET=CPU_1000_DDR_800 DDR_TOPOLOGY=5 \
-        MV_DDR_PATH=$PWD/mv-ddr-marvell/ WTP=$PWD/A3700-utils-marvell/ CRYPTOPP_PATH=$PWD/cryptopp/ \
-        BL33=$PWD/u-boot/u-boot.bin mrvl_flash
+        MV_DDR_PATH=$PWD/mv-ddr-marvell/ WTP=$PWD/A3700-utils-marvell/ \
+        CRYPTOPP_PATH=$PWD/cryptopp/ BL33=$PWD/u-boot/u-boot.bin \
+        WTMI_IMG=$PWD/mox-boot-builder/wtmi_app.bin FIP_ALIGN=0x100 mrvl_flash
 
 Produced Marvell firmware flash image: ``trusted-firmware-a/build/a3700/release/flash-image.bin``
 
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/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/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/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/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/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/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/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,