platform: msm_shared: Add support for qgic3

Implement Qgicv3 driver as per armv8 specifications.
This includes reusing some of Qgicv2 implementation, so
refactor the code to move the shared code to common file
and separate the Qgicv2 & Qgicv3 logic into different
drivers.

Change-Id: Idbf985a9bec4db5879fe0ff95670df232e80664f
diff --git a/platform/msm_shared/include/qgic.h b/platform/msm_shared/include/qgic.h
index 30abec5..cb4c573 100644
--- a/platform/msm_shared/include/qgic.h
+++ b/platform/msm_shared/include/qgic.h
@@ -30,11 +30,9 @@
 #ifndef __PLATFORM_MSM_SHARED_QGIC_H
 #define __PLATFORM_MSM_SHARED_QGIC_H
 
-#include <platform/iomap.h>
-#include <platform/interrupts.h>
+#include "qgic_common.h"
 
 #define GIC_CPU_REG(off)            (MSM_GIC_CPU_BASE  + (off))
-#define GIC_DIST_REG(off)           (MSM_GIC_DIST_BASE + (off))
 
 #define GIC_CPU_CTRL                GIC_CPU_REG(0x00)
 #define GIC_CPU_PRIMASK             GIC_CPU_REG(0x04)
@@ -44,29 +42,12 @@
 #define GIC_CPU_RUNNINGPRI          GIC_CPU_REG(0x14)
 #define GIC_CPU_HIGHPRI             GIC_CPU_REG(0x18)
 
-#define GIC_DIST_CTRL               GIC_DIST_REG(0x000)
-#define GIC_DIST_CTR                GIC_DIST_REG(0x004)
-#define GIC_DIST_ENABLE_SET         GIC_DIST_REG(0x100)
-#define GIC_DIST_ENABLE_CLEAR       GIC_DIST_REG(0x180)
-#define GIC_DIST_PENDING_SET        GIC_DIST_REG(0x200)
-#define GIC_DIST_PENDING_CLEAR      GIC_DIST_REG(0x280)
-#define GIC_DIST_ACTIVE_BIT         GIC_DIST_REG(0x300)
-#define GIC_DIST_PRI                GIC_DIST_REG(0x400)
-#define GIC_DIST_TARGET             GIC_DIST_REG(0x800)
-#define GIC_DIST_CONFIG             GIC_DIST_REG(0xc00)
-#define GIC_DIST_SOFTINT            GIC_DIST_REG(0xf00)
-
 #define INTERRUPT_LVL_N_TO_N        0x0
 #define INTERRUPT_LVL_1_TO_N        0x1
 #define INTERRUPT_EDGE_N_TO_N       0x2
 #define INTERRUPT_EDGE_1_TO_N       0x3
 
-struct ihandler {
-	int_handler func;
-	void *arg;
-};
-
-void qgic_init(void);
-void qgic_change_interrupt_cfg(uint32_t spi_number, uint8_t type);
+uint32_t qgic_read_iar(void);
+void qgic_write_eoi(uint32_t);
 
 #endif
diff --git a/platform/msm_shared/include/qgic_common.h b/platform/msm_shared/include/qgic_common.h
new file mode 100644
index 0000000..431803d
--- /dev/null
+++ b/platform/msm_shared/include/qgic_common.h
@@ -0,0 +1,61 @@
+/*
+ * Copyright (c) 2011,2014 The Linux Foundation. All rights reserved.
+ *
+ * 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 The Linux Foundation 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 "AS IS" AND ANY EXPRESS OR IMPLIED
+ * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
+ * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT
+ * ARE DISCLAIMED.  IN NO EVENT SHALL THE COPYRIGHT OWNER 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.
+ */
+
+#ifndef __PLATFORM_MSM_SHARED_QGIC_COMMON_H
+#define __PLATFORM_MSM_SHARED_QGIC_COMMON_H
+
+#include <platform/iomap.h>
+#include <platform/irqs.h>
+#include <platform/interrupts.h>
+
+#define GIC_DIST_REG(off)           (MSM_GIC_DIST_BASE + (off))
+
+#define GIC_DIST_CTRL               GIC_DIST_REG(0x000)
+#define GIC_DIST_CTR                GIC_DIST_REG(0x004)
+#define GIC_DIST_ENABLE_SET         GIC_DIST_REG(0x100)
+#define GIC_DIST_ENABLE_CLEAR       GIC_DIST_REG(0x180)
+#define GIC_DIST_PENDING_SET        GIC_DIST_REG(0x200)
+#define GIC_DIST_PENDING_CLEAR      GIC_DIST_REG(0x280)
+#define GIC_DIST_ACTIVE_BIT         GIC_DIST_REG(0x300)
+#define GIC_DIST_PRI                GIC_DIST_REG(0x400)
+#define GIC_DIST_TARGET             GIC_DIST_REG(0x800)
+#define GIC_DIST_CONFIG             GIC_DIST_REG(0xc00)
+#define GIC_DIST_SOFTINT            GIC_DIST_REG(0xf00)
+
+struct ihandler {
+	int_handler func;
+	void *arg;
+};
+
+void qgic_init(void);
+void qgic_dist_config(uint32_t);
+void qgic_dist_init(void);
+void qgic_cpu_init(void);
+void qgic_change_interrupt_cfg(uint32_t spi_number, uint8_t type);
+#endif
diff --git a/platform/msm_shared/include/qgic_v3.h b/platform/msm_shared/include/qgic_v3.h
new file mode 100644
index 0000000..e0c159d
--- /dev/null
+++ b/platform/msm_shared/include/qgic_v3.h
@@ -0,0 +1,45 @@
+/*
+ * Copyright (c) 2014, The Linux Foundation. All rights reserved.
+ *
+ * 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 The Linux Foundation 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 "AS IS" AND ANY EXPRESS OR IMPLIED
+ * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
+ * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT
+ * ARE DISCLAIMED.  IN NO EVENT SHALL THE COPYRIGHT OWNER 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.
+ */
+
+#ifndef __PLATFORM_MSM_SHARED_QGIC_V3_H
+#define __PLATFORM_MSM_SHARED_QGIC_V3_H
+
+#include "qgic_common.h"
+
+#define GICD_IROUTER                GIC_DIST_REG(0x6000)
+#define GICR_WAKER_CPU0             MSM_GIC_REDIST_BASE
+
+#define ENABLE_GRP0_SEC             BIT(0)
+#define ENABLE_GRP1_NS              BIT(1)
+#define ENABLE_ARE                  BIT(4)
+
+uint32_t qgic_read_iar(void);
+void qgic_write_eoi(uint32_t);
+
+#endif
diff --git a/platform/msm_shared/qgic.c b/platform/msm_shared/qgic.c
index 49299e7..7250c62 100644
--- a/platform/msm_shared/qgic.c
+++ b/platform/msm_shared/qgic.c
@@ -32,11 +32,7 @@
  */
 
 #include <reg.h>
-#include <bits.h>
-#include <debug.h>
 #include <arch/arm.h>
-#include <kernel/thread.h>
-#include <platform/irqs.h>
 #include <qgic.h>
 
 static struct ihandler handler[NR_IRQS];
@@ -53,15 +49,11 @@
 		if (mask)
 			break;
 	}
-
-	if (!mask)
-		dprintf(CRITICAL, "GIC CPU mask not found\n");
-
 	return mask;
 }
 
 /* Intialize distributor */
-static void qgic_dist_init(void)
+void qgic_dist_init(void)
 {
 	uint32_t i;
 	uint32_t num_irq = 0;
@@ -81,123 +73,29 @@
 	num_irq = readl(GIC_DIST_CTR) & 0x1f;
 	num_irq = (num_irq + 1) * 32;
 
-	/* Set each interrupt line to use N-N software model
-	 * and edge sensitive, active high
-	 */
-	for (i = 32; i < num_irq; i += 16)
-		writel(0xffffffff, GIC_DIST_CONFIG + i * 4 / 16);
-
-	writel(0xffffffff, GIC_DIST_CONFIG + 4);
-
 	/* Set up interrupts for this CPU */
 	for (i = 32; i < num_irq; i += 4)
 		writel(cpumask, GIC_DIST_TARGET + i * 4 / 4);
 
-	/* Set priority of all interrupts */
-
-	/*
-	 * In bootloader we dont care about priority so
-	 * setting up equal priorities for all
-	 */
-	for (i = 0; i < num_irq; i += 4)
-		writel(0xa0a0a0a0, GIC_DIST_PRI + i * 4 / 4);
-
-	/* Disabling interrupts */
-	for (i = 0; i < num_irq; i += 32)
-		writel(0xffffffff, GIC_DIST_ENABLE_CLEAR + i * 4 / 32);
-
-	writel(0x0000ffff, GIC_DIST_ENABLE_SET);
+	qgic_dist_config(num_irq);
 
 	/*Enabling GIC */
 	writel(1, GIC_DIST_CTRL);
 }
 
 /* Intialize cpu specific controller */
-static void qgic_cpu_init(void)
+void qgic_cpu_init(void)
 {
 	writel(0xf0, GIC_CPU_PRIMASK);
 	writel(1, GIC_CPU_CTRL);
 }
 
-/* Initialize QGIC. Called from platform specific init code */
-void qgic_init(void)
+uint32_t qgic_read_iar()
 {
-	qgic_dist_init();
-	qgic_cpu_init();
+	return readl(GIC_CPU_INTACK);
 }
 
-/* IRQ handler */
-enum handler_return gic_platform_irq(struct arm_iframe *frame)
+void qgic_write_eoi(uint32_t num)
 {
-	uint32_t num;
-	enum handler_return ret;
-
-	num = readl(GIC_CPU_INTACK);
-	if (num >= NR_IRQS)
-		return 0;
-
-	ret = handler[num].func(handler[num].arg);
 	writel(num, GIC_CPU_EOI);
-
-	return ret;
-}
-
-/* FIQ handler */
-void gic_platform_fiq(struct arm_iframe *frame)
-{
-	PANIC_UNIMPLEMENTED;
-}
-
-/* Mask interrupt */
-status_t gic_mask_interrupt(unsigned int vector)
-{
-	uint32_t reg = GIC_DIST_ENABLE_CLEAR + (vector / 32) * 4;
-	uint32_t bit = 1 << (vector & 31);
-
-	writel(bit, reg);
-
-	return 0;
-}
-
-/* Un-mask interrupt */
-status_t gic_unmask_interrupt(unsigned int vector)
-{
-	uint32_t reg = GIC_DIST_ENABLE_SET + (vector / 32) * 4;
-	uint32_t bit = 1 << (vector & 31);
-
-	writel(bit, reg);
-
-	return 0;
-}
-
-/* Register interrupt handler */
-void gic_register_int_handler(unsigned int vector, int_handler func, void *arg)
-{
-	ASSERT(vector < NR_IRQS);
-
-	enter_critical_section();
-	handler[vector].func = func;
-	handler[vector].arg = arg;
-	exit_critical_section();
-}
-
-void qgic_change_interrupt_cfg(uint32_t spi_number, uint8_t type)
-{
-	uint32_t register_number, register_address, bit_number, value;
-	register_number = spi_number >> 4; // r = n DIV 16
-	bit_number = (spi_number % 16) << 1; // b = (n MOD 16) * 2
-	value = readl(GIC_DIST_CONFIG + (register_number << 2));
-	// there are two bits per register to indicate the level
-	if (type == INTERRUPT_LVL_N_TO_N)
-		value &= ~(BIT(bit_number)|BIT(bit_number+1)); // 0x0 0x0
-	else if (type == INTERRUPT_LVL_1_TO_N)
-		value = (value & ~BIT(bit_number+1)) | BIT(bit_number); // 0x0 0x1
-	else if (type == INTERRUPT_EDGE_N_TO_N)
-		value =  BIT(bit_number+1) | (value & ~BIT(bit_number));// 0x1 0x0
-	else if (type == INTERRUPT_EDGE_1_TO_N)
-		value |= (BIT(bit_number)|BIT(bit_number+1)); // 0x1 0x1
-	else
-		dprintf(CRITICAL, "Invalid interrupt type change requested\n");
-	register_address = GIC_DIST_CONFIG + (register_number << 2);
-	writel(value, register_address);
 }
diff --git a/platform/msm_shared/qgic_common.c b/platform/msm_shared/qgic_common.c
new file mode 100644
index 0000000..7abb5a1
--- /dev/null
+++ b/platform/msm_shared/qgic_common.c
@@ -0,0 +1,155 @@
+/* Copyright (c) 2014, The Linux Foundation. All rights reserved.
+ *
+ * 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 The Linux Fundation, Inc. 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 "AS IS" AND ANY EXPRESS OR IMPLIED
+ * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
+ * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT
+ * ARE DISCLAIMED.  IN NO EVENT SHALL THE COPYRIGHT OWNER 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 <reg.h>
+#include <bits.h>
+#include <arch/arm.h>
+#include <kernel/thread.h>
+#include <platform/irqs.h>
+#include <platform/iomap.h>
+#include <qgic.h>
+#include <debug.h>
+
+static struct ihandler handler[NR_IRQS];
+
+/* Intialize distributor */
+void qgic_dist_config(uint32_t num_irq)
+{
+	uint32_t i;
+
+	/* Set each interrupt line to use N-N software model
+	 * and edge sensitive, active high
+	 */
+	for (i = 32; i < num_irq; i += 16)
+		writel(0xffffffff, GIC_DIST_CONFIG + i * 4 / 16);
+
+	writel(0xffffffff, GIC_DIST_CONFIG + 4);
+
+	/* Set priority of all interrupts */
+
+	/*
+	 * In bootloader we dont care about priority so
+	 * setting up equal priorities for all
+	 */
+	for (i = 0; i < num_irq; i += 4)
+		writel(0xa0a0a0a0, GIC_DIST_PRI + i * 4 / 4);
+
+	/* Disabling interrupts */
+	for (i = 0; i < num_irq; i += 32)
+		writel(0xffffffff, GIC_DIST_ENABLE_CLEAR + i * 4 / 32);
+
+	writel(0x0000ffff, GIC_DIST_ENABLE_SET);
+}
+
+/* Initialize QGIC. Called from platform specific init code */
+void qgic_init(void)
+{
+	qgic_dist_init();
+	qgic_cpu_init();
+}
+
+/* IRQ handler */
+enum handler_return gic_platform_irq(struct arm_iframe *frame)
+{
+	uint32_t num;
+	enum handler_return ret;
+
+	/* Read the interrupt number to be served*/
+	num = qgic_read_iar();
+
+	if (num >= NR_IRQS)
+		return 0;
+
+	ret = handler[num].func(handler[num].arg);
+
+	/* End of interrupt */
+	qgic_write_eoi(num);
+
+	return ret;
+}
+
+/* FIQ handler */
+void gic_platform_fiq(struct arm_iframe *frame)
+{
+	PANIC_UNIMPLEMENTED;
+}
+
+/* Mask interrupt */
+status_t gic_mask_interrupt(unsigned int vector)
+{
+	uint32_t reg = GIC_DIST_ENABLE_CLEAR + (vector / 32) * 4;
+	uint32_t bit = 1 << (vector & 31);
+
+	writel(bit, reg);
+
+	return 0;
+}
+
+/* Un-mask interrupt */
+status_t gic_unmask_interrupt(unsigned int vector)
+{
+	uint32_t reg = GIC_DIST_ENABLE_SET + (vector / 32) * 4;
+	uint32_t bit = 1 << (vector & 31);
+
+	writel(bit, reg);
+
+	return 0;
+}
+
+/* Register interrupt handler */
+void gic_register_int_handler(unsigned int vector, int_handler func, void *arg)
+{
+	ASSERT(vector < NR_IRQS);
+
+	enter_critical_section();
+	handler[vector].func = func;
+	handler[vector].arg = arg;
+	exit_critical_section();
+}
+
+void qgic_change_interrupt_cfg(uint32_t spi_number, uint8_t type)
+{
+	uint32_t register_number, register_address, bit_number, value;
+	register_number = spi_number >> 4; // r = n DIV 16
+	bit_number = (spi_number % 16) << 1; // b = (n MOD 16) * 2
+	value = readl(GIC_DIST_CONFIG + (register_number << 2));
+	// there are two bits per register to indicate the level
+	if (type == INTERRUPT_LVL_N_TO_N)
+		value &= ~(BIT(bit_number)|BIT(bit_number+1)); // 0x0 0x0
+	else if (type == INTERRUPT_LVL_1_TO_N)
+		value = (value & ~BIT(bit_number+1)) | BIT(bit_number); // 0x0 0x1
+	else if (type == INTERRUPT_EDGE_N_TO_N)
+		value =  BIT(bit_number+1) | (value & ~BIT(bit_number));// 0x1 0x0
+	else if (type == INTERRUPT_EDGE_1_TO_N)
+		value |= (BIT(bit_number)|BIT(bit_number+1)); // 0x1 0x1
+	else
+		dprintf(CRITICAL, "Invalid interrupt type change requested\n");
+	register_address = GIC_DIST_CONFIG + (register_number << 2);
+	writel(value, register_address);
+}
diff --git a/platform/msm_shared/qgic_v3.c b/platform/msm_shared/qgic_v3.c
new file mode 100644
index 0000000..1177a23
--- /dev/null
+++ b/platform/msm_shared/qgic_v3.c
@@ -0,0 +1,145 @@
+/* Copyright (c) 2014, The Linux Foundation. All rights reserved.
+ *
+ * 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 The Linux Fundation, Inc. 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 "AS IS" AND ANY EXPRESS OR IMPLIED
+ * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
+ * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT
+ * ARE DISCLAIMED.  IN NO EVENT SHALL THE COPYRIGHT OWNER 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 <reg.h>
+#include <bits.h>
+#include <debug.h>
+#include <arch/arm.h>
+#include <arch/defines.h>
+#include <qgic_v3.h>
+
+#define GIC_WAKER_PROCESSORSLEEP                 BIT(1)
+#define GIC_WAKER_CHILDRENASLEEP                 BIT(2)
+
+void qgic_dist_init()
+{
+	uint32_t num_irq;
+	uint32_t affinity;
+	uint32_t i;
+
+	/* Read the mpidr register to find out the boot up cluster */
+	__asm__ volatile("mrc p15, 0, %0, c0, c0, 5" : "=r" (affinity));
+
+	/* For aarch32 mode we have only 3 affinity values: aff0:aff1:aff2*/
+	affinity = affinity & 0x00ffffff;
+
+	writel(0, GIC_DIST_CTRL);
+
+	/*
+	 * Find out how many interrupts are supported.
+	 */
+	num_irq = readl(GIC_DIST_CTR) & 0x1f;
+	num_irq = (num_irq + 1) * 32;
+
+	/* Do the qgic dist initialization */
+	qgic_dist_config(num_irq);
+
+	/* Write the affinity value, for routing all the SPIs */
+	for (i = 32; i < num_irq; i++)
+		writel(affinity, GICD_IROUTER + i * 8);
+
+	/* Enable affinity routing of grp0/grp1 interrupts */
+	writel(ENABLE_GRP0_SEC | ENABLE_GRP1_NS | ENABLE_ARE, GIC_DIST_CTRL);
+}
+
+void qgic_cpu_init()
+{
+	uint32_t waker = 0;
+	uint32_t retry = 1000;
+	uint32_t sre = 0;
+	uint32_t pmr = 0xff;
+	uint32_t eoimode = 0;
+	uint32_t grpen1 = 0x1;
+
+	/* For cpu init need to wake up the redistributor */
+	writel((readl(GICR_WAKER_CPU0) & ~GIC_WAKER_PROCESSORSLEEP), GICR_WAKER_CPU0);
+
+	/* Wait until redistributor is up */
+	while(readl(GICR_WAKER_CPU0) & GIC_WAKER_CHILDRENASLEEP)
+	{
+		retry--;
+		if (!retry)
+		{
+			dprintf(CRITICAL, "Failed to wake redistributor for CPU0\n");
+			ASSERT(0);
+		}
+		mdelay(1);
+	}
+
+
+	/* Make sure the system register access is enabled for us */
+	__asm__ volatile("mrc p15, 0, %0, c12, c12, 5" : "=r" (sre));
+	sre |= BIT(0);
+	__asm__ volatile("mcr p15, 0, %0, c12, c12, 5" :: "r" (sre));
+
+	isb();
+
+	/* If system register access is not set, we fail */
+	__asm__ volatile("mrc p15, 0, %0, c12, c12, 5" : "=r" (sre));
+	if (!(sre & BIT(0)))
+	{
+		dprintf(CRITICAL, "Failed to set SRE for NS world\n");
+		ASSERT(0);
+	}
+
+	/* Set the priortiy mask register, interrupts with priority
+	 * higher than this value will be signalled to processor.
+	 * Lower value means higher priority.
+	 */
+	__asm__ volatile("mcr p15, 0, %0, c4, c6, 0" :: "r" (pmr));
+	isb();
+
+	/* Make sure EOI is handled in NS EL3 */
+	__asm__ volatile("mrc p15, 0, %0, c12, c12, 4" : "=r" (eoimode));
+	eoimode &= ~BIT(1);
+	__asm__ volatile("mcr p15, 0, %0, c12, c12, 4" :: "r" (eoimode));
+	isb();
+
+	/* Enable grp1 interrupts for NS EL3*/
+	__asm__ volatile("mcr p15, 0, %0, c12, c12, 7" :: "r" (grpen1));
+	isb();
+}
+
+uint32_t qgic_read_iar()
+{
+	uint32_t iar;
+
+	/* Read the interrupt ack register, for the current interrupt number */
+	__asm__ volatile("mrc p15, 0, %0, c12, c12, 0" : "=r" (iar));
+	isb();
+
+	return iar;
+}
+
+void qgic_write_eoi(uint32_t iar)
+{
+	/* Write end of interrupt to indicate CPU that this interrupt is processed*/
+	__asm__ volatile("mcr p15, 0, %0, c12, c12, 1" :: "r" (iar));
+	isb();
+}
diff --git a/platform/msm_shared/rules.mk b/platform/msm_shared/rules.mk
index d6e048a..0ef8463 100755
--- a/platform/msm_shared/rules.mk
+++ b/platform/msm_shared/rules.mk
@@ -14,7 +14,12 @@
 	$(LOCAL_DIR)/jtag.o \
 	$(LOCAL_DIR)/partition_parser.o \
 	$(LOCAL_DIR)/hsusb.o \
-	$(LOCAL_DIR)/boot_stats.o
+	$(LOCAL_DIR)/boot_stats.o \
+	$(LOCAL_DIR)/qgic_common.o
+
+ifeq ($(ENABLE_QGIC3), 1)
+OBJS += $(LOCAL_DIR)/qgic_v3.o
+endif
 
 ifeq ($(ENABLE_SMD_SUPPORT),1)
 OBJS += \