summaryrefslogtreecommitdiff
path: root/src/dev
diff options
context:
space:
mode:
authorARM gem5 Developers <none@none>2014-01-24 15:29:34 -0600
committerARM gem5 Developers <none@none>2014-01-24 15:29:34 -0600
commit612f8f074fa1099cf70faf495d46cc647762a031 (patch)
treebd1e99c43bf15292395eadd4b7ae3f5c823545c3 /src/dev
parentf3585c841e964c98911784a187fc4f081a02a0a6 (diff)
downloadgem5-612f8f074fa1099cf70faf495d46cc647762a031.tar.xz
arm: Add support for ARMv8 (AArch64 & AArch32)
Note: AArch64 and AArch32 interworking is not supported. If you use an AArch64 kernel you are restricted to AArch64 user-mode binaries. This will be addressed in a later patch. Note: Virtualization is only supported in AArch32 mode. This will also be fixed in a later patch. Contributors: Giacomo Gabrielli (TrustZone, LPAE, system-level AArch64, AArch64 NEON, validation) Thomas Grocutt (AArch32 Virtualization, AArch64 FP, validation) Mbou Eyole (AArch64 NEON, validation) Ali Saidi (AArch64 Linux support, code integration, validation) Edmund Grimley-Evans (AArch64 FP) William Wang (AArch64 Linux support) Rene De Jong (AArch64 Linux support, performance opt.) Matt Horsnell (AArch64 MP, validation) Matt Evans (device models, code integration, validation) Chris Adeniyi-Jones (AArch64 syscall-emulation) Prakash Ramrakhyani (validation) Dam Sunwoo (validation) Chander Sudanthi (validation) Stephan Diestelhorst (validation) Andreas Hansson (code integration, performance opt.) Eric Van Hensbergen (performance opt.) Gabe Black
Diffstat (limited to 'src/dev')
-rw-r--r--src/dev/arm/RealView.py43
-rw-r--r--src/dev/arm/SConscript5
-rw-r--r--src/dev/arm/generic_timer.cc204
-rw-r--r--src/dev/arm/generic_timer.hh199
-rw-r--r--src/dev/arm/gic_pl390.cc3
-rw-r--r--src/dev/arm/vgic.cc553
-rw-r--r--src/dev/arm/vgic.hh262
7 files changed, 1265 insertions, 4 deletions
diff --git a/src/dev/arm/RealView.py b/src/dev/arm/RealView.py
index b3c14580e..3c9c22ecc 100644
--- a/src/dev/arm/RealView.py
+++ b/src/dev/arm/RealView.py
@@ -1,4 +1,4 @@
-# Copyright (c) 2009-2012 ARM Limited
+# Copyright (c) 2009-2013 ARM Limited
# All rights reserved.
#
# The license below extends only to copyright in the software and shall
@@ -88,6 +88,17 @@ class RealViewCtrl(BasicPioDevice):
proc_id1 = Param.UInt32(0x0C000222, "Processor ID, SYS_PROCID1")
idreg = Param.UInt32(0x00000000, "ID Register, SYS_ID")
+class VGic(PioDevice):
+ type = 'VGic'
+ cxx_header = "dev/arm/vgic.hh"
+ gic = Param.BaseGic(Parent.any, "Gic to use for interrupting")
+ platform = Param.Platform(Parent.any, "Platform this device is part of.")
+ vcpu_addr = Param.Addr(0, "Address for vcpu interfaces")
+ hv_addr = Param.Addr(0, "Address for hv control")
+ pio_delay = Param.Latency('10ns', "Delay for PIO r/w")
+ # The number of list registers is not currently configurable at runtime.
+ ppint = Param.UInt32("HV maintenance interrupt number")
+
class AmbaFake(AmbaPioDevice):
type = 'AmbaFake'
cxx_header = "dev/arm/amba_fake.hh"
@@ -119,6 +130,15 @@ class CpuLocalTimer(BasicPioDevice):
int_num_timer = Param.UInt32("Interrrupt number used per-cpu to GIC")
int_num_watchdog = Param.UInt32("Interrupt number for per-cpu watchdog to GIC")
+class GenericTimer(SimObject):
+ type = 'GenericTimer'
+ cxx_header = "dev/arm/generic_timer.hh"
+ system = Param.System(Parent.any, "system")
+ gic = Param.BaseGic(Parent.any, "GIC to use for interrupting")
+ int_num = Param.UInt32("Interrupt number used per-cpu to GIC")
+ # @todo: for now only one timer per CPU is supported, which is the
+ # normal behaviour when Security and Virt. extensions are disabled.
+
class PL031(AmbaIntDevice):
type = 'PL031'
cxx_header = "dev/arm/rtc_pl031.hh"
@@ -166,6 +186,9 @@ class RealView(Platform):
conf_table_reported = False)
self.nvmem.port = mem_bus.master
cur_sys.boot_loader = loc('boot.arm')
+ cur_sys.atags_addr = 0x100
+ cur_sys.load_addr_mask = 0xfffffff
+ cur_sys.load_offset = 0
# Reference for memory map and interrupt number
@@ -340,12 +363,14 @@ class VExpress_EMM(RealView):
realview_io = RealViewCtrl(proc_id0=0x14000000, proc_id1=0x14000000, pio_addr=0x1C010000)
gic = Pl390(dist_addr=0x2C001000, cpu_addr=0x2C002000)
local_cpu_timer = CpuLocalTimer(int_num_timer=29, int_num_watchdog=30, pio_addr=0x2C080000)
+ generic_timer = GenericTimer(int_num=29)
timer0 = Sp804(int_num0=34, int_num1=34, pio_addr=0x1C110000, clock0='1MHz', clock1='1MHz')
timer1 = Sp804(int_num0=35, int_num1=35, pio_addr=0x1C120000, clock0='1MHz', clock1='1MHz')
clcd = Pl111(pio_addr=0x1c1f0000, int_num=46)
hdlcd = HDLcd(pio_addr=0x2b000000, int_num=117)
kmi0 = Pl050(pio_addr=0x1c060000, int_num=44)
kmi1 = Pl050(pio_addr=0x1c070000, int_num=45, is_mouse=True)
+ vgic = VGic(vcpu_addr=0x2c006000, hv_addr=0x2c004000, ppint=25)
cf_ctrl = IdeController(disks=[], pci_func=0, pci_dev=0, pci_bus=2,
io_shift = 2, ctrl_offset = 2, Command = 0x1,
BAR0 = 0x1C1A0000, BAR0Size = '256B',
@@ -380,7 +405,9 @@ class VExpress_EMM(RealView):
conf_table_reported = False)
self.nvmem.port = mem_bus.master
cur_sys.boot_loader = loc('boot_emm.arm')
- cur_sys.atags_addr = 0x80000100
+ cur_sys.atags_addr = 0x8000000
+ cur_sys.load_addr_mask = 0xfffffff
+ cur_sys.load_offset = 0x80000000
# Attach I/O devices that are on chip and also set the appropriate
# ranges for the bridge
@@ -396,6 +423,8 @@ class VExpress_EMM(RealView):
AddrRange(0x40000000, size='512MB'),
AddrRange(0x18000000, size='64MB'),
AddrRange(0x1C000000, size='64MB')]
+ self.vgic.pio = bus.master
+
# Attach I/O devices to specified bus object. Can't do this
# earlier, since the bus object itself is typically defined at the
@@ -435,3 +464,13 @@ class VExpress_EMM(RealView):
self.usb_fake.pio = bus.master
self.mmc_fake.pio = bus.master
+class VExpress_EMM64(VExpress_EMM):
+ def setupBootLoader(self, mem_bus, cur_sys, loc):
+ self.nvmem = SimpleMemory(range = AddrRange(0, size = '64MB'))
+ self.nvmem.port = mem_bus.master
+ cur_sys.boot_loader = loc('boot_emm.arm64')
+ cur_sys.atags_addr = 0x8000000
+ cur_sys.load_addr_mask = 0xfffffff
+ cur_sys.load_offset = 0x80000000
+
+
diff --git a/src/dev/arm/SConscript b/src/dev/arm/SConscript
index 68779ec64..419e2f471 100644
--- a/src/dev/arm/SConscript
+++ b/src/dev/arm/SConscript
@@ -1,6 +1,6 @@
# -*- mode:python -*-
-# Copyright (c) 2009 ARM Limited
+# Copyright (c) 2009, 2012-2013 ARM Limited
# All rights reserved.
#
# The license below extends only to copyright in the software and shall
@@ -47,6 +47,7 @@ if env['TARGET_ISA'] == 'arm':
Source('amba_device.cc')
Source('amba_fake.cc')
Source('base_gic.cc')
+ Source('generic_timer.cc')
Source('gic_pl390.cc')
Source('pl011.cc')
Source('pl111.cc')
@@ -57,6 +58,7 @@ if env['TARGET_ISA'] == 'arm':
Source('realview.cc')
Source('rtc_pl031.cc')
Source('timer_cpulocal.cc')
+ Source('vgic.cc')
DebugFlag('AMBA')
DebugFlag('HDLcd')
@@ -64,3 +66,4 @@ if env['TARGET_ISA'] == 'arm':
DebugFlag('Pl050')
DebugFlag('GIC')
DebugFlag('RVCTRL')
+ DebugFlag('VGIC')
diff --git a/src/dev/arm/generic_timer.cc b/src/dev/arm/generic_timer.cc
new file mode 100644
index 000000000..555c1050f
--- /dev/null
+++ b/src/dev/arm/generic_timer.cc
@@ -0,0 +1,204 @@
+/*
+ * Copyright (c) 2013 ARM Limited
+ * All rights reserved.
+ *
+ * The license below extends only to copyright in the software and shall
+ * not be construed as granting a license to any other intellectual
+ * property including but not limited to intellectual property relating
+ * to a hardware implementation of the functionality of the software
+ * licensed hereunder. You may use the software subject to the license
+ * terms below provided that you ensure that this notice is replicated
+ * unmodified and in its entirety in all distributions of the software,
+ * modified or unmodified, in source code or in binary form.
+ *
+ * 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 copyright holders 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 BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
+ * A PARTICULAR PURPOSE 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.
+ *
+ * Authors: Giacomo Gabrielli
+ */
+
+#include "arch/arm/system.hh"
+#include "debug/Checkpoint.hh"
+#include "debug/Timer.hh"
+#include "dev/arm/base_gic.hh"
+#include "dev/arm/generic_timer.hh"
+
+void
+GenericTimer::SystemCounter::setFreq(uint32_t freq)
+{
+ if (_freq != 0) {
+ // Altering the frequency after boot shouldn't be done in practice.
+ warn_once("The frequency of the system counter has already been set");
+ }
+ _freq = freq;
+ _period = (1.0 / freq) * SimClock::Frequency;
+ _resetTick = curTick();
+}
+
+void
+GenericTimer::SystemCounter::serialize(std::ostream &os)
+{
+ SERIALIZE_SCALAR(_freq);
+ SERIALIZE_SCALAR(_period);
+ SERIALIZE_SCALAR(_resetTick);
+}
+
+void
+GenericTimer::SystemCounter::unserialize(Checkpoint *cp,
+ const std::string &section)
+{
+ UNSERIALIZE_SCALAR(_freq);
+ UNSERIALIZE_SCALAR(_period);
+ UNSERIALIZE_SCALAR(_resetTick);
+}
+
+void
+GenericTimer::ArchTimer::counterLimitReached()
+{
+ _control.istatus = 1;
+
+ if (!_control.enable)
+ return;
+
+ // DPRINTF(Timer, "Counter limit reached\n");
+
+ if (!_control.imask) {
+ // DPRINTF(Timer, "Causing interrupt\n");
+ _parent->_gic->sendPPInt(_intNum, _cpuNum);
+ }
+}
+
+void
+GenericTimer::ArchTimer::setCompareValue(uint64_t val)
+{
+ _counterLimit = val;
+ if (_counterLimitReachedEvent.scheduled())
+ _parent->deschedule(_counterLimitReachedEvent);
+ if (counterValue() >= _counterLimit) {
+ counterLimitReached();
+ } else {
+ _control.istatus = 0;
+ _parent->schedule(_counterLimitReachedEvent,
+ curTick() + (_counterLimit - counterValue()) * _counter->period());
+ }
+}
+
+void
+GenericTimer::ArchTimer::setTimerValue(uint32_t val)
+{
+ setCompareValue(counterValue() + sext<32>(val));
+}
+
+void
+GenericTimer::ArchTimer::setControl(uint32_t val)
+{
+ ArchTimerCtrl new_ctl = val;
+ if ((new_ctl.enable && !new_ctl.imask) &&
+ !(_control.enable && !_control.imask)) {
+ // Re-evalute the timer condition
+ if (_counterLimit >= counterValue()) {
+ _control.istatus = 1;
+
+ DPRINTF(Timer, "Causing interrupt in control\n");
+ //_parent->_gic->sendPPInt(_intNum, _cpuNum);
+ }
+ }
+ _control.enable = new_ctl.enable;
+ _control.imask = new_ctl.imask;
+}
+
+void
+GenericTimer::ArchTimer::serialize(std::ostream &os)
+{
+ SERIALIZE_SCALAR(_cpuNum);
+ SERIALIZE_SCALAR(_intNum);
+ uint32_t control_serial = _control;
+ SERIALIZE_SCALAR(control_serial);
+ SERIALIZE_SCALAR(_counterLimit);
+ bool event_scheduled = _counterLimitReachedEvent.scheduled();
+ SERIALIZE_SCALAR(event_scheduled);
+ Tick event_time;
+ if (event_scheduled) {
+ event_time = _counterLimitReachedEvent.when();
+ SERIALIZE_SCALAR(event_time);
+ }
+}
+
+void
+GenericTimer::ArchTimer::unserialize(Checkpoint *cp, const std::string &section)
+{
+ UNSERIALIZE_SCALAR(_cpuNum);
+ UNSERIALIZE_SCALAR(_intNum);
+ uint32_t control_serial;
+ UNSERIALIZE_SCALAR(control_serial);
+ _control = control_serial;
+ bool event_scheduled;
+ UNSERIALIZE_SCALAR(event_scheduled);
+ Tick event_time;
+ if (event_scheduled) {
+ UNSERIALIZE_SCALAR(event_time);
+ _parent->schedule(_counterLimitReachedEvent, event_time);
+ }
+}
+
+GenericTimer::GenericTimer(Params *p)
+ : SimObject(p), _gic(p->gic)
+{
+ for (int i = 0; i < CPU_MAX; ++i) {
+ std::stringstream oss;
+ oss << name() << ".arch_timer" << i;
+ _archTimers[i]._name = oss.str();
+ _archTimers[i]._parent = this;
+ _archTimers[i]._counter = &_systemCounter;
+ _archTimers[i]._cpuNum = i;
+ _archTimers[i]._intNum = p->int_num;
+ }
+
+ ((ArmSystem *) p->system)->setGenericTimer(this);
+}
+
+void
+GenericTimer::serialize(std::ostream &os)
+{
+ nameOut(os, csprintf("%s.sys_counter", name()));
+ _systemCounter.serialize(os);
+ for (int i = 0; i < CPU_MAX; ++i) {
+ nameOut(os, csprintf("%s.arch_timer%d", name(), i));
+ _archTimers[i].serialize(os);
+ }
+}
+
+void
+GenericTimer::unserialize(Checkpoint *cp, const std::string &section)
+{
+ _systemCounter.unserialize(cp, csprintf("%s.sys_counter", section));
+ for (int i = 0; i < CPU_MAX; ++i) {
+ _archTimers[i].unserialize(cp, csprintf("%s.arch_timer%d", section, i));
+ }
+}
+
+GenericTimer *
+GenericTimerParams::create()
+{
+ return new GenericTimer(this);
+}
diff --git a/src/dev/arm/generic_timer.hh b/src/dev/arm/generic_timer.hh
new file mode 100644
index 000000000..bc43f8b3b
--- /dev/null
+++ b/src/dev/arm/generic_timer.hh
@@ -0,0 +1,199 @@
+/*
+ * Copyright (c) 2013 ARM Limited
+ * All rights reserved.
+ *
+ * The license below extends only to copyright in the software and shall
+ * not be construed as granting a license to any other intellectual
+ * property including but not limited to intellectual property relating
+ * to a hardware implementation of the functionality of the software
+ * licensed hereunder. You may use the software subject to the license
+ * terms below provided that you ensure that this notice is replicated
+ * unmodified and in its entirety in all distributions of the software,
+ * modified or unmodified, in source code or in binary form.
+ *
+ * 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 copyright holders 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 BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
+ * A PARTICULAR PURPOSE 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.
+ *
+ * Authors: Giacomo Gabrielli
+ */
+
+#ifndef __DEV_ARM_GENERIC_TIMER_HH__
+#define __DEV_ARM_GENERIC_TIMER_HH__
+
+#include "base/bitunion.hh"
+#include "params/GenericTimer.hh"
+#include "sim/core.hh"
+#include "sim/sim_object.hh"
+
+/// @file
+/// This module implements the global system counter and the local per-CPU
+/// architected timers as specified by the ARM Generic Timer extension (ARM
+/// ARM, Issue C, Chapter 17).
+
+class Checkpoint;
+class BaseGic;
+
+/// Wrapper around the actual counters and timers of the Generic Timer
+/// extension.
+class GenericTimer : public SimObject
+{
+ public:
+
+ /// Global system counter. It is shared by the architected timers.
+ /// @todo: implement memory-mapped controls
+ class SystemCounter
+ {
+ protected:
+ /// Counter frequency (as specified by CNTFRQ).
+ uint64_t _freq;
+ /// Cached copy of the counter period (inverse of the frequency).
+ Tick _period;
+ /// Tick when the counter was reset.
+ Tick _resetTick;
+
+ public:
+ /// Ctor.
+ SystemCounter()
+ : _freq(0), _period(0), _resetTick(0)
+ {
+ setFreq(0x01800000);
+ }
+
+ /// Returns the current value of the physical counter.
+ uint64_t value() const
+ {
+ if (_freq == 0)
+ return 0; // Counter is still off.
+ return (curTick() - _resetTick) / _period;
+ }
+
+ /// Returns the counter frequency.
+ uint64_t freq() const { return _freq; }
+ /// Sets the counter frequency.
+ /// @param freq frequency in Hz.
+ void setFreq(uint32_t freq);
+
+ /// Returns the counter period.
+ Tick period() const { return _period; }
+
+ void serialize(std::ostream &os);
+ void unserialize(Checkpoint *cp, const std::string &section);
+ };
+
+ /// Per-CPU architected timer.
+ class ArchTimer
+ {
+ protected:
+ /// Control register.
+ BitUnion32(ArchTimerCtrl)
+ Bitfield<0> enable;
+ Bitfield<1> imask;
+ Bitfield<2> istatus;
+ EndBitUnion(ArchTimerCtrl)
+
+ /// Name of this timer.
+ std::string _name;
+ /// Pointer to parent class.
+ GenericTimer *_parent;
+ /// Pointer to the global system counter.
+ SystemCounter *_counter;
+ /// ID of the CPU this timer is attached to.
+ int _cpuNum;
+ /// ID of the interrupt to be triggered.
+ int _intNum;
+ /// Cached value of the control register ({CNTP/CNTHP/CNTV}_CTL).
+ ArchTimerCtrl _control;
+ /// Programmed limit value for the upcounter ({CNTP/CNTHP/CNTV}_CVAL).
+ uint64_t _counterLimit;
+
+ /// Called when the upcounter reaches the programmed value.
+ void counterLimitReached();
+ EventWrapper<ArchTimer, &ArchTimer::counterLimitReached>
+ _counterLimitReachedEvent;
+
+ /// Returns the value of the counter which this timer relies on.
+ uint64_t counterValue() const { return _counter->value(); }
+
+ public:
+ /// Ctor.
+ ArchTimer()
+ : _control(0), _counterLimit(0), _counterLimitReachedEvent(this)
+ {}
+
+ /// Returns the timer name.
+ std::string name() const { return _name; }
+
+ /// Returns the CompareValue view of the timer.
+ uint64_t compareValue() const { return _counterLimit; }
+ /// Sets the CompareValue view of the timer.
+ void setCompareValue(uint64_t val);
+
+ /// Returns the TimerValue view of the timer.
+ uint32_t timerValue() const { return _counterLimit - counterValue(); }
+ /// Sets the TimerValue view of the timer.
+ void setTimerValue(uint32_t val);
+
+ /// Sets the control register.
+ uint32_t control() const { return _control; }
+ void setControl(uint32_t val);
+
+ virtual void serialize(std::ostream &os);
+ virtual void unserialize(Checkpoint *cp, const std::string &section);
+
+ friend class GenericTimer;
+ };
+
+ protected:
+
+ static const int CPU_MAX = 8;
+
+ /// Pointer to the GIC, needed to trigger timer interrupts.
+ BaseGic *_gic;
+ /// System counter.
+ SystemCounter _systemCounter;
+ /// Per-CPU architected timers.
+ // @todo: this would become a 2-dim. array with Security and Virt.
+ ArchTimer _archTimers[CPU_MAX];
+
+ public:
+ typedef GenericTimerParams Params;
+ const Params *
+ params() const
+ {
+ return dynamic_cast<const Params *>(_params);
+ }
+
+ /// Ctor.
+ GenericTimer(Params *p);
+
+ /// Returns a pointer to the system counter.
+ SystemCounter *getSystemCounter() { return &_systemCounter; }
+
+ /// Returns a pointer to the architected timer for cpu_id.
+ ArchTimer *getArchTimer(int cpu_id) { return &_archTimers[cpu_id]; }
+
+ virtual void serialize(std::ostream &os);
+ virtual void unserialize(Checkpoint *cp, const std::string &section);
+};
+
+#endif // __DEV_ARM_GENERIC_TIMER_HH__
diff --git a/src/dev/arm/gic_pl390.cc b/src/dev/arm/gic_pl390.cc
index d2a660e88..7fc65b2b7 100644
--- a/src/dev/arm/gic_pl390.cc
+++ b/src/dev/arm/gic_pl390.cc
@@ -56,7 +56,8 @@ Pl390::Pl390(const Params *p)
: BaseGic(p), distAddr(p->dist_addr),
cpuAddr(p->cpu_addr), distPioDelay(p->dist_pio_delay),
cpuPioDelay(p->cpu_pio_delay), intLatency(p->int_latency),
- enabled(false), itLines(p->it_lines), msixRegAddr(p->msix_addr),
+ enabled(false), itLines(p->it_lines), irqEnable(false),
+ msixRegAddr(p->msix_addr),
msixReg(0x0)
{
itLinesLog2 = ceilLog2(itLines);
diff --git a/src/dev/arm/vgic.cc b/src/dev/arm/vgic.cc
new file mode 100644
index 000000000..2faf2030e
--- /dev/null
+++ b/src/dev/arm/vgic.cc
@@ -0,0 +1,553 @@
+/*
+ * Copyright (c) 2013 ARM Limited
+ * All rights reserved
+ *
+ * The license below extends only to copyright in the software and shall
+ * not be construed as granting a license to any other intellectual
+ * property including but not limited to intellectual property relating
+ * to a hardware implementation of the functionality of the software
+ * licensed hereunder. You may use the software subject to the license
+ * terms below provided that you ensure that this notice is replicated
+ * unmodified and in its entirety in all distributions of the software,
+ * modified or unmodified, in source code or in binary form.
+ *
+ * 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 copyright holders 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 BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
+ * A PARTICULAR PURPOSE 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.
+ *
+ * Authors: Matt Evans
+ */
+
+#include "base/trace.hh"
+#include "debug/Checkpoint.hh"
+#include "debug/VGIC.hh"
+#include "dev/arm/base_gic.hh"
+#include "dev/arm/vgic.hh"
+#include "dev/terminal.hh"
+#include "mem/packet.hh"
+#include "mem/packet_access.hh"
+
+VGic::VGic(const Params *p)
+ : PioDevice(p), platform(p->platform), gic(p->gic), vcpuAddr(p->vcpu_addr),
+ hvAddr(p->hv_addr), pioDelay(p->pio_delay),
+ maintInt(p->ppint)
+{
+ for (int x = 0; x < VGIC_CPU_MAX; x++) {
+ postVIntEvent[x] = new PostVIntEvent(x, p->platform);
+ maintIntPosted[x] = false;
+ vIntPosted[x] = false;
+ }
+ for (int c = 0; c < VGIC_CPU_MAX; c++) {
+ memset(&vcpuData[c], 0, sizeof(struct vcpuIntData));
+ }
+ assert(sys->numRunningContexts() <= VGIC_CPU_MAX);
+}
+
+Tick
+VGic::read(PacketPtr pkt)
+{
+ Addr addr = pkt->getAddr();
+
+ if (addr >= vcpuAddr && addr < vcpuAddr + GICV_SIZE)
+ return readVCpu(pkt);
+ else if (addr >= hvAddr && addr < hvAddr + GICH_REG_SIZE)
+ return readCtrl(pkt);
+ else
+ panic("Read to unknown address %#x\n", pkt->getAddr());
+}
+
+Tick
+VGic::write(PacketPtr pkt)
+{
+ Addr addr = pkt->getAddr();
+
+ if (addr >= vcpuAddr && addr < vcpuAddr + GICV_SIZE)
+ return writeVCpu(pkt);
+ else if (addr >= hvAddr && addr < hvAddr + GICH_REG_SIZE)
+ return writeCtrl(pkt);
+ else
+ panic("Write to unknown address %#x\n", pkt->getAddr());
+}
+
+Tick
+VGic::readVCpu(PacketPtr pkt)
+{
+ Addr daddr = pkt->getAddr() - vcpuAddr;
+ pkt->allocate();
+
+ int ctx_id = pkt->req->contextId();
+ assert(ctx_id < VGIC_CPU_MAX);
+ struct vcpuIntData *vid = &vcpuData[ctx_id];
+
+ DPRINTF(VGIC, "VGIC VCPU read register %#x\n", daddr);
+
+ switch (daddr) {
+ case GICV_CTLR:
+ pkt->set<uint32_t>(vid->vctrl);
+ break;
+ case GICV_IAR: {
+ int i = findHighestPendingLR(vid);
+ if (i < 0 || !vid->vctrl.En) {
+ pkt->set<uint32_t>(1023); // "No int" marker
+ } else {
+ ListReg *lr = &vid->LR[i];
+
+ pkt->set<uint32_t>(lr->VirtualID |
+ (((int)lr->CpuID) << 10));
+ // We don't support auto-EOI of HW interrupts via real GIC!
+ // Fortunately, KVM doesn't use this. How about Xen...? Ulp!
+ if (lr->HW)
+ panic("VGIC does not support 'HW' List Register feature (LR %#x)!\n",
+ *lr);
+ lr->State = LR_ACTIVE;
+ DPRINTF(VGIC, "Consumed interrupt %d (cpu%d) from LR%d (EOI%d)\n",
+ lr->VirtualID, lr->CpuID, i, lr->EOI);
+ }
+ } break;
+ default:
+ panic("VGIC VCPU read of bad address %#x\n", daddr);
+ }
+
+ updateIntState(ctx_id);
+
+ pkt->makeAtomicResponse();
+ return pioDelay;
+}
+
+Tick
+VGic::readCtrl(PacketPtr pkt)
+{
+ Addr daddr = pkt->getAddr() - hvAddr;
+ pkt->allocate();
+
+ int ctx_id = pkt->req->contextId();
+
+ DPRINTF(VGIC, "VGIC HVCtrl read register %#x\n", daddr);
+
+ /* Munge the address: 0-0xfff is the usual space banked by requester CPU.
+ * Anything > that is 0x200-sized slices of 'per CPU' regs.
+ */
+ if (daddr & ~0x1ff) {
+ ctx_id = (daddr >> 9);
+ if (ctx_id > 8)
+ panic("VGIC: Weird unbanked hv ctrl address %#x!\n", daddr);
+ daddr &= ~0x1ff;
+ }
+ assert(ctx_id < VGIC_CPU_MAX);
+ struct vcpuIntData *vid = &vcpuData[ctx_id];
+
+ switch (daddr) {
+ case GICH_HCR:
+ pkt->set<uint32_t>(vid->hcr);
+ break;
+
+ case GICH_VTR:
+ pkt->set<uint32_t>(0x44000000 | (NUM_LR - 1));
+ break;
+
+ case GICH_VMCR:
+ pkt->set<uint32_t>(
+ ((uint32_t)vid->VMPriMask << 27) |
+ ((uint32_t)vid->VMBP << 21) |
+ ((uint32_t)vid->VMABP << 18) |
+ ((uint32_t)vid->VEM << 9) |
+ ((uint32_t)vid->VMCBPR << 4) |
+ ((uint32_t)vid->VMFiqEn << 3) |
+ ((uint32_t)vid->VMAckCtl << 2) |
+ ((uint32_t)vid->VMGrp1En << 1) |
+ ((uint32_t)vid->VMGrp0En << 0)
+ );
+ break;
+
+ case GICH_MISR:
+ pkt->set<uint32_t>(getMISR(vid));
+ break;
+
+ case GICH_EISR0:
+ pkt->set<uint32_t>(vid->eisr & 0xffffffff);
+ break;
+
+ case GICH_EISR1:
+ pkt->set<uint32_t>(vid->eisr >> 32);
+ break;
+
+ case GICH_ELSR0: {
+ uint32_t bm = 0;
+ for (int i = 0; i < ((NUM_LR < 32) ? NUM_LR : 32); i++) {
+ if (!vid->LR[i].State)
+ bm |= 1 << i;
+ }
+ pkt->set<uint32_t>(bm);
+ } break;
+
+ case GICH_ELSR1: {
+ uint32_t bm = 0;
+ for (int i = 32; i < NUM_LR; i++) {
+ if (!vid->LR[i].State)
+ bm |= 1 << (i-32);
+ }
+ pkt->set<uint32_t>(bm);
+ } break;
+
+ case GICH_APR0:
+ warn_once("VGIC GICH_APR read!\n");
+ pkt->set<uint32_t>(0);
+ break;
+
+ case GICH_LR0:
+ case GICH_LR1:
+ case GICH_LR2:
+ case GICH_LR3:
+ pkt->set<uint32_t>(vid->LR[(daddr - GICH_LR0) >> 2]);
+ break;
+
+ default:
+ panic("VGIC HVCtrl read of bad address %#x\n", daddr);
+ }
+
+ pkt->makeAtomicResponse();
+ return pioDelay;
+}
+
+Tick
+VGic::writeVCpu(PacketPtr pkt)
+{
+ Addr daddr = pkt->getAddr() - vcpuAddr;
+ pkt->allocate();
+
+ int ctx_id = pkt->req->contextId();
+ assert(ctx_id < VGIC_CPU_MAX);
+ struct vcpuIntData *vid = &vcpuData[ctx_id];
+
+ DPRINTF(VGIC, "VGIC VCPU write register %#x <= %#x\n", daddr, pkt->get<uint32_t>());
+
+ switch (daddr) {
+ case GICV_CTLR:
+ vid->vctrl = pkt->get<uint32_t>();
+ break;
+ case GICV_PMR:
+ vid->VMPriMask = pkt->get<uint32_t>();
+ break;
+ case GICV_EOIR: {
+ // We don't handle the split EOI-then-DIR mode. Linux (guest)
+ // doesn't need it though.
+ assert(!vid->vctrl.EOImode);
+ uint32_t w = pkt->get<uint32_t>();
+ unsigned int virq = w & 0x3ff;
+ unsigned int vcpu = (w >> 10) & 7;
+ int i = findLRForVIRQ(vid, virq, vcpu);
+ if (i < 0) {
+ DPRINTF(VGIC, "EOIR: No LR for irq %d(cpu%d)\n", virq, vcpu);
+ } else {
+ DPRINTF(VGIC, "EOIR: Found LR%d for irq %d(cpu%d)\n", i, virq, vcpu);
+ ListReg *lr = &vid->LR[i];
+ lr->State = 0;
+ // Maintenance interrupt -- via eisr -- is flagged when
+ // LRs have EOI=1 and State=INVALID!
+ }
+ } break;
+ default:
+ panic("VGIC VCPU write %#x to unk address %#x\n", pkt->get<uint32_t>(), daddr);
+ }
+
+ // This updates the EISRs and flags IRQs:
+ updateIntState(ctx_id);
+
+ pkt->makeAtomicResponse();
+ return pioDelay;
+}
+
+Tick
+VGic::writeCtrl(PacketPtr pkt)
+{
+ Addr daddr = pkt->getAddr() - hvAddr;
+ pkt->allocate();
+
+ int ctx_id = pkt->req->contextId();
+
+ DPRINTF(VGIC, "VGIC HVCtrl write register %#x <= %#x\n", daddr, pkt->get<uint32_t>());
+
+ /* Munge the address: 0-0xfff is the usual space banked by requester CPU.
+ * Anything > that is 0x200-sized slices of 'per CPU' regs.
+ */
+ if (daddr & ~0x1ff) {
+ ctx_id = (daddr >> 9);
+ if (ctx_id > 8)
+ panic("VGIC: Weird unbanked hv ctrl address %#x!\n", daddr);
+ daddr &= ~0x1ff;
+ }
+ assert(ctx_id < VGIC_CPU_MAX);
+ struct vcpuIntData *vid = &vcpuData[ctx_id];
+
+ switch (daddr) {
+ case GICH_HCR:
+ vid->hcr = pkt->get<uint32_t>();
+ // update int state
+ break;
+
+ case GICH_VMCR: {
+ uint32_t d = pkt->get<uint32_t>();
+ vid->VMPriMask = d >> 27;
+ vid->VMBP = (d >> 21) & 7;
+ vid->VMABP = (d >> 18) & 7;
+ vid->VEM = (d >> 9) & 1;
+ vid->VMCBPR = (d >> 4) & 1;
+ vid->VMFiqEn = (d >> 3) & 1;
+ vid->VMAckCtl = (d >> 2) & 1;
+ vid->VMGrp1En = (d >> 1) & 1;
+ vid->VMGrp0En = d & 1;
+ } break;
+
+ case GICH_APR0:
+ warn_once("VGIC GICH_APR0 written, ignored\n");
+ break;
+
+ case GICH_LR0:
+ case GICH_LR1:
+ case GICH_LR2:
+ case GICH_LR3:
+ vid->LR[(daddr - GICH_LR0) >> 2] = pkt->get<uint32_t>();
+ // update int state
+ break;
+
+ default:
+ panic("VGIC HVCtrl write to bad address %#x\n", daddr);
+ }
+
+ updateIntState(ctx_id);
+
+ pkt->makeAtomicResponse();
+ return pioDelay;
+}
+
+
+uint32_t
+VGic::getMISR(struct vcpuIntData *vid)
+{
+ return (!!vid->hcr.VGrp1DIE && !vid->VMGrp1En ? 0x80 : 0) |
+ (!!vid->hcr.VGrp1EIE && vid->VMGrp1En ? 0x40 : 0) |
+ (!!vid->hcr.VGrp0DIE && !vid->VMGrp0En ? 0x20 : 0) |
+ (!!vid->hcr.VGrp0EIE && vid->VMGrp0En ? 0x10 : 0) |
+ (!!vid->hcr.NPIE && !lrPending(vid) ? 0x08 : 0) |
+ (!!vid->hcr.LRENPIE && vid->hcr.EOICount ? 0x04 : 0) |
+ (!!vid->hcr.UIE && lrValid(vid) <= 1 ? 0x02 : 0) |
+ (vid->eisr ? 0x01 : 0);
+}
+
+void
+VGic::postVInt(uint32_t cpu, Tick when)
+{
+ DPRINTF(VGIC, "Posting VIRQ to %d\n", cpu);
+ if (!(postVIntEvent[cpu]->scheduled()))
+ eventq->schedule(postVIntEvent[cpu], when);
+}
+
+void
+VGic::unPostVInt(uint32_t cpu)
+{
+ DPRINTF(VGIC, "Unposting VIRQ to %d\n", cpu);
+ platform->intrctrl->clear(cpu, ArmISA::INT_VIRT_IRQ, 0);
+}
+
+void
+VGic::postMaintInt(uint32_t cpu)
+{
+ DPRINTF(VGIC, "Posting maintenance PPI to GIC/cpu%d\n", cpu);
+ // Linux DT configures this as Level.
+ gic->sendPPInt(maintInt, cpu);
+}
+
+void
+VGic::unPostMaintInt(uint32_t cpu)
+{
+ DPRINTF(VGIC, "Unposting maintenance PPI to GIC/cpu%d\n", cpu);
+ gic->clearPPInt(maintInt, cpu);
+}
+
+/* Update state (in general); something concerned with ctx_id has changed.
+ * This may raise a maintenance interrupt.
+ */
+void
+VGic::updateIntState(int ctx_id)
+{
+ // @todo This should update APRs!
+
+ // Build EISR contents:
+ // (Cached so that regs can read them without messing about again)
+ struct vcpuIntData *tvid = &vcpuData[ctx_id];
+
+ tvid->eisr = 0;
+ for (int i = 0; i < NUM_LR; i++) {
+ if (!tvid->LR[i].State && tvid->LR[i].EOI) {
+ tvid->eisr |= 1 << i;
+ }
+ }
+
+ assert(sys->numRunningContexts() <= VGIC_CPU_MAX);
+ for (int i = 0; i < sys->numRunningContexts(); i++) {
+ struct vcpuIntData *vid = &vcpuData[i];
+ // Are any LRs active that weren't before?
+ if (!vIntPosted[i]) {
+ if (lrPending(vid) && vid->vctrl.En) {
+ vIntPosted[i] = true;
+ postVInt(i, curTick() + 1);
+ }
+ } else if (!lrPending(vid)) {
+ vIntPosted[i] = false;
+ unPostVInt(i);
+ }
+
+ // Any maintenance ints to send?
+ if (!maintIntPosted[i]) {
+ if (vid->hcr.En && getMISR(vid)) {
+ maintIntPosted[i] = true;
+ postMaintInt(i);
+ }
+ } else {
+ if (!vid->hcr.En || !getMISR(vid)) {
+ unPostMaintInt(i);
+ maintIntPosted[i] = false;
+ }
+ }
+ }
+}
+
+AddrRangeList
+VGic::getAddrRanges() const
+{
+ AddrRangeList ranges;
+ ranges.push_back(RangeSize(hvAddr, GICH_REG_SIZE));
+ ranges.push_back(RangeSize(vcpuAddr, GICV_SIZE));
+ return ranges;
+}
+
+void
+VGic::serialize(std::ostream &os)
+{
+ Tick interrupt_time[VGIC_CPU_MAX];
+ for (uint32_t cpu = 0; cpu < VGIC_CPU_MAX; cpu++) {
+ interrupt_time[cpu] = 0;
+ if (postVIntEvent[cpu]->scheduled()) {
+ interrupt_time[cpu] = postVIntEvent[cpu]->when();
+ }
+ }
+
+ DPRINTF(Checkpoint, "Serializing VGIC\n");
+
+ SERIALIZE_ARRAY(interrupt_time, VGIC_CPU_MAX);
+ SERIALIZE_ARRAY(maintIntPosted, VGIC_CPU_MAX);
+ SERIALIZE_ARRAY(vIntPosted, VGIC_CPU_MAX);
+ SERIALIZE_SCALAR(vcpuAddr);
+ SERIALIZE_SCALAR(hvAddr);
+ SERIALIZE_SCALAR(pioDelay);
+ SERIALIZE_SCALAR(maintInt);
+
+ for (uint32_t cpu = 0; cpu < VGIC_CPU_MAX; cpu++) {
+ nameOut(os, csprintf("%s.vcpuData%d", name(), cpu));
+ uint32_t vctrl_val = vcpuData[cpu].vctrl;
+ SERIALIZE_SCALAR(vctrl_val);
+ uint32_t hcr_val = vcpuData[cpu].hcr;
+ SERIALIZE_SCALAR(hcr_val);
+ uint64_t eisr_val = vcpuData[cpu].eisr;
+ SERIALIZE_SCALAR(eisr_val);
+ uint8_t VMGrp0En_val = vcpuData[cpu].VMGrp0En;
+ SERIALIZE_SCALAR(VMGrp0En_val);
+ uint8_t VMGrp1En_val = vcpuData[cpu].VMGrp1En;
+ SERIALIZE_SCALAR(VMGrp1En_val);
+ uint8_t VMAckCtl_val = vcpuData[cpu].VMAckCtl;
+ SERIALIZE_SCALAR(VMAckCtl_val);
+ uint8_t VMFiqEn_val = vcpuData[cpu].VMFiqEn;
+ SERIALIZE_SCALAR(VMFiqEn_val);
+ uint8_t VMCBPR_val = vcpuData[cpu].VMCBPR;
+ SERIALIZE_SCALAR(VMCBPR_val);
+ uint8_t VEM_val = vcpuData[cpu].VEM;
+ SERIALIZE_SCALAR(VEM_val);
+ uint8_t VMABP_val = vcpuData[cpu].VMABP;
+ SERIALIZE_SCALAR(VMABP_val);
+ uint8_t VMBP_val = vcpuData[cpu].VMBP;
+ SERIALIZE_SCALAR(VMBP_val);
+ uint8_t VMPriMask_val = vcpuData[cpu].VMPriMask;
+ SERIALIZE_SCALAR(VMPriMask_val);
+
+ for (int i = 0; i < NUM_LR; i++) {
+ uint32_t lr = vcpuData[cpu].LR[i];
+ nameOut(os, csprintf("%s.vcpuData%d.LR%d", name(), cpu, i));
+ SERIALIZE_SCALAR(lr);
+ }
+ }
+}
+
+void VGic::unserialize(Checkpoint *cp, const std::string &section)
+{
+ DPRINTF(Checkpoint, "Unserializing Arm GIC\n");
+
+ Tick interrupt_time[VGIC_CPU_MAX];
+ UNSERIALIZE_ARRAY(interrupt_time, VGIC_CPU_MAX);
+ for (uint32_t cpu = 0; cpu < VGIC_CPU_MAX; cpu++) {
+ if (interrupt_time[cpu])
+ schedule(postVIntEvent[cpu], interrupt_time[cpu]);
+
+ uint32_t tmp;
+ paramIn(cp, csprintf("%s.vcpuData%d", section, cpu),
+ "vctrl_val", tmp);
+ vcpuData[cpu].vctrl = tmp;
+ paramIn(cp, csprintf("%s.vcpuData%d", section, cpu),
+ "hcr_val", tmp);
+ vcpuData[cpu].hcr = tmp;
+ paramIn(cp, csprintf("%s.vcpuData%d", section, cpu),
+ "eisr_val", vcpuData[cpu].eisr);
+ paramIn(cp, csprintf("%s.vcpuData%d", section, cpu),
+ "VMGrp0En_val", vcpuData[cpu].VMGrp0En);
+ paramIn(cp, csprintf("%s.vcpuData%d", section, cpu),
+ "VMGrp1En_val", vcpuData[cpu].VMGrp1En);
+ paramIn(cp, csprintf("%s.vcpuData%d", section, cpu),
+ "VMAckCtl_val", vcpuData[cpu].VMAckCtl);
+ paramIn(cp, csprintf("%s.vcpuData%d", section, cpu),
+ "VMFiqEn_val", vcpuData[cpu].VMFiqEn);
+ paramIn(cp, csprintf("%s.vcpuData%d", section, cpu),
+ "VMCBPR_val", vcpuData[cpu].VMCBPR);
+ paramIn(cp, csprintf("%s.vcpuData%d", section, cpu),
+ "VEM_val", vcpuData[cpu].VEM);
+ paramIn(cp, csprintf("%s.vcpuData%d", section, cpu),
+ "VMABP_val", vcpuData[cpu].VMABP);
+ paramIn(cp, csprintf("%s.vcpuData%d", section, cpu),
+ "VMPriMask_val", vcpuData[cpu].VMPriMask);
+
+ for (int i = 0; i < NUM_LR; i++) {
+ paramIn(cp, csprintf("%s.vcpuData%d.LR%d", section, cpu, i),
+ "lr", tmp);
+ vcpuData[cpu].LR[i] = tmp;
+ }
+ }
+ UNSERIALIZE_ARRAY(maintIntPosted, VGIC_CPU_MAX);
+ UNSERIALIZE_ARRAY(vIntPosted, VGIC_CPU_MAX);
+ UNSERIALIZE_SCALAR(vcpuAddr);
+ UNSERIALIZE_SCALAR(hvAddr);
+ UNSERIALIZE_SCALAR(pioDelay);
+ UNSERIALIZE_SCALAR(maintInt);
+}
+
+VGic *
+VGicParams::create()
+{
+ return new VGic(this);
+}
diff --git a/src/dev/arm/vgic.hh b/src/dev/arm/vgic.hh
new file mode 100644
index 000000000..e1c4960e9
--- /dev/null
+++ b/src/dev/arm/vgic.hh
@@ -0,0 +1,262 @@
+/*
+ * Copyright (c) 2013 ARM Limited
+ * All rights reserved
+ *
+ * The license below extends only to copyright in the software and shall
+ * not be construed as granting a license to any other intellectual
+ * property including but not limited to intellectual property relating
+ * to a hardware implementation of the functionality of the software
+ * licensed hereunder. You may use the software subject to the license
+ * terms below provided that you ensure that this notice is replicated
+ * unmodified and in its entirety in all distributions of the software,
+ * modified or unmodified, in source code or in binary form.
+ *
+ * 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 copyright holders 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 BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
+ * A PARTICULAR PURPOSE 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.
+ *
+ * Authors: Matt Evans
+ */
+
+
+/** @file
+ * Implementiation of a GIC-400 List Register-based VGIC interface.
+ * The VGIC is, in this implementation, completely separate from the GIC itself.
+ * Only a VIRQ line to the CPU and a PPI line to the GIC (for a HV maintenance IRQ)
+ * is required.
+ *
+ * The mode in which the List Registers may flag (via LR.HW) that a hardware EOI
+ * is to be performed is NOT supported. (This requires tighter integration with
+ * the GIC.)
+ */
+
+#ifndef __DEV_ARM_VGIC_H__
+#define __DEV_ARM_VGIC_H__
+
+#include "base/addr_range.hh"
+#include "base/bitunion.hh"
+#include "cpu/intr_control.hh"
+#include "dev/io_device.hh"
+#include "dev/platform.hh"
+#include "params/VGic.hh"
+
+class VGic : public PioDevice
+{
+ private:
+ static const int VGIC_CPU_MAX = 256;
+ static const int NUM_LR = 4;
+
+ static const int GICH_SIZE = 0x200;
+ static const int GICH_REG_SIZE = 0x2000;
+
+ static const int GICH_HCR = 0x000;
+ static const int GICH_VTR = 0x004;
+ static const int GICH_VMCR = 0x008;
+ static const int GICH_MISR = 0x010;
+ static const int GICH_EISR0 = 0x020;
+ static const int GICH_EISR1 = 0x024;
+ static const int GICH_ELSR0 = 0x030;
+ static const int GICH_ELSR1 = 0x034;
+ static const int GICH_APR0 = 0x0f0;
+ static const int GICH_LR0 = 0x100;
+ static const int GICH_LR1 = 0x104;
+ static const int GICH_LR2 = 0x108;
+ static const int GICH_LR3 = 0x10c;
+
+ static const int GICV_SIZE = 0x2000;
+ static const int GICV_CTLR = 0x000;
+ static const int GICV_PMR = 0x004;
+ static const int GICV_BPR = 0x008;
+ static const int GICV_IAR = 0x00c;
+ static const int GICV_EOIR = 0x010;
+ static const int GICV_RPR = 0x014;
+ static const int GICV_HPPIR = 0x018;
+ static const int GICV_ABPR = 0x01c;
+ static const int GICV_AIAR = 0x020;
+ static const int GICV_AEOIR = 0x024;
+ static const int GICV_AHPPIR = 0x028;
+ static const int GICV_APR0 = 0x0d0;
+ static const int GICV_IIDR = 0x0fc;
+ static const int GICV_DIR = 0x1000;
+
+ static const uint32_t LR_PENDING = 1;
+ static const uint32_t LR_ACTIVE = 2;
+
+ /** Event definition to post interrupt to CPU after a delay
+ */
+ class PostVIntEvent : public Event
+ {
+ private:
+ uint32_t cpu;
+ Platform *platform;
+ public:
+ PostVIntEvent( uint32_t c, Platform* p)
+ : cpu(c), platform(p)
+ { }
+ void process() { platform->intrctrl->post(cpu, ArmISA::INT_VIRT_IRQ, 0);}
+ const char *description() const { return "Post VInterrupt to CPU"; }
+ };
+
+ PostVIntEvent *postVIntEvent[VGIC_CPU_MAX];
+ bool maintIntPosted[VGIC_CPU_MAX];
+ bool vIntPosted[VGIC_CPU_MAX];
+
+ Platform *platform;
+ BaseGic *gic;
+
+ Addr vcpuAddr;
+ Addr hvAddr;
+ Tick pioDelay;
+ int maintInt;
+
+ BitUnion32(ListReg)
+ Bitfield<31> HW;
+ Bitfield<30> Grp1;
+ Bitfield<29,28> State;
+ Bitfield<27,23> Priority;
+ Bitfield<19> EOI;
+ Bitfield<12,10> CpuID;
+ Bitfield<9,0> VirtualID;
+ EndBitUnion(ListReg)
+
+ BitUnion32(HCR)
+ Bitfield<31,27> EOICount;
+ Bitfield<7> VGrp1DIE;
+ Bitfield<6> VGrp1EIE;
+ Bitfield<5> VGrp0DIE;
+ Bitfield<4> VGrp0EIE;
+ Bitfield<3> NPIE;
+ Bitfield<2> LRENPIE;
+ Bitfield<1> UIE;
+ Bitfield<0> En;
+ EndBitUnion(HCR)
+
+ BitUnion32(VCTLR)
+ Bitfield<9> EOImode;
+ Bitfield<4> CPBR;
+ Bitfield<3> FIQEn;
+ Bitfield<2> AckCtl;
+ Bitfield<1> EnGrp1;
+ Bitfield<0> En; // This gets written to enable, not group 1.
+ EndBitUnion(VCTLR)
+
+ /* State per CPU. EVERYTHING should be in this struct and simply replicated
+ * N times.
+ */
+ struct vcpuIntData {
+ ListReg LR[NUM_LR];
+ VCTLR vctrl;
+
+ HCR hcr;
+ uint64_t eisr;
+
+ /* Host info, guest info (should be 100% accessible via GICH_* regs!) */
+ uint8_t VMGrp0En;
+ uint8_t VMGrp1En;
+ uint8_t VMAckCtl;
+ uint8_t VMFiqEn;
+ uint8_t VMCBPR;
+ uint8_t VEM;
+ uint8_t VMABP;
+ uint8_t VMBP;
+ uint8_t VMPriMask;
+ };
+
+ struct vcpuIntData vcpuData[VGIC_CPU_MAX];
+
+ public:
+ typedef VGicParams Params;
+ const Params *
+ params() const
+ {
+ return dynamic_cast<const Params *>(_params);
+ }
+ VGic(const Params *p);
+
+ virtual AddrRangeList getAddrRanges() const;
+
+ virtual Tick read(PacketPtr pkt);
+ virtual Tick write(PacketPtr pkt);
+
+ virtual void serialize(std::ostream &os);
+ virtual void unserialize(Checkpoint *cp, const std::string &section);
+
+ private:
+ Tick readVCpu(PacketPtr pkt);
+ Tick readCtrl(PacketPtr pkt);
+
+ Tick writeVCpu(PacketPtr pkt);
+ Tick writeCtrl(PacketPtr pkt);
+
+ void updateIntState(int ctx_id);
+ uint32_t getMISR(struct vcpuIntData *vid);
+ void postVInt(uint32_t cpu, Tick when);
+ void unPostVInt(uint32_t cpu);
+ void postMaintInt(uint32_t cpu);
+ void unPostMaintInt(uint32_t cpu);
+
+ unsigned int lrPending(struct vcpuIntData *vid)
+ {
+ unsigned int pend = 0;
+ for (int i = 0; i < NUM_LR; i++) {
+ if (vid->LR[i].State & LR_PENDING)
+ pend++;
+ }
+ return pend;
+ }
+ unsigned int lrValid(struct vcpuIntData *vid)
+ {
+ unsigned int valid = 0;
+ for (int i = 0; i < NUM_LR; i++) {
+ if (vid->LR[i].State)
+ valid++;
+ }
+ return valid;
+ }
+
+ /** Returns LR index or -1 if none pending */
+ int findHighestPendingLR(struct vcpuIntData *vid)
+ {
+ unsigned int prio = 0xff;
+ int p = -1;
+ for (int i = 0; i < NUM_LR; i++) {
+ if ((vid->LR[i].State & LR_PENDING) && (vid->LR[i].Priority < prio)) {
+ p = i;
+ prio = vid->LR[i].Priority;
+ }
+ }
+ return p;
+ }
+
+ int findLRForVIRQ(struct vcpuIntData *vid, int virq, int vcpu)
+ {
+ for (int i = 0; i < NUM_LR; i++) {
+ if (vid->LR[i].State &&
+ vid->LR[i].VirtualID == virq &&
+ vid->LR[i].CpuID == vcpu)
+ return i;
+ }
+ return -1;
+ }
+};
+
+#endif