Merge changes from topic "mp/giv3-discovery" into integration

* changes:
  Migrate ARM platforms to use the new GICv3 API
  Adding new optional PSCI hook pwr_domain_on_finish_late
  GICv3: Enable multi socket GIC redistributor frame discovery
diff --git a/docs/getting_started/porting-guide.rst b/docs/getting_started/porting-guide.rst
index 97ed1fa..9eb7c17 100644
--- a/docs/getting_started/porting-guide.rst
+++ b/docs/getting_started/porting-guide.rst
@@ -2209,6 +2209,19 @@
 above the CPU might require initialization due to having previously been in
 low power states. The generic code expects the handler to succeed.
 
+plat_psci_ops.pwr_domain_on_finish_late() [optional]
+...........................................................
+
+This optional function is called by the PSCI implementation after the calling
+CPU is fully powered on with respective data caches enabled. The calling CPU and
+the associated cluster are guaranteed to be participating in coherency. This
+function gives the flexibility to perform any platform-specific actions safely,
+such as initialization or modification of shared data structures, without the
+overhead of explicit cache maintainace operations.
+
+The ``target_state`` has a similar meaning as described in the ``pwr_domain_on_finish()``
+operation. The generic code expects the handler to succeed.
+
 plat_psci_ops.pwr_domain_suspend_finish()
 .........................................
 
diff --git a/drivers/arm/gic/v3/gicv3_main.c b/drivers/arm/gic/v3/gicv3_main.c
index 94a20ba..f371330 100644
--- a/drivers/arm/gic/v3/gicv3_main.c
+++ b/drivers/arm/gic/v3/gicv3_main.c
@@ -16,7 +16,6 @@
 #include "gicv3_private.h"
 
 const gicv3_driver_data_t *gicv3_driver_data;
-static unsigned int gicv2_compat;
 
 /*
  * Spinlock to guard registers needing read-modify-write. APIs protected by this
@@ -60,51 +59,61 @@
 void __init gicv3_driver_init(const gicv3_driver_data_t *plat_driver_data)
 {
 	unsigned int gic_version;
+	unsigned int gicv2_compat;
 
 	assert(plat_driver_data != NULL);
 	assert(plat_driver_data->gicd_base != 0U);
-	assert(plat_driver_data->gicr_base != 0U);
 	assert(plat_driver_data->rdistif_num != 0U);
 	assert(plat_driver_data->rdistif_base_addrs != NULL);
 
 	assert(IS_IN_EL3());
 
-	assert(plat_driver_data->interrupt_props_num > 0 ?
-	       plat_driver_data->interrupt_props != NULL : 1);
+	assert((plat_driver_data->interrupt_props_num != 0U) ?
+	       (plat_driver_data->interrupt_props != NULL) : 1);
 
 	/* Check for system register support */
-#ifdef __aarch64__
+#ifndef __aarch64__
+	assert((read_id_pfr1() &
+			(ID_PFR1_GIC_MASK << ID_PFR1_GIC_SHIFT)) != 0U);
+#else
 	assert((read_id_aa64pfr0_el1() &
 			(ID_AA64PFR0_GIC_MASK << ID_AA64PFR0_GIC_SHIFT)) != 0U);
-#else
-	assert((read_id_pfr1() & (ID_PFR1_GIC_MASK << ID_PFR1_GIC_SHIFT)) != 0U);
-#endif /* __aarch64__ */
+#endif /* !__aarch64__ */
 
 	/* The GIC version should be 3.0 */
 	gic_version = gicd_read_pidr2(plat_driver_data->gicd_base);
-	gic_version >>=	PIDR2_ARCH_REV_SHIFT;
+	gic_version >>= PIDR2_ARCH_REV_SHIFT;
 	gic_version &= PIDR2_ARCH_REV_MASK;
 	assert(gic_version == ARCH_REV_GICV3);
 
 	/*
-	 * Find out whether the GIC supports the GICv2 compatibility mode. The
-	 * ARE_S bit resets to 0 if supported
+	 * Find out whether the GIC supports the GICv2 compatibility mode.
+	 * The ARE_S bit resets to 0 if supported
 	 */
 	gicv2_compat = gicd_read_ctlr(plat_driver_data->gicd_base);
 	gicv2_compat >>= CTLR_ARE_S_SHIFT;
-	gicv2_compat = !(gicv2_compat & CTLR_ARE_S_MASK);
+	gicv2_compat = gicv2_compat & CTLR_ARE_S_MASK;
 
-	/*
-	 * Find the base address of each implemented Redistributor interface.
-	 * The number of interfaces should be equal to the number of CPUs in the
-	 * system. The memory for saving these addresses has to be allocated by
-	 * the platform port
-	 */
-	gicv3_rdistif_base_addrs_probe(plat_driver_data->rdistif_base_addrs,
-					   plat_driver_data->rdistif_num,
-					   plat_driver_data->gicr_base,
-					   plat_driver_data->mpidr_to_core_pos);
-
+	if (plat_driver_data->gicr_base != 0U) {
+		/*
+		 * Find the base address of each implemented Redistributor interface.
+		 * The number of interfaces should be equal to the number of CPUs in the
+		 * system. The memory for saving these addresses has to be allocated by
+		 * the platform port
+		 */
+		gicv3_rdistif_base_addrs_probe(plat_driver_data->rdistif_base_addrs,
+						   plat_driver_data->rdistif_num,
+						   plat_driver_data->gicr_base,
+						   plat_driver_data->mpidr_to_core_pos);
+#if !HW_ASSISTED_COHERENCY
+		/*
+		 * Flush the rdistif_base_addrs[] contents linked to the GICv3 driver.
+		 */
+		flush_dcache_range((uintptr_t)(plat_driver_data->rdistif_base_addrs),
+			plat_driver_data->rdistif_num *
+			sizeof(*(plat_driver_data->rdistif_base_addrs)));
+#endif
+	}
 	gicv3_driver_data = plat_driver_data;
 
 	/*
@@ -112,19 +121,19 @@
 	 * enabled. When the secondary CPU boots up, it initializes the
 	 * GICC/GICR interface with the caches disabled. Hence flush the
 	 * driver data to ensure coherency. This is not required if the
-	 * platform has HW_ASSISTED_COHERENCY or WARMBOOT_ENABLE_DCACHE_EARLY
-	 * enabled.
+	 * platform has HW_ASSISTED_COHERENCY enabled.
 	 */
-#if !(HW_ASSISTED_COHERENCY || WARMBOOT_ENABLE_DCACHE_EARLY)
-	flush_dcache_range((uintptr_t) &gicv3_driver_data,
-			sizeof(gicv3_driver_data));
-	flush_dcache_range((uintptr_t) gicv3_driver_data,
-			sizeof(*gicv3_driver_data));
+#if !HW_ASSISTED_COHERENCY
+	flush_dcache_range((uintptr_t)&gicv3_driver_data,
+		sizeof(gicv3_driver_data));
+	flush_dcache_range((uintptr_t)gicv3_driver_data,
+		sizeof(*gicv3_driver_data));
 #endif
 
-	INFO("GICv3 %s legacy support detected."
-			" ARM GICV3 driver initialized in EL3\n",
-			gicv2_compat ? "with" : "without");
+	INFO("GICv3 with%s legacy support detected."
+			" ARM GICv3 driver initialized in EL3\n",
+			(gicv2_compat == 0U) ? "" : "out");
+
 }
 
 /*******************************************************************************
@@ -192,6 +201,7 @@
 	gicv3_rdistif_on(proc_num);
 
 	gicr_base = gicv3_driver_data->rdistif_base_addrs[proc_num];
+	assert(gicr_base != 0U);
 
 	/* Set the default attribute of all SGIs and PPIs */
 	gicv3_ppi_sgi_config_defaults(gicr_base);
@@ -313,6 +323,7 @@
 
 	/* Mark the connected core as asleep */
 	gicr_base = gicv3_driver_data->rdistif_base_addrs[proc_num];
+	assert(gicr_base != 0U);
 	gicv3_rdistif_mark_core_asleep(gicr_base);
 }
 
@@ -1081,3 +1092,71 @@
 
 	return old_mask;
 }
+
+/*******************************************************************************
+ * This function delegates the responsibility of discovering the corresponding
+ * Redistributor frames to each CPU itself. It is a modified version of
+ * gicv3_rdistif_base_addrs_probe() and is executed by each CPU in the platform
+ * unlike the previous way in which only the Primary CPU did the discovery of
+ * all the Redistributor frames for every CPU. It also handles the scenario in
+ * which the frames of various CPUs are not contiguous in physical memory.
+ ******************************************************************************/
+int gicv3_rdistif_probe(const uintptr_t gicr_frame)
+{
+	u_register_t mpidr;
+	unsigned int proc_num, proc_self;
+	uint64_t typer_val;
+	uintptr_t rdistif_base;
+	bool gicr_frame_found = false;
+
+	assert(gicv3_driver_data->gicr_base == 0U);
+
+	/* Ensure this function is called with Data Cache enabled */
+#ifndef __aarch64__
+	assert((read_sctlr() & SCTLR_C_BIT) != 0U);
+#else
+	assert((read_sctlr_el3() & SCTLR_C_BIT) != 0U);
+#endif /* !__aarch64__ */
+
+	proc_self = gicv3_driver_data->mpidr_to_core_pos(read_mpidr_el1());
+	rdistif_base = gicr_frame;
+	do {
+		typer_val = gicr_read_typer(rdistif_base);
+		if (gicv3_driver_data->mpidr_to_core_pos != NULL) {
+			mpidr = mpidr_from_gicr_typer(typer_val);
+			proc_num = gicv3_driver_data->mpidr_to_core_pos(mpidr);
+		} else {
+			proc_num = (unsigned int)(typer_val >> TYPER_PROC_NUM_SHIFT) &
+					TYPER_PROC_NUM_MASK;
+		}
+		if (proc_num == proc_self) {
+			/* The base address doesn't need to be initialized on
+			 * every warm boot.
+			 */
+			if (gicv3_driver_data->rdistif_base_addrs[proc_num] != 0U)
+				return 0;
+			gicv3_driver_data->rdistif_base_addrs[proc_num] =
+			rdistif_base;
+			gicr_frame_found = true;
+			break;
+		}
+		rdistif_base += (uintptr_t)(ULL(1) << GICR_PCPUBASE_SHIFT);
+	} while ((typer_val & TYPER_LAST_BIT) == 0U);
+
+	if (!gicr_frame_found)
+		return -1;
+
+	/*
+	 * Flush the driver data to ensure coherency. This is
+	 * not required if platform has HW_ASSISTED_COHERENCY
+	 * enabled.
+	 */
+#if !HW_ASSISTED_COHERENCY
+	/*
+	 * Flush the rdistif_base_addrs[] contents linked to the GICv3 driver.
+	 */
+	flush_dcache_range((uintptr_t)&(gicv3_driver_data->rdistif_base_addrs[proc_num]),
+		sizeof(*(gicv3_driver_data->rdistif_base_addrs)));
+#endif
+	return 0; /* Found matching GICR frame */
+}
diff --git a/include/drivers/arm/gicv3.h b/include/drivers/arm/gicv3.h
index 9c72d4d..c4f42d0 100644
--- a/include/drivers/arm/gicv3.h
+++ b/include/drivers/arm/gicv3.h
@@ -1,5 +1,5 @@
 /*
- * Copyright (c) 2015-2018, ARM Limited and Contributors. All rights reserved.
+ * Copyright (c) 2015-2019, ARM Limited and Contributors. All rights reserved.
  *
  * SPDX-License-Identifier: BSD-3-Clause
  */
@@ -366,6 +366,7 @@
  * GICv3 EL3 driver API
  ******************************************************************************/
 void gicv3_driver_init(const gicv3_driver_data_t *plat_driver_data);
+int gicv3_rdistif_probe(const uintptr_t gicr_frame);
 void gicv3_distif_init(void);
 void gicv3_rdistif_init(unsigned int proc_num);
 void gicv3_rdistif_on(unsigned int proc_num);
diff --git a/include/lib/psci/psci.h b/include/lib/psci/psci.h
index 04e5e3d..7f7b7e3 100644
--- a/include/lib/psci/psci.h
+++ b/include/lib/psci/psci.h
@@ -1,5 +1,5 @@
 /*
- * Copyright (c) 2013-2018, ARM Limited and Contributors. All rights reserved.
+ * Copyright (c) 2013-2019, ARM Limited and Contributors. All rights reserved.
  *
  * SPDX-License-Identifier: BSD-3-Clause
  */
@@ -301,6 +301,8 @@
 				const psci_power_state_t *target_state);
 	void (*pwr_domain_suspend)(const psci_power_state_t *target_state);
 	void (*pwr_domain_on_finish)(const psci_power_state_t *target_state);
+	void (*pwr_domain_on_finish_late)(
+				const psci_power_state_t *target_state);
 	void (*pwr_domain_suspend_finish)(
 				const psci_power_state_t *target_state);
 	void __dead2 (*pwr_domain_pwr_down_wfi)(
diff --git a/include/plat/arm/css/common/css_pm.h b/include/plat/arm/css/common/css_pm.h
index b82ff47..93f8616 100644
--- a/include/plat/arm/css/common/css_pm.h
+++ b/include/plat/arm/css/common/css_pm.h
@@ -27,6 +27,7 @@
 
 int css_pwr_domain_on(u_register_t mpidr);
 void css_pwr_domain_on_finish(const psci_power_state_t *target_state);
+void css_pwr_domain_on_finish_late(const psci_power_state_t *target_state);
 void css_pwr_domain_off(const psci_power_state_t *target_state);
 void css_pwr_domain_suspend(const psci_power_state_t *target_state);
 void css_pwr_domain_suspend_finish(
diff --git a/lib/psci/psci_on.c b/lib/psci/psci_on.c
index aa6b324..470b4f3 100644
--- a/lib/psci/psci_on.c
+++ b/lib/psci/psci_on.c
@@ -1,5 +1,5 @@
 /*
- * Copyright (c) 2013-2018, ARM Limited and Contributors. All rights reserved.
+ * Copyright (c) 2013-2019, ARM Limited and Contributors. All rights reserved.
  *
  * SPDX-License-Identifier: BSD-3-Clause
  */
@@ -182,6 +182,14 @@
 #endif
 
 	/*
+	 * Plat. management: Perform any platform specific actions which
+	 * can only be done with the cpu and the cluster guaranteed to
+	 * be coherent.
+	 */
+	if (psci_plat_pm_ops->pwr_domain_on_finish_late != NULL)
+		psci_plat_pm_ops->pwr_domain_on_finish_late(state_info);
+
+	/*
 	 * All the platform specific actions for turning this cpu
 	 * on have completed. Perform enough arch.initialization
 	 * to run in the non-secure address space.
diff --git a/plat/arm/board/fvp/fvp_pm.c b/plat/arm/board/fvp/fvp_pm.c
index 42dec8d..0a62543 100644
--- a/plat/arm/board/fvp/fvp_pm.c
+++ b/plat/arm/board/fvp/fvp_pm.c
@@ -1,5 +1,5 @@
 /*
- * Copyright (c) 2013-2018, ARM Limited and Contributors. All rights reserved.
+ * Copyright (c) 2013-2019, ARM Limited and Contributors. All rights reserved.
  *
  * SPDX-License-Identifier: BSD-3-Clause
  */
@@ -247,10 +247,19 @@
 {
 	fvp_power_domain_on_finish_common(target_state);
 
-	/* Enable the gic cpu interface */
+}
+
+/*******************************************************************************
+ * FVP handler called when a power domain has just been powered on and the cpu
+ * and its cluster are fully participating in coherent transaction on the
+ * interconnect. Data cache must be enabled for CPU at this point.
+ ******************************************************************************/
+static void fvp_pwr_domain_on_finish_late(const psci_power_state_t *target_state)
+{
+	/* Program GIC per-cpu distributor or re-distributor interface */
 	plat_arm_gic_pcpu_init();
 
-	/* Program the gic per-cpu distributor or re-distributor interface */
+	/* Enable GIC CPU interface */
 	plat_arm_gic_cpuif_enable();
 }
 
@@ -272,7 +281,7 @@
 
 	fvp_power_domain_on_finish_common(target_state);
 
-	/* Enable the gic cpu interface */
+	/* Enable GIC CPU interface */
 	plat_arm_gic_cpuif_enable();
 }
 
@@ -397,6 +406,7 @@
 	.pwr_domain_off = fvp_pwr_domain_off,
 	.pwr_domain_suspend = fvp_pwr_domain_suspend,
 	.pwr_domain_on_finish = fvp_pwr_domain_on_finish,
+	.pwr_domain_on_finish_late = fvp_pwr_domain_on_finish_late,
 	.pwr_domain_suspend_finish = fvp_pwr_domain_suspend_finish,
 	.system_off = fvp_system_off,
 	.system_reset = fvp_system_reset,
diff --git a/plat/arm/common/arm_gicv3.c b/plat/arm/common/arm_gicv3.c
index 7f4957f..fef5376 100644
--- a/plat/arm/common/arm_gicv3.c
+++ b/plat/arm/common/arm_gicv3.c
@@ -4,6 +4,7 @@
  * SPDX-License-Identifier: BSD-3-Clause
  */
 
+#include <assert.h>
 #include <platform_def.h>
 
 #include <common/interrupt_props.h>
@@ -67,7 +68,7 @@
 
 static const gicv3_driver_data_t arm_gic_data __unused = {
 	.gicd_base = PLAT_ARM_GICD_BASE,
-	.gicr_base = PLAT_ARM_GICR_BASE,
+	.gicr_base = 0U,
 	.interrupt_props = arm_interrupt_props,
 	.interrupt_props_num = ARRAY_SIZE(arm_interrupt_props),
 	.rdistif_num = PLATFORM_CORE_COUNT,
@@ -86,6 +87,11 @@
 #if (!defined(__aarch64__) && defined(IMAGE_BL32)) || \
 	(defined(__aarch64__) && defined(IMAGE_BL31))
 	gicv3_driver_init(&arm_gic_data);
+
+	if (gicv3_rdistif_probe(PLAT_ARM_GICR_BASE) == -1) {
+		ERROR("No GICR base frame found for Primary CPU\n");
+		panic();
+	}
 #endif
 }
 
@@ -116,10 +122,20 @@
 }
 
 /******************************************************************************
- * ARM common helper to initialize the per-cpu redistributor interface in GICv3
+ * ARM common helper function to iterate over all GICR frames and discover the
+ * corresponding per-cpu redistributor frame as well as initialize the
+ * corresponding interface in GICv3. At the moment, Arm platforms do not have
+ * non-contiguous GICR frames.
  *****************************************************************************/
 void plat_arm_gic_pcpu_init(void)
 {
+	int result;
+
+	result = gicv3_rdistif_probe(PLAT_ARM_GICR_BASE);
+	if (result == -1) {
+		ERROR("No GICR base frame found for CPU 0x%lx\n", read_mpidr());
+		panic();
+	}
 	gicv3_rdistif_init(plat_my_core_pos());
 }
 
diff --git a/plat/arm/css/common/css_pm.c b/plat/arm/css/common/css_pm.c
index f6fc6aa..01c674f 100644
--- a/plat/arm/css/common/css_pm.c
+++ b/plat/arm/css/common/css_pm.c
@@ -1,5 +1,5 @@
 /*
- * Copyright (c) 2015-2018, ARM Limited and Contributors. All rights reserved.
+ * Copyright (c) 2015-2019, ARM Limited and Contributors. All rights reserved.
  *
  * SPDX-License-Identifier: BSD-3-Clause
  */
@@ -76,9 +76,6 @@
 {
 	assert(CSS_CORE_PWR_STATE(target_state) == ARM_LOCAL_STATE_OFF);
 
-	/* Enable the gic cpu interface */
-	plat_arm_gic_cpuif_enable();
-
 	/*
 	 * Perform the common cluster specific operations i.e enable coherency
 	 * if this cluster was off.
@@ -100,10 +97,21 @@
 	/* Assert that the system power domain need not be initialized */
 	assert(css_system_pwr_state(target_state) == ARM_LOCAL_STATE_RUN);
 
+	css_pwr_domain_on_finisher_common(target_state);
+}
+
+/*******************************************************************************
+ * Handler called when a power domain has just been powered on and the cpu
+ * and its cluster are fully participating in coherent transaction on the
+ * interconnect. Data cache must be enabled for CPU at this point.
+ ******************************************************************************/
+void css_pwr_domain_on_finish_late(const psci_power_state_t *target_state)
+{
 	/* Program the gic per-cpu distributor or re-distributor interface */
 	plat_arm_gic_pcpu_init();
 
-	css_pwr_domain_on_finisher_common(target_state);
+	/* Enable the gic cpu interface */
+	plat_arm_gic_cpuif_enable();
 }
 
 /*******************************************************************************
@@ -185,6 +193,9 @@
 		arm_system_pwr_domain_resume();
 
 	css_pwr_domain_on_finisher_common(target_state);
+
+	/* Enable the gic cpu interface */
+	plat_arm_gic_cpuif_enable();
 }
 
 /*******************************************************************************
@@ -306,6 +317,7 @@
 plat_psci_ops_t plat_arm_psci_pm_ops = {
 	.pwr_domain_on		= css_pwr_domain_on,
 	.pwr_domain_on_finish	= css_pwr_domain_on_finish,
+	.pwr_domain_on_finish_late = css_pwr_domain_on_finish_late,
 	.pwr_domain_off		= css_pwr_domain_off,
 	.cpu_standby		= css_cpu_standby,
 	.pwr_domain_suspend	= css_pwr_domain_suspend,