Merge pull request #1064 from islmit01/im/shifted_afinity

FVP: Always assume shifted affinity with MT bit
diff --git a/Makefile b/Makefile
index b57b212..0a64514 100644
--- a/Makefile
+++ b/Makefile
@@ -571,10 +571,10 @@
 
 locate-checkpatch:
 ifndef CHECKPATCH
-	$(error "Please set CHECKPATCH to point to the Linux checkpatch.pl file, eg: CHECKPATCH=../linux/script/checkpatch.pl")
+	$(error "Please set CHECKPATCH to point to the Linux checkpatch.pl file, eg: CHECKPATCH=../linux/scripts/checkpatch.pl")
 else
 ifeq (,$(wildcard ${CHECKPATCH}))
-	$(error "The file CHECKPATCH points to cannot be found, use eg: CHECKPATCH=../linux/script/checkpatch.pl")
+	$(error "The file CHECKPATCH points to cannot be found, use eg: CHECKPATCH=../linux/scripts/checkpatch.pl")
 endif
 endif
 
diff --git a/docs/firmware-design.rst b/docs/firmware-design.rst
index 4c3c420..36038ad 100644
--- a/docs/firmware-design.rst
+++ b/docs/firmware-design.rst
@@ -1045,8 +1045,8 @@
    ``bl31_main()`` will set up the return to the normal world firmware BL33 and
    continue the boot process in the normal world.
 
-#. .. rubric:: Crash Reporting in BL31
-      :name: crash-reporting-in-bl31
+Crash Reporting in BL31
+-----------------------
 
 BL31 implements a scheme for reporting the processor state when an unhandled
 exception is encountered. The reporting mechanism attempts to preserve all the
@@ -1864,7 +1864,7 @@
     `offset_address`: The offset address at which the corresponding payload data
         can be found. The offset is calculated from the ToC base address.
     `size`: The size of the corresponding payload data in bytes.
-    `flags`: Flags associated with this entry. Non are yet defined.
+    `flags`: Flags associated with this entry. None are yet defined.
 
 Firmware Image Package creation tool
 ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
@@ -2333,8 +2333,8 @@
 
 #. ``pmf_helpers.h`` is an internal header used by ``pmf.h``.
 
-#. .. rubric:: ARMv8 Architecture Extensions
-      :name: armv8-architecture-extensions
+ARMv8 Architecture Extensions
+-----------------------------
 
 ARM Trusted Firmware makes use of ARMv8 Architecture Extensions where
 applicable. This section lists the usage of Architecture Extensions, and build
diff --git a/include/plat/arm/board/common/drivers/norflash.h b/include/plat/arm/board/common/drivers/norflash.h
index e74635e..5763b36 100644
--- a/include/plat/arm/board/common/drivers/norflash.h
+++ b/include/plat/arm/board/common/drivers/norflash.h
@@ -1,5 +1,5 @@
 /*
- * Copyright (c) 2015, ARM Limited and Contributors. All rights reserved.
+ * Copyright (c) 2015-2017, ARM Limited and Contributors. All rights reserved.
  *
  * SPDX-License-Identifier: BSD-3-Clause
  */
@@ -19,6 +19,7 @@
 #define NOR_CMD_WORD_PROGRAM		0x40
 #define NOR_CMD_BLOCK_ERASE		0x20
 #define NOR_CMD_LOCK_UNLOCK		0x60
+#define NOR_CMD_BLOCK_ERASE_ACK		0xD0
 
 /* Second bus cycle */
 #define NOR_LOCK_BLOCK			0x01
@@ -37,8 +38,9 @@
 /* Public API */
 void nor_send_cmd(uintptr_t base_addr, unsigned long cmd);
 int nor_word_program(uintptr_t base_addr, unsigned long data);
-void nor_lock(uintptr_t base_addr);
-void nor_unlock(uintptr_t base_addr);
+int nor_lock(uintptr_t base_addr);
+int nor_unlock(uintptr_t base_addr);
+int nor_erase(uintptr_t base_addr);
 
 #endif /* __NORFLASH_H_ */
 
diff --git a/lib/el3_runtime/aarch64/context_mgmt.c b/lib/el3_runtime/aarch64/context_mgmt.c
index 5257bf1..3d26056 100644
--- a/lib/el3_runtime/aarch64/context_mgmt.c
+++ b/lib/el3_runtime/aarch64/context_mgmt.c
@@ -229,7 +229,7 @@
 			/* Use SCTLR_EL1.EE value to initialise sctlr_el2 */
 			sctlr_elx = read_ctx_reg(get_sysregs_ctx(ctx),
 						 CTX_SCTLR_EL1);
-			sctlr_elx &= ~SCTLR_EE_BIT;
+			sctlr_elx &= SCTLR_EE_BIT;
 			sctlr_elx |= SCTLR_EL2_RES1;
 			write_sctlr_el2(sctlr_elx);
 		} else if (EL_IMPLEMENTED(2)) {
diff --git a/lib/psci/psci_common.c b/lib/psci/psci_common.c
index f31b323..4502c24 100644
--- a/lib/psci/psci_common.c
+++ b/lib/psci/psci_common.c
@@ -194,8 +194,15 @@
 					 unsigned int cpu_idx,
 					 plat_local_state_t req_pwr_state)
 {
+	/*
+	 * This should never happen, we have this here to avoid
+	 * "array subscript is above array bounds" errors in GCC.
+	 */
 	assert(pwrlvl > PSCI_CPU_PWR_LVL);
+#pragma GCC diagnostic push
+#pragma GCC diagnostic ignored "-Warray-bounds"
 	psci_req_local_pwr_states[pwrlvl - 1][cpu_idx] = req_pwr_state;
+#pragma GCC diagnostic pop
 }
 
 /******************************************************************************
diff --git a/plat/arm/board/common/drivers/norflash/norflash.c b/plat/arm/board/common/drivers/norflash/norflash.c
index cc63d75..722cf33 100644
--- a/plat/arm/board/common/drivers/norflash/norflash.c
+++ b/plat/arm/board/common/drivers/norflash/norflash.c
@@ -1,5 +1,5 @@
 /*
- * Copyright (c) 2015, ARM Limited and Contributors. All rights reserved.
+ * Copyright (c) 2015-2017, ARM Limited and Contributors. All rights reserved.
  *
  * SPDX-License-Identifier: BSD-3-Clause
  */
@@ -8,8 +8,6 @@
 #include <mmio.h>
 #include <norflash.h>
 
-/* Helper macros to access two flash banks in parallel */
-#define NOR_2X16(d)			((d << 16) | (d & 0xffff))
 
 /*
  * DWS ready poll retries. The number of retries in this driver have been
@@ -17,84 +15,182 @@
  * model
  */
 #define DWS_WORD_PROGRAM_RETRIES	1000
+#define DWS_WORD_ERASE_RETRIES		3000000
+#define DWS_WORD_LOCK_RETRIES		1000
+
+/* Helper macro to detect end of command */
+#define NOR_CMD_END (NOR_DWS | NOR_DWS << 16l)
 
 /*
- * Poll Write State Machine. Return values:
+ * This file supplies a low level interface to the vexpress NOR flash
+ * memory of juno and fvp. This memory is organized as an interleaved
+ * memory of two chips with a 16 bit word. It means that every 32 bit
+ * access is going to access to two different chips. This is very
+ * important when we send commands or read status of the chips
+ */
+
+/* Helper macros to access two flash banks in parallel */
+#define NOR_2X16(d)			((d << 16) | (d & 0xffff))
+
+static unsigned int nor_status(uintptr_t base_addr)
+{
+	unsigned long status;
+
+	nor_send_cmd(base_addr, NOR_CMD_READ_STATUS_REG);
+	status = mmio_read_32(base_addr);
+	status |= status >> 16; /* merge status from both flash banks */
+
+	return status & 0xFFFF;
+}
+
+/*
+ * Poll Write State Machine.
+ * Return values:
  *    0      = WSM ready
  *    -EBUSY = WSM busy after the number of retries
  */
-static int nor_poll_dws(uintptr_t base_addr, unsigned int retries)
+static int nor_poll_dws(uintptr_t base_addr, unsigned long int retries)
 {
-	uint32_t status;
-	int ret;
+	unsigned long status;
 
-	for (;;) {
+	do {
 		nor_send_cmd(base_addr, NOR_CMD_READ_STATUS_REG);
 		status = mmio_read_32(base_addr);
-		if ((status & NOR_DWS) &&
-		    (status & (NOR_DWS << 16))) {
-			ret = 0;
-			break;
-		}
-		if (retries-- == 0) {
-			ret = -EBUSY;
-			break;
-		}
-	}
+		if ((status & NOR_CMD_END) == NOR_CMD_END)
+			return 0;
+	} while (retries-- > 0);
 
-	return ret;
+	return -EBUSY;
 }
 
+/*
+ * Return values:
+ *    0      = success
+ *    -EPERM = Device protected or Block locked
+ *    -EIO   = General I/O error
+ */
+static int nor_full_status_check(uintptr_t base_addr)
+{
+	unsigned long status;
+
+	/* Full status check */
+	status = nor_status(base_addr);
+
+	if (status & (NOR_PS | NOR_BLS | NOR_ESS | NOR_PSS))
+		return -EPERM;
+	if (status & (NOR_VPPS | NOR_ES))
+		return -EIO;
+	return 0;
+}
+
 void nor_send_cmd(uintptr_t base_addr, unsigned long cmd)
 {
 	mmio_write_32(base_addr, NOR_2X16(cmd));
 }
 
 /*
+ * This function programs a word in the flash. Be aware that it only
+ * can reset bits that were previously set. It cannot set bits that
+ * were previously reset. The resulting bits = old_bits & new bits.
  * Return values:
- *    0      = success
- *    -EBUSY = WSM not ready
- *    -EPERM = Device protected or Block locked
+ *  0 = success
+ *  otherwise it returns a negative value
  */
 int nor_word_program(uintptr_t base_addr, unsigned long data)
 {
 	uint32_t status;
 	int ret;
 
+	nor_send_cmd(base_addr, NOR_CMD_CLEAR_STATUS_REG);
+
 	/* Set the device in write word mode */
 	nor_send_cmd(base_addr, NOR_CMD_WORD_PROGRAM);
 	mmio_write_32(base_addr, data);
 
 	ret = nor_poll_dws(base_addr, DWS_WORD_PROGRAM_RETRIES);
-	if (ret != 0) {
-		goto word_program_end;
+	if (ret == 0) {
+		/* Full status check */
+		nor_send_cmd(base_addr, NOR_CMD_READ_STATUS_REG);
+		status = mmio_read_32(base_addr);
+
+		if (status & (NOR_PS | NOR_BLS)) {
+			nor_send_cmd(base_addr, NOR_CMD_CLEAR_STATUS_REG);
+			ret = -EPERM;
+		}
 	}
 
-	/* Full status check */
-	nor_send_cmd(base_addr, NOR_CMD_READ_STATUS_REG);
-	status = mmio_read_32(base_addr);
+	if (ret == 0)
+		ret = nor_full_status_check(base_addr);
+	nor_send_cmd(base_addr, NOR_CMD_READ_ARRAY);
 
-	if (status & (NOR_PS | NOR_BLS)) {
-		nor_send_cmd(base_addr, NOR_CMD_CLEAR_STATUS_REG);
-		ret = -EPERM;
-	}
+	return ret;
+}
 
-word_program_end:
+/*
+ * Erase a full 256K block
+ * Return values:
+ *  0 = success
+ *  otherwise it returns a negative value
+ */
+int nor_erase(uintptr_t base_addr)
+{
+	int ret;
+
+	nor_send_cmd(base_addr, NOR_CMD_CLEAR_STATUS_REG);
+
+	nor_send_cmd(base_addr, NOR_CMD_BLOCK_ERASE);
+	nor_send_cmd(base_addr, NOR_CMD_BLOCK_ERASE_ACK);
+
+	ret = nor_poll_dws(base_addr, DWS_WORD_ERASE_RETRIES);
+	if (ret == 0)
+		ret = nor_full_status_check(base_addr);
 	nor_send_cmd(base_addr, NOR_CMD_READ_ARRAY);
+
 	return ret;
 }
 
-void nor_lock(uintptr_t base_addr)
+/*
+ * Lock a full 256 block
+ * Return values:
+ *  0 = success
+ *  otherwise it returns a negative value
+ */
+int nor_lock(uintptr_t base_addr)
 {
+	int ret;
+
+	nor_send_cmd(base_addr, NOR_CMD_CLEAR_STATUS_REG);
+
 	nor_send_cmd(base_addr, NOR_CMD_LOCK_UNLOCK);
-	mmio_write_32(base_addr, NOR_2X16(NOR_LOCK_BLOCK));
+	nor_send_cmd(base_addr, NOR_LOCK_BLOCK);
+
+	ret = nor_poll_dws(base_addr, DWS_WORD_LOCK_RETRIES);
+	if (ret == 0)
+		ret = nor_full_status_check(base_addr);
 	nor_send_cmd(base_addr, NOR_CMD_READ_ARRAY);
+
+	return ret;
 }
 
-void nor_unlock(uintptr_t base_addr)
+/*
+ * unlock a full 256 block
+ * Return values:
+ *  0 = success
+ *  otherwise it returns a negative value
+ */
+int nor_unlock(uintptr_t base_addr)
 {
+	int ret;
+
+	nor_send_cmd(base_addr, NOR_CMD_CLEAR_STATUS_REG);
+
 	nor_send_cmd(base_addr, NOR_CMD_LOCK_UNLOCK);
-	mmio_write_32(base_addr, NOR_2X16(NOR_UNLOCK_BLOCK));
+	nor_send_cmd(base_addr, NOR_UNLOCK_BLOCK);
+
+	ret = nor_poll_dws(base_addr, DWS_WORD_LOCK_RETRIES);
+	if (ret == 0)
+		ret = nor_full_status_check(base_addr);
 	nor_send_cmd(base_addr, NOR_CMD_READ_ARRAY);
-}
 
+	return ret;
+}
diff --git a/plat/qemu/include/platform_def.h b/plat/qemu/include/platform_def.h
index ceb0539..e91a7db 100644
--- a/plat/qemu/include/platform_def.h
+++ b/plat/qemu/include/platform_def.h
@@ -73,6 +73,11 @@
 #define SEC_DRAM_BASE			0x0e100000
 #define SEC_DRAM_SIZE			0x00f00000
 
+/* Load pageable part of OP-TEE at end of secure DRAM */
+#define QEMU_OPTEE_PAGEABLE_LOAD_BASE	(SEC_DRAM_BASE + SEC_DRAM_SIZE - \
+					 QEMU_OPTEE_PAGEABLE_LOAD_SIZE)
+#define QEMU_OPTEE_PAGEABLE_LOAD_SIZE	0x00400000
+
 /*
  * ARM-TF lives in SRAM, partition it here
  */
@@ -154,7 +159,8 @@
 
 #define NS_IMAGE_OFFSET			0x60000000
 
-#define ADDR_SPACE_SIZE			(1ull << 32)
+#define PLAT_PHY_ADDR_SPACE_SIZE	(1ull << 32)
+#define PLAT_VIRT_ADDR_SPACE_SIZE	(1ull << 32)
 #define MAX_MMAP_REGIONS		8
 #define MAX_XLAT_TABLES			6
 #define MAX_IO_DEVICES			3
diff --git a/plat/qemu/platform.mk b/plat/qemu/platform.mk
index dc3b5d9..ed197a1 100644
--- a/plat/qemu/platform.mk
+++ b/plat/qemu/platform.mk
@@ -65,6 +65,10 @@
 				plat/qemu/qemu_image_load.c		\
 				common/desc_image_load.c
 endif
+ifeq (${SPD},opteed)
+BL2_SOURCES		+=	lib/optee/optee_utils.c
+endif
+
 
 BL31_SOURCES		+=	lib/cpus/aarch64/aem_generic.S		\
 				lib/cpus/aarch64/cortex_a53.S		\
@@ -72,13 +76,23 @@
 				drivers/arm/gic/v2/gicv2_helpers.c	\
 				drivers/arm/gic/v2/gicv2_main.c		\
 				drivers/arm/gic/common/gic_common.c	\
-				plat/common/aarch64/plat_psci_common.c	\
+				plat/common/plat_psci_common.c		\
 				plat/qemu/qemu_pm.c			\
 				plat/qemu/topology.c			\
 				plat/qemu/aarch64/plat_helpers.S	\
 				plat/qemu/qemu_bl31_setup.c		\
 				plat/qemu/qemu_gic.c
 
+
+# Add the build options to pack Trusted OS Extra1 and Trusted OS Extra2 images
+# in the FIP if the platform requires.
+ifneq ($(BL32_EXTRA1),)
+$(eval $(call FIP_ADD_IMG,BL32_EXTRA1,--tos-fw-extra1))
+endif
+ifneq ($(BL32_EXTRA2),)
+$(eval $(call FIP_ADD_IMG,BL32_EXTRA2,--tos-fw-extra2))
+endif
+
 # Disable the PSCI platform compatibility layer
 ENABLE_PLAT_COMPAT	:= 	0
 
diff --git a/plat/qemu/qemu_bl2_mem_params_desc.c b/plat/qemu/qemu_bl2_mem_params_desc.c
index 3396140..47f88ac 100644
--- a/plat/qemu/qemu_bl2_mem_params_desc.c
+++ b/plat/qemu/qemu_bl2_mem_params_desc.c
@@ -72,6 +72,43 @@
 
 	  .next_handoff_image_id = BL33_IMAGE_ID,
 	},
+
+	/*
+	 * Fill BL32 external 1 related information.
+	 * A typical use for extra1 image is with OP-TEE where it is the
+	 * pager image.
+	 */
+	{ .image_id = BL32_EXTRA1_IMAGE_ID,
+
+	   SET_STATIC_PARAM_HEAD(ep_info, PARAM_EP, VERSION_2,
+				 entry_point_info_t, SECURE | NON_EXECUTABLE),
+
+	   SET_STATIC_PARAM_HEAD(image_info, PARAM_EP, VERSION_2,
+				 image_info_t, IMAGE_ATTRIB_SKIP_LOADING),
+	   .image_info.image_base = BL32_BASE,
+	   .image_info.image_max_size = BL32_LIMIT - BL32_BASE,
+
+	   .next_handoff_image_id = INVALID_IMAGE_ID,
+	},
+
+	/*
+	 * Fill BL32 external 2 related information.
+	 * A typical use for extra2 image is with OP-TEE where it is the
+	 * paged image.
+	 */
+	{ .image_id = BL32_EXTRA2_IMAGE_ID,
+
+	   SET_STATIC_PARAM_HEAD(ep_info, PARAM_EP, VERSION_2,
+				 entry_point_info_t, SECURE | NON_EXECUTABLE),
+
+	   SET_STATIC_PARAM_HEAD(image_info, PARAM_EP, VERSION_2,
+				 image_info_t, IMAGE_ATTRIB_SKIP_LOADING),
+#ifdef SPD_opteed
+	   .image_info.image_base = QEMU_OPTEE_PAGEABLE_LOAD_BASE,
+	   .image_info.image_max_size = QEMU_OPTEE_PAGEABLE_LOAD_SIZE,
+#endif
+	   .next_handoff_image_id = INVALID_IMAGE_ID,
+	},
 # endif /* QEMU_LOAD_BL32 */
 
 	/* Fill BL33 related information */
diff --git a/plat/qemu/qemu_bl2_setup.c b/plat/qemu/qemu_bl2_setup.c
index 1306f34..60d9623 100644
--- a/plat/qemu/qemu_bl2_setup.c
+++ b/plat/qemu/qemu_bl2_setup.c
@@ -9,6 +9,9 @@
 #include <console.h>
 #include <debug.h>
 #include <desc_image_load.h>
+#ifdef SPD_opteed
+#include <optee_utils.h>
+#endif
 #include <libfdt.h>
 #include <platform_def.h>
 #include <string.h>
@@ -225,12 +228,36 @@
 {
 	int err = 0;
 	bl_mem_params_node_t *bl_mem_params = get_bl_mem_params_node(image_id);
+#ifdef SPD_opteed
+	bl_mem_params_node_t *pager_mem_params = NULL;
+	bl_mem_params_node_t *paged_mem_params = NULL;
+#endif
 
 	assert(bl_mem_params);
 
 	switch (image_id) {
 # ifdef AARCH64
 	case BL32_IMAGE_ID:
+#ifdef SPD_opteed
+		pager_mem_params = get_bl_mem_params_node(BL32_EXTRA1_IMAGE_ID);
+		assert(pager_mem_params);
+
+		paged_mem_params = get_bl_mem_params_node(BL32_EXTRA2_IMAGE_ID);
+		assert(paged_mem_params);
+
+		err = parse_optee_header(&bl_mem_params->ep_info,
+					 &pager_mem_params->image_info,
+					 &paged_mem_params->image_info);
+		if (err != 0) {
+			WARN("OPTEE header parse error.\n");
+		}
+
+		/*
+		 * OP-TEE expect to receive DTB address in x2.
+		 * This will be copied into x2 by dispatcher.
+		 */
+		bl_mem_params->ep_info.args.arg3 = PLAT_QEMU_DT_BASE;
+#endif
 		bl_mem_params->ep_info.spsr = qemu_get_spsr_for_bl32_entry();
 		break;
 # endif
diff --git a/plat/qemu/qemu_io_storage.c b/plat/qemu/qemu_io_storage.c
index 19baf21..e0f7e8a 100644
--- a/plat/qemu/qemu_io_storage.c
+++ b/plat/qemu/qemu_io_storage.c
@@ -21,6 +21,8 @@
 #define BL2_IMAGE_NAME			"bl2.bin"
 #define BL31_IMAGE_NAME			"bl31.bin"
 #define BL32_IMAGE_NAME			"bl32.bin"
+#define BL32_EXTRA1_IMAGE_NAME		"bl32_extra1.bin"
+#define BL32_EXTRA2_IMAGE_NAME		"bl32_extra2.bin"
 #define BL33_IMAGE_NAME			"bl33.bin"
 
 #if TRUSTED_BOARD_BOOT
@@ -61,6 +63,14 @@
 	.uuid = UUID_SECURE_PAYLOAD_BL32,
 };
 
+static const io_uuid_spec_t bl32_extra1_uuid_spec = {
+	.uuid = UUID_SECURE_PAYLOAD_BL32_EXTRA1,
+};
+
+static const io_uuid_spec_t bl32_extra2_uuid_spec = {
+	.uuid = UUID_SECURE_PAYLOAD_BL32_EXTRA2,
+};
+
 static const io_uuid_spec_t bl33_uuid_spec = {
 	.uuid = UUID_NON_TRUSTED_FIRMWARE_BL33,
 };
@@ -112,6 +122,14 @@
 		.path = BL32_IMAGE_NAME,
 		.mode = FOPEN_MODE_RB
 	},
+	[BL32_EXTRA1_IMAGE_ID] = {
+		.path = BL32_EXTRA1_IMAGE_NAME,
+		.mode = FOPEN_MODE_RB
+	},
+	[BL32_EXTRA2_IMAGE_ID] = {
+		.path = BL32_EXTRA2_IMAGE_NAME,
+		.mode = FOPEN_MODE_RB
+	},
 	[BL33_IMAGE_ID] = {
 		.path = BL33_IMAGE_NAME,
 		.mode = FOPEN_MODE_RB
@@ -185,6 +203,16 @@
 		(uintptr_t)&bl32_uuid_spec,
 		open_fip
 	},
+	[BL32_EXTRA1_IMAGE_ID] = {
+		&fip_dev_handle,
+		(uintptr_t)&bl32_extra1_uuid_spec,
+		open_fip
+	},
+	[BL32_EXTRA2_IMAGE_ID] = {
+		&fip_dev_handle,
+		(uintptr_t)&bl32_extra2_uuid_spec,
+		open_fip
+	},
 	[BL33_IMAGE_ID] = {
 		&fip_dev_handle,
 		(uintptr_t)&bl33_uuid_spec,
diff --git a/services/spd/opteed/opteed_common.c b/services/spd/opteed/opteed_common.c
index a0cd86c..2693e7d 100644
--- a/services/spd/opteed/opteed_common.c
+++ b/services/spd/opteed/opteed_common.c
@@ -20,7 +20,7 @@
 void opteed_init_optee_ep_state(struct entry_point_info *optee_entry_point,
 				uint32_t rw, uint64_t pc,
 				uint64_t pageable_part, uint64_t mem_limit,
-				optee_context_t *optee_ctx)
+				uint64_t dt_addr, optee_context_t *optee_ctx)
 {
 	uint32_t ep_attr;
 
@@ -54,6 +54,7 @@
 	zeromem(&optee_entry_point->args, sizeof(optee_entry_point->args));
 	optee_entry_point->args.arg0 = pageable_part;
 	optee_entry_point->args.arg1 = mem_limit;
+	optee_entry_point->args.arg2 = dt_addr;
 }
 
 /*******************************************************************************
diff --git a/services/spd/opteed/opteed_main.c b/services/spd/opteed/opteed_main.c
index b3031e4..13a307a 100644
--- a/services/spd/opteed/opteed_main.c
+++ b/services/spd/opteed/opteed_main.c
@@ -96,6 +96,7 @@
 	uint32_t linear_id;
 	uint64_t opteed_pageable_part;
 	uint64_t opteed_mem_limit;
+	uint64_t dt_addr;
 
 	linear_id = plat_my_core_pos();
 
@@ -120,19 +121,17 @@
 	if (!optee_ep_info->pc)
 		return 1;
 
-	/*
-	 * We could inspect the SP image and determine it's execution
-	 * state i.e whether AArch32 or AArch64.
-	 */
 	opteed_rw = optee_ep_info->args.arg0;
 	opteed_pageable_part = optee_ep_info->args.arg1;
 	opteed_mem_limit = optee_ep_info->args.arg2;
+	dt_addr = optee_ep_info->args.arg3;
 
 	opteed_init_optee_ep_state(optee_ep_info,
 				opteed_rw,
 				optee_ep_info->pc,
 				opteed_pageable_part,
 				opteed_mem_limit,
+				dt_addr,
 				&opteed_sp_context[linear_id]);
 
 	/*
diff --git a/services/spd/opteed/opteed_pm.c b/services/spd/opteed/opteed_pm.c
index 5a1dd4f..2420b1e 100644
--- a/services/spd/opteed/opteed_pm.c
+++ b/services/spd/opteed/opteed_pm.c
@@ -99,7 +99,7 @@
 
 	opteed_init_optee_ep_state(&optee_on_entrypoint, opteed_rw,
 				(uint64_t)&optee_vectors->cpu_on_entry,
-				0, 0, optee_ctx);
+				0, 0, 0, optee_ctx);
 
 	/* Initialise this cpu's secure context */
 	cm_init_my_context(&optee_on_entrypoint);
diff --git a/services/spd/opteed/opteed_private.h b/services/spd/opteed/opteed_private.h
index 11c1a1f..6cda2c8 100644
--- a/services/spd/opteed/opteed_private.h
+++ b/services/spd/opteed/opteed_private.h
@@ -149,6 +149,7 @@
 				uint64_t pc,
 				uint64_t pageable_part,
 				uint64_t mem_limit,
+				uint64_t dt_addr,
 				optee_context_t *optee_ctx);
 
 extern optee_context_t opteed_sp_context[OPTEED_CORE_COUNT];