Add initial interrupt support for Microwatt in LiteX

There is a conflict between the LiteX way of doing things and the POWER
way of handling interrupt tables.  LiteX expects to be able to put a ROM
at address 0 and load an application into RAM at a higher address; POWER
is architected to jump to exception handlers at 0x100...0x1000.

As a result of this, we have taken the approach of placing generic exception
handler entry / exit routines into ROM, and reserving a single pointer in
SRAM to determine the C ISR handler location.  If no application is loaded,
this pointer is set to the BIOS ROM ISR.  When an application loads, before
reenabling interrupts, it needs to set __rom_isr_address to the address of
the application's ISR, otherwise the BIOS ROM ISR will continue to be used.

Tested to operate with the built-in UART in IRQ mode, both in BIOS and in
loaded RAM application.
This commit is contained in:
Raptor Engineering Development Team 2020-10-16 14:45:55 -05:00
parent af82abb807
commit 90d71ec247
6 changed files with 680 additions and 9 deletions

View File

@ -3,6 +3,7 @@
#
# Copyright (c) 2019 Florent Kermarrec <florent@enjoy-digital.fr>
# Copyright (c) 2019 Benjamin Herrenschmidt <benh@ozlabs.org>
# Copyright (c) 2020 Raptor Engineering <sales@raptorengineering.com>
# SPDX-License-Identifier: BSD-2-Clause
import os
@ -11,11 +12,134 @@ from migen import *
from litex import get_data_mod
from litex.soc.interconnect import wishbone
from litex.soc.interconnect.csr import *
from litex.gen.common import reverse_bytes
from litex.soc.cores.cpu import CPU
CPU_VARIANTS = ["standard", "standard+ghdl"]
class XICSSlave(Module, AutoCSR):
def __init__(self, platform, core_irq_out=Signal(), int_level_in=Signal(16), endianness="big", variant="standard"):
self.variant = variant
self.icp_bus = icp_bus = wishbone.Interface(data_width=32, adr_width=12)
self.ics_bus = ics_bus = wishbone.Interface(data_width=32, adr_width=12)
# Bus endianness handlers
self.icp_dat_w = Signal(32)
self.icp_dat_r = Signal(32)
self.comb += self.icp_dat_w.eq(icp_bus.dat_w if endianness == "big" else reverse_bytes(icp_bus.dat_w))
self.comb += icp_bus.dat_r.eq(self.icp_dat_r if endianness == "big" else reverse_bytes(self.icp_dat_r))
self.ics_dat_w = Signal(32)
self.ics_dat_r = Signal(32)
self.comb += self.ics_dat_w.eq(ics_bus.dat_w if endianness == "big" else reverse_bytes(ics_bus.dat_w))
self.comb += ics_bus.dat_r.eq(self.ics_dat_r if endianness == "big" else reverse_bytes(self.ics_dat_r))
# XICS signals
self.ics_icp_xfer_src = Signal(4)
self.ics_icp_xfer_pri = Signal(8)
self.icp_params = dict(
# Clock / Reset
i_clk = ClockSignal(),
i_rst = ResetSignal(),
# Wishbone bus
o_wishbone_dat_r = self.icp_dat_r,
o_wishbone_ack = icp_bus.ack,
i_wishbone_adr = icp_bus.adr,
i_wishbone_dat_w = self.icp_dat_w,
i_wishbone_cyc = icp_bus.cyc,
i_wishbone_stb = icp_bus.stb,
i_wishbone_sel = icp_bus.sel,
i_wishbone_we = icp_bus.we,
i_ics_in_src = self.ics_icp_xfer_src,
i_ics_in_pri = self.ics_icp_xfer_pri,
o_core_irq_out = core_irq_out,
)
self.ics_params = dict(
# Clock / Reset
i_clk = ClockSignal(),
i_rst = ResetSignal(),
# Wishbone bus
o_wishbone_dat_r = self.ics_dat_r,
o_wishbone_ack = ics_bus.ack,
i_wishbone_adr = ics_bus.adr,
i_wishbone_dat_w = self.ics_dat_w,
i_wishbone_cyc = ics_bus.cyc,
i_wishbone_stb = ics_bus.stb,
i_wishbone_sel = ics_bus.sel,
i_wishbone_we = ics_bus.we,
i_int_level_in = int_level_in,
o_icp_out_src = self.ics_icp_xfer_src,
o_icp_out_pri = self.ics_icp_xfer_pri,
)
# add vhdl sources
self.add_sources(platform, use_ghdl_yosys_plugin="ghdl" in self.variant)
@staticmethod
def add_sources(platform, use_ghdl_yosys_plugin=False):
sources = [
# Common / Types / Helpers
"decode_types.vhdl",
"wishbone_types.vhdl",
"utils.vhdl",
"common.vhdl",
"helpers.vhdl",
# XICS controller
"xics.vhdl",
]
sdir = get_data_mod("cpu", "microwatt").data_location
cdir = os.path.dirname(__file__)
if use_ghdl_yosys_plugin:
from litex.build import tools
import subprocess
# ICP
ys = []
ys.append("ghdl --ieee=synopsys -fexplicit -frelaxed-rules --std=08 \\")
for source in sources:
ys.append(os.path.join(sdir, source) + " \\")
ys.append(os.path.join(os.path.dirname(__file__), "xics_wrapper.vhdl") + " \\")
ys.append("-e xics_icp_wrapper")
ys.append("chformal -assert -remove")
ys.append("write_verilog {}".format(os.path.join(cdir, "xics_icp.v")))
tools.write_to_file(os.path.join(cdir, "xics_icp.ys"), "\n".join(ys))
if subprocess.call(["yosys", "-q", "-m", "ghdl", os.path.join(cdir, "xics_icp.ys")]):
raise OSError("Unable to convert Microwatt XICS ICP controller to verilog, please check your GHDL-Yosys-plugin install")
platform.add_source(os.path.join(cdir, "xics_icp.v"))
# ICS
ys = []
ys.append("ghdl --ieee=synopsys -fexplicit -frelaxed-rules --std=08 \\")
for source in sources:
ys.append(os.path.join(sdir, source) + " \\")
ys.append(os.path.join(os.path.dirname(__file__), "xics_wrapper.vhdl") + " \\")
ys.append("-e xics_ics_wrapper")
ys.append("chformal -assert -remove")
ys.append("write_verilog {}".format(os.path.join(cdir, "xics_ics.v")))
tools.write_to_file(os.path.join(cdir, "xics_ics.ys"), "\n".join(ys))
if subprocess.call(["yosys", "-q", "-m", "ghdl", os.path.join(cdir, "xics_ics.ys")]):
raise OSError("Unable to convert Microwatt XICS ICP controller to verilog, please check your GHDL-Yosys-plugin install")
platform.add_source(os.path.join(cdir, "xics_ics.v"))
else:
platform.add_sources(sdir, *sources)
platform.add_source(os.path.join(os.path.dirname(__file__), "xics_wrapper.vhdl"))
def do_finalize(self):
self.specials += Instance("xics_icp_wrapper", **self.icp_params)
self.specials += Instance("xics_ics_wrapper", **self.ics_params)
class Microwatt(CPU):
name = "microwatt"
@ -56,6 +180,8 @@ class Microwatt(CPU):
self.wb_data = wb_data = wishbone.Interface(data_width=64, adr_width=29)
self.periph_buses = [wb_insn, wb_data]
self.memory_buses = []
self.interrupt = Signal(16)
self.core_ext_irq = Signal()
# # #
@ -95,16 +221,30 @@ class Microwatt(CPU):
i_dmi_req = 0,
i_dmi_wr = 0,
#o_dmi_ack =,
# Interrupt controller
i_core_ext_irq = self.core_ext_irq,
)
# add vhdl sources
self.add_sources(platform, use_ghdl_yosys_plugin="ghdl" in self.variant)
# add XICS controller
self.add_xics()
def set_reset_address(self, reset_address):
assert not hasattr(self, "reset_address")
self.reset_address = reset_address
assert reset_address == 0x00000000
def add_xics(self):
self.submodules.xics = XICSSlave(
platform = self.platform,
variant = self.variant,
core_irq_out = self.core_ext_irq,
int_level_in = self.interrupt,
endianness = self.endianness)
@staticmethod
def add_sources(platform, use_ghdl_yosys_plugin=False):
sources = [

View File

@ -1,4 +1,5 @@
/* Copyright 2013-2014 IBM Corp.
* Copyright 2020 Raptor Engineering, LLC
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
@ -81,10 +82,27 @@ _start:
bl main
b .
#define EXCEPTION(nr) \
.= nr; \
#define REDZONE_SIZE (512)
#define REG_SAVE_SIZE ((32 + 5)*8)
#define STACK_FRAME_C_MINIMAL 64
#define SAVE_NIA (32*8)
#define SAVE_LR (33*8)
#define SAVE_CTR (34*8)
#define SAVE_CR (35*8)
#define SAVE_SRR1 (36*8)
#define EXCEPTION(nr) \
.= nr; \
b .
#define FORWARD_EXCEPTION(nr) \
. = nr; \
stdu %r1,-(REG_SAVE_SIZE+REDZONE_SIZE)(%r1); \
std %r0, 1*8(%r1); \
LOAD_IMM64(%r0, nr); \
b __isr
/* More exception stubs */
EXCEPTION(0x100)
EXCEPTION(0x200)
@ -92,11 +110,11 @@ _start:
EXCEPTION(0x380)
EXCEPTION(0x400)
EXCEPTION(0x480)
EXCEPTION(0x500)
FORWARD_EXCEPTION(0x500)
EXCEPTION(0x600)
EXCEPTION(0x700)
EXCEPTION(0x800)
EXCEPTION(0x900)
FORWARD_EXCEPTION(0x900)
EXCEPTION(0x980)
EXCEPTION(0xa00)
EXCEPTION(0xb00)
@ -122,5 +140,130 @@ _start:
EXCEPTION(0x1600)
#endif
// Exception handler
__isr:
/*
* Assume where we are coming from has a stack and can save there.
* We save the full register set. Since we are calling out to C, we
* could just save the ABI volatile registers
*/
/*
* The first two lines below are executed in the exception handler, so that r0
* can be used to store the origin exception vector
*/
// stdu %r1,-(REG_SAVE_SIZE+REDZONE_SIZE)(%r1)
// std %r0, 1*8(%r1)
// std %r1, 1*8(%r1)
std %r2, 2*8(%r1)
std %r3, 3*8(%r1)
std %r4, 4*8(%r1)
std %r5, 5*8(%r1)
std %r6, 6*8(%r1)
std %r7, 7*8(%r1)
std %r8, 8*8(%r1)
std %r9, 9*8(%r1)
std %r10, 10*8(%r1)
std %r11, 11*8(%r1)
std %r12, 12*8(%r1)
std %r13, 13*8(%r1)
std %r14, 14*8(%r1)
std %r15, 15*8(%r1)
std %r16, 16*8(%r1)
std %r17, 17*8(%r1)
std %r18, 18*8(%r1)
std %r19, 19*8(%r1)
std %r20, 20*8(%r1)
std %r21, 21*8(%r1)
std %r22, 22*8(%r1)
std %r23, 23*8(%r1)
std %r24, 24*8(%r1)
std %r25, 25*8(%r1)
std %r26, 26*8(%r1)
std %r27, 27*8(%r1)
std %r28, 28*8(%r1)
std %r29, 29*8(%r1)
std %r30, 30*8(%r1)
std %r31, 31*8(%r1)
mr %r10, %r0
mfsrr0 %r0
std %r0, SAVE_NIA(%r1)
mflr %r0
std %r0, SAVE_LR(%r1)
mfctr %r0
std %r0, SAVE_CTR(%r1)
mfcr %r0
std %r0, SAVE_CR(%r1)
mfsrr1 %r0
std %r0, SAVE_SRR1(%r1)
stdu %r1,-STACK_FRAME_C_MINIMAL(%r1)
/* Load IRQ handler address from SRAM */
LOAD_IMM64(%r3, __isr_address)
ld %r3, 0(%r3)
mtctr %r3,
mr %r3, %r10
bctrl
nop
ld %r1, 0(%r1)
ld %r0, 1*8(%r1)
// ld %r1, 1*8(%r1) // do this at rfid
ld %r2, 2*8(%r1)
// ld %r3, 3*8(%r1) // do this at rfid
ld %r4, 4*8(%r1)
ld %r5, 5*8(%r1)
ld %r6, 6*8(%r1)
ld %r7, 7*8(%r1)
ld %r8, 8*8(%r1)
ld %r9, 9*8(%r1)
ld %r10, 10*8(%r1)
ld %r11, 11*8(%r1)
ld %r12, 12*8(%r1)
ld %r13, 13*8(%r1)
ld %r14, 14*8(%r1)
ld %r15, 15*8(%r1)
ld %r16, 16*8(%r1)
ld %r17, 17*8(%r1)
ld %r18, 18*8(%r1)
ld %r19, 19*8(%r1)
ld %r20, 20*8(%r1)
ld %r21, 21*8(%r1)
ld %r22, 22*8(%r1)
ld %r23, 23*8(%r1)
ld %r24, 24*8(%r1)
ld %r25, 25*8(%r1)
ld %r26, 26*8(%r1)
ld %r27, 27*8(%r1)
ld %r28, 28*8(%r1)
ld %r29, 29*8(%r1)
ld %r30, 30*8(%r1)
ld %r31, 31*8(%r1)
ld %r3, SAVE_LR(%r1)
mtlr %r3
ld %r3, SAVE_CTR(%r1)
mtctr %r3
ld %r3, SAVE_CR(%r1)
mtcr %r3
ld %r3, SAVE_SRR1(%r1)
mtsrr1 %r3
ld %r3, SAVE_NIA(%r1)
mtsrr0 %r3
/* restore %r3 */
ld %r3, 3*8(%r1)
/* do final fixup r1 */
ld %r1, 0*8(%r1)
rfid
.text
.globl __isr_address
.data
.align 8
__isr_address:
.long isr

View File

@ -1,4 +1,161 @@
// (c) 2020 Raptor Engineering, LLC <sales@raptorengineering.com>
#ifndef __IRQ_H
#define __IRQ_H
#ifdef __cplusplus
extern "C" {
#endif
#include <system.h>
#include <generated/csr.h>
#include <generated/soc.h>
#include <generated/mem.h>
// Address of exception / IRQ handler routine
extern void * __rom_isr_address;
void isr(uint64_t vec);
// External interrupt enable bit
#define PPC_MSR_EE_SHIFT 15
// XICS registers
#define PPC_XICS_XIRR_POLL 0x0
#define PPC_XICS_XIRR 0x4
#define PPC_XICS_RESV 0x8
#define PPC_XICS_MFRR 0xc
// Must match corresponding XICS ICS HDL parameter
#define PPC_XICS_SRC_NUM 16
// Default external interrupt priority set by software during IRQ enable
#define PPC_EXT_INTERRUPT_PRIO 0x08
uint8_t inline xics_icp_readb(int reg)
{
return *((uint8_t*)(HOSTXICSICP_BASE + reg));
}
void inline xics_icp_writeb(int reg, uint8_t value)
{
*((uint8_t*)(HOSTXICSICP_BASE + reg)) = value;
}
uint32_t inline xics_icp_readw(int reg)
{
return *((uint32_t*)(HOSTXICSICP_BASE + reg));
}
void inline xics_icp_writew(int reg, uint32_t value)
{
*((uint32_t*)(HOSTXICSICP_BASE + reg)) = value;
}
uint32_t inline xics_ics_read_xive(int irq_number)
{
return *((uint32_t*)(HOSTXICSICS_BASE + 0x800 + (irq_number << 2)));
}
void inline xics_ics_write_xive(int irq_number, uint32_t priority)
{
*((uint32_t*)(HOSTXICSICS_BASE + 0x800 + (irq_number << 2))) = priority;
}
void inline mtmsrd(uint64_t val)
{
__asm__ volatile("mtmsrd %0" : : "r" (val) : "memory");
}
uint64_t inline mfmsr(void)
{
uint64_t rval;
__asm__ volatile("mfmsr %0" : "=r" (rval) : : "memory");
return rval;
}
void inline mtdec(uint64_t val)
{
__asm__ volatile("mtdec %0" : : "r" (val) : "memory");
}
uint64_t inline mfdec(void)
{
uint64_t rval;
__asm__ volatile("mfdec %0" : "=r" (rval) : : "memory");
return rval;
}
static inline unsigned int irq_getie(void)
{
return (mfmsr() & (1 << PPC_MSR_EE_SHIFT)) != 0;
}
static inline void irq_setie(unsigned int ie)
{
if (ie)
{
// Unmask all IRQs
xics_icp_writeb(PPC_XICS_XIRR, 0xff);
// Enable DEC + external interrupts
mtmsrd(mfmsr() | (1 << PPC_MSR_EE_SHIFT));
}
else
{
// Disable DEC + external interrupts
mtmsrd(mfmsr() & ~(1 << PPC_MSR_EE_SHIFT));
// Mask all IRQs
xics_icp_writeb(PPC_XICS_XIRR, 0x00);
}
}
static inline unsigned int irq_getmask(void)
{
// Compute mask from enabled external interrupts in ICS
uint32_t mask;
int irq;
mask = 0;
for (irq = PPC_XICS_SRC_NUM - 1; irq >= 0; irq--) {
mask = mask << 1;
if ((xics_ics_read_xive(irq) & 0xff) != 0xff)
mask |= 0x1;
}
return mask;
}
static inline void irq_setmask(unsigned int mask)
{
int irq;
// Enable all interrupts at a fixed priority level for now
int priority_level = PPC_EXT_INTERRUPT_PRIO;
// Iterate over IRQs configured in mask, and enable / mask in ICS
for (irq = 0; irq < PPC_XICS_SRC_NUM; irq++) {
if ((mask >> irq) & 0x1)
xics_ics_write_xive(irq, priority_level);
else
xics_ics_write_xive(irq, 0xff);
}
}
static inline unsigned int irq_pending(void)
{
// Compute pending interrupt bitmask from asserted external interrupts in ICS
uint32_t pending;
int irq;
pending = 0;
for (irq = PPC_XICS_SRC_NUM - 1; irq >= 0; irq--) {
pending = pending << 1;
if ((xics_ics_read_xive(irq) & (0x1 << 31)) != 0)
pending |= 0x1;
}
return pending;
}
#ifdef __cplusplus
}
#endif
#endif /* __IRQ_H */

View File

@ -2,6 +2,7 @@
-- This file is part of LiteX.
--
-- Copyright (c) 2019 Florent Kermarrec <florent@enjoy-digital.fr>
-- Copyright (c) 2020 Raptor Engineering, LLC <sales@raptorengineering.com>
-- SPDX-License-Identifier: BSD-2-Clause
library ieee;
@ -50,6 +51,8 @@ entity microwatt_wrapper is
dmi_wr : in std_ulogic;
dmi_ack : out std_ulogic;
core_ext_irq : in std_ulogic;
terminated_out : out std_logic
);
end microwatt_wrapper;
@ -62,8 +65,6 @@ architecture rtl of microwatt_wrapper is
signal wishbone_data_in : wishbone_slave_out;
signal wishbone_data_out : wishbone_master_out;
signal core_ext_irq : std_ulogic;
begin
-- wishbone_insn mapping
@ -90,9 +91,6 @@ begin
wishbone_data_sel <= wishbone_data_out.sel;
wishbone_data_we <= wishbone_data_out.we;
-- core_ext_irq mapping
core_ext_irq <= '0';
microwatt_core : entity work.core
generic map (
SIM => SIM,

View File

@ -0,0 +1,182 @@
-- This file is Copyright (c) 2019 Florent Kermarrec <florent@enjoy-digital.fr>
-- Copyright (c) 2020 Raptor Engineering, LLC <sales@raptorengineering.com>
-- License: BSD
library ieee;
use ieee.std_logic_1164.all;
use ieee.numeric_std.all;
library work;
use work.common.all;
use work.wishbone_types.all;
entity xics_icp_wrapper is
port (
clk : in std_logic;
rst : in std_logic;
wishbone_dat_r : out std_ulogic_vector(31 downto 0);
wishbone_ack : out std_ulogic;
wishbone_stall : out std_ulogic;
wishbone_adr : in std_ulogic_vector(29 downto 0);
wishbone_dat_w : in std_ulogic_vector(31 downto 0);
wishbone_cyc : in std_ulogic;
wishbone_stb : in std_ulogic;
wishbone_sel : in std_ulogic_vector(3 downto 0);
wishbone_we : in std_ulogic;
ics_in_src : in std_ulogic_vector(3 downto 0);
ics_in_pri : in std_ulogic_vector(7 downto 0);
core_irq_out : out std_ulogic
);
end xics_icp_wrapper;
architecture rtl of xics_icp_wrapper is
signal wishbone_in : wb_io_master_out;
signal wishbone_out : wb_io_slave_out;
signal ics_in : ics_to_icp_t;
begin
-- wishbone mapping
wishbone_dat_r <= wishbone_out.dat;
wishbone_ack <= wishbone_out.ack;
wishbone_stall <= wishbone_out.stall;
wishbone_in.adr <= wishbone_adr(27 downto 0) & "00";
wishbone_in.dat <= wishbone_dat_w;
wishbone_in.cyc <= wishbone_cyc;
wishbone_in.stb <= wishbone_stb;
wishbone_in.sel <= wishbone_sel;
wishbone_in.we <= wishbone_we;
ics_in.src <= ics_in_src;
ics_in.pri <= ics_in_pri;
xics_icp : entity work.xics_icp
port map (
clk => clk,
rst => rst,
wb_in => wishbone_in,
wb_out => wishbone_out,
ics_in => ics_in,
core_irq_out => core_irq_out
);
end rtl;
library ieee;
use ieee.std_logic_1164.all;
use ieee.numeric_std.all;
library work;
use work.common.all;
use work.wishbone_types.all;
entity xics_ics_wrapper is
port (
clk : in std_logic;
rst : in std_logic;
wishbone_dat_r : out std_ulogic_vector(31 downto 0);
wishbone_ack : out std_ulogic;
wishbone_stall : out std_ulogic;
wishbone_adr : in std_ulogic_vector(29 downto 0);
wishbone_dat_w : in std_ulogic_vector(31 downto 0);
wishbone_cyc : in std_ulogic;
wishbone_stb : in std_ulogic;
wishbone_sel : in std_ulogic_vector(3 downto 0);
wishbone_we : in std_ulogic;
int_level_in : in std_ulogic_vector(31 downto 0);
icp_out_src : out std_ulogic_vector(3 downto 0);
icp_out_pri : out std_ulogic_vector(7 downto 0)
);
end xics_ics_wrapper;
architecture rtl of xics_ics_wrapper is
signal wishbone_in : wb_io_master_out;
signal wishbone_out : wb_io_slave_out;
signal icp_out : ics_to_icp_t;
signal int_level_uw : std_ulogic_vector(255 downto 0);
begin
-- wishbone mapping
wishbone_dat_r <= wishbone_out.dat;
wishbone_ack <= wishbone_out.ack;
wishbone_stall <= wishbone_out.stall;
wishbone_in.adr <= wishbone_adr(27 downto 0) & "00";
wishbone_in.dat <= wishbone_dat_w;
wishbone_in.cyc <= wishbone_cyc;
wishbone_in.stb <= wishbone_stb;
wishbone_in.sel <= wishbone_sel;
wishbone_in.we <= wishbone_we;
icp_out_src <= icp_out.src;
icp_out_pri <= icp_out.pri;
-- Assign external interrupts
interrupts: process(all)
begin
int_level_uw <= (others => '0');
int_level_uw(0) <= int_level_in(0);
int_level_uw(1) <= int_level_in(1);
int_level_uw(2) <= int_level_in(2);
int_level_uw(3) <= int_level_in(3);
int_level_uw(4) <= int_level_in(4);
int_level_uw(5) <= int_level_in(5);
int_level_uw(6) <= int_level_in(6);
int_level_uw(7) <= int_level_in(7);
int_level_uw(8) <= int_level_in(8);
int_level_uw(9) <= int_level_in(9);
int_level_uw(10) <= int_level_in(10);
int_level_uw(11) <= int_level_in(11);
int_level_uw(12) <= int_level_in(12);
int_level_uw(13) <= int_level_in(13);
int_level_uw(14) <= int_level_in(14);
int_level_uw(15) <= int_level_in(15);
int_level_uw(16) <= int_level_in(16);
int_level_uw(17) <= int_level_in(17);
int_level_uw(18) <= int_level_in(18);
int_level_uw(19) <= int_level_in(19);
int_level_uw(20) <= int_level_in(20);
int_level_uw(21) <= int_level_in(21);
int_level_uw(22) <= int_level_in(22);
int_level_uw(23) <= int_level_in(23);
int_level_uw(24) <= int_level_in(24);
int_level_uw(25) <= int_level_in(25);
int_level_uw(26) <= int_level_in(26);
int_level_uw(27) <= int_level_in(27);
int_level_uw(28) <= int_level_in(28);
int_level_uw(29) <= int_level_in(29);
int_level_uw(30) <= int_level_in(30);
int_level_uw(31) <= int_level_in(31);
end process;
xics_ics : entity work.xics_ics
generic map (
SRC_NUM => 16
)
port map (
clk => clk,
rst => rst,
wb_in => wishbone_in,
wb_out => wishbone_out,
int_level_in => int_level_uw,
icp_out => icp_out
);
end rtl;

View File

@ -1,5 +1,6 @@
// This file is Copyright (c) 2013-2014 Sebastien Bourdeauducq <sb@m-labs.hk>
// This file is Copyright (c) 2019 Gabriel L. Somlo <gsomlo@gmail.com>
// This file is Copyright (c) 2020 Raptor Engineering, LLC <sales@raptorengineering.com>
// License: BSD
@ -9,7 +10,12 @@
#include <uart.h>
#include <stdio.h>
#if defined(__microwatt__)
void isr(uint64_t vec);
void isr_dec(void);
#else
void isr(void);
#endif
#ifdef CONFIG_CPU_HAS_INTERRUPT
@ -96,6 +102,47 @@ void isr(void)
#endif
}
}
#elif defined(__microwatt__)
void isr(uint64_t vec)
{
if (vec == 0x900)
return isr_dec();
if (vec == 0x500) {
// Read interrupt source
uint32_t xirr = xics_icp_readw(PPC_XICS_XIRR);
uint32_t irq_source = xirr & 0x00ffffff;
__attribute__((unused)) unsigned int irqs;
// Handle IPI interrupts separately
if (irq_source == 2) {
// IPI interrupt
xics_icp_writeb(PPC_XICS_MFRR, 0xff);
}
else {
// External interrupt
irqs = irq_pending() & irq_getmask();
#ifndef UART_POLLING
if(irqs & (1 << UART_INTERRUPT))
uart_isr();
#endif
}
// Clear interrupt
xics_icp_writew(PPC_XICS_XIRR, xirr);
return;
}
}
void isr_dec(void)
{
// For now, just set DEC back to a large enough value to slow the flood of DEC-initiated timer interrupts
mtdec(0x000000000ffffff);
}
#else
void isr(void)
@ -113,6 +160,10 @@ void isr(void)
#else
#if defined(__microwatt__)
void isr(uint64_t vec){};
#else
void isr(void){};
#endif
#endif