[Top][All Lists]
[Date Prev][Date Next][Thread Prev][Thread Next][Date Index][Thread Index]
[Qemu-devel] [PATCH] Add Qemu A15 minimal support for ARM KVM
From: |
bill4carson |
Subject: |
[Qemu-devel] [PATCH] Add Qemu A15 minimal support for ARM KVM |
Date: |
Thu, 29 Sep 2011 15:30:03 +0800 |
From: Bill Carson <address@hidden>
This patch add some A15 codes which enables ARM KVM could run
Guest OS build with Versatile Express Cortex-A15x4 tile.
Signed-off-by: Bill Carson <address@hidden>
---
Makefile.target | 2 +-
hw/a15mpcore.c | 146 ++++++++++++++++++++++++++++++++++++++
hw/vexpress.c | 192 +++++++++++++++++++++++++++++++++++++++++++++++++++
target-arm/cpu.h | 1 +
target-arm/helper.c | 31 ++++++++
5 files changed, 371 insertions(+), 1 deletions(-)
create mode 100644 hw/a15mpcore.c
diff --git a/Makefile.target b/Makefile.target
index 2501c63..3899869 100644
--- a/Makefile.target
+++ b/Makefile.target
@@ -331,7 +331,7 @@ endif
obj-arm-y = integratorcp.o versatilepb.o arm_pic.o arm_timer.o
obj-arm-y += arm_boot.o pl011.o pl031.o pl050.o pl080.o pl110.o pl181.o pl190.o
obj-arm-y += versatile_pci.o
-obj-arm-y += realview_gic.o realview.o arm_sysctl.o arm11mpcore.o a9mpcore.o
+obj-arm-y += realview_gic.o realview.o arm_sysctl.o arm11mpcore.o a9mpcore.o
a15mpcore.o
obj-arm-y += armv7m.o armv7m_nvic.o stellaris.o pl022.o stellaris_enet.o
obj-arm-y += pl061.o
obj-arm-y += arm-semi.o
diff --git a/hw/a15mpcore.c b/hw/a15mpcore.c
new file mode 100644
index 0000000..cf7ec38
--- /dev/null
+++ b/hw/a15mpcore.c
@@ -0,0 +1,146 @@
+/*
+ * ARM MPCore internal peripheral emulation (common code).
+ *
+ * Copyright (c) 2006-2007 CodeSourcery.
+ * Written by Paul Brook
+ *
+ * This code is licenced under the GPL.
+ */
+
+#include "sysbus.h"
+#include "qemu-timer.h"
+
+/* 64 external IRQ lines. */
+#define GIC_NIRQ 96
+
+
+#define NCPU 4
+
+static inline int
+gic_get_current_cpu(void)
+{
+ return cpu_single_env->cpu_index;
+}
+
+#include "arm_gic.c"
+
+/* MPCore private memory region. */
+
+typedef struct {
+ uint32_t count;
+ uint32_t load;
+ uint32_t control;
+ uint32_t status;
+ uint32_t old_status;
+ int64_t tick;
+ QEMUTimer *timer;
+ struct a15mpcore_priv_state *mpcore;
+ int id; /* Encodes both timer/watchdog and CPU. */
+} mpcore_timer_state;
+
+typedef struct a15mpcore_priv_state {
+ gic_state gic;
+ uint32_t scu_control;
+ int iomemtype;
+ mpcore_timer_state timer[8];
+ uint32_t num_cpu;
+} a15mpcore_priv_state;
+
+/* TODO:Per-CPU Timers. */
+
+
+/* Per-CPU private memory mapped IO. */
+
+static uint32_t a15mpcore_priv_read(void *opaque, target_phys_addr_t offset)
+{
+ a15mpcore_priv_state *s = (a15mpcore_priv_state *)opaque;
+ int id;
+ offset &= 0xfff;
+ uint32_t value;
+
+ /* Interrupt controller. */
+ if (offset < 0x200) {
+ id = gic_get_current_cpu();
+ } else {
+ id = (offset - 0x200) >> 8;
+ if (id >= s->num_cpu) {
+ return 0;
+ }
+ }
+
+ value = gic_cpu_read(&s->gic, id, offset & 0xff);
+ return value;
+}
+
+static void a15mpcore_priv_write(void *opaque, target_phys_addr_t offset,
+ uint32_t value)
+{
+ a15mpcore_priv_state *s = (a15mpcore_priv_state *)opaque;
+ int id;
+
+ offset &= 0xfff;
+ /* Interrupt controller. */
+ if (offset < 0x200) {
+ id = gic_get_current_cpu();
+ } else {
+ id = (offset - 0x200) >> 8;
+ }
+ if (id < s->num_cpu) {
+ gic_cpu_write(&s->gic, id, offset & 0xff, value);
+ }
+
+ return;
+}
+
+static CPUReadMemoryFunc * const a15mpcore_priv_readfn[] = {
+ a15mpcore_priv_read,
+ a15mpcore_priv_read,
+ a15mpcore_priv_read
+};
+
+static CPUWriteMemoryFunc * const a15mpcore_priv_writefn[] = {
+ a15mpcore_priv_write,
+ a15mpcore_priv_write,
+ a15mpcore_priv_write
+};
+
+static void a15mpcore_priv_map(SysBusDevice *dev, target_phys_addr_t base)
+{
+ a15mpcore_priv_state *s = FROM_SYSBUSGIC(a15mpcore_priv_state, dev);
+ cpu_register_physical_memory(base + 0x2000, 0x1000, s->iomemtype);/* cpu
interface */
+ cpu_register_physical_memory(base + 0x1000, 0x1000, s->gic.iomemtype);/*
distributor */
+}
+
+static int a15mpcore_priv_init(SysBusDevice *dev)
+{
+ a15mpcore_priv_state *s = FROM_SYSBUSGIC(a15mpcore_priv_state, dev);
+
+ gic_init(&s->gic, s->num_cpu);
+ s->iomemtype = cpu_register_io_memory(a15mpcore_priv_readfn,
+ a15mpcore_priv_writefn, s,
+ DEVICE_NATIVE_ENDIAN);
+ sysbus_init_mmio_cb(dev, 0x2000, a15mpcore_priv_map);
+ return 0;
+}
+
+
+static SysBusDeviceInfo a15mpcore_priv_info = {
+ .init = a15mpcore_priv_init,
+ .qdev.name = "a15mpcore_priv",
+ .qdev.size = sizeof(a15mpcore_priv_state),
+ .qdev.props = (Property[]) {
+ DEFINE_PROP_UINT32("num-cpu", a15mpcore_priv_state, num_cpu, 1),
+ DEFINE_PROP_END_OF_LIST(),
+ }
+};
+
+static void a15mpcore_register_devices(void)
+{
+ sysbus_register_withprop(&a15mpcore_priv_info);
+}
+
+device_init(a15mpcore_register_devices)
+
+
+
+
diff --git a/hw/vexpress.c b/hw/vexpress.c
index 9ffd332..168819f 100644
--- a/hw/vexpress.c
+++ b/hw/vexpress.c
@@ -34,6 +34,10 @@ static struct arm_boot_info vexpress_binfo = {
.smp_loader_start = SMP_BOOT_ADDR,
};
+static struct arm_boot_info vexpress_a15_binfo = {
+ .smp_loader_start = SMP_BOOT_ADDR,
+};
+
static void vexpress_a9_init(ram_addr_t ram_size,
const char *boot_device,
const char *kernel_filename, const char *kernel_cmdline,
@@ -216,9 +220,197 @@ static QEMUMachine vexpress_a9_machine = {
.max_cpus = 4,
};
+
+
+static void vexpress_a15_init(ram_addr_t ram_size,
+ const char *boot_device,
+ const char *kernel_filename, const char *kernel_cmdline,
+ const char *initrd_filename, const char *cpu_model)
+{
+ CPUState *env = NULL;
+ ram_addr_t ram_offset, vram_offset, sram_offset;
+ DeviceState *dev, *sysctl;
+ SysBusDevice *busdev;
+ qemu_irq *irqp;
+ qemu_irq pic[64];
+ int n;
+ qemu_irq cpu_irq[4];
+ uint32_t proc_id;
+ uint32_t sys_id;
+ ram_addr_t low_ram_size, vram_size, sram_size;
+
+ if (!cpu_model) {
+ cpu_model = "cortex-a15";
+ }
+
+ for (n = 0; n < smp_cpus; n++) {
+ env = cpu_init(cpu_model);
+ if (!env) {
+ fprintf(stderr, "Unable to find CPU definition\n");
+ exit(1);
+ }
+ irqp = arm_pic_init_cpu(env);
+ cpu_irq[n] = irqp[ARM_PIC_CPU_IRQ];
+ }
+
+ if (ram_size > 0x40000000) {
+ /* 1GB is the maximum the address space permits */
+ fprintf(stderr, "vexpress: cannot model more than 1GB RAM\n");
+ exit(1);
+ }
+
+ ram_offset = qemu_ram_alloc(NULL, "vexpress.highmem", ram_size);
+ low_ram_size = ram_size;
+ if (low_ram_size > 0x4000000) {
+ low_ram_size = 0x4000000;
+ }
+ /* RAM is from 0x60000000 upwards. The bottom 64MB of the
+ * address space should in theory be remappable to various
+ * things including ROM or RAM; we always map the RAM there.
+ */
+ cpu_register_physical_memory(0x0, low_ram_size, ram_offset | IO_MEM_RAM);
+ cpu_register_physical_memory(0x80000000, ram_size,
+ ram_offset | IO_MEM_RAM);
+
+ /* 0x2c000000 A15MPCore (SCU) private memory region */
+ dev = qdev_create(NULL, "a15mpcore_priv");
+ qdev_prop_set_uint32(dev, "num-cpu", smp_cpus);
+ qdev_init_nofail(dev);
+ busdev = sysbus_from_qdev(dev);
+ vexpress_a15_binfo.smp_priv_base = 0x2c000000;
+ sysbus_mmio_map(busdev, 0, vexpress_a15_binfo.smp_priv_base);
+ for (n = 0; n < smp_cpus; n++) {
+ sysbus_connect_irq(busdev, n, cpu_irq[n]);
+ }
+ /* Interrupts [42:0] are from the motherboard;
+ * [47:43] are reserved; [63:48] are daughterboard
+ * peripherals. Note that some documentation numbers
+ * external interrupts starting from 32 (because the
+ * A9MP has internal interrupts 0..31).
+ */
+ for (n = 0; n < 64; n++) {
+ pic[n] = qdev_get_gpio_in(dev, n);
+ }
+
+ /* Motherboard peripherals CS7 : 0x10000000 .. 0x10020000 */
+ sys_id = 0x1190f500;
+ proc_id = 0x0c000000; /*depend on Fast module*/
+
+ /* 0x10000000 System registers */
+ sysctl = qdev_create(NULL, "realview_sysctl");
+ qdev_prop_set_uint32(sysctl, "sys_id", sys_id);
+ qdev_init_nofail(sysctl);
+ qdev_prop_set_uint32(sysctl, "proc_id", proc_id);
+
+ sysbus_mmio_map(sysbus_from_qdev(sysctl), 0, 0x1c010000);
+
+ /* 0x10001000 SP810 system control */
+ /* 0x10002000 serial bus PCI */
+ /* 0x10004000 PL041 audio */
+
+ dev = sysbus_create_varargs("pl181", 0x10005000, pic[9], pic[10], NULL);
+ /* Wire up MMC card detect and read-only signals */
+ qdev_connect_gpio_out(dev, 0,
+ qdev_get_gpio_in(sysctl, ARM_SYSCTL_GPIO_MMC_WPROT));
+ qdev_connect_gpio_out(dev, 1,
+ qdev_get_gpio_in(sysctl,
ARM_SYSCTL_GPIO_MMC_CARDIN));
+
+ sysbus_create_simple("pl050_keyboard", 0x1c060000, pic[12]);
+ sysbus_create_simple("pl050_mouse", 0x1c070000, pic[13]);
+
+ sysbus_create_simple("pl011", 0x1c090000, pic[5]);
+ sysbus_create_simple("pl011", 0x1c0a0000, pic[6]);
+ sysbus_create_simple("pl011", 0x1c0b0000, pic[7]);
+ sysbus_create_simple("pl011", 0x1c0c0000, pic[8]);
+
+ /* 0x1000f000 SP805 WDT */
+
+ sysbus_create_simple("sp804", 0x1c110000, pic[2]);
+ sysbus_create_simple("sp804", 0x1c120000, pic[3]);
+
+ /* 0x10016000 Serial Bus DVI */
+
+ sysbus_create_simple("pl031", 0x1c170000, pic[36]); /* RTC */
+
+ /* 0x1001a000 Compact Flash */
+
+ /* 0x1001f000 PL111 CLCD (motherboard) */
+
+ /* Daughterboard peripherals : 0x10020000 .. 0x20000000 */
+
+ /* 0x10020000 PL111 CLCD (daughterboard) */
+ sysbus_create_simple("pl110", 0x10020000, pic[44]);
+
+ /* 0x10060000 AXI RAM */
+ /* 0x100e0000 PL341 Dynamic Memory Controller */
+ /* 0x100e1000 PL354 Static Memory Controller */
+ /* 0x100e2000 System Configuration Controller */
+
+ sysbus_create_simple("sp804", 0x100e4000, pic[48]);
+ /* 0x100e5000 SP805 Watchdog module */
+ /* 0x100e6000 BP147 TrustZone Protection Controller */
+ /* 0x100e9000 PL301 'Fast' AXI matrix */
+ /* 0x100ea000 PL301 'Slow' AXI matrix */
+ /* 0x100ec000 TrustZone Address Space Controller */
+ /* 0x10200000 CoreSight debug APB */
+ /* 0x1e00a000 PL310 L2 Cache Controller */
+
+ /* CS0: NOR0 flash : 0x40000000 .. 0x44000000 */
+ /* CS4: NOR1 flash : 0x44000000 .. 0x48000000 */
+ /* CS2: SRAM : 0x48000000 .. 0x4a000000 */
+ sram_size = 0x2000000;
+ sram_offset = qemu_ram_alloc(NULL, "vexpress.sram", sram_size);
+ cpu_register_physical_memory(0x48000000, sram_size,
+ sram_offset | IO_MEM_RAM);
+
+ /* CS3: USB, ethernet, VRAM : 0x4c000000 .. 0x50000000 */
+
+ /* 0x4c000000 Video RAM */
+ vram_size = 0x2000000; /* 32MB */
+ vram_offset = qemu_ram_alloc(NULL, "vexpress.vram", vram_size);
+ cpu_register_physical_memory(0x18000000, vram_size,
+ vram_offset | IO_MEM_RAM);
+
+ /* 0x4e000000 LAN9118 Ethernet */
+ if (nd_table[0].vlan) {
+ lan9118_init(&nd_table[0], 0x4e000000, pic[15]);
+ }
+
+ /* 0x4f000000 ISP1761 USB */
+
+ /* ??? Hack to map an additional page of ram for the secondary CPU
+ startup code. I guess this works on real hardware because the
+ BootROM happens to be in ROM/flash or in memory that isn't clobbered
+ until after Linux boots the secondary CPUs. */
+ ram_offset = qemu_ram_alloc(NULL, "vexpress.hack", 0x1000);
+ cpu_register_physical_memory(SMP_BOOT_ADDR, 0x1000,
+ ram_offset | IO_MEM_RAM);
+
+ vexpress_a15_binfo.ram_size = ram_size;
+ vexpress_a15_binfo.kernel_filename = kernel_filename;
+ vexpress_a15_binfo.kernel_cmdline = kernel_cmdline;
+ vexpress_a15_binfo.initrd_filename = initrd_filename;
+ vexpress_a15_binfo.nb_cpus = smp_cpus;
+ vexpress_a15_binfo.board_id = VEXPRESS_BOARD_ID;
+ vexpress_a15_binfo.loader_start = 0x80000000;
+ arm_load_kernel(first_cpu, &vexpress_a15_binfo);
+}
+
+
+static QEMUMachine vexpress_a15_machine = {
+ .name = "vexpress-a15",
+ .desc = "ARM Versatile Express for Cortex-A15",
+ .init = vexpress_a15_init,
+ .use_scsi = 1,
+ .max_cpus = 4,
+};
+
+
+
static void vexpress_machine_init(void)
{
qemu_register_machine(&vexpress_a9_machine);
+ qemu_register_machine(&vexpress_a15_machine);
}
machine_init(vexpress_machine_init);
diff --git a/target-arm/cpu.h b/target-arm/cpu.h
index b8e7419..94b42ab 100644
--- a/target-arm/cpu.h
+++ b/target-arm/cpu.h
@@ -419,6 +419,7 @@ void cpu_arm_set_cp_io(CPUARMState *env, int cpnum,
#define ARM_CPUID_ARM11MPCORE 0x410fb022
#define ARM_CPUID_CORTEXA8 0x410fc080
#define ARM_CPUID_CORTEXA9 0x410fc090
+#define ARM_CPUID_CORTEXA15 0x410fc0f0
#define ARM_CPUID_CORTEXM3 0x410fc231
#define ARM_CPUID_ANY 0xffffffff
diff --git a/target-arm/helper.c b/target-arm/helper.c
index b051b8c..c7a0ac9 100644
--- a/target-arm/helper.c
+++ b/target-arm/helper.c
@@ -153,6 +153,36 @@ static void cpu_reset_model_id(CPUARMState *env, uint32_t
id)
env->cp15.c0_ccsid[1] = 0x200fe015; /* 16k L1 icache. */
env->cp15.c1_sys = 0x00c50078;
break;
+ case ARM_CPUID_CORTEXA15: /* most same as A9 */
+ set_feature(env, ARM_FEATURE_V4T);
+ set_feature(env, ARM_FEATURE_V5);
+ set_feature(env, ARM_FEATURE_V6);
+ set_feature(env, ARM_FEATURE_V6K);
+ set_feature(env, ARM_FEATURE_V7);
+ set_feature(env, ARM_FEATURE_AUXCR);
+ set_feature(env, ARM_FEATURE_THUMB2);
+ set_feature(env, ARM_FEATURE_VFP);
+ set_feature(env, ARM_FEATURE_VFP3);
+ set_feature(env, ARM_FEATURE_VFP_FP16);
+ set_feature(env, ARM_FEATURE_NEON);
+ set_feature(env, ARM_FEATURE_THUMB2EE);
+ /* Note that A9 supports the MP extensions even for
+ * A9UP and single-core A9MP (which are both different
+ * and valid configurations; we don't model A9UP).
+ */
+ set_feature(env, ARM_FEATURE_V7MP);
+ env->vfp.xregs[ARM_VFP_FPSID] = 0x41034000; /* Guess */
+ env->vfp.xregs[ARM_VFP_MVFR0] = 0x11110222;
+ env->vfp.xregs[ARM_VFP_MVFR1] = 0x01111111;
+ memcpy(env->cp15.c0_c1, cortexa9_cp15_c0_c1, 8 * sizeof(uint32_t));
+ memcpy(env->cp15.c0_c2, cortexa9_cp15_c0_c2, 8 * sizeof(uint32_t));
+ env->cp15.c0_cachetype = 0x80038003;
+ env->cp15.c0_clid = (1 << 27) | (1 << 24) | 3;
+ env->cp15.c0_ccsid[0] = 0xe00fe015; /* 16k L1 dcache. */
+ env->cp15.c0_ccsid[1] = 0x200fe015; /* 16k L1 icache. */
+ env->cp15.c1_sys = 0x00c50078;
+ break;
+
case ARM_CPUID_CORTEXM3:
set_feature(env, ARM_FEATURE_V4T);
set_feature(env, ARM_FEATURE_V5);
@@ -385,6 +415,7 @@ static const struct arm_cpu_t arm_cpu_names[] = {
{ ARM_CPUID_CORTEXM3, "cortex-m3"},
{ ARM_CPUID_CORTEXA8, "cortex-a8"},
{ ARM_CPUID_CORTEXA9, "cortex-a9"},
+ { ARM_CPUID_CORTEXA15, "cortex-a15"},
{ ARM_CPUID_TI925T, "ti925t" },
{ ARM_CPUID_PXA250, "pxa250" },
{ ARM_CPUID_SA1100, "sa1100" },
--
1.7.1