[Date Prev][Date Next][Thread Prev][Thread Next][Date Index][Thread Index]

[Xen-devel] [PATCH v3 13/16] xen/arm: Add support for GIC v3



From: Vijaya Kumar K <Vijaya.Kumar@xxxxxxxxxxxxxxxxxx>

Add support for GIC v3 specification System register access(SRE)
is enabled to access cpu and virtual interface regiseters based
on kernel GICv3 driver.

This patch adds only basic v3 support.
Does not support Interrupt Translation support (ITS)

Signed-off-by: Vijaya Kumar K <Vijaya.Kumar@xxxxxxxxxxxxxxxxxx>
---
 xen/arch/arm/Makefile                 |    2 +-
 xen/arch/arm/gic-v3.c                 |  967 +++++++++++++++++++++++++++++++++
 xen/include/asm-arm/arm64/processor.h |   14 +
 xen/include/asm-arm/domain.h          |    6 +
 xen/include/asm-arm/gic.h             |   15 +
 xen/include/asm-arm/gic_v3_defs.h     |  198 +++++++
 6 files changed, 1201 insertions(+), 1 deletion(-)

diff --git a/xen/arch/arm/Makefile b/xen/arch/arm/Makefile
index 20f59f4..39166aa 100644
--- a/xen/arch/arm/Makefile
+++ b/xen/arch/arm/Makefile
@@ -10,7 +10,7 @@ obj-y += vpsci.o
 obj-y += domctl.o
 obj-y += sysctl.o
 obj-y += domain_build.o
-obj-y += gic.o gic-v2.o
+obj-y += gic.o gic-v3.o gic-v2.o
 obj-y += io.o
 obj-y += irq.o
 obj-y += kernel.o
diff --git a/xen/arch/arm/gic-v3.c b/xen/arch/arm/gic-v3.c
new file mode 100644
index 0000000..8625e0c
--- /dev/null
+++ b/xen/arch/arm/gic-v3.c
@@ -0,0 +1,967 @@
+/*
+ * xen/arch/arm/gic-v3.c
+ *
+ * ARM Generic Interrupt Controller support v3 version
+ * based on xen/arch/arm/gic-v2.c and kernel GICv3 driver
+ * 
+ * Vijaya Kumar K <vijaya.kumar@xxxxxxxxxxxxxxxxxx>
+ * Copyright (c) 2014 Cavium Inc.
+ * 
+ * This program is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * GNU General Public License for more details.
+ */
+
+#include <xen/config.h>
+#include <xen/lib.h>
+#include <xen/init.h>
+#include <xen/cpu.h>
+#include <xen/mm.h>
+#include <xen/irq.h>
+#include <xen/sched.h>
+#include <xen/errno.h>
+#include <xen/serial.h>
+#include <xen/softirq.h>
+#include <xen/list.h>
+#include <xen/device_tree.h>
+#include <xen/delay.h>
+#include <asm/p2m.h>
+#include <asm/domain.h>
+#include <asm/platform.h>
+
+#include <asm/gic_v3_defs.h>
+#include <asm/gic.h>
+#include <asm/io.h>
+#include <asm/device.h>
+
+static struct gic_hw_operations gic_ops;
+
+struct rdist_region {
+    paddr_t rdist_base;
+    paddr_t rdist_base_size;
+    void __iomem *map_rdist_base;
+};
+
+/* Global state */
+static struct {
+    paddr_t dbase;            /* Address of distributor registers */
+    paddr_t dbase_size;
+    void __iomem *map_dbase;  /* Mapped address of distributor registers */
+    struct rdist_region *rdist_regions;
+    u32  rdist_stride;
+    unsigned int rdist_count; /* Number of rdist regions count */
+    unsigned int lines;       /* Number of interrupts (SPIs + PPIs + SGIs) */
+    struct dt_irq maintenance;
+}gic;
+
+/* per-cpu re-distributor base */
+static DEFINE_PER_CPU(void __iomem*, rbase);
+
+static uint8_t nr_lrs;
+static uint32_t nr_priorities;
+
+#define GICD                   (gic.map_dbase)
+#define GICD_RDIST_BASE        (this_cpu(rbase))
+#define GICD_RDIST_SGI_BASE    (GICD_RDIST_BASE + SZ_64K)
+
+static u64 gich_read_lr(int lr)
+{
+    switch ( lr )
+    {
+    case 0: /* ICH_LRn is 64 bit */
+        return READ_SYSREG(ICH_LR0_EL2);
+        break;
+    case 1:
+        return READ_SYSREG(ICH_LR1_EL2);
+        break;
+    case 2:
+        return READ_SYSREG(ICH_LR2_EL2);
+        break;
+    case 3:
+        return READ_SYSREG(ICH_LR3_EL2);
+        break;
+    case 4:
+        return READ_SYSREG(ICH_LR4_EL2);
+        break;
+    case 5:
+        return READ_SYSREG(ICH_LR5_EL2);
+        break;
+    case 6:
+        return READ_SYSREG(ICH_LR6_EL2);
+        break;
+    case 7:
+        return READ_SYSREG(ICH_LR7_EL2);
+        break;
+    case 8:
+        return READ_SYSREG(ICH_LR8_EL2);
+        break;
+    case 9:
+        return READ_SYSREG(ICH_LR9_EL2);
+        break;
+    case 10:
+        return READ_SYSREG(ICH_LR10_EL2);
+        break;
+    case 11:
+        return READ_SYSREG(ICH_LR11_EL2);
+        break;
+    case 12:
+        return READ_SYSREG(ICH_LR12_EL2);
+        break;
+    case 13:
+        return READ_SYSREG(ICH_LR13_EL2);
+        break;
+    case 14:
+        return READ_SYSREG(ICH_LR14_EL2);
+        break;
+    case 15:
+        return READ_SYSREG(ICH_LR15_EL2);
+        break;
+    default:
+        return 0;
+    }
+}
+
+static void gich_write_lr(int lr, u64 val)
+{
+    switch ( lr )
+    {
+    case 0:
+        WRITE_SYSREG(val, ICH_LR0_EL2);
+        break;
+    case 1:
+        WRITE_SYSREG(val, ICH_LR1_EL2);
+        break;
+    case 2:
+        WRITE_SYSREG(val, ICH_LR2_EL2);
+        break;
+    case 3:
+        WRITE_SYSREG(val, ICH_LR3_EL2);
+        break;
+    case 4:
+        WRITE_SYSREG(val, ICH_LR4_EL2);
+        break;
+    case 5:
+        WRITE_SYSREG(val, ICH_LR5_EL2);
+        break;
+    case 6:
+        WRITE_SYSREG(val, ICH_LR6_EL2);
+        break;
+    case 7:
+        WRITE_SYSREG(val, ICH_LR7_EL2);
+        break;
+    case 8:
+        WRITE_SYSREG(val, ICH_LR8_EL2);
+        break;
+    case 9:
+        WRITE_SYSREG(val, ICH_LR9_EL2);
+        break;
+    case 10:
+        WRITE_SYSREG(val, ICH_LR10_EL2);
+        break;
+    case 11:
+        WRITE_SYSREG(val, ICH_LR11_EL2);
+        break;
+    case 12:
+        WRITE_SYSREG(val, ICH_LR12_EL2);
+        break;
+    case 13:
+        WRITE_SYSREG(val, ICH_LR13_EL2);
+        break;
+    case 14:
+        WRITE_SYSREG(val, ICH_LR14_EL2);
+        break;
+    case 15:
+        WRITE_SYSREG(val, ICH_LR15_EL2);
+        break;
+    default:
+        return;
+    }
+}
+
+/* 
+ * System Register Enable (SRE). Enable to access CPU & Virtual
+ * interface registers as system registers in EL2
+ */
+static void gicv3_enable_sre(void)
+{
+    uint32_t val;
+
+    val = READ_SYSREG32(ICC_SRE_EL2);
+    val |= GICC_SRE_EL2_SRE | GICC_SRE_EL2_ENEL1 | GICC_SRE_EL2_DFB | 
GICC_SRE_EL2_DIB;
+    WRITE_SYSREG32(val, ICC_SRE_EL2);
+    isb();
+}
+
+/* Wait for completion of a distributor change */
+static void gicv3_do_wait_for_rwp(void __iomem *base)
+{
+    u32 val;
+    u32 count = 1000000;
+
+    do {
+        val = readl_relaxed(base + GICD_CTLR);
+        if ( !(val & GICD_CTLR_RWP) )
+           break;
+        cpu_relax();
+        udelay(1);
+    } while ( count-- );
+
+    if ( !count )
+        dprintk(XENLOG_WARNING, "RWP timeout\n");
+}
+
+static void gicv3_dist_wait_for_rwp(void)
+{
+    gicv3_do_wait_for_rwp(GICD);
+}
+
+static void gicv3_redist_wait_for_rwp(void)
+{
+    gicv3_do_wait_for_rwp(GICD_RDIST_BASE);
+}
+
+static void gicv3_wait_for_rwp(int irq)
+{
+    if ( irq < NR_LOCAL_IRQS )
+         gicv3_redist_wait_for_rwp();
+    else
+         gicv3_dist_wait_for_rwp();
+}
+
+static unsigned int gicv3_mask_cpu(const cpumask_t *cpumask)
+{
+    unsigned int cpu;
+    cpumask_t possible_mask;
+
+    cpumask_and(&possible_mask, cpumask, &cpu_possible_map);
+    cpu = cpumask_any(&possible_mask);
+    return cpu;
+}
+
+static void write_aprn_regs(union gic_state_data *d)
+{
+    ASSERT((nr_priorities > 4 && nr_priorities < 8));
+    /* Write APRn register based on number of priorities
+       plaform has implemented */
+    switch ( nr_priorities )
+    {
+    case 7:
+        WRITE_SYSREG32(d->v3.apr0[2], ICH_AP0R2_EL2);
+        WRITE_SYSREG32(d->v3.apr1[2], ICH_AP1R2_EL2);
+        /* Fall through */
+    case 6:
+        WRITE_SYSREG32(d->v3.apr0[1], ICH_AP0R1_EL2);
+        WRITE_SYSREG32(d->v3.apr1[1], ICH_AP1R1_EL2);
+        /* Fall through */
+    case 5:
+        WRITE_SYSREG32(d->v3.apr0[0], ICH_AP0R0_EL2);
+        WRITE_SYSREG32(d->v3.apr1[0], ICH_AP1R0_EL2);
+        break;
+    default:
+        break;
+    }
+}
+
+static void read_aprn_regs(union gic_state_data *d)
+{
+    ASSERT((nr_priorities > 4 && nr_priorities < 8));
+    /* Read APRn register based on number of priorities
+       plaform has implemented */
+    switch ( nr_priorities )
+    {
+    case 7:
+        d->v3.apr0[2] = READ_SYSREG32(ICH_AP0R2_EL2);
+        d->v3.apr1[2] = READ_SYSREG32(ICH_AP1R2_EL2);
+        /* Fall through */
+    case 6:
+        d->v3.apr0[1] = READ_SYSREG32(ICH_AP0R1_EL2);
+        d->v3.apr1[1] = READ_SYSREG32(ICH_AP1R1_EL2);
+        /* Fall through */
+    case 5:
+        d->v3.apr0[0] = READ_SYSREG32(ICH_AP0R0_EL2);
+        d->v3.apr1[0] = READ_SYSREG32(ICH_AP1R0_EL2);
+        break;
+    default:
+        break;
+    }
+}
+
+static void gicv3_save_state(struct vcpu *v)
+{
+    int i;
+
+    /* No need for spinlocks here because interrupts are disabled around
+     * this call and it only accesses struct vcpu fields that cannot be
+     * accessed simultaneously by another pCPU.
+     */
+    for ( i = 0; i < nr_lrs; i++)
+        v->arch.gic.v3.lr[i] = gich_read_lr(i);
+
+    read_aprn_regs(&v->arch.gic); 
+    v->arch.gic.v3.vmcr = READ_SYSREG32(ICH_VMCR_EL2);
+}
+
+static void gicv3_restore_state(struct vcpu *v)
+{
+    int i;
+
+    for ( i = 0; i < nr_lrs; i++)
+        gich_write_lr(i, v->arch.gic.v3.lr[i]);
+
+    write_aprn_regs(&v->arch.gic);
+
+    WRITE_SYSREG32(v->arch.gic.v3.vmcr, ICH_VMCR_EL2);
+}
+
+static void gicv3_dump_state(struct vcpu *v)
+{
+    int i;
+    if ( v == current )
+    {
+        for ( i = 0; i < nr_lrs; i++ )
+            printk("   HW_LR[%d]=%lx\n", i, gich_read_lr(i));
+    }
+    else
+    {
+        for ( i = 0; i < nr_lrs; i++ )
+            printk("   VCPU_LR[%d]=%lx\n", i, v->arch.gic.v3.lr[i]);
+    }
+}
+ 
+static void gicv3_enable_irq(struct irq_desc *irqd)
+{
+    int irq = irqd->irq;
+    uint32_t enabler;
+
+    /* Enable routing */
+    if ( irq < NR_GIC_LOCAL_IRQS )
+    {
+        enabler = readl_relaxed(GICD_RDIST_SGI_BASE + GICR_ISENABLER0);
+        enabler |= (1u << irq);
+        writel_relaxed(enabler, GICD_RDIST_SGI_BASE + GICR_ISENABLER0);
+    }
+    else
+    {
+        enabler = readl_relaxed(GICD + GICD_ISENABLER + (irq / 32) * 4);
+        enabler |= (1u << (irq % 32));
+        writel_relaxed(enabler, GICD + GICD_ISENABLER + (irq / 32) * 4);
+    }
+    gicv3_wait_for_rwp(irq);
+}
+
+static void gicv3_disable_irq(struct irq_desc *irqd)
+{
+    int irq = irqd->irq;
+    uint32_t val;
+    /* Disable routing */
+    if ( irq < NR_GIC_LOCAL_IRQS )
+    {
+        val = 1u << irq;
+        writel_relaxed(val, GICD_RDIST_SGI_BASE + GICR_ICENABLER0);
+    } else {
+        val = 1u << (irq % 32);
+        writel_relaxed(val, GICD + GICD_ICENABLER + ((irq / 32) * 4));
+    }
+}
+
+static void gicv3_eoi_irq(struct irq_desc *irqd)
+{
+    int irq = irqd->irq;
+    /* Lower the priority */
+    WRITE_SYSREG32(irq, ICC_EOIR1_EL1);
+}
+
+static void gicv3_dir_irq(int irq)
+{
+    /* Deactivate */
+    WRITE_SYSREG32(irq, ICC_DIR_EL1);
+}
+
+static unsigned int gicv3_ack_irq(void)
+{
+    return (READ_SYSREG32(ICC_IAR1_EL1) & GICC_IA_IRQ);
+}
+
+
+static u64 gic_mpidr_to_affinity(u64 mpidr)
+{
+    u64 aff;
+    /* Make sure we don't broadcast the interrupt */
+     aff = (MPIDR_AFFINITY_LEVEL(mpidr, 3) << 32 |
+            MPIDR_AFFINITY_LEVEL(mpidr, 2) << 16 |
+            MPIDR_AFFINITY_LEVEL(mpidr, 1) << 8  |
+            MPIDR_AFFINITY_LEVEL(mpidr, 0)) & ~GICD_IROUTER_SPI_MODE_ANY;
+    return aff;
+}
+
+/*
+ * - needs to be called with gic.lock held
+ * - needs to be called with a valid cpu_mask, ie each cpu in the mask has
+ * already called gic_cpu_init
+ */
+static void gicv3_set_irq_property(unsigned int irq, bool_t level,
+                                   const cpumask_t *cpu_mask,
+                                   unsigned int priority)
+{
+    uint32_t cfg, edgebit;
+    u64 affinity;
+    unsigned int cpu = gicv3_mask_cpu(cpu_mask);
+
+
+    /* Set edge / level */
+    if ( irq < NR_GIC_SGI )
+        /* SGI's are always edge-triggered not need to call GICD_ICFGR0 */
+        cfg = readl_relaxed(GICD_RDIST_SGI_BASE + GICR_ICFGR0);
+    else if ( irq < NR_GIC_LOCAL_IRQS )
+        cfg = readl_relaxed(GICD_RDIST_SGI_BASE + GICR_ICFGR1);
+    else
+        cfg = readl_relaxed(GICD + GICD_ICFGR + (irq / 16) * 4);
+
+    edgebit = 2u << (2 * (irq % 16));
+    if ( level )
+        cfg &= ~edgebit;
+    else
+        cfg |= edgebit;
+
+    if ( irq < NR_GIC_SGI )
+       writel_relaxed(cfg, GICD_RDIST_SGI_BASE + GICR_ICFGR0);
+    else if ( irq < NR_GIC_LOCAL_IRQS )
+       writel_relaxed(cfg, GICD_RDIST_SGI_BASE + GICR_ICFGR1);
+    else
+       writel_relaxed(cfg, GICD + GICD_ICFGR + (irq / 16) * 4);
+
+    affinity = gic_mpidr_to_affinity(cpu_logical_map(cpu));
+    if ( irq >= NR_GIC_LOCAL_IRQS )
+        writeq_relaxed(affinity, (GICD + GICD_IROUTER + irq * 8));
+
+    /* Set priority */
+    if ( irq < NR_GIC_LOCAL_IRQS )
+    {
+        writeb_relaxed(priority, GICD_RDIST_SGI_BASE + GICR_IPRIORITYR0 + irq);
+    }
+    else 
+    {
+        writeb_relaxed(priority, GICD + GICD_IPRIORITYR + irq);
+    }
+}
+
+static void __init gicv3_dist_init(void)
+{
+    uint32_t type;
+    uint32_t priority;
+    u64 affinity;
+    int i;
+
+    /* Disable the distributor */
+    writel_relaxed(0, GICD + GICD_CTLR);
+
+    type = readl_relaxed(GICD + GICD_TYPER);
+    gic.lines = 32 * ((type & GICD_TYPE_LINES) + 1);
+
+    gic_ops.nr_lines = gic.lines;
+
+    printk("GIC: %d lines, (IID %8.8x).\n",
+           gic.lines, readl_relaxed(GICD + GICD_IIDR));
+
+    /* Default all global IRQs to level, active low */
+    for ( i = NR_GIC_LOCAL_IRQS; i < gic.lines; i += 16 )
+        writel_relaxed(0, GICD + GICD_ICFGR + (i / 16) * 4);
+
+    /* Default priority for global interrupts */
+    for ( i = NR_GIC_LOCAL_IRQS; i < gic.lines; i += 4 )
+    {
+        priority = (GIC_PRI_IRQ << 24 | GIC_PRI_IRQ << 16 |
+                    GIC_PRI_IRQ << 8 | GIC_PRI_IRQ);
+        writel_relaxed(priority, GICD + GICD_IPRIORITYR + (i / 4) * 4);
+    }
+
+    /* Disable all global interrupts */
+    for ( i = NR_GIC_LOCAL_IRQS; i < gic.lines; i += 32 )
+        writel_relaxed(0xffffffff, GICD + GICD_ICENABLER + (i / 32) * 4);
+
+    gicv3_dist_wait_for_rwp();
+
+    /* Turn on the distributor */
+    writel_relaxed(GICD_CTL_ENABLE | GICD_CTLR_ARE_NS |
+                GICD_CTLR_ENABLE_G1A | GICD_CTLR_ENABLE_G1, GICD + GICD_CTLR);
+ 
+    /* Route all global IRQs to this CPU */
+    affinity = gic_mpidr_to_affinity(cpu_logical_map(smp_processor_id()));
+    for ( i = NR_GIC_LOCAL_IRQS; i < gic.lines; i++ )
+        writeq_relaxed(affinity, GICD + GICD_IROUTER + i * 8);
+}
+
+static void gicv3_enable_redist(void)
+{
+    u32 val;
+    /* Wait for 1s */
+    u32 count = 1000000;
+
+    /* Wake up this CPU redistributor */
+    val = readl_relaxed(GICD_RDIST_BASE + GICR_WAKER);
+    val &= ~GICR_WAKER_ProcessorSleep;
+    writel_relaxed(val, GICD_RDIST_BASE + GICR_WAKER);
+
+    do {
+         val = readl_relaxed(GICD_RDIST_BASE + GICR_WAKER);
+         if ( !(val & GICR_WAKER_ChildrenAsleep) )
+           break;
+         cpu_relax();
+         udelay(1);
+    } while ( count-- );
+
+    if ( !count )
+        gdprintk(XENLOG_WARNING, "Redist enable RWP timeout\n");
+}
+
+static int __init gicv3_populate_rdist(void)
+{
+    u64 mpidr = cpu_logical_map(smp_processor_id());
+    u64 typer;
+    uint32_t aff;
+    int i;
+    uint32_t reg;
+
+    aff = (MPIDR_AFFINITY_LEVEL(mpidr, 3) << 24 |
+           MPIDR_AFFINITY_LEVEL(mpidr, 2) << 16 |
+           MPIDR_AFFINITY_LEVEL(mpidr, 1) << 8 |
+           MPIDR_AFFINITY_LEVEL(mpidr, 0));
+
+    for ( i = 0; i < gic.rdist_count; i++ )
+    {
+        void __iomem *ptr = gic.rdist_regions[i].map_rdist_base;
+
+        reg = readl_relaxed(ptr + GICR_PIDR2);
+        if ( (reg & GICR_PIDR2_ARCH_MASK) != GICR_PIDR2_GICV3 ) {
+            dprintk(XENLOG_WARNING, "No redistributor present @%"PRIpaddr"\n",
+                   (u64)ptr);
+            break;
+        }
+
+        do {
+            typer = readq_relaxed(ptr + GICR_TYPER);
+            if ( (typer >> 32) == aff )
+            {
+                this_cpu(rbase) = ptr;
+                printk("CPU%d: Found redistributor in region %d\n",
+                           smp_processor_id(), i);
+                return 0;
+            }
+            if ( gic.rdist_stride ) {
+                ptr += gic.rdist_stride;
+            } else {
+                ptr += SZ_64K * 2; /* Skip RD_base + SGI_base */
+                if ( typer & GICR_TYPER_VLPIS )
+                    ptr += SZ_64K * 2; /* Skip VLPI_base + reserved page */
+            }
+        } while ( !(typer & GICR_TYPER_LAST) );
+    }
+
+    dprintk(XENLOG_WARNING, "CPU%d: mpidr %"PRIpaddr" has no 
re-distributor!\n",
+                  smp_processor_id(), mpidr);
+    return -ENODEV;
+}
+
+static void __cpuinit gicv3_cpu_init(void)
+{
+    int i;
+    uint32_t priority;
+
+    /* Register ourselves with the rest of the world */
+    if ( gicv3_populate_rdist() )
+        return;
+
+    gicv3_enable_redist();
+
+    /* Set priority on PPI and SGI interrupts */
+    priority = (GIC_PRI_IPI << 24 | GIC_PRI_IPI << 16 | GIC_PRI_IPI << 8 |
+                GIC_PRI_IPI);
+    for (i = 0; i < NR_GIC_SGI; i += 4)
+        writel_relaxed(priority,
+                GICD_RDIST_SGI_BASE + GICR_IPRIORITYR0 + (i / 4) * 4);
+
+    priority = (GIC_PRI_IRQ << 24 | GIC_PRI_IRQ << 16 | GIC_PRI_IRQ << 8 |
+                GIC_PRI_IRQ);
+    for (i = NR_GIC_SGI; i < NR_GIC_LOCAL_IRQS; i += 4)
+        writel_relaxed(priority,
+                GICD_RDIST_SGI_BASE + GICR_IPRIORITYR0 + (i / 4) * 4);
+
+    /*
+     * Disable all PPI interrupts, ensure all SGI interrupts are
+     * enabled.
+     */
+    writel_relaxed(0xffff0000, GICD_RDIST_SGI_BASE + GICR_ICENABLER0);
+    writel_relaxed(0x0000ffff, GICD_RDIST_SGI_BASE + GICR_ISENABLER0);
+
+    gicv3_redist_wait_for_rwp();
+
+    /* Enable system registers */
+    gicv3_enable_sre();
+
+    WRITE_SYSREG32(0, ICC_BPR1_EL1);
+    /* Set priority mask register */
+    WRITE_SYSREG32(DEFAULT_PMR_VALUE, ICC_PMR_EL1);
+
+    /* EOI drops priority too (mode 0) */
+    WRITE_SYSREG32(GICC_CTLR_EL1_EOImode_drop, ICC_CTLR_EL1);
+
+    /* Enable Group1 interrupts */
+    WRITE_SYSREG32(1, ICC_IGRPEN1_EL1);
+}
+
+static void gicv3_cpu_disable(void)
+{
+    WRITE_SYSREG32(0, ICC_CTLR_EL1);
+}
+
+static void __cpuinit gicv3_hyp_init(void)
+{
+    uint32_t vtr;
+
+    vtr = READ_SYSREG32(ICH_VTR_EL2);
+    nr_lrs  = (vtr & GICH_VTR_NRLRGS) + 1;
+    nr_priorities = ((vtr >> GICH_VTR_PRIBITS_SHIFT) &
+                    GICH_VTR_PRIBITS_MASK) + 1;
+
+    gic_ops.nr_lrs = nr_lrs;
+
+    WRITE_SYSREG32(GICH_VMCR_EOI | GICH_VMCR_VENG1, ICH_VMCR_EL2);
+    WRITE_SYSREG32(GICH_HCR_EN, ICH_HCR_EL2);
+
+    update_cpu_lr_mask();
+    vtr = READ_SYSREG32(ICH_HCR_EL2);
+}
+
+/* Set up the per-CPU parts of the GIC for a secondary CPU */
+static void gicv3_secondary_cpu_init(void)
+{
+    gicv3_cpu_init();
+    gicv3_hyp_init();
+}
+
+static void __cpuinit gicv3_hyp_disable(void)
+{
+    uint32_t vtr;
+    vtr = READ_SYSREG32(ICH_HCR_EL2);
+    vtr &= ~0x1;
+    WRITE_SYSREG32( vtr, ICH_HCR_EL2);
+}
+
+static u16 gicv3_compute_target_list(int *base_cpu, const struct cpumask *mask,
+                                   u64 cluster_id)
+{
+    int cpu = *base_cpu;
+    u64 mpidr = cpu_logical_map(cpu);
+    u16 tlist = 0;
+
+    while ( cpu < nr_cpu_ids )
+    {
+        /*
+         * If we ever get a cluster of more than 16 CPUs, just
+         * scream and skip that CPU.
+         */
+        if ( (mpidr & 0xff) >= 16 )
+        {
+            dprintk(XENLOG_WARNING, "Cluster more than 16's cpus\n");
+            goto out;
+        }
+        tlist |= 1 << (mpidr & 0xf);
+
+        cpu = cpumask_next(cpu, mask);
+        if ( cpu == nr_cpu_ids )
+        {
+            cpu--;
+            goto out;
+        }
+
+        mpidr = cpu_logical_map(cpu);
+        if ( cluster_id != (mpidr & ~0xffUL) ) {
+            cpu--;
+            goto out;
+        }
+    }
+out:
+    *base_cpu = cpu;
+    return tlist;
+}
+
+static void send_sgi(u64 cluster_id, u16 tlist, unsigned int irq)
+{
+    u64 val;
+
+    val = (MPIDR_AFFINITY_LEVEL(cluster_id, 3) << 48        |
+           MPIDR_AFFINITY_LEVEL(cluster_id, 2) << 32        |
+           irq << 24                                        |
+           MPIDR_AFFINITY_LEVEL(cluster_id, 1) << 16        |
+           tlist);
+
+    WRITE_SYSREG(val, ICC_SGI1R_EL1);   
+}
+
+static void gicv3_send_sgi(const cpumask_t *cpumask, enum gic_sgi sgi,
+            uint8_t mode)
+{
+    int cpu = 0;
+
+    dsb();
+
+    for_each_cpu(cpu, cpumask)
+    {
+        u64 cluster_id = cpu_logical_map(cpu) & ~0xffUL;
+        u16 tlist;
+
+        tlist = gicv3_compute_target_list(&cpu, cpumask, cluster_id);
+        send_sgi(cluster_id, tlist, sgi);
+    }
+}
+
+/* Shut down the per-CPU GIC interface */
+static void gicv3_disable_interface(void)
+{
+    ASSERT(!local_irq_is_enabled());
+
+    gicv3_cpu_disable();
+    gicv3_hyp_disable();
+}
+
+static void gicv3_update_lr(int lr, struct pending_irq *p, unsigned int state)
+{
+    u64 grp = GICH_LR_GRP1;
+    u64 val = 0;
+
+    BUG_ON(lr >= nr_lrs);
+    BUG_ON(lr < 0);
+
+    val =  ((((u64)state) & 0x3) << GICH_LR_STATE_SHIFT) | grp |
+        ((((u64)p->priority) & 0xff) << GICH_LR_PRIORITY_SHIFT) |
+        (((u64)p->irq & GICH_LR_VIRTUAL_MASK) << GICH_LR_VIRTUAL_SHIFT);
+
+   if ( p->desc != NULL )
+       val |= GICH_LR_HW |
+         (((u64) p->desc->irq & GICH_LR_PHYSICAL_MASK) << 
GICH_LR_PHYSICAL_SHIFT);
+
+    gich_write_lr(lr, val);
+}
+
+static void gicv3_clear_lr(int lr)
+{
+    gich_write_lr(lr, 0);
+}
+
+static void gicv3_read_lr(int lr, struct gic_lr *lr_reg)
+{
+    u64 lrv;
+    lrv = gich_read_lr(lr);
+    lr_reg->pirq = (lrv >> GICH_LR_PHYSICAL_SHIFT) & GICH_LR_PHYSICAL_MASK;
+    lr_reg->virq = (lrv >> GICH_LR_VIRTUAL_SHIFT) & GICH_LR_VIRTUAL_MASK; 
+    lr_reg->priority = (lrv >> GICH_LR_PRIORITY_SHIFT) & GICH_LR_PRIORITY_MASK;
+    lr_reg->state    = (lrv >> GICH_LR_STATE_SHIFT) & GICH_LR_STATE_MASK;
+    lr_reg->hw_status = (lrv >> GICH_LR_HW_SHIFT) & GICH_LR_HW_MASK;
+    lr_reg->grp = (lrv >> GICH_LR_GRP_SHIFT) & GICH_LR_GRP_MASK;
+}
+
+static void gicv3_write_lr(int lr_reg, struct gic_lr *lr)
+{
+    u64 lrv = 0;
+    lrv = ( ((u64)(lr->pirq & GICH_LR_PHYSICAL_MASK) << 
GICH_LR_PHYSICAL_SHIFT) |
+        ((u64)(lr->virq & GICH_LR_VIRTUAL_MASK) << GICH_LR_VIRTUAL_SHIFT) |
+        ((u64)(lr->priority & GICH_LR_PRIORITY_MASK) << 
GICH_LR_PRIORITY_SHIFT) |
+        ((u64)(lr->state & GICH_LR_STATE_MASK) << GICH_LR_STATE_SHIFT) |
+        ((u64)(lr->hw_status & GICH_LR_HW_MASK)  << GICH_LR_HW_SHIFT)  |
+        ((u64)(lr->grp & GICH_LR_GRP_MASK) << GICH_LR_GRP_SHIFT) );
+    gich_write_lr(lr_reg, lrv);
+}
+
+int gicv_v3_init(struct domain *d)
+{
+    int i;
+    /*
+     * Domain 0 gets the hardware address.
+     * Guests get the virtual platform layout.
+     */
+    if ( d->domain_id == 0 )
+    {
+        d->arch.vgic.dbase = gic.dbase;
+        d->arch.vgic.dbase_size = gic.dbase_size;
+        for ( i = 0; i < gic.rdist_count; i++ )
+        {
+            d->arch.vgic.rbase[i] = gic.rdist_regions[i].rdist_base;
+            d->arch.vgic.rbase_size[i] = gic.rdist_regions[i].rdist_base_size;
+        }
+        d->arch.vgic.rdist_stride = gic.rdist_stride;
+        d->arch.vgic.rdist_count = gic.rdist_count;
+    }
+    else
+    {
+        d->arch.vgic.dbase = GUEST_GICD_BASE;
+    }
+
+    d->arch.vgic.nr_lines = 0;
+    return 0;
+}
+
+static struct dt_irq * gicv3_maintenance_irq(void)
+{
+    return &gic.maintenance;
+}
+
+static void gicv3_hcr_status(uint32_t flag, bool_t status)
+{
+    if ( status )
+      WRITE_SYSREG32((READ_SYSREG32(ICH_HCR_EL2) | flag), ICH_HCR_EL2);
+    else
+      WRITE_SYSREG32((READ_SYSREG32(ICH_HCR_EL2) & (~flag)), ICH_HCR_EL2);
+}
+
+static unsigned int gicv3_read_vmcr_priority(void)
+{
+   return ((READ_SYSREG32(ICH_VMCR_EL2) >> GICH_VMCR_PRIORITY_SHIFT) &
+            GICH_VMCR_PRIORITY_MASK);
+}
+
+static hw_irq_controller irq_ops = {
+        .enable   = gicv3_enable_irq,
+        .disable  = gicv3_disable_irq,
+        .end      = gicv3_eoi_irq,
+};
+
+static struct gic_hw_operations gic_ops = {
+    .get_maintenance_irq = gicv3_maintenance_irq,
+    .save_state          = gicv3_save_state,
+    .restore_state       = gicv3_restore_state,
+    .dump_state          = gicv3_dump_state,
+    .gicv_setup          = gicv_v3_init,
+    .gic_irq_ops         = &irq_ops,
+    .deactivate_irq      = gicv3_dir_irq,
+    .ack_irq             = gicv3_ack_irq,
+    .set_irq_property    = gicv3_set_irq_property,
+    .send_sgi            = gicv3_send_sgi,
+    .disable_interface   = gicv3_disable_interface,
+    .update_lr           = gicv3_update_lr,
+    .update_hcr_status   = gicv3_hcr_status,
+    .clear_lr            = gicv3_clear_lr,
+    .read_lr             = gicv3_read_lr,
+    .write_lr            = gicv3_write_lr,
+    .read_vmcr_priority  = gicv3_read_vmcr_priority,
+    .secondary_init      = gicv3_secondary_cpu_init,
+};
+
+/* Set up the GIC */
+static int __init gicv3_init(struct dt_device_node *node,
+                                       const void *data)
+{
+    struct rdist_region *rdist_regs;
+    int res, i;
+    uint32_t reg;
+
+    dt_device_set_used_by(node, DOMID_XEN);
+
+    res = dt_device_get_address(node, 0, &gic.dbase, &gic.dbase_size);
+    if ( res || !gic.dbase  || (gic.dbase & ~PAGE_MASK) ||
+       (gic.dbase_size & ~PAGE_MASK) )
+        panic("GIC: Cannot find a valid address for the distributor");
+
+    gic.map_dbase = ioremap_nocache(gic.dbase, gic.dbase_size);
+    if ( !gic.map_dbase )
+        panic("Failed to ioremap for GIC distributor\n");
+
+    reg = readl_relaxed(GICD + GICD_PIDR2);
+    if ( (reg & GICD_PIDR2_ARCH_MASK) != GICD_PIDR2_GICV3 )
+        panic("GIC: no distributor detected, giving up\n"); 
+
+    gic_ops.hw_version = GIC_V3;
+ 
+    if ( !dt_property_read_u32(node, "#redistributor-regions",
+                &gic.rdist_count) )
+        gic.rdist_count = 1;
+
+    if ( gic.rdist_count > MAX_RDIST_COUNT )
+        panic("GIC: Number of redistributor regions is more than \
+               MAX_RDIST_COUNT (Increase MAX_RDIST_COUNT!!)\n");
+
+    rdist_regs = xzalloc_array(struct rdist_region, gic.rdist_count);
+    if ( !rdist_regs )
+        panic("GIC: no distributor detected, giving up\n");
+
+    for ( i = 0; i < gic.rdist_count; i++ ) {
+        u64 rdist_base, rdist_size;
+
+        res = dt_device_get_address(node, 1 + i, &rdist_base, &rdist_size);
+        if ( res || !rdist_base)
+            panic("No rdist base found\n");
+
+        rdist_regs[i].rdist_base = rdist_base;
+        rdist_regs[i].rdist_base_size = rdist_size;
+    }
+
+    if ( !dt_property_read_u32(node, "redistributor-stride", 
&gic.rdist_stride) )
+        gic.rdist_stride = 0x0;
+
+    gic.rdist_regions= rdist_regs;
+ 
+    res = dt_device_get_irq(node, 0, &gic.maintenance);
+    if ( res )
+        panic("GIC: Cannot find the maintenance IRQ");
+
+    /* Set the GIC as the primary interrupt controller */
+    dt_interrupt_controller = node;
+
+    for ( i = 0; i < gic.rdist_count; i++ ) {
+        /* map dbase & rdist regions */
+        gic.rdist_regions[i].map_rdist_base =
+                ioremap_nocache(gic.rdist_regions[i].rdist_base,
+                          gic.rdist_regions[i].rdist_base_size);
+
+        if ( !gic.rdist_regions[i].map_rdist_base )
+            panic("Failed to ioremap for GIC redistributor\n");
+    }
+
+    printk("GIC initialization:\n"
+              "        gic_dist_addr=%"PRIpaddr"\n"
+              "        gic_dist_size=%"PRIpaddr"\n"
+              "        gic_dist_mapaddr=%"PRIpaddr"\n"
+              "        gic_rdist_regions=%d\n"
+              "        gic_rdist_stride=%x\n"
+              "        gic_rdist_base=%"PRIpaddr"\n"
+              "        gic_rdist_base_size=%"PRIpaddr"\n"
+              "        gic_rdist_base_mapaddr=%"PRIpaddr"\n"
+              "        gic_maintenance_irq=%u\n",
+              gic.dbase, gic.dbase_size, (u64)gic.map_dbase, gic.rdist_count,
+              gic.rdist_stride, gic.rdist_regions[0].rdist_base,
+              gic.rdist_regions[0].rdist_base_size,
+              (u64)gic.rdist_regions[0].map_rdist_base, gic.maintenance.irq);
+
+    gicv3_dist_init();
+    gicv3_cpu_init();
+    gicv3_hyp_init();
+
+    /* Register hw ops*/
+    register_gic_ops(&gic_ops);
+    return 0;
+}
+
+static const char * const gicv3_dt_compat[] __initconst =
+{
+    "arm,gic-v3",
+    NULL
+};
+
+DT_DEVICE_START(gicv3, "GIC", DEVICE_GIC)
+        .compatible = gicv3_dt_compat,
+        .init = gicv3_init,
+DT_DEVICE_END
+
+/*
+ * Local variables:
+ * mode: C
+ * c-file-style: "BSD"
+ * c-basic-offset: 4
+ * indent-tabs-mode: nil
+ * End:
+ */
diff --git a/xen/include/asm-arm/arm64/processor.h 
b/xen/include/asm-arm/arm64/processor.h
index 5bf0867..3ecdc70 100644
--- a/xen/include/asm-arm/arm64/processor.h
+++ b/xen/include/asm-arm/arm64/processor.h
@@ -3,6 +3,20 @@
 
 #ifndef __ASSEMBLY__
 
+/*
+ * Macros to extract affinity level. picked from kernel
+ */
+
+#define MPIDR_LEVEL_BITS_SHIFT  3
+#define MPIDR_LEVEL_BITS        (1 << MPIDR_LEVEL_BITS_SHIFT)
+#define MPIDR_LEVEL_MASK        ((1 << MPIDR_LEVEL_BITS) - 1)
+
+#define MPIDR_LEVEL_SHIFT(level) \
+         (((1 << level) >> 1) << MPIDR_LEVEL_BITS_SHIFT)
+
+#define MPIDR_AFFINITY_LEVEL(mpidr, level) \
+         ((mpidr >> MPIDR_LEVEL_SHIFT(level)) & MPIDR_LEVEL_MASK)
+
 /* Anonymous union includes both 32- and 64-bit names (e.g., r0/x0). */
 
 #define __DECL_REG(n64, n32) union {            \
diff --git a/xen/include/asm-arm/domain.h b/xen/include/asm-arm/domain.h
index ccd9640..c27085b 100644
--- a/xen/include/asm-arm/domain.h
+++ b/xen/include/asm-arm/domain.h
@@ -151,6 +151,12 @@ struct arch_domain
         /* Base address for guest GIC */
         paddr_t dbase; /* Distributor base address */
         paddr_t cbase; /* CPU base address */
+        /* GIC V3 addressing */
+        paddr_t dbase_size; /* Distributor base size */
+        paddr_t rbase[MAX_RDIST_COUNT];      /* Re-Distributor base address */
+        paddr_t rbase_size[MAX_RDIST_COUNT]; /* Re-Distributor size */
+        uint32_t rdist_stride;               /* Re-Distributor stride */
+        int rdist_count;                     /* No. of Re-Distributors */
     } vgic;
 
     struct vuart {
diff --git a/xen/include/asm-arm/gic.h b/xen/include/asm-arm/gic.h
index 7489684..3c37120 100644
--- a/xen/include/asm-arm/gic.h
+++ b/xen/include/asm-arm/gic.h
@@ -18,6 +18,12 @@
 #ifndef __ASM_ARM_GIC_H__
 #define __ASM_ARM_GIC_H__
 
+#define SZ_64K  0x00010000
+
+#define NR_GIC_LOCAL_IRQS  NR_LOCAL_IRQS
+#define NR_GIC_SGI         16
+#define MAX_RDIST_COUNT    4
+
 /*
  * The minimum GICC_BPR is required to be in the range 0-3. We set
  * GICC_BPR to 0 but we must expect that it might be 3. This means we
@@ -62,6 +68,13 @@
 #define DT_MATCH_GIC    DT_MATCH_COMPATIBLE("arm,cortex-a15-gic"), \
                         DT_MATCH_COMPATIBLE("arm,cortex-a7-gic")
 
+struct gic_v3 {
+    uint32_t hcr, vmcr;
+    uint32_t apr0[4];
+    uint32_t apr1[4];
+    uint64_t lr[16];
+};
+
 struct gic_v2 {
     uint32_t hcr, vmcr;
     uint32_t apr;
@@ -70,6 +83,7 @@ struct gic_v2 {
 
 union gic_state_data {
     struct gic_v2 v2;
+    struct gic_v3 v3;
 };
 
 /*
@@ -146,6 +160,7 @@ void gic_clear_lrs(struct vcpu *v);
 
 enum gic_version {
     GIC_V2 = 2,
+    GIC_V3 = 3,
 };
 
 struct gic_hw_operations {
diff --git a/xen/include/asm-arm/gic_v3_defs.h 
b/xen/include/asm-arm/gic_v3_defs.h
new file mode 100644
index 0000000..578832b
--- /dev/null
+++ b/xen/include/asm-arm/gic_v3_defs.h
@@ -0,0 +1,198 @@
+/*
+ * ARM Generic Interrupt Controller v3 definitions
+ *
+ * Vijaya Kumar K <vijaya.kumar@xxxxxxxxxxxxxxxxxx>
+ * Copyright (c) 2014 Cavium Inc.
+ *
+ * This program is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * GNU General Public License for more details.
+ */
+
+#ifndef __ASM_ARM_GIC_V3_DEFS_H__
+#define __ASM_ARM_GIC_V3_DEFS_H__
+
+#define GICD_CTLR       (0x000)
+#define GICD_TYPER      (0x004)
+#define GICD_IIDR       (0x008)
+#define GICD_STATUSR    (0x010)
+#define GICD_SETSPI_NSR (0x040)
+#define GICD_CLRSPI_NSR (0x048)
+#define GICD_SETSPI_SR  (0x050)
+#define GICD_CLRSPI_SR  (0x058)
+#define GICD_IGROUPR    (0x080)
+#define GICD_IGROUPRN   (0x0FC)
+#define GICD_ISENABLER  (0x100)
+#define GICD_ISENABLERN (0x17C)
+#define GICD_ICENABLER  (0x180)
+#define GICD_ICENABLERN (0x1fC)
+#define GICD_ISPENDR    (0x200)
+#define GICD_ISPENDRN   (0x27C)
+#define GICD_ICPENDR    (0x280)
+#define GICD_ICPENDRN   (0x2FC)
+#define GICD_ISACTIVER  (0x300)
+#define GICD_ISACTIVERN (0x37C)
+#define GICD_ICACTIVER  (0x380)
+#define GICD_ICACTIVERN (0x3FC)
+#define GICD_IPRIORITYR (0x400)
+#define GICD_IPRIORITYRN (0x7F8)
+#define GICD_ICFGR      (0xC00)
+#define GICD_ICFGRN     (0xCFC)
+#define GICD_NSACR      (0xE00)
+#define GICD_NSACRN     (0xEFC)
+#define GICD_SGIR       (0xF00)
+#define GICD_CPENDSGIR  (0xF10)
+#define GICD_CPENDSGIRN (0xF1C)
+#define GICD_SPENDSGIR  (0xF20)
+#define GICD_SPENDSGIRN (0xF2C)
+#define GICD_IROUTER    (0x6000)
+#define GICD_IROUTERN   (0x7FF8)
+#define GICD_PIDR0      (0xFFE0)
+#define GICD_PIDR2      (0xFFE8)
+#define GICD_PIDR7      (0xFFDC)
+
+#define GICD_SGI_TARGET_LIST_SHIFT   (24)
+#define GICD_SGI_TARGET_LIST_MASK    (0x3UL << GICD_SGI_TARGET_LIST_SHIFT)
+#define GICD_SGI_TARGET_LIST         (0UL<<GICD_SGI_TARGET_LIST_SHIFT)
+#define GICD_SGI_TARGET_OTHERS       (1UL<<GICD_SGI_TARGET_LIST_SHIFT)
+#define GICD_SGI_TARGET_SELF         (2UL<<GICD_SGI_TARGET_LIST_SHIFT)
+#define GICD_SGI_TARGET_SHIFT        (16)
+#define GICD_SGI_TARGET_MASK         (0xFFUL<<GICD_SGI_TARGET_SHIFT)
+#define GICD_SGI_GROUP1              (1UL<<15)
+#define GICD_SGI_INTID_MASK          (0xFUL)
+
+#define GICC_SRE_EL2_SRE             (1UL << 0)
+#define GICC_SRE_EL2_DFB             (1UL << 1)
+#define GICC_SRE_EL2_DIB             (1UL << 2)
+#define GICC_SRE_EL2_ENEL1           (1UL << 3)
+
+#define GICD_CTLR_RWP                (1UL << 31)
+#define GICD_CTLR_ARE_NS             (1U << 4)
+#define GICD_CTLR_ENABLE_G1A         (1U << 1)
+#define GICD_CTLR_ENABLE_G1          (1U << 0)
+#define GICD_IROUTER_SPI_MODE_ONE    (0UL << 31)
+#define GICD_IROUTER_SPI_MODE_ANY    (1UL << 31)
+
+#define GICH_HCR_EN                  (1 << 0)
+
+#define GICC_CTLR_EL1_EOImode_drop_dir  (0U << 1)
+#define GICC_CTLR_EL1_EOImode_drop      (1U << 1)
+
+#define GICR_WAKER_ProcessorSleep       (1U << 1)
+#define GICR_WAKER_ChildrenAsleep       (1U << 2)
+
+#define GICD_PIDR0_GICV3              (0x92)
+#define GICR_PIDR0_GICV3              (0x93)
+#define GICD_PIDR2_GICV3              (0x30)
+#define GICR_PIDR2_GICV3              GICD_PIDR2_GICV3
+#define GICD_PIDR2_ARCH_MASK          (0xf0)
+#define GICR_PIDR2_ARCH_MASK          GICD_PIDR2_ARCH_MASK
+#define GICR_SYNCR_NOT_BUSY           1
+
+#define GICR_CTLR       (0x0000)
+#define GICR_IIDR       (0x0004)
+#define GICR_TYPER      (0x0008)
+#define GICR_STATUSR    (0x0010)
+#define GICR_WAKER      (0x0014)
+#define GICR_SETLPIR    (0x0040)
+#define GICR_CLRLPIR    (0x0048)
+#define GICR_PROPBASER  (0x0070)
+#define GICR_PENDBASER  (0x0078)
+#define GICR_INVLPIR    (0x00A0)
+#define GICR_INVALLR    (0x00B0)
+#define GICR_SYNCR      (0x00C0)
+#define GICR_MOVLPIR    (0x100)
+#define GICR_MOVALLR    (0x0110)
+#define GICR_PIDR0      GICD_PIDR0
+#define GICR_PIDR2      GICD_PIDR2
+#define GICR_PIDR7      GICD_PIDR7
+
+/* GICR for SGI's & PPI's */
+
+#define GICR_IGROUPR0    (0x0080)
+#define GICR_IGRPMODR0   (0x0F80)
+#define GICR_ISENABLER0  (0x0100)
+#define GICR_ICENABLER0  (0x0180)
+#define GICR_ISPENDR0    (0x0200)
+#define GICR_ICPENDR0    (0x0280)
+#define GICR_ISACTIVER0  (0x0300)
+#define GICR_ICACTIVER0  (0x0380)
+#define GICR_IPRIORITYR0 (0x0400)
+#define GICR_IPRIORITYR7 (0x041C)
+#define GICR_ICFGR0      (0x0C00)
+#define GICR_ICFGR1      (0x0C04)
+#define GICR_NSACR       (0x0E00)
+
+#define GICR_TYPER_PLPIS                (1U << 0)
+#define GICR_TYPER_VLPIS                (1U << 1)
+#define GICR_TYPER_LAST                 (1U << 4)
+
+/* Register bits */
+#define GICD_CTL_ENABLE 0x1
+
+#define GICD_TYPE_LINES 0x01f
+#define GICD_TYPE_CPUS  0x0e0
+#define GICD_TYPE_SEC   0x400
+
+#define GICC_CTL_ENABLE 0x1
+#define GICC_CTL_EOI    (0x1 << 9)
+
+#define GICC_IA_IRQ       0x03ff
+#define GICC_IA_CPU_MASK  0x1c00
+#define GICC_IA_CPU_SHIFT 10
+
+#define DEFAULT_PMR_VALUE 0xff
+
+#define GICH_HCR_TC       (1 << 10)
+
+#define GICH_MISR_EOI     (1 << 0)
+#define GICH_MISR_U       (1 << 1)
+#define GICH_MISR_LRENP   (1 << 2)
+#define GICH_MISR_NP      (1 << 3)
+#define GICH_MISR_VGRP0E  (1 << 4)
+#define GICH_MISR_VGRP0D  (1 << 5)
+#define GICH_MISR_VGRP1E  (1 << 6)
+#define GICH_MISR_VGRP1D  (1 << 7)
+
+#define GICH_VMCR_EOI     (1 << 9)
+#define GICH_VMCR_VENG1    (1 << 1)
+
+#define GICH_LR_VIRTUAL_MASK    0xffff
+#define GICH_LR_VIRTUAL_SHIFT   0
+#define GICH_LR_PHYSICAL_MASK   0x3ff
+#define GICH_LR_PHYSICAL_SHIFT  32
+#define GICH_LR_STATE_MASK      0x3
+#define GICH_LR_STATE_SHIFT     62
+#define GICH_LR_PRIORITY_MASK   0xff
+#define GICH_LR_PRIORITY_SHIFT  48
+#define GICH_LR_HW_MASK         0x1
+#define GICH_LR_HW_SHIFT        61
+#define GICH_LR_GRP_MASK        0x1
+#define GICH_LR_GRP_SHIFT       60
+#define GICH_LR_MAINTENANCE_IRQ (1UL<<41)
+#define GICH_LR_GRP1            (1UL<<60)
+#define GICH_LR_HW              (1UL<<61)
+
+#define GICH_VTR_NRLRGS         0x3f
+#define GICH_VTR_PRIBITS_MASK   0x7
+#define GICH_VTR_PRIBITS_SHIFT  29
+
+#define GICH_VMCR_PRIORITY_MASK   0xff
+#define GICH_VMCR_PRIORITY_SHIFT  24
+
+#endif /* __ASM_ARM_GIC_V3_DEFS_H__ */
+
+/*
+ * Local variables:
+ * mode: C
+ * c-file-style: "BSD"
+ * c-basic-offset: 4
+ * indent-tabs-mode: nil
+ * End:
+ */
-- 
1.7.9.5


_______________________________________________
Xen-devel mailing list
Xen-devel@xxxxxxxxxxxxx
http://lists.xen.org/xen-devel


 


Rackspace

Lists.xenproject.org is hosted with RackSpace, monitoring our
servers 24x7x365 and backed by RackSpace's Fanatical Support®.