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

[Xen-devel] [PATCH v2 07/15] xen/arm: split gic driver into generic and gic-v2 driver



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

Existing GIC driver has both generic code and hw specific
code. Segregate GIC low level driver into gic-v2.c and
keep generic code in existing gic.c file

GIC v2 driver registers required functions
to generic GIC driver. This helps to plug in next version
of GIC drivers like GIC v3.

Signed-off-by: Vijaya Kumar K <Vijaya.Kumar@xxxxxxxxxxxxxxxxxx>
---
 xen/arch/arm/Makefile     |    2 +-
 xen/arch/arm/gic-v2.c     |  538 +++++++++++++++++++++++++++++++++++++++++++++
 xen/arch/arm/gic.c        |  492 +----------------------------------------
 xen/include/asm-arm/gic.h |    1 +
 4 files changed, 542 insertions(+), 491 deletions(-)

diff --git a/xen/arch/arm/Makefile b/xen/arch/arm/Makefile
index 63e0460..969ee52 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
+obj-y += gic.o gic-v2.o
 obj-y += io.o
 obj-y += irq.o
 obj-y += kernel.o
diff --git a/xen/arch/arm/gic-v2.c b/xen/arch/arm/gic-v2.c
new file mode 100644
index 0000000..e39099f
--- /dev/null
+++ b/xen/arch/arm/gic-v2.c
@@ -0,0 +1,538 @@
+/*
+ * xen/arch/arm/gic-v2.c
+ *
+ * ARM Generic Interrupt Controller support v2
+ *
+ * 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/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 <asm/p2m.h>
+#include <asm/domain.h>
+#include <asm/platform.h>
+
+#include <asm/gic_v2_defs.h>
+#include <asm/gic.h>
+
+/* Access to the GIC Distributor registers through the fixmap */
+#define GICD ((volatile uint32_t *) FIXMAP_ADDR(FIXMAP_GICD))
+#define GICC ((volatile uint32_t *) FIXMAP_ADDR(FIXMAP_GICC1))
+#define GICH ((volatile uint32_t *) FIXMAP_ADDR(FIXMAP_GICH))
+
+/* Global state */
+static struct {
+    paddr_t dbase;       /* Address of distributor registers */
+    paddr_t cbase;       /* Address of CPU interface registers */
+    paddr_t hbase;       /* Address of virtual interface registers */
+    paddr_t vbase;       /* Address of virtual cpu interface registers */
+    unsigned int lines;  /* Number of interrupts (SPIs + PPIs + SGIs) */
+    struct dt_irq maintenance; /* IRQ maintenance */
+    unsigned int cpus;
+} gic;
+
+static struct gic_hw_operations gic_ops;
+
+static uint8_t nr_lrs;
+
+/* The GIC mapping of CPU interfaces does not necessarily match the
+ * logical CPU numbering. Let's use mapping as returned by the GIC
+ * itself
+ */
+static DEFINE_PER_CPU(u8, gic_cpu_id);
+
+/* Maximum cpu interface per GIC */
+#define NR_GIC_CPU_IF 8
+
+static unsigned int gic_cpu_mask(const cpumask_t *cpumask)
+{
+    unsigned int cpu;
+    unsigned int mask = 0;
+    cpumask_t possible_mask;
+
+    cpumask_and(&possible_mask, cpumask, &cpu_possible_map);
+    for_each_cpu(cpu, &possible_mask)
+    {
+        ASSERT(cpu < NR_GIC_CPU_IF);
+        mask |= per_cpu(gic_cpu_id, cpu);
+    }
+
+    return mask;
+}
+
+static unsigned int gic_nr_lines(void)
+{
+    return gic.lines;
+}
+
+static unsigned int gic_nr_lrs(void)
+{
+    return nr_lrs;
+}
+
+static int gic_state_init(struct vcpu *v)
+{
+     v->arch.gic_state = xzalloc(struct gic_state_data);
+     if ( !v->arch.gic_state )
+        return -ENOMEM;
+     return 0;
+}
+
+static void 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_state->gic_lr[i] = GICH[GICH_LR + i];
+    v->arch.gic_state->gic_apr = GICH[GICH_APR];
+    v->arch.gic_state->gic_vmcr = GICH[GICH_VMCR];
+    /* Disable until next VCPU scheduled */
+    GICH[GICH_HCR] = 0;
+}
+
+static void restore_state(struct vcpu *v)
+{
+    int i;
+
+    for ( i = 0; i < nr_lrs; i++ )
+        GICH[GICH_LR + i] = v->arch.gic_state->gic_lr[i];
+    GICH[GICH_APR] = v->arch.gic_state->gic_apr;
+    GICH[GICH_VMCR] = v->arch.gic_state->gic_vmcr;
+    GICH[GICH_HCR] = GICH_HCR_EN;
+}
+
+static void gic_dump_state(struct vcpu *v)
+{
+    int i;
+    if ( v == current )
+    {
+        for ( i = 0; i < nr_lrs; i++ )
+            printk("   HW_LR[%d]=%x\n", i, GICH[GICH_LR + i]);
+    } else {
+        for ( i = 0; i < nr_lrs; i++ )
+            printk("   VCPU_LR[%d]=%x\n", i, v->arch.gic_state->gic_lr[i]);
+    }
+}
+
+static void gic_enable_irq(int irq)
+{
+    /* Enable routing */
+    GICD[GICD_ISENABLER + irq / 32] = (1u << (irq % 32));
+}
+
+static void gic_disable_irq(int irq)
+{
+    /* Disable routing */
+    GICD[GICD_ICENABLER + irq / 32] = (1u << (irq % 32));
+}
+
+static void gic_eoi_irq(int irq)
+{
+    /* Lower the priority */
+    GICC[GICC_EOIR] = irq;
+}
+
+static void gic_dir_irq(int irq)
+{
+    /* Deactivate */
+    GICC[GICC_DIR] = irq;
+}
+
+static unsigned int gic_ack_irq(void)
+{
+    return (GICC[GICC_IAR] & GICC_IA_IRQ);
+}
+
+/*
+ * - 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 gic_set_irq_property(unsigned int irq, bool_t level,
+                                   const cpumask_t *cpu_mask,
+                                   unsigned int priority)
+{
+    volatile unsigned char *bytereg;
+    uint32_t cfg, edgebit;
+    unsigned int mask = gic_cpu_mask(cpu_mask);
+
+    /* Set edge / level */
+    cfg = GICD[GICD_ICFGR + irq / 16];
+    edgebit = 2u << (2 * (irq % 16));
+    if ( level )
+        cfg &= ~edgebit;
+    else
+        cfg |= edgebit;
+    GICD[GICD_ICFGR + irq / 16] = cfg;
+
+    /* Set target CPU mask (RAZ/WI on uniprocessor) */
+    bytereg = (unsigned char *) (GICD + GICD_ITARGETSR);
+    bytereg[irq] = mask;
+
+    /* Set priority */
+    bytereg = (unsigned char *) (GICD + GICD_IPRIORITYR);
+    bytereg[irq] = priority;
+
+}
+
+static void __init gic_dist_init(void)
+{
+    uint32_t type;
+    uint32_t cpumask;
+    int i;
+
+    cpumask = GICD[GICD_ITARGETSR] & 0xff;
+    cpumask |= cpumask << 8;
+    cpumask |= cpumask << 16;
+
+    /* Disable the distributor */
+    GICD[GICD_CTLR] = 0;
+
+    type = GICD[GICD_TYPER];
+    gic.lines = 32 * ((type & GICD_TYPE_LINES) + 1);
+    gic.cpus = 1 + ((type & GICD_TYPE_CPUS) >> 5);
+    printk("GIC: %d lines, %d cpu%s%s (IID %8.8x).\n",
+           gic.lines, gic.cpus, (gic.cpus == 1) ? "" : "s",
+           (type & GICD_TYPE_SEC) ? ", secure" : "",
+           GICD[GICD_IIDR]);
+
+    /* Default all global IRQs to level, active low */
+    for ( i = 32; i < gic.lines; i += 16 )
+        GICD[GICD_ICFGR + i / 16] = 0x0;
+
+    /* Route all global IRQs to this CPU */
+    for ( i = 32; i < gic.lines; i += 4 )
+        GICD[GICD_ITARGETSR + i / 4] = cpumask;
+
+    /* Default priority for global interrupts */
+    for ( i = 32; i < gic.lines; i += 4 )
+        GICD[GICD_IPRIORITYR + i / 4] =
+            GIC_PRI_IRQ<<24 | GIC_PRI_IRQ<<16 | GIC_PRI_IRQ<<8 | GIC_PRI_IRQ;
+
+    /* Disable all global interrupts */
+    for ( i = 32; i < gic.lines; i += 32 )
+        GICD[GICD_ICENABLER + i / 32] = (uint32_t)~0ul;
+
+    /* Turn on the distributor */
+    GICD[GICD_CTLR] = GICD_CTL_ENABLE;
+}
+
+static void __cpuinit gic_cpu_init(void)
+{
+    int i;
+
+    this_cpu(gic_cpu_id) = GICD[GICD_ITARGETSR] & 0xff;
+
+    /* The first 32 interrupts (PPI and SGI) are banked per-cpu, so
+     * even though they are controlled with GICD registers, they must
+     * be set up here with the other per-cpu state. */
+    GICD[GICD_ICENABLER] = 0xffff0000; /* Disable all PPI */
+    GICD[GICD_ISENABLER] = 0x0000ffff; /* Enable all SGI */
+    /* Set SGI priorities */
+    for ( i = 0; i < 16; i += 4 )
+        GICD[GICD_IPRIORITYR + i / 4] =
+            GIC_PRI_IPI<<24 | GIC_PRI_IPI<<16 | GIC_PRI_IPI<<8 | GIC_PRI_IPI;
+    /* Set PPI priorities */
+    for ( i = 16; i < 32; i += 4 )
+        GICD[GICD_IPRIORITYR + i / 4] =
+            GIC_PRI_IRQ<<24 | GIC_PRI_IRQ<<16 | GIC_PRI_IRQ<<8 | GIC_PRI_IRQ;
+
+    /* Local settings: interface controller */
+    GICC[GICC_PMR] = 0xff;                /* Don't mask by priority */
+    GICC[GICC_BPR] = 0;                   /* Finest granularity of priority */
+    GICC[GICC_CTLR] = GICC_CTL_ENABLE|GICC_CTL_EOI;    /* Turn on delivery */
+}
+
+static void gic_cpu_disable(void)
+{
+    GICC[GICC_CTLR] = 0;
+}
+
+static void __cpuinit gic_hyp_init(void)
+{
+    uint32_t vtr;
+
+    vtr = GICH[GICH_VTR];
+    nr_lrs  = (vtr & GICH_VTR_NRLRGS) + 1;
+
+    GICH[GICH_MISR] = GICH_MISR_EOI;
+    update_cpu_lr_mask();
+}
+
+static void __cpuinit gic_hyp_disable(void)
+{
+    GICH[GICH_HCR] = 0;
+}
+
+/* Set up the GIC */
+void __init gicv2_init(void)
+{
+    static const struct dt_device_match gic_ids[] __initconst =
+    {
+        DT_MATCH_GIC,
+        { /* sentinel */ },
+    };
+    struct dt_device_node *node;
+    int res;
+
+    node = dt_find_interrupt_controller(gic_ids);
+    if ( !node )
+        panic("Unable to find compatible GIC in the device tree");
+
+    dt_device_set_used_by(node, DOMID_XEN);
+
+    res = dt_device_get_address(node, 0, &gic.dbase, NULL);
+    if ( res || !gic.dbase || (gic.dbase & ~PAGE_MASK) )
+        panic("GIC: Cannot find a valid address for the distributor");
+
+    res = dt_device_get_address(node, 1, &gic.cbase, NULL);
+    if ( res || !gic.cbase || (gic.cbase & ~PAGE_MASK) )
+        panic("GIC: Cannot find a valid address for the CPU");
+
+    res = dt_device_get_address(node, 2, &gic.hbase, NULL);
+    if ( res || !gic.hbase || (gic.hbase & ~PAGE_MASK) )
+        panic("GIC: Cannot find a valid address for the hypervisor");
+
+    res = dt_device_get_address(node, 3, &gic.vbase, NULL);
+    if ( res || !gic.vbase || (gic.vbase & ~PAGE_MASK) )
+        panic("GIC: Cannot find a valid address for the virtual CPU");
+
+    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;
+
+    /* TODO: Add check on distributor, cpu size */
+
+    printk("GIC initialization:\n"
+              "        gic_dist_addr=%"PRIpaddr"\n"
+              "        gic_cpu_addr=%"PRIpaddr"\n"
+              "        gic_hyp_addr=%"PRIpaddr"\n"
+              "        gic_vcpu_addr=%"PRIpaddr"\n"
+              "        gic_maintenance_irq=%u\n",
+              gic.dbase, gic.cbase, gic.hbase, gic.vbase,
+              gic.maintenance.irq);
+
+    if ( (gic.dbase & ~PAGE_MASK) || (gic.cbase & ~PAGE_MASK) ||
+         (gic.hbase & ~PAGE_MASK) || (gic.vbase & ~PAGE_MASK) )
+        panic("GIC interfaces not page aligned");
+
+    set_fixmap(FIXMAP_GICD, gic.dbase >> PAGE_SHIFT, DEV_SHARED);
+    BUILD_BUG_ON(FIXMAP_ADDR(FIXMAP_GICC1) !=
+                 FIXMAP_ADDR(FIXMAP_GICC2)-PAGE_SIZE);
+    set_fixmap(FIXMAP_GICC1, gic.cbase >> PAGE_SHIFT, DEV_SHARED);
+    if ( platform_has_quirk(PLATFORM_QUIRK_GIC_64K_STRIDE) )
+        set_fixmap(FIXMAP_GICC2, (gic.cbase >> PAGE_SHIFT) + 0x10, DEV_SHARED);
+    else
+        set_fixmap(FIXMAP_GICC2, (gic.cbase >> PAGE_SHIFT) + 0x1, DEV_SHARED);
+    set_fixmap(FIXMAP_GICH, gic.hbase >> PAGE_SHIFT, DEV_SHARED);
+
+    /* Global settings: interrupt distributor */
+
+    gic_dist_init();
+    gic_cpu_init();
+    gic_hyp_init();
+
+    register_gic_ops(&gic_ops);
+}
+
+static void gic_secondary_cpu_init(void)
+{
+    gic_cpu_init();
+    gic_hyp_init();
+}
+
+static struct dt_irq * gic_maintenance_irq(void)
+{
+    return &gic.maintenance;
+}
+
+static void gic_send_sgi(const cpumask_t *cpumask, enum gic_sgi sgi)
+{
+    unsigned int mask = 0;
+    cpumask_t online_mask;
+
+    ASSERT(sgi < 16); /* There are only 16 SGIs */
+
+    cpumask_and(&online_mask, cpumask, &cpu_online_map);
+    mask = gic_cpu_mask(&online_mask);
+
+    dsb(sy);
+
+    GICD[GICD_SGIR] = GICD_SGI_TARGET_LIST
+        | (mask<<GICD_SGI_TARGET_SHIFT)
+        | sgi;
+}
+
+/* Shut down the per-CPU GIC interface */
+static void gic_disable_interface(void)
+{
+    gic_cpu_disable();
+    gic_hyp_disable();
+}
+
+static void gic_update_lr(int lr, struct pending_irq *p, unsigned int state)
+{
+    int maintenance_int = GICH_LR_MAINTENANCE_IRQ;
+
+    BUG_ON(lr >= nr_lrs);
+    BUG_ON(lr < 0);
+    BUG_ON(state & ~(GICH_LR_STATE_MASK<<GICH_LR_STATE_SHIFT));
+
+    GICH[GICH_LR + lr] = ((state & 0x3) << GICH_LR_STATE_SHIFT) |
+        maintenance_int |
+        ((p->priority >> 3) << GICH_LR_PRIORITY_SHIFT) |
+        ((p->irq & GICH_LR_VIRTUAL_MASK) << GICH_LR_VIRTUAL_SHIFT);
+}
+
+static void gic_clear_lr(int lr)
+{
+    GICH[GICH_LR + lr] = 0;
+}
+
+static int gicv_init(struct domain *d)
+{
+    int ret;
+
+    /*
+     * 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.cbase = gic.cbase;
+    }
+    else
+    {
+        d->arch.vgic.dbase = GUEST_GICD_BASE;
+        d->arch.vgic.cbase = GUEST_GICC_BASE;
+    }
+
+    d->arch.vgic.nr_lines = 0;
+
+    /*
+     * Map the gic virtual cpu interface in the gic cpu interface
+     * region of the guest.
+     *
+     * The second page is always mapped at +4K irrespective of the
+     * GIC_64K_STRIDE quirk. The DTB passed to the guest reflects this.
+     */
+    ret = map_mmio_regions(d, d->arch.vgic.cbase,
+                           d->arch.vgic.cbase + PAGE_SIZE - 1,
+                           gic.vbase);
+    if ( ret )
+        return ret;
+
+    if ( !platform_has_quirk(PLATFORM_QUIRK_GIC_64K_STRIDE) )
+        ret = map_mmio_regions(d, d->arch.vgic.cbase + PAGE_SIZE,
+                               d->arch.vgic.cbase + (2 * PAGE_SIZE) - 1,
+                               gic.vbase + PAGE_SIZE);
+    else
+        ret = map_mmio_regions(d, d->arch.vgic.cbase + PAGE_SIZE,
+                               d->arch.vgic.cbase + (2 * PAGE_SIZE) - 1,
+                               gic.vbase + 16*PAGE_SIZE);
+
+    return ret;
+
+}
+
+static void gic_read_lr(int lr, struct gic_lr *lr_reg)
+{
+    uint32_t lrv;
+
+    lrv = GICH[GICH_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 gic_write_lr(int lr, struct gic_lr *lr_reg)
+{
+    uint32_t lrv = 0;
+    lrv = ( ((lr_reg->pirq & GICH_LR_PHYSICAL_MASK) << GICH_LR_PHYSICAL_SHIFT) 
 |
+            ((lr_reg->virq & GICH_LR_VIRTUAL_MASK) << GICH_LR_VIRTUAL_SHIFT)   
|
+            ((uint32_t)(lr_reg->priority & GICH_LR_PRIORITY_MASK) << 
GICH_LR_PRIORITY_SHIFT) |
+            ((uint32_t)(lr_reg->state & GICH_LR_STATE_MASK) << 
GICH_LR_STATE_SHIFT) |
+            ((uint32_t)(lr_reg->hw_status & GICH_LR_HW_MASK)  << 
GICH_LR_HW_SHIFT)  |
+            ((uint32_t)(lr_reg->grp & GICH_LR_GRP_MASK) << GICH_LR_GRP_SHIFT) 
);
+
+    GICH[GICH_LR + lr] = lrv;
+}
+
+static void gic_hcr_status(uint32_t flag, uint8_t status)
+{
+    if ( status )
+      GICH[GICH_HCR] |= flag;
+    else
+      GICH[GICH_HCR] &= ~flag;
+}
+
+static unsigned int gic_read_vmcr_priority(void)
+{
+   return (GICH[GICH_VMCR] >> GICH_VMCR_PRIORITY_SHIFT) & 
GICH_VMCR_PRIORITY_MASK;
+}
+
+static struct gic_hw_operations gic_ops = {
+    .nr_lines            = gic_nr_lines,
+    .nr_lrs              = gic_nr_lrs,
+    .secondary_init      = gic_secondary_cpu_init,
+    .get_maintenance_irq = gic_maintenance_irq,
+    .state_init          = gic_state_init,
+    .save_state          = save_state,
+    .restore_state       = restore_state,
+    .dump_state          = gic_dump_state,
+    .gicv_setup          = gicv_init,
+    .enable_irq          = gic_enable_irq,
+    .disable_irq         = gic_disable_irq,
+    .eoi_irq             = gic_eoi_irq,
+    .deactivate_irq      = gic_dir_irq,
+    .ack_irq             = gic_ack_irq,
+    .set_irq_property    = gic_set_irq_property,
+    .send_sgi            = gic_send_sgi,
+    .disable_interface   = gic_disable_interface,
+    .update_lr           = gic_update_lr,
+    .update_hcr_status   = gic_hcr_status,
+    .clear_lr            = gic_clear_lr,
+    .read_lr             = gic_read_lr,
+    .write_lr            = gic_write_lr,
+    .read_vmcr_priority  = gic_read_vmcr_priority,
+};
+
+/*
+ * Local variables:
+ * mode: C
+ * c-file-style: "BSD"
+ * c-basic-offset: 4
+ * indent-tabs-mode: nil
+ * End:
+ */
diff --git a/xen/arch/arm/gic.c b/xen/arch/arm/gic.c
index 77243cb..eb2f2d4 100644
--- a/xen/arch/arm/gic.c
+++ b/xen/arch/arm/gic.c
@@ -32,33 +32,16 @@
 #include <asm/domain.h>
 #include <asm/platform.h>
 
-#include <asm/gic_v2_defs.h>
 #include <asm/gic.h>
 
-/* Access to the GIC Distributor registers through the fixmap */
-#define GICD ((volatile uint32_t *) FIXMAP_ADDR(FIXMAP_GICD))
-#define GICC ((volatile uint32_t *) FIXMAP_ADDR(FIXMAP_GICC1))
-#define GICH ((volatile uint32_t *) FIXMAP_ADDR(FIXMAP_GICH))
 static void gic_restore_pending_irqs(struct vcpu *v);
 
-/* Global state */
-static struct {
-    paddr_t dbase;       /* Address of distributor registers */
-    paddr_t cbase;       /* Address of CPU interface registers */
-    paddr_t hbase;       /* Address of virtual interface registers */
-    paddr_t vbase;       /* Address of virtual cpu interface registers */
-    unsigned int lines;  /* Number of interrupts (SPIs + PPIs + SGIs) */
-    struct dt_irq maintenance; /* IRQ maintenance */
-    unsigned int cpus;
-} gic;
-
 static spinlock_t gic_lock;
 static irq_desc_t irq_desc[NR_IRQS];
 static DEFINE_PER_CPU(irq_desc_t[NR_LOCAL_IRQS], local_irq_desc);
 static DEFINE_PER_CPU(uint64_t, lr_mask);
 
 static struct gic_hw_operations *gic_hw_ops;
-static struct gic_hw_operations gic_ops;
 
 void register_gic_ops(struct gic_hw_operations *ops)
 {
@@ -70,128 +53,15 @@ void update_cpu_lr_mask(void)
     this_cpu(lr_mask) = 0ULL;
 }
 
-static uint8_t nr_lrs;
 #define lr_all_full() (this_cpu(lr_mask) == ((1 << gic_hw_ops->nr_lrs()) - 1))
 
-/* The GIC mapping of CPU interfaces does not necessarily match the
- * logical CPU numbering. Let's use mapping as returned by the GIC
- * itself
- */
-static DEFINE_PER_CPU(u8, gic_cpu_id);
-
-/* Maximum cpu interface per GIC */
-#define NR_GIC_CPU_IF 8
-
 static void gic_clear_one_lr(struct vcpu *v, int i);
 
-static unsigned int gic_cpu_mask(const cpumask_t *cpumask)
-{
-    unsigned int cpu;
-    unsigned int mask = 0;
-    cpumask_t possible_mask;
-
-    cpumask_and(&possible_mask, cpumask, &cpu_possible_map);
-    for_each_cpu(cpu, &possible_mask)
-    {
-        ASSERT(cpu < NR_GIC_CPU_IF);
-        mask |= per_cpu(gic_cpu_id, cpu);
-    }
-
-    return mask;
-}
-
 unsigned int gic_number_lines(void)
 {
     return gic_hw_ops->nr_lines();
 }
 
-static unsigned int gic_nr_lines(void)
-{
-    return gic.lines;
-}
-
-static unsigned int gic_nr_lrs(void)
-{
-    return nr_lrs;
-}
-
-static int gic_state_init(struct vcpu *v)
-{
-     v->arch.gic_state = xzalloc(struct gic_state_data);
-     if(!v->arch.gic_state)
-        return -ENOMEM;
-     return 0;
-}
-
-static void 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_state->gic_lr[i] = GICH[GICH_LR + i];
-    v->arch.gic_state->gic_apr = GICH[GICH_APR];
-    v->arch.gic_state->gic_vmcr = GICH[GICH_VMCR];
-    /* Disable until next VCPU scheduled */
-    GICH[GICH_HCR] = 0;
-}
-
-static void restore_state(struct vcpu *v)
-{
-    int i;
-
-    for ( i = 0; i < nr_lrs; i++ )
-        GICH[GICH_LR + i] = v->arch.gic_state->gic_lr[i];
-    GICH[GICH_APR] = v->arch.gic_state->gic_apr;
-    GICH[GICH_VMCR] = v->arch.gic_state->gic_vmcr;
-    GICH[GICH_HCR] = GICH_HCR_EN;
-}
-
-static void gic_dump_state(struct vcpu *v)
-{
-    int i;
-    if ( v == current )
-    {
-        for ( i = 0; i < nr_lrs; i++ )
-            printk("   HW_LR[%d]=%x\n", i, GICH[GICH_LR + i]);
-    } else {
-        for ( i = 0; i < nr_lrs; i++ )
-            printk("   VCPU_LR[%d]=%x\n", i, v->arch.gic_state->gic_lr[i]);
-    }
-}
-
-static void gic_enable_irq(int irq)
-{
-    /* Enable routing */
-    GICD[GICD_ISENABLER + irq / 32] = (1u << (irq % 32));
-}
-
-static void gic_disable_irq(int irq)
-{
-    /* Disable routing */
-    GICD[GICD_ICENABLER + irq / 32] = (1u << (irq % 32));
-}
-
-static void gic_eoi_irq(int irq)
-{
-    /* Lower the priority */
-    GICC[GICC_EOIR] = irq;
-}
-
-static void gic_dir_irq(int irq)
-{
-    /* Deactivate */
-    GICC[GICC_DIR] = irq;
-}
-
-static unsigned int gic_ack_irq(void)
-{
-    return (GICC[GICC_IAR] & GICC_IA_IRQ);
-}
-
 irq_desc_t *__irq_to_desc(int irq)
 {
     if (irq < NR_LOCAL_IRQS) return &this_cpu(local_irq_desc)[irq];
@@ -314,38 +184,6 @@ static hw_irq_controller gic_guest_irq_type = {
     .set_affinity = gic_irq_set_affinity,
 };
 
-/*
- * - 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 gic_set_irq_property(unsigned int irq, bool_t level,
-                                   const cpumask_t *cpu_mask,
-                                   unsigned int priority)
-{
-    volatile unsigned char *bytereg;
-    uint32_t cfg, edgebit;
-    unsigned int mask = gic_cpu_mask(cpu_mask);
-
-    /* Set edge / level */
-    cfg = GICD[GICD_ICFGR + irq / 16];
-    edgebit = 2u << (2 * (irq % 16));
-    if ( level )
-        cfg &= ~edgebit;
-    else
-        cfg |= edgebit;
-    GICD[GICD_ICFGR + irq / 16] = cfg;
-
-    /* Set target CPU mask (RAZ/WI on uniprocessor) */
-    bytereg = (unsigned char *) (GICD + GICD_ITARGETSR);
-    bytereg[irq] = mask;
-
-    /* Set priority */
-    bytereg = (unsigned char *) (GICD + GICD_IPRIORITYR);
-    bytereg[irq] = priority;
-
-}
-
 static void gic_set_irq_properties(unsigned int irq, bool_t level,
                                    const cpumask_t *cpu_mask,
                                    unsigned int priority)
@@ -361,7 +199,7 @@ static int gic_route_irq(unsigned int irq, bool_t level,
     unsigned long flags;
 
     ASSERT(priority <= 0xff);     /* Only 8 bits of priority */
-    ASSERT(irq < gic.lines);      /* Can't route interrupts that don't exist */
+    ASSERT(irq < gic_number_lines());
 
     if ( desc->action != NULL )
         return -EBUSY;
@@ -392,95 +230,6 @@ void gic_route_dt_irq(const struct dt_irq *irq, const 
cpumask_t *cpu_mask,
     gic_route_irq(irq->irq, level, cpu_mask, priority);
 }
 
-static void __init gic_dist_init(void)
-{
-    uint32_t type;
-    uint32_t cpumask;
-    int i;
-
-    cpumask = GICD[GICD_ITARGETSR] & 0xff;
-    cpumask |= cpumask << 8;
-    cpumask |= cpumask << 16;
-
-    /* Disable the distributor */
-    GICD[GICD_CTLR] = 0;
-
-    type = GICD[GICD_TYPER];
-    gic.lines = 32 * ((type & GICD_TYPE_LINES) + 1);
-    gic.cpus = 1 + ((type & GICD_TYPE_CPUS) >> 5);
-    printk("GIC: %d lines, %d cpu%s%s (IID %8.8x).\n",
-           gic.lines, gic.cpus, (gic.cpus == 1) ? "" : "s",
-           (type & GICD_TYPE_SEC) ? ", secure" : "",
-           GICD[GICD_IIDR]);
-
-    /* Default all global IRQs to level, active low */
-    for ( i = 32; i < gic.lines; i += 16 )
-        GICD[GICD_ICFGR + i / 16] = 0x0;
-
-    /* Route all global IRQs to this CPU */
-    for ( i = 32; i < gic.lines; i += 4 )
-        GICD[GICD_ITARGETSR + i / 4] = cpumask;
-
-    /* Default priority for global interrupts */
-    for ( i = 32; i < gic.lines; i += 4 )
-        GICD[GICD_IPRIORITYR + i / 4] =
-            GIC_PRI_IRQ<<24 | GIC_PRI_IRQ<<16 | GIC_PRI_IRQ<<8 | GIC_PRI_IRQ;
-
-    /* Disable all global interrupts */
-    for ( i = 32; i < gic.lines; i += 32 )
-        GICD[GICD_ICENABLER + i / 32] = (uint32_t)~0ul;
-
-    /* Turn on the distributor */
-    GICD[GICD_CTLR] = GICD_CTL_ENABLE;
-}
-
-static void __cpuinit gic_cpu_init(void)
-{
-    int i;
-
-    this_cpu(gic_cpu_id) = GICD[GICD_ITARGETSR] & 0xff;
-
-    /* The first 32 interrupts (PPI and SGI) are banked per-cpu, so
-     * even though they are controlled with GICD registers, they must
-     * be set up here with the other per-cpu state. */
-    GICD[GICD_ICENABLER] = 0xffff0000; /* Disable all PPI */
-    GICD[GICD_ISENABLER] = 0x0000ffff; /* Enable all SGI */
-    /* Set SGI priorities */
-    for (i = 0; i < 16; i += 4)
-        GICD[GICD_IPRIORITYR + i / 4] =
-            GIC_PRI_IPI<<24 | GIC_PRI_IPI<<16 | GIC_PRI_IPI<<8 | GIC_PRI_IPI;
-    /* Set PPI priorities */
-    for (i = 16; i < 32; i += 4)
-        GICD[GICD_IPRIORITYR + i / 4] =
-            GIC_PRI_IRQ<<24 | GIC_PRI_IRQ<<16 | GIC_PRI_IRQ<<8 | GIC_PRI_IRQ;
-
-    /* Local settings: interface controller */
-    GICC[GICC_PMR] = 0xff;                /* Don't mask by priority */
-    GICC[GICC_BPR] = 0;                   /* Finest granularity of priority */
-    GICC[GICC_CTLR] = GICC_CTL_ENABLE|GICC_CTL_EOI;    /* Turn on delivery */
-}
-
-static void gic_cpu_disable(void)
-{
-    GICC[GICC_CTLR] = 0;
-}
-
-static void __cpuinit gic_hyp_init(void)
-{
-    uint32_t vtr;
-
-    vtr = GICH[GICH_VTR];
-    nr_lrs  = (vtr & GICH_VTR_NRLRGS) + 1;
-
-    GICH[GICH_MISR] = GICH_MISR_EOI;
-    update_cpu_lr_mask();
-}
-
-static void __cpuinit gic_hyp_disable(void)
-{
-    GICH[GICH_HCR] = 0;
-}
-
 int gic_irq_xlate(const u32 *intspec, unsigned int intsize,
                   unsigned int *out_hwirq,
                   unsigned int *out_type)
@@ -504,106 +253,8 @@ int gic_irq_xlate(const u32 *intspec, unsigned int 
intsize,
 /* Set up the GIC */
 void __init gic_init(void)
 {
-    static const struct dt_device_match gic_ids[] __initconst =
-    {
-        DT_MATCH_GIC,
-        { /* sentinel */ },
-    };
-    struct dt_device_node *node;
-    int res;
-
-    node = dt_find_interrupt_controller(gic_ids);
-    if ( !node )
-        panic("Unable to find compatible GIC in the device tree");
-
-    dt_device_set_used_by(node, DOMID_XEN);
-
-    res = dt_device_get_address(node, 0, &gic.dbase, NULL);
-    if ( res || !gic.dbase || (gic.dbase & ~PAGE_MASK) )
-        panic("GIC: Cannot find a valid address for the distributor");
-
-    res = dt_device_get_address(node, 1, &gic.cbase, NULL);
-    if ( res || !gic.cbase || (gic.cbase & ~PAGE_MASK) )
-        panic("GIC: Cannot find a valid address for the CPU");
-
-    res = dt_device_get_address(node, 2, &gic.hbase, NULL);
-    if ( res || !gic.hbase || (gic.hbase & ~PAGE_MASK) )
-        panic("GIC: Cannot find a valid address for the hypervisor");
-
-    res = dt_device_get_address(node, 3, &gic.vbase, NULL);
-    if ( res || !gic.vbase || (gic.vbase & ~PAGE_MASK) )
-        panic("GIC: Cannot find a valid address for the virtual CPU");
-
-    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;
-
-    /* TODO: Add check on distributor, cpu size */
-
-    printk("GIC initialization:\n"
-              "        gic_dist_addr=%"PRIpaddr"\n"
-              "        gic_cpu_addr=%"PRIpaddr"\n"
-              "        gic_hyp_addr=%"PRIpaddr"\n"
-              "        gic_vcpu_addr=%"PRIpaddr"\n"
-              "        gic_maintenance_irq=%u\n",
-              gic.dbase, gic.cbase, gic.hbase, gic.vbase,
-              gic.maintenance.irq);
-
-    if ( (gic.dbase & ~PAGE_MASK) || (gic.cbase & ~PAGE_MASK) ||
-         (gic.hbase & ~PAGE_MASK) || (gic.vbase & ~PAGE_MASK) )
-        panic("GIC interfaces not page aligned");
-
-    set_fixmap(FIXMAP_GICD, gic.dbase >> PAGE_SHIFT, DEV_SHARED);
-    BUILD_BUG_ON(FIXMAP_ADDR(FIXMAP_GICC1) !=
-                 FIXMAP_ADDR(FIXMAP_GICC2)-PAGE_SIZE);
-    set_fixmap(FIXMAP_GICC1, gic.cbase >> PAGE_SHIFT, DEV_SHARED);
-    if ( platform_has_quirk(PLATFORM_QUIRK_GIC_64K_STRIDE) )
-        set_fixmap(FIXMAP_GICC2, (gic.cbase >> PAGE_SHIFT) + 0x10, DEV_SHARED);
-    else
-        set_fixmap(FIXMAP_GICC2, (gic.cbase >> PAGE_SHIFT) + 0x1, DEV_SHARED);
-    set_fixmap(FIXMAP_GICH, gic.hbase >> PAGE_SHIFT, DEV_SHARED);
-
-    /* Global settings: interrupt distributor */
+    gicv2_init();
     spin_lock_init(&gic_lock);
-    spin_lock(&gic_lock);
-
-    gic_dist_init();
-    gic_cpu_init();
-    gic_hyp_init();
-
-    register_gic_ops(&gic_ops);
-    spin_unlock(&gic_lock);
-}
-
-static void gic_secondary_cpu_init(void)
-{
-    gic_cpu_init();
-    gic_hyp_init();
-}
-
-static struct dt_irq * gic_maintenance_irq(void)
-{
-    return &gic.maintenance;
-}
-
-static void gic_send_sgi(const cpumask_t *cpumask, enum gic_sgi sgi)
-{
-    unsigned int mask = 0;
-    cpumask_t online_mask;
-
-    ASSERT(sgi < 16); /* There are only 16 SGIs */
-
-    cpumask_and(&online_mask, cpumask, &cpu_online_map);
-    mask = gic_cpu_mask(&online_mask);
-
-    dsb(sy);
-
-    GICD[GICD_SGIR] = GICD_SGI_TARGET_LIST
-        | (mask<<GICD_SGI_TARGET_SHIFT)
-        | sgi;
 }
 
 void send_SGI_mask(const cpumask_t *cpumask, enum gic_sgi sgi)
@@ -613,7 +264,6 @@ void send_SGI_mask(const cpumask_t *cpumask, enum gic_sgi 
sgi)
 
 void send_SGI_one(unsigned int cpu, enum gic_sgi sgi)
 {
-    ASSERT(cpu < NR_GIC_CPU_IF);  /* Targets bitmap only supports 8 CPUs */
     send_SGI_mask(cpumask_of(cpu), sgi);
 }
 
@@ -641,13 +291,6 @@ void __cpuinit gic_init_secondary_cpu(void)
     spin_unlock(&gic_lock);
 }
 
-/* Shut down the per-CPU GIC interface */
-static void gic_disable_interface(void)
-{
-    gic_cpu_disable();
-    gic_hyp_disable();
-}
-
 void gic_disable_cpu(void)
 {
     ASSERT(!local_irq_is_enabled());
@@ -735,25 +378,6 @@ int __init setup_dt_irq(const struct dt_irq *irq, struct 
irqaction *new)
     return rc;
 }
 
-static void gic_update_lr(int lr, struct pending_irq *p, unsigned int state)
-{
-    int maintenance_int = GICH_LR_MAINTENANCE_IRQ;
-
-    BUG_ON(lr >= nr_lrs);
-    BUG_ON(lr < 0);
-    BUG_ON(state & ~(GICH_LR_STATE_MASK<<GICH_LR_STATE_SHIFT));
-
-    GICH[GICH_LR + lr] = ((state & 0x3) << GICH_LR_STATE_SHIFT) |
-        maintenance_int |
-        ((p->priority >> 3) << GICH_LR_PRIORITY_SHIFT) |
-        ((p->irq & GICH_LR_VIRTUAL_MASK) << GICH_LR_VIRTUAL_SHIFT);
-}
-
-static void gic_clear_lr(int lr)
-{
-    GICH[GICH_LR + lr] = 0;
-}
-
 static inline void gic_set_lr(int lr, struct pending_irq *p,
         unsigned int state)
 {
@@ -1097,53 +721,6 @@ void gic_interrupt(struct cpu_user_regs *regs, int is_fiq)
     } while (1);
 }
 
-static int gicv_init(struct domain *d)
-{
-    int ret;
-
-    /*
-     * 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.cbase = gic.cbase;
-    }
-    else
-    {
-        d->arch.vgic.dbase = GUEST_GICD_BASE;
-        d->arch.vgic.cbase = GUEST_GICC_BASE;
-    }
-
-    d->arch.vgic.nr_lines = 0;
-
-    /*
-     * Map the gic virtual cpu interface in the gic cpu interface
-     * region of the guest.
-     *
-     * The second page is always mapped at +4K irrespective of the
-     * GIC_64K_STRIDE quirk. The DTB passed to the guest reflects this.
-     */
-    ret = map_mmio_regions(d, d->arch.vgic.cbase,
-                           d->arch.vgic.cbase + PAGE_SIZE - 1,
-                           gic.vbase);
-    if (ret)
-        return ret;
-
-    if ( !platform_has_quirk(PLATFORM_QUIRK_GIC_64K_STRIDE) )
-        ret = map_mmio_regions(d, d->arch.vgic.cbase + PAGE_SIZE,
-                               d->arch.vgic.cbase + (2 * PAGE_SIZE) - 1,
-                               gic.vbase + PAGE_SIZE);
-    else
-        ret = map_mmio_regions(d, d->arch.vgic.cbase + PAGE_SIZE,
-                               d->arch.vgic.cbase + (2 * PAGE_SIZE) - 1,
-                               gic.vbase + 16*PAGE_SIZE);
-
-    return ret;
-
-}
-
 int vcpu_gic_init(struct vcpu *v)
 {
      return gic_hw_ops->state_init(v);
@@ -1158,71 +735,6 @@ int gicv_setup(struct domain *d)
 
 }
 
-static void gic_read_lr(int lr, struct gic_lr *lr_reg)
-{
-    uint32_t lrv;
-
-    lrv = GICH[GICH_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 gic_write_lr(int lr, struct gic_lr *lr_reg)
-{
-    uint32_t lrv = 0;
-    lrv = ( ((lr_reg->pirq & GICH_LR_PHYSICAL_MASK) << GICH_LR_PHYSICAL_SHIFT) 
 |
-            ((lr_reg->virq & GICH_LR_VIRTUAL_MASK) << GICH_LR_VIRTUAL_SHIFT)   
|
-            ((uint32_t)(lr_reg->priority & GICH_LR_PRIORITY_MASK) << 
GICH_LR_PRIORITY_SHIFT) |
-            ((uint32_t)(lr_reg->state & GICH_LR_STATE_MASK) << 
GICH_LR_STATE_SHIFT) |
-            ((uint32_t)(lr_reg->hw_status & GICH_LR_HW_MASK)  << 
GICH_LR_HW_SHIFT)  |
-            ((uint32_t)(lr_reg->grp & GICH_LR_GRP_MASK) << GICH_LR_GRP_SHIFT) 
);
-
-    GICH[GICH_LR + lr] = lrv;
-}
-
-static void gic_hcr_status(uint32_t flag, uint8_t status)
-{
-    if ( status )
-      GICH[GICH_HCR] |= flag;
-    else
-      GICH[GICH_HCR] &= ~flag;
-}
-
-static unsigned int gic_read_vmcr_priority(void)
-{
-   return (GICH[GICH_VMCR] >> GICH_VMCR_PRIORITY_SHIFT) & 
GICH_VMCR_PRIORITY_MASK;
-}
-
-static struct gic_hw_operations gic_ops = {
-    .nr_lines            = gic_nr_lines,
-    .nr_lrs              = gic_nr_lrs,
-    .secondary_init      = gic_secondary_cpu_init,
-    .get_maintenance_irq = gic_maintenance_irq,
-    .state_init          = gic_state_init,
-    .save_state          = save_state,
-    .restore_state       = restore_state,
-    .dump_state          = gic_dump_state,
-    .gicv_setup          = gicv_init,
-    .enable_irq          = gic_enable_irq,
-    .disable_irq         = gic_disable_irq,
-    .eoi_irq             = gic_eoi_irq,
-    .deactivate_irq      = gic_dir_irq,
-    .ack_irq             = gic_ack_irq,
-    .set_irq_property    = gic_set_irq_property,
-    .send_sgi            = gic_send_sgi,
-    .disable_interface   = gic_disable_interface,
-    .update_lr           = gic_update_lr,
-    .update_hcr_status   = gic_hcr_status,
-    .clear_lr            = gic_clear_lr,
-    .read_lr             = gic_read_lr,
-    .write_lr            = gic_write_lr,
-    .read_vmcr_priority  = gic_read_vmcr_priority,
-};
-
 static void maintenance_interrupt(int irq, void *dev_id, struct cpu_user_regs 
*regs)
 {
     /* 
diff --git a/xen/include/asm-arm/gic.h b/xen/include/asm-arm/gic.h
index 27d2792..cc6d8c4 100644
--- a/xen/include/asm-arm/gic.h
+++ b/xen/include/asm-arm/gic.h
@@ -116,6 +116,7 @@ extern int gic_route_irq_to_guest(struct domain *d,
 extern void gic_interrupt(struct cpu_user_regs *regs, int is_fiq);
 /* Bring up the interrupt controller, and report # cpus attached */
 extern void gic_init(void);
+extern void gicv2_init(void);
 /* Bring up a secondary CPU's per-CPU GIC interface */
 extern void gic_init_secondary_cpu(void);
 /* Take down a CPU's per-CPU GIC interface */
-- 
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®.